From f29c9143d522473f6ba3b11684c11d0daca8be81 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Tue, 29 Sep 2020 19:22:18 +0900 Subject: [PATCH] remove ROS1 packages temporarily Signed-off-by: mitsudome-r --- localization/ekf_localizer/CMakeLists.txt | 82 -- localization/ekf_localizer/README.md | 222 ------ .../include/ekf_localizer/ekf_localizer.h | 233 ------ .../include/kalman_filter/kalman_filter.hpp | 208 ----- .../time_delay_kalman_filter.hpp | 85 -- .../ekf_localizer/launch/ekf_localizer.launch | 100 --- .../ekf_localizer/media/delay_model_eq.png | Bin 4906 -> 0 bytes .../ekf_localizer/media/ekf_autoware_res.png | Bin 69064 -> 0 bytes .../ekf_localizer/media/ekf_delay_comp.png | Bin 147442 -> 0 bytes .../ekf_localizer/media/ekf_dynamics.png | Bin 5346 -> 0 bytes .../ekf_localizer/media/ekf_flowchart.png | Bin 146302 -> 0 bytes .../ekf_localizer/media/ekf_smooth_update.png | Bin 146470 -> 0 bytes localization/ekf_localizer/package.xml | 17 - .../ekf_localizer/src/ekf_localizer.cpp | 736 ------------------ .../ekf_localizer/src/ekf_localizer_node.cpp | 27 - .../src/kalman_filter/kalman_filter.cpp | 126 --- .../time_delay_kalman_filter.cpp | 95 --- .../test/src/test_ekf_localizer.cpp | 289 ------- .../test/test_ekf_localizer.test | 5 - 19 files changed, 2225 deletions(-) delete mode 100644 localization/ekf_localizer/CMakeLists.txt delete mode 100644 localization/ekf_localizer/README.md delete mode 100644 localization/ekf_localizer/include/ekf_localizer/ekf_localizer.h delete mode 100644 localization/ekf_localizer/include/kalman_filter/kalman_filter.hpp delete mode 100644 localization/ekf_localizer/include/kalman_filter/time_delay_kalman_filter.hpp delete mode 100644 localization/ekf_localizer/launch/ekf_localizer.launch delete mode 100644 localization/ekf_localizer/media/delay_model_eq.png delete mode 100644 localization/ekf_localizer/media/ekf_autoware_res.png delete mode 100644 localization/ekf_localizer/media/ekf_delay_comp.png delete mode 100644 localization/ekf_localizer/media/ekf_dynamics.png delete mode 100644 localization/ekf_localizer/media/ekf_flowchart.png delete mode 100644 localization/ekf_localizer/media/ekf_smooth_update.png delete mode 100644 localization/ekf_localizer/package.xml delete mode 100644 localization/ekf_localizer/src/ekf_localizer.cpp delete mode 100644 localization/ekf_localizer/src/ekf_localizer_node.cpp delete mode 100644 localization/ekf_localizer/src/kalman_filter/kalman_filter.cpp delete mode 100644 localization/ekf_localizer/src/kalman_filter/time_delay_kalman_filter.cpp delete mode 100644 localization/ekf_localizer/test/src/test_ekf_localizer.cpp delete mode 100644 localization/ekf_localizer/test/test_ekf_localizer.test diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt deleted file mode 100644 index b53457b0215ba..0000000000000 --- a/localization/ekf_localizer/CMakeLists.txt +++ /dev/null @@ -1,82 +0,0 @@ -cmake_minimum_required(VERSION 3.0.2) -project(ekf_localizer) - -add_compile_options(-std=c++14) - -find_package(catkin REQUIRED - roscpp - std_msgs - tf2 - tf2_ros - geometry_msgs - sensor_msgs - rostest - rosunit -) - -find_package(Eigen3 REQUIRED) - -catkin_package( - INCLUDE_DIRS include - CATKIN_DEPENDS - roscpp - std_msgs - tf2 - tf2_ros - geometry_msgs - sensor_msgs -) - -########### -## Build ## -########### - -include_directories( - include - ${catkin_INCLUDE_DIRS} - ${EIGEN3_INCLUDE_DIR} -) - -add_executable(ekf_localizer -src/ekf_localizer_node.cpp -src/ekf_localizer.cpp -src/kalman_filter/kalman_filter.cpp -src/kalman_filter/time_delay_kalman_filter.cpp) -add_dependencies(ekf_localizer ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) -target_link_libraries(ekf_localizer ${catkin_LIBRARIES}) - -############# -## Install ## -############# - -## Install executables and/or libraries -install(TARGETS ekf_localizer - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - -## Install project namespaced headers -install(DIRECTORY include/ekf_localizer/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) - -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) - -############# -## Testing ## -############# - -if(CATKIN_ENABLE_TESTING) - find_package(rostest REQUIRED) - - add_rostest_gtest(ekf_localizer-test test/test_ekf_localizer.test - test/src/test_ekf_localizer.cpp - src/ekf_localizer.cpp - src/kalman_filter/kalman_filter.cpp - src/kalman_filter/time_delay_kalman_filter.cpp) - - target_link_libraries(ekf_localizer-test ${catkin_LIBRARIES}) -endif() diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md deleted file mode 100644 index 0411d5228d577..0000000000000 --- a/localization/ekf_localizer/README.md +++ /dev/null @@ -1,222 +0,0 @@ -# Overview - -The **Extend Kalman Filter Localizer** estimates robust and less noisy robot pose and twist by integrating the 2D vehicle dynamics model with input ego-pose and ego-twist messages. The algorithm is designed especially for fast moving robot such as autonomous driving system. - - -## Flowchart - -The overall flowchart of the ekf_localizer is described below. - -

- -

- - -## Features -This package includes the following features: - - - **Time delay compensation** for input messages, which enables proper integration of input information with varying time delay. This is important especially for high speed moving robot, such as autonomous driving vehicle. (see following figure). -- **Automatic estimation of yaw bias** prevents modeling errors caused by sensor mounting angle errors, which can improve estimation accuracy. -- **Mahalanobis distance gate** enables probabilistic outlier detection to determine which inputs should be used or ignored. -- **Smooth update**, the Kalman Filter measurement update is typically performed when a measurement is obtained, but it can cause large changes in the estimated value especially for low frequency measurements. Since the algorithm can consider the measurement time, the measurement data can be divided into multiple pieces and integrated smoothly while maintaining consistency (see following figure). - - -

- -

- -#### - -

- -

- -# Launch - -The `ekf_localizer` starts with the default parameters with the following command. - -``` -roslaunch ekf_localizer ekf_localizer.launch -``` - -The parameters and input topic names can be set in the `ekf_localizer.launch` file. - - -# Node - -## Subscribed Topics - - measured_pose_with_covariance (geometry_msgs/PoseWithCovarianceStamped) - - Input pose source with measurement covariance matrix, used when `use_pose_with_covariance` is true. - - - measured_twist_with_covariance (geometry_msgs/PoseWithCovarianceStamped) - - Input twist source with measurement covariance matrix, used when `use_twist_with_covariance` is true. - - - measured_pose (geometry_msgs/PoseStamped) - - Input pose source, used when `use_pose_with_covariance` is false. - - - measured_twist (geometry_msgs/TwistStamped) - - Input twist source, used when `use_twist_with_covariance` is false. - - - initialpose (geometry_msgs/PoseWithCovarianceStamped) - - Initial pose for EKF. The estimated pose is initialized with zeros at start. It is initialized with this message whenever published. - - -## Published Topics - - - ekf_pose (geometry_msgs/PoseStamped) - - Estimated pose. - - - ekf_pose_with_covariance (geometry_msgs/PoseWithCovarianceStamped) - - Estimated pose with covariance. - - ekf_pose_with_covariance (geometry_msgs/PoseStamped) - - Estimated pose without yawbias effect. - - - ekf_pose_with_covariance_without_yawbias (geometry_msgs/PoseWithCovarianceStamped) - - Estimated pose with covariance without yawbias effect. - - - ekf_twist (geometry_msgs/TwistStamped) - - Estimated twist. - - - ekf_twist_with_covariance (geometry_msgs/TwistWithCovarianceStamped) - - Estimated twist with covariance. - - -## Published TF - - - base_link - - TF from "map" coordinate to estimated pose. - - -# Functions - - -## Predict - -The current robot state is predicted from previously estimated data using a given prediction model. This calculation is called at constant interval (`predict_frequency [Hz]`). The prediction equation is described at the end of this page. - - -## Measurement Update - -Before update, the Mahalanobis distance is calculated between the measured input and the predicted state, the measurement update is not performed for inputs where the Mahalanobis distance exceeds the given threshold. - -The predicted state is updated with the latest measured inputs, measured_pose and measured_twist. The updates are performed with the same frequency as prediction, usually at a high frequency, in order to enable smooth state estimation. - - - - - -# Parameter description - -The parameters are set in `launch/ekf_localizer.launch` . - - -## For Node - -|Name|Type|Description|Default value| -|:---|:---|:---|:---| -|show_debug_info|bool|Flag to display debug info|false| -|predict_frequency|double|Frequency for filtering and publishing [Hz]|50.0| -|tf_rate|double|Frqcuency for tf broadcasting [Hz]|10.0| -|extend_state_step|int|Max delay step which can be dealt with in EKF. Large number increases computational cost. |50| -|enable_yaw_bias_estimation| bool |Flag to enable yaw bias estimation|true| - -## For pose measurement - -|Name|Type|Description|Default value| -|:---|:---|:---|:---| -|pose_additional_delay|double|Additional delay time for pose measurement [s]|0.0| -|pose_measure_uncertainty_time|double|Measured time uncertainty used for covariance calculation [s]|0.01| -|pose_rate|double|Approximated input pose rate used for covariance calculation [Hz]|10.0| -|pose_gate_dist|double|Limit of Mahalanobis distance used for outliers detection|10000.0| -|use_pose_with_covariance|bool|Flag to use covariance in pose_with_covarianve message|false| -|pose_stddev_x|double|Standard deviation for pose position x [m] (used when use_pose_with_covariance is false)|0.05| -|pose_stddev_y|double|Standard deviation for pose position y [m] (used when use_pose_with_covariance is false)|0.05| -|pose_stddev_yaw|double|Standard deviation for pose yaw angle [rad] (used when use_pose_with_covariance is false)|0.025| - -## For twist measurement -|Name|Type|Description|Default value| -|:---|:---|:---|:---| -|twist_additional_delay|double|Additional delay time for twist [s]|0.0| -|twist_rate|double|Approximated input twist rate used for covariance calculation [Hz]|10.0| -|twist_gate_dist|double|Limit of Mahalanobis distance used for outliers detection|10000.0| -|use_twist_with_covariance|bool|Flag to use covariance in twist_with_covariance message|false| -|twist_stddev_vx|double|Standard deviation for twist linear x [m/s] (used when use_twist_with_covariance is false) |0.2| -|twist_stddev_wz|double|Standard deviation for twist angular z [rad/s] (used when use_twist_with_covariance is false) |0.03| - -## For process noise -|Name|Type|Description|Default value| -|:---|:---|:---|:---| -|proc_stddev_vx_c|double|Standard deviation of process noise in time differentiation expression of linear velocity x, noise for d_vx = 0|2.0| -|proc_stddev_wz_c|double|Standard deviation of process noise in time differentiation expression of angular velocity z, noise for d_wz = 0|0.2| -|proc_stddev_yaw_c|double|Standard deviation of process noise in time differentiation expression of yaw, noise for d_yaw = omege |0.005| -|proc_stddev_yaw_bias_c|double|Standard deviation of process noise in time differentiation expression of yaw_bias, noise for d_yaw_bias = 0|0.001| - -note: process noise for position x & y are calculated automatically from nonlinear dynamics. - -# How to turn EKF parameters - -**0. Preliminaries** - - Check header time in pose and twist message is set to sensor time appropriately, because time delay is calculated from this value. If it is difficult to set appropriate time due to timer synchronization problem, use `twist_additional_delay` and `pose_additional_delay` to correct the time. - - Check the relation between measurement pose and twist is appropriate (whether the derivative of pose has similar value to twist). This discrepancy is caused mainly by unit error (such as comfusing radian/degree) or bias noise, and it causes large estimation errors. - - -**1. Set sensor parameters** - -Set sensor-rate and standard-deviation from the basic information of the sensor. The `pose_measure_uncertainty_time` is for uncertainty of the header timestamp data. - - - `pose_measure_uncertainty_time` - - `pose_rate` - - `pose_stddev_x` - - `pose_stddev_y` - - `pose_stddev_yaw` - - `twist_rate` - - `twist_stddev_vx` - - `twist_stddev_wz` - -**2. Set process model parameters** - - - - `proc_stddev_vx_c` : set to maximum linear acceleration - - `proc_stddev_wz_c` : set to maximum angular acceleration - - `proc_stddev_yaw_c` : This parameter describes the correlation between the yaw and yaw-rate. Large value means the change in yaw does not correlate to the estiamted yaw-rate. If this is set to 0, it means the change in estimate yaw is equal to yaw-rate. Usually this should be set to 0. - - `proc_stddev_yaw_bias_c` : This parameter is the standard deviation for the rate of change in yaw bias. In most cases, yaw bias is constant, so it can be very small, but must be non-zero. - - **3. Tune sensor standard deviation parameters with rosbag simulation.** - - If the position measurement seems more reliable, make these parameters smaller. If the estimated position seems to be noisy due to pose measurement noise, make these values bigger. - - - `pose_stddev_x` - - `pose_stddev_y` - - `pose_stddev_yaw` - - If the twist measurement seems more reliable, make these parameters smaller. If the estimated twist seems to be noisy due to pose measurement noise, make these values bigger. - - `twist_stddev_vx` - - `twist_stddev_wz` - -# Kalman Filter Model - -## kinematics model in update function - - -where `b_k` is the yaw-bias. - -## time delay model - - -# Test Result with Autoware NDT - -

- -

diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.h b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.h deleted file mode 100644 index 6a319608ea742..0000000000000 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.h +++ /dev/null @@ -1,233 +0,0 @@ -/* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "kalman_filter/kalman_filter.hpp" -#include "kalman_filter/time_delay_kalman_filter.hpp" - -class EKFLocalizer -{ -public: - EKFLocalizer(); - ~EKFLocalizer(); - -private: - ros::NodeHandle nh_; //!< @brief ros public node handler - ros::NodeHandle pnh_; //!< @brief ros private node handler - ros::Publisher pub_pose_; //!< @brief ekf estimated pose publisher - ros::Publisher pub_pose_cov_; //!< @brief estimated ekf pose with covariance publisher - ros::Publisher pub_twist_; //!< @brief ekf estimated twist publisher - ros::Publisher pub_twist_cov_; //!< @brief ekf estimated twist with covariance publisher - ros::Publisher pub_debug_; //!< @brief debug info publisher - ros::Publisher pub_measured_pose_; //!< @brief debug measurement pose publisher - ros::Publisher pub_yaw_bias_; //!< @brief ekf estimated yaw bias publisher - ros::Publisher pub_pose_no_yawbias_; //!< @brief ekf estimated yaw bias publisher - ros::Publisher pub_pose_cov_no_yawbias_; //!< @brief ekf estimated yaw bias publisher - ros::Subscriber sub_initialpose_; //!< @brief initial pose subscriber - ros::Subscriber sub_pose_; //!< @brief measurement pose subscriber - ros::Subscriber sub_twist_; //!< @brief measurement twist subscriber - ros::Subscriber sub_pose_with_cov_; //!< @brief measurement pose with covariance subscriber - ros::Subscriber sub_twist_with_cov_; //!< @brief measurement twist with covariance subscriber - ros::Timer timer_control_; //!< @brief time for ekf calculation callback - ros::Timer timer_tf_; //!< @brief timer to send transform - tf2_ros::TransformBroadcaster tf_br_; //!< @brief tf broadcaster - - TimeDelayKalmanFilter ekf_; //!< @brief extended kalman filter instance. - - /* parameters */ - bool show_debug_info_; - double ekf_rate_; //!< @brief EKF predict rate - double ekf_dt_; //!< @brief = 1 / ekf_rate_ - double tf_rate_; //!< @brief tf publish rate - bool - enable_yaw_bias_estimation_; //!< @brief for LiDAR mount error. if true, publish /estimate_yaw_bias - std::string pose_frame_id_; - - int dim_x_; //!< @brief dimension of EKF state - int extend_state_step_; //!< @brief for time delay compensation - int dim_x_ex_; //!< @brief dimension of extended EKF state (dim_x_ * extended_state_step) - - /* Pose */ - double - pose_additional_delay_; //!< @brief compensated pose delay time = (pose.header.stamp - now) + - //!< additional_delay [s] - double pose_measure_uncertainty_time_; //!< @brief added for measurement covariance - double pose_rate_; //!< @brief pose rate [s], used for covariance calculation - double - pose_gate_dist_; //!< @brief the maharanobis distance threshold to ignore pose measurement - double pose_stddev_x_; //!< @brief standard deviation for pose position x [m] - double pose_stddev_y_; //!< @brief standard deviation for pose position y [m] - double pose_stddev_yaw_; //!< @brief standard deviation for pose position yaw [rad] - bool use_pose_with_covariance_; //!< @brief use covariance in pose_with_covarianve message - bool use_twist_with_covariance_; //!< @brief use covariance in twist_with_covarianve message - - /* twist */ - double - twist_additional_delay_; //!< @brief compensated delay = (twist.header.stamp - now) + additional_delay [s] - double twist_rate_; //!< @brief rate [s], used for covariance calculation - double - twist_gate_dist_; //!< @brief measurement is ignored if the maharanobis distance is larger than this value. - double twist_stddev_vx_; //!< @brief standard deviation for linear vx - double twist_stddev_wz_; //!< @brief standard deviation for angular wx - - /* process noise variance for discrete model */ - double proc_cov_yaw_d_; //!< @brief discrete yaw process noise - double proc_cov_yaw_bias_d_; //!< @brief discrete yaw bias process noise - double proc_cov_vx_d_; //!< @brief discrete process noise in d_vx=0 - double proc_cov_wz_d_; //!< @brief discrete process noise in d_wz=0 - - enum IDX { - X = 0, - Y = 1, - YAW = 2, - YAWB = 3, - VX = 4, - WZ = 5, - }; - - /* for model prediction */ - std::shared_ptr - current_twist_ptr_; //!< @brief current measured twist - std::shared_ptr current_pose_ptr_; //!< @brief current measured pose - geometry_msgs::PoseStamped current_ekf_pose_; //!< @brief current estimated pose - geometry_msgs::PoseStamped - current_ekf_pose_no_yawbias_; //!< @brief current estimated pose w/o yaw bias - geometry_msgs::TwistStamped current_ekf_twist_; //!< @brief current estimated twist - boost::array current_pose_covariance_; - boost::array current_twist_covariance_; - - /** - * @brief computes update & prediction of EKF for each ekf_dt_[s] time - */ - void timerCallback(const ros::TimerEvent & e); - - /** - * @brief publish tf for tf_rate [Hz] - */ - void timerTFCallback(const ros::TimerEvent & e); - - /** - * @brief set pose measurement - */ - void callbackPose(const geometry_msgs::PoseStamped::ConstPtr & msg); - - /** - * @brief set twist measurement - */ - void callbackTwist(const geometry_msgs::TwistStamped::ConstPtr & msg); - - /** - * @brief set poseWithCovariance measurement - */ - void callbackPoseWithCovariance(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & msg); - - /** - * @brief set twistWithCovariance measurement - */ - void callbackTwistWithCovariance(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr & msg); - - /** - * @brief set initial_pose to current EKF pose - */ - void callbackInitialPose(const geometry_msgs::PoseWithCovarianceStamped & msg); - - /** - * @brief initialization of EKF - */ - void initEKF(); - - /** - * @brief compute EKF prediction - */ - void predictKinematicsModel(); - - /** - * @brief compute EKF update with pose measurement - * @param pose measurement value - */ - void measurementUpdatePose(const geometry_msgs::PoseStamped & pose); - - /** - * @brief compute EKF update with pose measurement - * @param twist measurement value - */ - void measurementUpdateTwist(const geometry_msgs::TwistStamped & twist); - - /** - * @brief check whether a measurement value falls within the mahalanobis distance threshold - * @param dist_max mahalanobis distance threshold - * @param estimated current estimated state - * @param measured measured state - * @param estimated_cov current estimation covariance - * @return whether it falls within the mahalanobis distance threshold - */ - bool mahalanobisGate( - const double & dist_max, const Eigen::MatrixXd & estimated, const Eigen::MatrixXd & measured, - const Eigen::MatrixXd & estimated_cov) const; - - /** - * @brief get transform from frame_id - */ - bool getTransformFromTF( - std::string parent_frame, std::string child_frame, geometry_msgs::TransformStamped & transform); - - /** - * @brief normalize yaw angle - * @param yaw yaw angle - * @return normalized yaw - */ - double normalizeYaw(const double & yaw) const; - - /** - * @brief create quaternion from roll, pitch and yaw. - */ - geometry_msgs::Quaternion createQuaternionFromRPY(double r, double p, double y) const; - - /** - * @brief set current EKF estimation result to current_ekf_pose_ & current_ekf_twist_ - */ - void setCurrentResult(); - - /** - * @brief publish current EKF estimation result - */ - void publishEstimateResult(); - - /** - * @brief for debug - */ - void showCurrentX(); - - friend class EKFLocalizerTestSuite; // for test code -}; diff --git a/localization/ekf_localizer/include/kalman_filter/kalman_filter.hpp b/localization/ekf_localizer/include/kalman_filter/kalman_filter.hpp deleted file mode 100644 index b2a538f2b8a5f..0000000000000 --- a/localization/ekf_localizer/include/kalman_filter/kalman_filter.hpp +++ /dev/null @@ -1,208 +0,0 @@ -/* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#pragma once - -#include -#include - -/** - * @file kalman_filter.h - * @brief kalman filter class - * @author Takamasa Horibe - * @date 2019.05.01 - */ - -class KalmanFilter -{ -public: - /** - * @brief No initialization constructor. - */ - KalmanFilter(); - - /** - * @brief constructor with initialization - * @param x initial state - * @param A coefficient matrix of x for process model - * @param B coefficient matrix of u for process model - * @param C coefficient matrix of x for measurement model - * @param Q covariace matrix for process model - * @param R covariance matrix for measurement model - * @param P initial covariance of estimated state - */ - KalmanFilter( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P); - - /** - * @brief destructor - */ - ~KalmanFilter(); - - /** - * @brief initialization of kalman filter - * @param x initial state - * @param A coefficient matrix of x for process model - * @param B coefficient matrix of u for process model - * @param C coefficient matrix of x for measurement model - * @param Q covariace matrix for process model - * @param R covariance matrix for measurement model - * @param P initial covariance of estimated state - */ - bool init( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P); - - /** - * @brief initialization of kalman filter - * @param x initial state - * @param P initial covariance of estimated state - */ - bool init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0); - - /** - * @brief set A of process model - * @param A coefficient matrix of x for process model - */ - void setA(const Eigen::MatrixXd & A); - - /** - * @brief set B of process model - * @param B coefficient matrix of u for process model - */ - void setB(const Eigen::MatrixXd & B); - - /** - * @brief set C of measurement model - * @param C coefficient matrix of x for measurement model - */ - void setC(const Eigen::MatrixXd & C); - - /** - * @brief set covariace matrix Q for process model - * @param Q covariace matrix for process model - */ - void setQ(const Eigen::MatrixXd & Q); - - /** - * @brief set covariance matrix R for measurement model - * @param R covariance matrix for measurement model - */ - void setR(const Eigen::MatrixXd & R); - - /** - * @brief get current kalman filter state - * @param x kalman filter state - */ - void getX(Eigen::MatrixXd & x); - - /** - * @brief get current kalman filter covariance - * @param P kalman filter covariance - */ - void getP(Eigen::MatrixXd & P); - - /** - * @brief get component of current kalman filter state - * @param i index of kalman filter state - * @return value of i's component of the kalman filter state x[i] - */ - double getXelement(unsigned int i); - - /** - * @brief calculate kalman filter state and covariance by prediction model with A, B, Q matrix. This is mainly for EKF - * with variable matrix. - * @param u input for model - * @param A coefficient matrix of x for process model - * @param B coefficient matrix of u for process model - * @param Q covariace matrix for process model - * @return bool to check matrix operations are being performed properly - */ - bool predict( - const Eigen::MatrixXd & u, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & Q); - - /** - * @brief calculate kalman filter covariance with prediction model with x, A, Q matrix. This is mainly for EKF with - * variable matrix. - * @param x_next predicted state - * @param A coefficient matrix of x for process model - * @param Q covariace matrix for process model - * @return bool to check matrix operations are being performed properly - */ - bool predict( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q); - - /** - * @brief calculate kalman filter covariance with prediction model with x, A, Q matrix. This is mainly for EKF with - * variable matrix. - * @param x_next predicted state - * @param A coefficient matrix of x for process model - * @return bool to check matrix operations are being performed properly - */ - bool predict(const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A); - - /** - * @brief calculate kalman filter state by prediction model with A, B and Q being class menber variables. - * @param u input for the model - * @return bool to check matrix operations are being performed properly - */ - bool predict(const Eigen::MatrixXd & u); - - /** - * @brief calculate kalman filter state by measurement model with y_pred, C and R matrix. This is mainly for EKF with - * variable matrix. - * @param y measured values - * @param y output values expected from measurement model - * @param C coefficient matrix of x for measurement model - * @param R covariance matrix for measurement model - * @return bool to check matrix operations are being performed properly - */ - bool update( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & y_pred, const Eigen::MatrixXd & C, - const Eigen::MatrixXd & R); - - /** - * @brief calculate kalman filter state by measurement model with C and R matrix. This is mainly for EKF with variable - * matrix. - * @param y measured values - * @param C coefficient matrix of x for measurement model - * @param R covariance matrix for measurement model - * @return bool to check matrix operations are being performed properly - */ - bool update(const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R); - - /** - * @brief calculate kalman filter state by measurement model with C and R being class menber variables. - * @param y measured values - * @return bool to check matrix operations are being performed properly - */ - bool update(const Eigen::MatrixXd & y); - -protected: - Eigen::MatrixXd x_; //!< @brief current estimated state - Eigen::MatrixXd - A_; //!< @brief coefficient matrix of x for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd - B_; //!< @brief coefficient matrix of u for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd C_; //!< @brief coefficient matrix of x for measurement model y[k] = C * x[k] - Eigen::MatrixXd Q_; //!< @brief covariace matrix for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd R_; //!< @brief covariance matrix for measurement model y[k] = C * x[k] - Eigen::MatrixXd P_; //!< @brief covariance of estimated state -}; \ No newline at end of file diff --git a/localization/ekf_localizer/include/kalman_filter/time_delay_kalman_filter.hpp b/localization/ekf_localizer/include/kalman_filter/time_delay_kalman_filter.hpp deleted file mode 100644 index 3fc884a3e700f..0000000000000 --- a/localization/ekf_localizer/include/kalman_filter/time_delay_kalman_filter.hpp +++ /dev/null @@ -1,85 +0,0 @@ -/* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#pragma once - -#include -#include -#include -#include "kalman_filter/kalman_filter.hpp" - -/** - * @file time_delay_kalman_filter.h - * @brief kalman filter with delayed measurement class - * @author Takamasa Horibe - * @date 2019.05.01 - */ - -class TimeDelayKalmanFilter : public KalmanFilter -{ -public: - /** - * @brief No initialization constructor. - */ - TimeDelayKalmanFilter(); - - /** - * @brief initialization of kalman filter - * @param x initial state - * @param P0 initial covariance of estimated state - * @param max_delay_step Maximum number of delay steps, which determines the dimension of the extended kalman filter - */ - void init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P, const int max_delay_step); - - /** - * @brief get latest time estimated state - * @param x latest time estimated state - */ - void getLatestX(Eigen::MatrixXd & x); - - /** - * @brief get latest time estimation covariance - * @param P latest time estimation covariance - */ - void getLatestP(Eigen::MatrixXd & P); - - /** - * @brief calculate kalman filter covariance by predicion model with time delay. This is mainly for EKF of nonlinear - * process model. - * @param x_next predicted state by prediction model - * @param A coefficient matrix of x for process model - * @param Q covariace matrix for process model - */ - bool predictWithDelay( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q); - - /** - * @brief calculate kalman filter covariance by measurement model with time delay. This is mainly for EKF of nonlinear - * process model. - * @param y measured values - * @param C coefficient matrix of x for measurement model - * @param R covariance matrix for measurement model - * @param delay_step measurement delay - */ - bool updateWithDelay( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R, - const int delay_step); - -private: - int max_delay_step_; //!< @brief maximum number of delay steps - int dim_x_; //!< @brief dimension of latest state - int dim_x_ex_; //!< @brief dimension of extended state with dime delay -}; \ No newline at end of file diff --git a/localization/ekf_localizer/launch/ekf_localizer.launch b/localization/ekf_localizer/launch/ekf_localizer.launch deleted file mode 100644 index 38b278c67ce30..0000000000000 --- a/localization/ekf_localizer/launch/ekf_localizer.launch +++ /dev/null @@ -1,100 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/localization/ekf_localizer/media/delay_model_eq.png b/localization/ekf_localizer/media/delay_model_eq.png deleted file mode 100644 index 41777d756b9745cb874eed3d5175470e76ecc8b9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 4906 zcma)A2UJsAvjzcypeW4BO(NEVhO^UU!$I~(&EA*t-o{JDZKFxK7Q-)9d0|Cih_$&aah!V_tPVo4r8S#$OL zvyQ@_UUtShd7l^yOcA#S%=|G63vc7W&H6%?_Y4aQe;8ax%h)INN1E$Xaj0;!bGiG7 zy>~1d2mtZp4)-CwyO`Q)Jv7}emFQx&Ex5+&JnQm|INuRyss6bcV(9AniNnI2D=q8tWztznyYGQ@Bc3R&Z?`x^ao z^`rjmrWXk4?-l*SX#%7XTRw*nf{35#H^q+#cO|ld(7L+01FJGGa@7C9O6TKFc043c z=jYqE9D=2Sdg?(bJ+8{z!qvW4J>~aA@LQ+T2%U->r$JvC(g`fNJ1?smZKdQJ7Z)ln zp|(_316-c%Eska`5Ok7kTQ|t`J`vJ;Hs&g>-3-s%PvBKDR?r-rd}~An(+d0nHV&mA z7fze+B|H@6r}vh1jO3=oH~n_zqPMNkURQRay8@rQCK^Nugo-*j_X$Q;YgPOnR4T>7 z@@J(7SEfo_78GgTWU8$RrZw`eIGYv7@;$}S!{sy4$|bQqLhH)TrlQb*80C(BPO?(GZH)e6>KJK443)PxipLVdC`}dm z$v@FwC@xJeUs7>@F!+^jU-NF+xFgIk!4ZjK370=%=rm2&Zv9eU$PTd@mfayL+eewr zN>iQ4k43%{(vTd5+R|k03cW7+D2*d?(W#&{iyL>K;X<2*JERz+-n)h`Ro=j-%#jgB zFN35o&!TZJ+@^>%jzr3+5?lnx7739tGdDU;_-0dP^_Rdf)|nq3kUWCo^z8kd|Ei@s z>reOCtBi#XUloaWQ=)WNPiljrJ!-U6GLDuv{}Z&GUnZ6-aa-~TSudc>vB=x()r z`v9Fa;#sKQk`X=xpHeVewHmc zt2w0Y#EXxoGh}*P?au>Kw_EcyT_j5cI(2Nw8y_nzS9`XE_)sd4K91p&iUu5o^>Nb+ z*`95y^~cWt7+c}FYe-vR^cVzJSM`7P@~HBllXI(1NwHmey6`yvOwJ$jjG=&vq?ClT z`7^X7K8NsAXC9XVHbR7TwC$41{n&|}h9}gE-ywD}AU?kLa>&njI~XQk9*0Y`P`(G?NxpyX`Wxxo=0R zX3(ihEuOYMZ&jscR2IDDBrK&iObqI!6WEh%S}_M zJjaH;eq_pvs4y^Q?k4ls?PKz2g?BJ2Z{EF8FYp*HbHXn7xoX?V{_dGFS7W3yA^=8{ zqXWAa<HIdhh<;KT1vmNw-ujp-ly(*^fS-3`~+=cNbcU*en+{zqM#k^XL55 z2P`{ME;XHeCfaLUSTDmTEr0|>m%oHsz6}BE(J}td(7$E3e|7G9u8PIS?D|i(XfNn@ zn>@kxl3P^et_||*?JfxrN18SK?Vq{r+CDD{*em=Un8Y74Anr2wU4`(qZr3rI(Dm)GzUSPoc}sa|KHhIS zxA?S1zik#qNqpO!Se&Ov_f9PLN+6SzIkl)O8qSGP>+8KV33}=S`@B)c?s2VvaW#rt zJlIbUb;7isy=F*J(mzNC@zaPfpu1A0PNqZ@mb>w*-lH~eK-sYh2qEQFL%&wC+fbR1 z@$-u)mHS$y-L+r$q3jIxnSoA=$=5xZ={BxjA4bw`=~aatwEcRq&HenHPy@LJcG))C zO(vkME6sGuR*}I1Ms=~ZI?!45ek8<#<8sqO6&d0=6e*CQI=3So4ny76PQmf_&=Ls$ zh)&FXoDZW3G|WN?GK^DGlwhI{2)wDQwSledialpS-*(Sli@+pw5&?4J5_QrZp{(0G zT*%lfqE8p}^=b)%J6RuS^%|OZBIOL#z5xH?l$|j)43Kv1q7c{<`b&?i*Xs|y-tls;@Svm1qj36G;eTYTb6@(`M`A6gct2CDO zLsCb?EpNvG`3K|xTB38S7ho@{cQ#eyW#q)mFoL;Vd^4*TI!Q3gJqsoHi+|JlzQGfJ zJohsX_ZaX6Mj-ERo5mEm8=d|=lVO5$KnVx8Td8AYqhaJO7R-kI%; z37s`AmIJRbUkSd~uaXZXtzUaa$ik0O?(A!Qc>KpMp1H7k0t5r+PK^6n7hG7KvmFqY z%c-yH#+dNW0H>Ye%j_EGhpflm^R6>PNxvxV&1$a~1w@u$h@?RJ7#G{YG>m#w|0rrA zOmG4y0ecP^VlqC@xcb^zLIMo~1>V8a@;@H~h}P#^j=rj{PfeP4+@jOATI8<%*;XnV0Dv^NcF>Q zGr@JW)R{YjSkK?s*5!_Tf@AJEY4Og_jVOLWRtAD;<9qhVPoRYK5qc(bpG%?CQD#(k zpTAdqM$A75ck5Y3V4bunHdb}ob~m)07p9p={J-)X;ZKVlPxlL6Xd8>bw#Iff8%KbY zegm`e=|#gc@6#l7_xs|;41{{nt(GK)4EvV^z3#mEN08K~w7dSMD#gRV# z@8u(v*_MIB%zWD~iO4;hre=bs*~7~{L%9?Gsjq)PrA2Aa6P||I6RT7C)-UI<8E+jk zyDd!Rfp>EG0g*tP?vyV9mYrN@thLqO)wW7wuV1*xn5cG1!#~L03sW+fx6aYF?3^oY zw~p=%uSF>8L3u-v7BpwUxpNA&ida({2X7Z!N4okY^z)*qtkRq6xmq0Cw}e7pwjE<6 z9Ti#>GdX$hvI1>V*tlDv;9Qx7U4FAdKFQu#%c1HuBGwV1)s>I${?k13Y%d9)eupD- zx>Q>|U5kU74bX104a2F00B}$ynm#Avcd?VzQ6Zf*yzc>g)X##W;ShR3H~`yD!Y84x z9OB5(rlU(}HgyHT!p0|id1izUtY0uyx)K6-fU8%#uyUi#cB`)bL z@%1Uwi=PKx%zw5m(ZmGO%O0Ok65IJqG6!EN!XI^K` z24%K2a;)qj10pqagi}bT?SSRb7-r7I#Ik7tR(<}M2STgtZ#?m$o18+60wnLxhoQKe zUwBN0Yff|}T88UVq7Yps1aJfw@waMNbt?(~WCV1`YMyj9X#Ze>Fp{}<5TmO-b!Yqk z6|es}9wgy+553O`N^4Zkw;DZQCOnV1o!k@mk(5K>grQFSN0R(6@8^H==RZV5QM#2} zPLe@_*ANe-?I`A()rMJ$2+pQ)F)UQcP-Zn#;&MwQsFq;-$TxrXHmbVgB`(}8J@rHi zcR>=BP?8J(bg9sDvcne+jt0id6a{m=a~Uqe4Brcp6NkzBfyNCJWcrTRWH$JMDB~g| z4cFlum9LE#C2lO^K;R@vL$-9?4}Xi&vxkJIuQ-8OBl~&a^@@%{-TV`^1e(WjMAu_z zX#CEI>5~bDHu8#LL7TcV0S$AiJgU$v;U%?P4|97MbGU{AstXWZ2+Ij|CTz*5>$Q$G zKfWnc4CMc$*b=X0+l3#e5{Mqhk;UDsQ{Vh=JW74Q&~8YQ{4T;VMKfczC5sSRq34B- z%YQO`_{zg=lk!lO)2EyLZ$Rc>j#FBa4SzP#!*Z;yUD2LyQSak{b0^-`G>E!2eMY3v zJ{({5>Bu=tsGnW_*h;1b@cV_Gw}&LLtn-io9ymwh2}aK^<{6r4mPx~j_2P0j8YWZe zpFgS#x;%aI5IKd$x+7l(j0arK=v(^|vjAM9Yhc_sMyM?#M`Me2?)`k+I)MvrU3|c; zQN-qP3954USd8Oyx%O&loL zgDT(3w%tE0S4(Sq-Bmiimfm*+`DS8??`{tLEP@&pcN4|w2g)=|s3sU$rvmwp^@AF2 zetfqCMAQ8weHku=&q?)~dU?P52LGDy=L2C&n0;80BC%Rw!_2;V4^fbsqJPtF!%gbv zH=@mHwWPySGw)?P|9HiL2c$>>6K`-aLo!{rHcYrN4{7D$ep={IzL8em4OmCXT{92-sFwkA-gwvOV^v}YHLF{B1VZS- zM3=%s6%7YCR5S2?AgxC)+JBVz!yPzu>0!O^JVQFrKH)u5XnPFS=npZoqXLDIRgB;M zVX6kMCBVJ?h&q=}}7W4;9cWuDLMwX4`W7Ma8vyT5-5%1G_R8b~?*^z2+=@ zzRM`)Ecf-zRiLqMfh73_Ca=yyO$rZu@A z5I$;o?|x9>D%bwn`f54)A?hL``FT8`Dg8>LgPy{BF@xEz-Tk?{%W!+5>rv zVo;lnQ2=?vQkr>OUg@%!w1hXcKmAq%`i0H!H?LL{u$VpJ0B2X&S2ENUi>Af08^|H7pQJijl2j0~GWSOt99@ z^uWkhTW_1IvU1Snr=FdTJ8l}tDQHXv71BTKX*Ofn%6^};#~*y|g6kUT6lq)G{|g*8 BgHr$i diff --git a/localization/ekf_localizer/media/ekf_autoware_res.png b/localization/ekf_localizer/media/ekf_autoware_res.png deleted file mode 100644 index c771e3620b1610a08b0a064a51bc762f7152347b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 69064 zcmeFZWmH%1^Dazxw;(N`ba$hGfFRP1AOh0ejnX9z0wSf--6bjAUDDm1&;7yg@Bj1b zb6%Vm=hazfE!Xn1Znt~id+wQQX0DmpK`-T{&{2p{prD}8pG!Y|1qB6{4h02^i39^y zeDM_Zp`a+Bo<9{+c81=bMb#crxfQux>g??K+Ntt7C7p7HHcOciixpop%bsgmUr|@3Qx}*5Zky#_WZ`2~(xT225MmGwnJ&`sCJi{Xp$!#7#a2 zXGGzo5oy(|X}`F8>YR_i9`U6?{XQXO^n_|m}#(oTnYKPOYKe6?=eS{3iqG?|IY;mg6;@^-J&W2%0TeUCEgk5 zubTuO>_7PZ@c;RT1!0)LgPAp*#pi$BgrdF0_<#2L`*QCqB#L&sG^ZdspMSp$WW#^H z8szf-x8Z-J_kWLsoqfCs)r$?DJ%5gz=EwP$IiVHZTU<`sQyXdT7JKaIs3E4TVUw$8^ls#Cs~jPB^ei zcMSvx4Js`1(l%Jw!Xypr#p)A7ij(TUh15{~%YcxM^Pvpt8cy10|5DxKY_L8z@@)1W zOZ$(qU#dc}>CU?@S^l-|ssz@pHosW@=fZ#P=fU7jRA^Oi!}HgA{S&ax(~I$E~pSNfNj5IzF2`W#mbsQx97Q+TYU$+KpSzm{R2 zLmeF;3{8t`{dsN!OEAgY7W_7gaJk&v+>T4_Vg8XXlDTPUY2{P+W3gVTsGMB&750nV zePXF|Ia&?Er7JPpdBkloWq*5paW?0sK*e^(fscpx#@IL~D{GJ>h1W)$DhllZ`y)V__16dA9X-3l$Z0 zuXeA&bU1s^RWgkD8SeY{@6TrJFe#U>_8QZKJuaup&2kjd8eERvHWbNZ+3xRx3tU`W zYMu5xPbZC$DMv>~+uGW;CE3{6hI16GtgJ*FHb=H6OViwTtJl)JJV(E)l!@Bf9)3V4 zFW+r(TL;lygu*j z?DX~Zt=+8&F{1ia1^ib>{!5%cwB!b~Sf|#Jl;1uu8@#)0fD(@Q z>GmWpIe9;#vwvhu0Os9M+TA1n8K-%VIJUVYE;BjW=zL?BilQ%|c=3EqyAFr483n%m0WmEK&s?0@Q z6Y4s@-kvCy$r@7qwYj-jS6A1Y%ri~z?S2I_LEhhh*(d&AH4<%Ffs2!TznmAGH$kLU z%vNv)BX~K%*~36jui4;UO^pQanJl}C-A=9Hrnbp;a_)7}Ka>9cnBdz3A7J5)O&Zi#M1b@mD z%ezSwM>Lcta*kjM<c5xuDUd1JNu;e%E#Ch-tkKtlVoUWP|Mb@~ zYa|@j5_)Fk`-(pW4n$PM;$4rseYL>&C;rc9>kntYpp*ZkkNJRvq}FChQoJ+!MKTU9 zZjOA44AQsn-!DDZ#sNh15zYa?YYoDkEO*3#K&030wcB1jT~xwVA_@vhNoncu(9n9A z{3l+@DCrMq4{(TyYpj3$`1M-{}ak5 za9JPFZs&bW)U#gk zStHs-flGk4&el4KTy2;7M*`(tTr_aZ06?%YoKsm@na1z%4j6DhK&zvEk;ZqU^qLfW zd@d~?&^h->INqXpb;!muGij78PZS$2bwu1PM=L-qnrIIwt7e(WAVXo@VUEbnbNW~^ zVRz^G29LWFy}M^frk0kT2W^B>5o9Ux@f|SI0_dwG3%;hU&dlep1|I$Oiem)2-FnhU zQIBKhzCWs_9o02O>;ovfTO~d!E1UjHCoF6EFQp_3Fmtb@b0N+m$W= zYfM@dp{tA=*IzaouUA-tf`X#y6#9C4-msBTw#xfma93#(v!&+NW0xWRSM8hp;6lsa z?>M|SAg{_YC#-LM^VNKqoWPBbvXy~Cl9;H4+1%2yAU8K7U~X;>h&5wladB}pS8Z>u z-VM0by!~pswZp?hBuZ)k+9IBU-8n&|0*=~^o;OWCu)gl%(sFV=i5$kd9w(zfQ|AsD zyB~;ny1#kzMog?($7!~W-Gb)JmoLC^mb+gZiriiFS9D>C2L}g#&&`cz)G#RT(Xy(4 zc7@DE+`CoS*eCuHk;J^b&$H)g=y=3=71w{w#XASJY#hJDyO$3&I(;aJc$xS|hjXpt z4!`|6mPOM{wcUobjCg0NklW(Y(gjommhJieF9<^TM_%pL_OrKZmA(!8`KIKAk)`q4 zR$Kew7EYOpT)rwHA>lO2&+}Yv%Nggr`mr~5VEX>sHmwi z;GyKU@b-V=JDPQx7rI=}zzKT9&3(Gi?3Y&DxL>5*9@9CZYP~mw=6@f7 zPw=QcjD*K(t`3-Nd+W>?lvr`DT4BkBkFV18YZaBz)17HEGcy5xejFT}+x-9$b8w^m zUoGZTN+^t|a9$6Z_>a(e zp&DkWX}VpGABj@&v6oA0+R#f-%^B4M_P;s+1@{!mIrpQ7 z@$yAq=aE$X$wadisWoUPnyB&7sUhVv061rOkn%02*m zsXu5ZkqUqKfX$#aC(YA!Ij8XAXl-x4F|9G=2H}WC=TR6@|1({k#h~N)AA;Or{T2G=eEU-=srcB~6Dtyg z*4g{yfeh<~LzJYr+;)gJQEMwoAX7wt!ech;phYTwQ8a^7curz;&$TiI&X;|T7xchf ziw!$2&us=G#yb|ONdG(|3Me04NLmw8^_BR)I0P{XQF2s@_ANu}8H~TySx~_GGi_z` zKLv;+`Z)rm4<~HAmWY3?6T)jdVIC{x$m>*DQ!+C%v$96Q*xTE?pZ^M&cRvbKrcVJ` z!N@ly)7$ym)5`F03^LQPJdIc1V)`ll6Xddi6S~`P!6YRm1pz7kr#8wzw~r9)eGuI6 zL`_zUB(lWvGbhQ;HVHIg*ugt9v*F?4jRt?tb`Ih&2DO6i_4NcUGgULQExI)K9|m>c zu9fBGiiKTWT|kfT4&xikmfbe8;v3EvQOh-Nz>$%#rDkE;{*jU*__ZZ%c5aeZ+F5Q%J-zwYyA3IPEDCZ;f~5|D=A(#cCd`ba79!T-Yt zX6-6gdir22cH_Q>-P0BmMLsvdmM#Q*9<&Qz*yezSq`Gc?J3h8YH~`LEuhCP8gJals z_!1y>D!vv#PY@j-V3PINsxM-CowoqIi69fI0m)HZ5Zu3H5(#9I3h(TXWf+!<^{U=2 zpPgEk|JBNjA07b#FuI+&`m0IfG_G+~9UX0LxmzrcTtj^;6+5QS}IGi>J_hteJ`g()Cf@&Kuce zbKg%;Nl8i1bt4Oyt|o0XGIQfvs@vP11TiERpf1L}NnEdg_-AHjPL>)E8|dolf-G@6 zvJv21T8fC*?cH_%-N@)@{ZXI5e5gk`gn?3}9XdWRPy`Yoo_Y6ZFYoa1aDXc-%gfud zwQBjQ@i8%Zn&s~XzdUn)Al@lO?qR0OGKA`HN>E1WdYh6Y|iQd@33m z87i ziL9n8EP(68KtW+A4$G^ijSli;6h2>o{if`Cxcn2G#ib7-*~{F~JT%JXr3jH!5ijAi zrKdG{c|Ae7g8Mko4Tva#9&ZB0ot!?F|@; z&F8vV8Xpo8RvNUSbSt@sYvuz~$ga0=Zx}rWPHKO`Fk(;%Y==8h4#AI-mUa~!BuIFY z1YK;El}Fk_2y?%GmywkvcU?~h=Ecd$=?>gTadEM(E;HeGb&vKJDSE03*y7tx6q7aI zlP?P3)n2`_1@8gagoi?|G3^e30XRK4P|O|033{_TQ*B?j0>bqGOmffN8NS;b=V1&ZjQj-r`C@stx16RCx7X(`s5xC_v$WcqT|~Onf@6CqnY>=2|dHlr9FxmxPgioJN<#m5=ttd`c3&T_GsgOQqH5q@XWiDLa%!8 zpn0Iaz?ULXUcc;bZEdBN3RhNDZ8#az^6~M3XjMo^h||v0igfv7LzSj-gF4{8%F-n> zY(QiH!kkoI8!DaD6TnS;;;~BAX72Cq<{&}?BoB*QW?WpHg2;_M2+|lqZqbZLURGWX ze607|B)M#W^~8^dd_Jqcf4?UFhx^eNMUs~KzT0(~{zS?wZ&21x`7lsDM{NX8aF5h! zrr4k@7(`j}39Mq)!C0@9m1B~U{z-MaOHb|45MU|&3nJ4}Qf@%(S9}Pvw&^m{Xz_F+ zj<<5w*86|~GJE%~2od(khUyoPbPA&L^+88}nn+qg0;X)OAGzqTDB^OFoBxhz#;mTMgvtTMZ;-X#b8lyw$;;4BB3j{k6OW0uj4e zC%-tcKSFr$6ASRY3VB3bf6#G|SF_duw<)-?9AN+Jr42yf5`-_|^4D?!xJ|#qJh~>r zzXKZ4JU~Ab8$8DR_i~d1xJ~tLtyuRTF$3ghAfS`!RMA%cl4w-{xXri+kI94o3hJJ> zCYU(4g*HfuF|2uyzeW;ZAR8=k7p78CIA<%Jq>8||~%&qjYqxfMtam*K%JI60~$j;gJ*0#*Qt<8cd&Nc zZ_)H0#g~WJB@RaXy;+JjB9+AusMoWQ)R>+yvj1ZQsnp)ZNvTH#2bqvZ%!oCq8)h~3 zsb>@p@0xTCc2OIE4d_zG64h*Au#ois&Uxhly=NDUPWbz_X{ZAZs+(m3=ChN6mKLyD4WO_H2_Hj;ZT6Zzq{Ayx$d`#y7ya7KX$&GNB6A1?=m5$P;?KOJS( zyj7I0*np3(l@9(Z!@iYPnm0uw3o{CoU7P7t+1>$5Mg@qOanPV8|N+m&1GRbKNZWQ8fow!D6D%fy9x z`5&{`1{IW2KR>14`>BPAyP`TCT9Bh7^J{l|7pl9W@}RmnX=|X z+_`mQ>UZ3e`&)R|LNtGzCu9xMC9tpwbHl|u%ty$b$>Ds`m;Eqb-%nW6SSdWNkJ5gZ zprW9Q$x3>{&KK*;X*^T4$fKKdRxO&Sf4mBXKiWCb9>|IbnY9B$LQv7rGOfxoGL}G$ zbq!de%vT#_AiD(2^U>XDWut?={l1mQKUuTb??~!WR1}N)C$)iJ+9aR%+Y+E%>R|_= zT&p`%TV(>SMLe(6=4D_7?L>4vwm?DXo!8{hSFFpVfyQw}a9iT%rj!T?-2f zSJ%rd+4woE?lMjW zYC0Zfl8*3RggPEuB@)K*r2M(3@ofQDMg(feM$RGLgDf7JN)efN0jNiVM zd4v=992XR%1iLlSdOxyMFFL4xWzQ)L5~*&_FhKXT(p z*!wu5o{}QLwF9${6L9pTG$>gMV;(Lt)@F#9@IsNCJsG5~oYx#<>tWTGaYHaJPxFAh z0QV4;G<>JnEamjh>j7!>bEL^eeMZXV+(Stn4_QkW>fEr?bE7wE1AK1abb&Aj+dACu z1+kzA1IyKJW@0h{>Ym9~4L=+6|MzoT*RO*nd8@-c|4MRQj-1#rUFLR0Xj@x}#my;# zpBLz5_j02nzujq6)EjMZItlxbEF}N&wcn!?e@5l6ZXu{As?EUk<%xJIhb>Ass@F-BIT_(_xwj%ySWx*D1H^fKz;Iz4^ zHBUd%kF@df(thji{54-8t0RSG-?1UAWE`Y;9<;>8B_bfk8a6UAx~3eefP?#95loqeEE=lFo8X<`_cBjCEl6WWm*c)(VS*8dCu61ZQ9GKR z=+l!2+|mTh4+wJO=8f1N2xsy)(u=snBh z4f;7f#Z+7P+j#@Voe?Q7h?xK%eC;Wumu}nhiuUcKv*s&nsqR$Ch6L7p)#&HN%j3C8 zwq@o4^(5#jJ6^MlH;3LUUl>=*RZioIZuy&Wk}B`KdfXYxlgcm-vQiw}@5oZpJ9x57 zzTF&sZ;-Hm=B_qn^Dh#?3L-#cMKL7XMX zV)MFWl<107x}sq7?X7p{fsBlde5xRyao?v5sfeMf-Q$g6VPWBS<(gDcJt+e51#x^f zi><#}0@4JW!o5;xXlMXcUHZ0nllCDq#IY~T!BqNYO$WTxL=TYrAVa(`_&E24*ZC%) zRC0r0S72QWB4(Pwtw{LKmlsPx$;AW$vbeMoG_~JWo`_)xlsWwDjUy^ie=hu*UHS5p zyosO{87X}fgNC3fyK=<_rW<^#G_0YCOK!icLb29##7z%F;iF8VLVM=ckGVAdMc-UG zhqkmOSJ394#K#e>b|N6#pQcPH$alOMx^OlPdR@JO&Ul*fqPMev*Sd~gc*e@LYH#Rk zsd=4Q~$59apR^JJ}n~+ip~6 zUK4j$|E>Dds`LkRVzMG zx^2=h=w3FfZb8PafRtYAgP56THf&tnQ2WaUQG@US>4fRl$Ux_gkXsjnHM`!gtks2q zsMR}UN9&ZxvK5i{?|%e!03AYS$%1BMG{9^1EJM)!usYyX`b>jZ>Q<&DeIED5 zP{h+ij{7ufo{3!GWc7Acr#-U5Qp~E==>S{YwwnY4Pi?S3ocm$SZbgTYKVbjkt z@>i@}QH0d~b#|wR8Mow@Lfo18bs6O|Z{9Vq)zqJ=^}4)Kn_E#@^+_oydMTFBdx>eP z;_F1mE8D%V<1Tw6v5xhk*%PhiQdLJH1o!B8eMCUQ)Kk{fXJKO^-6boL!PPPFH+g-W z*z~!*U5kO`Y*Girj-WWAZr2u7nK8U^t`Q!tz4*(Bg7y>^s+bI~bm~`2P3FVuL2zb6 z-bBRd8jf8DxWy)CI(p#)rCjAbs-BiE5ev(D0X!S+5| zpru&fPggL`V=~AMEn3SO41CHq#X!+MVryoE*Ss#%u-5DRtWZJLK#0%Wnl`tz5|>dQ z7w)aEyB(pb1nMlqr`}h&=I=zTXX-LwXFZsyuTUs`%tdU#4uxkFc36&7X~-?=u2j#* zP2{{D_h`M=)%Jhy($>P$9&un%$h66-i~_@VB;7YHaDzlis0AxwRE}r7UnJ%ifKEmr z)ONfSmYcRQMbDg6izOgcPb}}y`GY1HdG$`IavZ;6Tw^V>KClcmD%=mh&b}d@1>oSF zZ!wyWu+@*bk2GfiMb`1NAM&H0J2?D35Q#id1by!-5@$kLdqnKSz}t>V#Is85Vms3aXwx&$;k%=e==QTK2@09bT3UR%(X(F{@72SsiJnms)b4Rs<3*zvo)q%EGMQWJq?E4D&1_|gh@!wu9F z1PH1ETkA=2_Eu1ycvR$X?OnF`cQB@kC1gQv4Kjj_^TQxjSZ+_E^c#6T*Wto0lJj1K z8gn}VK=qEf{g%e9cw8L9H@T>w zhK2?m=FdYh8C+xQSz`1+1Qy@(jWQ~%zBFFD(u?p8kCB;R zAlTXy6EXGh$4ppS**{7*;@DmrD2{heENf-uo|jXb@3JiOYF3Y9Ss(lot8HRJ#7(bR% zAbk*)Et6Ne3y!`@AScC#f}JN-ER@S1VR37Ug3dW9L!ph#d zy>&L9;FflBlwO-6D`~i@TY9>RnwJ?K4Y`@dT)d=5+y$f54vW&&&yibO0`DC?R!7qq z7d>9$*y1O~e7RH?71-j79p~R~mSbaMF+&?Q<~}{xl{&gWiXP(@nu#wA+vT&Y?&oEa zyX%z#WJx#o{(Fn8Nl8?uEO>`0(p4jRv*UJc52XTC;!J}Oi}ekarHC{1&|};!$?H1!bl%5j<&Gy+xMIjRg+OeNT+_K8!_n;> z#w9vp-1E*Nu}#H&n~;20s*-A<7H(sQp1U16sUzu^{txG8^RG0mxy}mnaAS8wJKK9@ z{FME%h_4a_j^7q3q)@{YC*W@^$eHK85ymVpFhC1z)a@pBrw2kGrCJ>ywhEX zJ34lK+0&3S{po$egc@?O57ijUjdS3E<&`r%=J5Fq7xohkAlfn8h`%d*~D@a4(1@ie`HLg6C;n#e% zL#KAt%_u>unUn7>wQG_i7vbKX*Y2s~_-M*hB|e9d&Eb-uY%6boHj5Lhp?!a+=4^KAp} zI?FkaC}iakN>(L((5|ed!wFuqII+FX3t>h)3tg*Jw`?<$bZQd#;#Qi%rn3Nf0o%2u zcOr=sZSv=-JXg@k`H??W8zzjGyU$LI^LVCurmQCM+vPQACr}fB%^fzF>tVv)rk#Twvx^MaZn&mzO2X!rex!FC=_xaTky!b#8Arugu{nD3{Bz zBX&+bdS*UestRzdoU#zfp2d{nb~1&bYC{h@Usg{@a4STl*{OpHc}zy^JrQB&UawkQDS2P1umtlZ{b72{Wayx@VG2!9R6Nn6 zuGLwYK(MaOZ^S;^p0rwY=>BUr)8Ql^*-d_cSn}4|;PMvVVTZ?Qy(;3LrU##~m_ZTZ7?qM1AxS?=$W`BkJ^g?#ulPwlg9I5JIx~=HvM>o6D#? zCcJ%n5uC9E;#!(;g4T7wk#%bc#8X2EO-`%ICMnl;?IXOW0ONI}Myiu+ z?n$|R&~UPrxJRl0QkdgXZ+$sh%GS-Ve9fCreCPX8+z_U)rKDyCxx_K>^l1GK*h6wBY#C3@9IqM4HwH(ICiuSq zzZQ7>F#hRtNC@_y8Jhu2nCk>NPf^<0hELok&NIzq$eZUKOC4`Y5*;$8%~W~TZh(U1 zE%Th+oF+eSlqFue(yU5LDQDP-gWaZobg4^WuAtcV{pYnu>;sLyFsozLM7N`=*PqNn z9p2lct^HV#aSeH?vGZf$+JbNuur&{Pb)Ur>{@RBJ*(G!R++fI(# z5x|H1(Dh86)~SNtdd$`HA1k*Eq~B^7wh(LhX|%N3HdGJ2ls+5s)~oykxsFIEhq7v| zR_UJpNleB`l2Jh4+c#?N#rBy~3czOT?T(3ZtSns8UBY_(@s{v!fY>*}u{np9&JfD# zQ26fCIZ-6B(0~YNNDQZow?H>r%+#$xTU(4dZq#v?+KUn>v!CK1yUSyBL2sfy8%`t zQT-;={pj6CwlrFmk-KK&+5KM>CQ1$2FW{B!Px9?`oZ=+cmKU^hjz>IP3k4)~xmqzYSsxwP-Eu!p znhTwF(n_pYoqC)u)Sn%n+cF*#Fb|A>=DKTlw z=qn~F%5-ur9Wmb*b$W;`{@tn2!4;l3CpiEWQW&c81=RgNZG^1e@aNEpbM!|t zG!~aFjGJ3oh`4B-J$a4!d(6T!Je74(b4du!*Y>ni-M^wEeVfhej~xYbrUaxSOgUz! zY<#dv#BK(GRROOSN6KDU|GW`S*NiCRd1waSAx;B9xA0Fc(tv!sGX zw{-_-VCvKG%`@HUG9Mqun70(~%GKc7e*ozG<~rlYVe?{(M^3=i;A>kz_LxuCfT+45 z9#(0OaU*i6%)65Q;^UhyQwom7T&&8f)9wZyCOVX1$Kl-XCJJ2Pxf%yXbI#6{g$Oo^ zU0kpIh|DYN9#oy%nt=d-NZg6YJ21>X{buWlmLT;!|9C)_>4C7QWQ5 zFqEaCth_~QmOqjHK}WfAxb-bg<)Za$qW~ukT@(X?1)iX0G|sYJ^#qQBbsz4WS-?)A zO##><3XQ<1A1u46cjflL10Osc%3)j4Yy1dks zzA>7b9c_h&{yR^;t8*n5J}1Ktfj4x)$^?4U51z5cw@0i1>QcNcO)PmosQ9@VqgUf{la`+%+KXPoR9H(m)p7o{j@TUHhA=MH_ID|yAkxEUN}h?8 zo2$Yb*Jp|mWitG)9Mr}zU+`&y3gT^TRvGAD3-K6o^CygjlsROf*yfsC^-P%HC zf!V^{1uIMDMJK|E6aX5)=m4KblY$Z650uaEfGOJL%^n9QH#c^^~$pa)Xrz3)MPYle5CY}Z?xB~p3>j@3TeUgd-J zoVmg*(tYX6`URx7;`hYCXD_((1H+U?kGC2K&a>tZ8nJx~8n{ZUWCm;Wc?5u(;87%DSO-W>Y6yTI8^jQ*ev5uJI;<5t)BDZIHw;VNZ@sAJoUOrp+}5${ zoi9cop1GMP6aVvcRV}6nIi#vUDDsA&Pe%)x|WJM`RmO%%R`4_%*_b74_(>U@69(aHOgVMDcu0CommiW|hrK-w-D$Vf83^Jt<*M|HK zT{n}}8yE~r|E8{Cf1n_o(ks!CIFTjtFVO<9h#te(Kc^&K9Sr)0_%nvi_=Z070x9`? zN=eqzpmkOBLiuwFz)wtoXs9WKpcYzD1^p~%Z z1?<omNa*i z!W;))16C23yQsUF2?vPB>Yy5nP#`lJZ`GF_2}X+jhk1%-w&izNGLCjlQhfC+c4mw-DB=K6*lS#4n=mRr9y-h8J<5Xzdl{LX&$lMzNe8HElXxb6+Pp2}@JRy5n47 zF@J(vDNT!hghbg+EYwKLG!F&AQ>3aesLO+yRh30CfZ)?`a9(>n59pH>@{G0SW>rTf zVJnJ)rxY3haC^>?=CT{BWKQX|W7Nv2&k{l_?bX;z`1m{)9e?=h>Zb!b6JjunF@YM$ zWA*q2zOgUv9JjKLDXrzpaF5|v=m_>Sc%>wN55P`_J&^F_28PfFY5M3xR|6df%uG!R zHGsNIM2k1UOnsUjgV0)Zc=oLRe|iDx$TZZSL1B~c)_OJb0>0TVdG;V4HGA%N5&Q}1 zx5aLN7*05!CE`bK*~`OuJ^@wK&bp;eXoK_DE z)sEx!6f6MDm%rA7%MSJrKmzsxMnKyl4ze;*?7B%>DwdBz@HO}czPSSIC)hxC-D6^j z3g^UhD;VDWOwC=)P(y^j`OCaN&P_w zZq4Nwh|-a|*7AaTG`OCdn@DBU0(c2liPrEA_~rzo_0TmOsDWNvJMZn4G-M96$^|Xw zcZ#G43R@PJd1e==BqC{3+5NU}DpD2Pg8?gxH58L;(KT3t5(NRM1$mhD4!fMnAY;&@ z(F4<7BM$8kYDXBQB-*Q@R5yObgihe<2DZm!Haw$iHL!p)|G?{pu@qvBU9V+c6!0ULB4=Rx5> z(yJL!AQFQMc{)U z99#laW4`$Ah2&*QLX?gTm;?r(u;GXb;(E^049b~{h56mFZ9^{qu6H6yMLP>CPo|j# zZSO-_Sp^+)bijAfz8w`jIO1yD&|di}Uz>4h90iiLHR4pyJcLJ(ek3$)U>>k%v*{~X z`}WY>GSOma5dx3VITgk?ZsV&Ft*nqq!hX`*Qx#;46U!Wd*0C(NBtvW3qo*)16>t+3 zC}1m~sbc+%dP_5Bt7LyZ9e&)aco@&?b5*dUeOljzr*dx^0Rnl-q82Usr-wt=JmMf5 zZ2HYy<>Xq;zEUU%ciuizn+J_)BF-BTci2UrFqX=uR7`TC?i<4vl7N%dKC1t$0{jFa zjQwWH=K=lquOgSufAyXa@t>7%eM9fvm}NS9*0dnkF^?)E?k(@ttHBqfcMuq{J91kB z$g!#B+l6{`b2FLf*NVx)3}xno8)*ATl<6f?@0%~wBnvv3tiV*dC#(79az*K2zOmQn zC$(jvQ&{$$rUUw^_ehSvyJCR<@b>gD5rh+b=It;!c;UcgB(PE7WS@fneITV=#hfYc zV;oW3?aKr^;6!p+d54vRGo1T$3BW)z7zsxDpfEfTK5yo;XKKt)vY(t2(DiOUiS61T z_u}eOw0O@eM(AcGtK2_wUeDt$!91@(_-lL`>?kA&T}K6n-2ywsihCd?EB z?+lb}pF=?9K>+r`q*IFq(gfk>EsGL%j9m??3BeS{+dF3ikKw`hv=T8Uc4}~r+F*0;NzJ3Ph12N2kPv3H_ zR*cV!w0OsDq@3zO4m}2XhQ1fs(q@Rlz|0crZ&?gIcg0Zcv`U?;mT*;-oh&%5`2k`c z;4{9Gm-4@zH*ucVen496@{=KOZ>~d=5raR22mmNQMETZqKGT565+52c<`nUk?sT2@ z`;km}IOMzWw-G4KGh~`UekrhVPIz+lAo-D{S{D6$1=Dwf`~iLKZS?Wf@v3yhZZ*5} z1Vx*F^9LnTKth$m*a?TtHQiYQwKHIf+im0>0k(Jy8TxJ*X|D%{i49}F(sMd(SeL4) z{*3j+@($)mnyKPpTA->ULAf@c-S3u9gDo*YEq=CwQ_t*(Gd#c`H?MPVQMWi0IT^IW z6s)peqJFJ)s9|W5CQ_lIPazG|hnX4V&TV>FNr=$>IQrBa^|>4*3gn-a_Ucrgm+gh$ z(99v@c`oBO7Rm4ss|#O>F;hElc$al-y^xet&^=gft^aGwyBF^+C0+x(R?n1*xBT%j znfY*W01Zjho6vgpuiizb-SzczFvZt+u}bnyncrfn3=Eo;&=uPS$5Q$)gF#R*-|dHp znJVD43r2A+lpvgl2W=Ap1Q#lMo0Vuv=jzD!+(+jpJ?rkjt3h|(@!RQ6r%@EXJ10l4#(pD=XYMmw>Y#~swXKnqR0kLb($vxtxmd;} zSeoQ(YfOiXNAH12PS5~3IXGAhzM#QnHrA6Wl+5A{bPDA3j9;T6Z3RTcBOqW&tMW_9 zO-v4ueva2go6=X^Uc{!neOT67w0nK|zBy422N`6t-u9XFAQ=XeJGkNnE0tFw-2NZ} zYaGyueKelANvsKn@n8~PFP3LpkF~EF8pe0Z8VPj00CWHwx0ozh`IeI^qo81{aQ;8@ zgGy9UMRG|+K+IqOa-z}ePL`z}Op4iy2S!Bnn-$i7Ad0x4fCg1|kc=e+h&%w}Mu3g1 zrj6zHei3R@Af!63szHpusBHnVBR(E&cxWCh&@l<0nU@Qcfos0Xv21oP3UO)+MXSpZ zR2I3uft(PZu{u#}E}^IrPS&!fIk$sav`Glg|KKBo;3$|RlR--4JF3Vx1&xvHpi>mg z41yUcFhg{>Q)UOgU%|j&W@Qx-9-hs2Ht*&2;ze)eyk|EGq`T+X2Z|)?=PsAvE(Pj+ z7Syx&y@=_edL^t+hq>xIh(-)XmjNA@#1avRKCR?mt^y~+>+em1dfu7?SOa8Aixtw3 zlo3C2JNVcuVGRl-OQD6I1O9Qw ztv*p31<`g62zUEv!Io_feAur-o(_`gW<|@ z(Bx>G>H_)~r_2gLqt&3mH4SN2kFEc)=AEV*>@a))8 zzl0BAY-n3~`4rV1Va1LcnL9rvj!ja$Q}Xpr?jL;)3`?O?)srsd^M;D%%9xHqqIGAwiS;fo?qSKsAx@E9gDCttjF@ z+6e?nF=0cTLgCv+MbPnF!iD+i+!^KcS)^3!cXo_vi_hIDWz?&-77k$uVsayH`*O@n z847w0_SsowP4?H(QFdOrfq@(kV!~$9a>2m_gdelBR6mzaef6MXWi^6UT-r$KYE8v& zxMRsHKHPIa@Q7peYk0XWR%x~YOJRH~w}aG}SCzyF@^^L;({?f!h;?{ltmUDr8h&q~mF;K<_h-Ivh*swvK7 z>i78i@v^mtJZ~_KD08@+p@9LW5h_4!g`w5DGhf^p`W+>1k6#lH=icmpIg|_(cFNe+ z(Q6mcmC50#tFG!&my~{gl+5NquR}HTHzWopNUf(>eQ0fCWog>L$>GebpGW#4o6_1~ zj^cT0k7?{pqc)gZv~cegw9f8Bl9}s>VTo+t+}OB)-3YCt^711h+yA%mki2ifE-5Jq z+?E?N?J#hp&Dwo4rrsMz>pdMz;+VgLK42q*A?CjR!)jpC+usD}Qt-<|uRxJ37#WnM z@W@pcX7L+lh+gobmo%s4-}7*CFbCWL>JXq$aW@5+uX6KoZyZ?`S2@7Qb1&%oW=F7S zM@-rkDkEue5L~RN7EhW)XfHg1#&MVp0qeSC@UZ|`DT`u zI>^hnH@v}5aQ@3CTH444fnOA18OEIH6V&zWoe~QOnwattBvP^J>TigyQN~hzC?M#G z>s!U5kgBW38p@dmrycmKWu^pl0k0{VNr`CDJW6JeAh8!7Rq-`u$6JVPRLM0&3G3Bc2^CzevT(6C*Qc*bx8q`mpn!^ zP5GfD$Mi!3prLh~gFIBgh3ye8}DXP&W*q}x%nJbyow?s7zFkk>}qZ-cPHrV}iayBBM z!Rfjg5FxY~SSVE?o{dgjtPd=Qz&~GHt00u3xIVQAP@v(eNQi)L&thMQx+j>Ku_Ovr z!fhzg;~AV;f#5}A&ig7#A$1H@UZ{S4Kmd=!q$F(F{K)k>%}*FMWkOp@wGvtQ@{y(i zB~8+Yk2;r1m=aD3m%4|yJRYw_GMovK!cd%cmj8m$MV@QPd~7XwqaNipBj2mO?H@|O z8(8P})e#F_@qdtS{!-oyJ)4EjNM~r`8l3DJ%`>vnmw3%j8Tzq^rQp)O?bQ;E?~|)~ z(h3LB)#ML(FJl#|W>J0Jod|9`l{l{E|F24}BM%Bw+qv zR!orGhDS=nf|=vdK~xqSBxwT-F#(}aY$&wJXkz`)f-_M1z*d;&@uis8mEZX@;3@7Y z9FT+)NkxwRQSKqr*t>H6(8(kv&YDm?S@6_#B>Gy0byh1#`IJ?tT#MTcT+!>N6cYBr zrut`xxz8r3c2gsCf`*nh(rDtS(>CR;&MTyzBa_@}CcEkmF814JO);ui-N7c|SW&b%MXTg-5^uszq~oRr*t{xk?}M7xuzo)C>#5PP0_gF< zWvJ5@gXj}k(6p^c%UOl4N0hNpOF-pv%7*NH-1{1X+u^M6d?XWDFqc-}bCr1m8+!Ta zglHI1FG#;GaZY2E;CxaVV(_V%QNW6!PIekA5Z+#?+%IyQU!)l!{|25 z#&{v0m})tg?M*A!vr;*>aZgjvwaj|tj(*W$XZ<&9OmAL{M+5W~i%F5*=5PvRu$qE~ zj?7vWZ*shJ0UaULQcZrC%kcR}sEo6exsQ|bQXkUey2uY*jsbQUqa|~m>u*rWg&Fuy zyHL%M!>d=73DGMN;x+Ef$Kg!Cq^{P;Lyfz=YX;J?(MWdCT@fJ?m*`QqP$6761reUp z7M2^Fz_>VLHEAzuH@sgCRVsb*z`-h$sAOhf)`eqYn*FRn%aarCaLKa|gy_l?Q-c~* zA~uIl--H0;i(K{zn!&~enX0o*mf+RcB`FRZ6KJq%jGtAi!q-N?wQzv(i?7BWGhDw@%9`~{frP?9WgmHiyX%@!$KlHddY1m`C+As&i87b z`)WjHPXq2IEh%}Ll;4)pG*Ac58wW$Igc}j#CbKIo={fj~`Wp;PNZiGOXyu&ncicjH z{KHCUr=FAtf!0a}#HEiw#MCfC%tgbr#7(@~6>(vMe#!=sH60{gu3h++6T9waoV
-1Yz)bkHS z6||^kQ?s^y-HEsnz|4okMz!d#N}eRTTu+gBM!PM^-ugY~{*a16t<>4HyMF_H>p1F+ zy?F>k(1U42BImDs){r_ybPP%g-k-9?T%g{50`v>iocP!#*RNTfd}d$`K0BAk>~u64 zD9vx=EzlVi5p$jIKaVo5BsaX=PPY}2q5};xl=ryCcxx` zw;)pE#R6}bNUE_);8_14RO9o5phrwIS=t}r2x(|bTYF`1V*W&(RzM44uEcaxeh7{T z-T|_cp<(Zq+~rwqI~k z9=pA-t?XB*@$4_s4*i=gS2Cu0J6l#!{(|8R+T(hQVr-O`B_3r844u3cKYj;m2x9tl zr&hQa-%A(k7cfFH07j%17=!wa&bF8%&4Tr%Uq{#XtN}?|Mv_N0l>f(rXm0L6GEqja zlZEW{&5SJC3b=dvtnIf^{h*#t(6h=7P|^5>2|6UhCq`3*lZ>vVV3Q&UIBa&p!Tmp+jfj zE$Y*?P`$J5gYVzH_EbbE2jL$;-z)0#1G=Zve&X`}MB$443O=RqH9U;?z%FJ($IsoXgP`J@C^5ZO(JVGhzPW20yhWoZQTci0Fii`e@H5}Z}aw_6vRIHxPu`kA{1&r*^}V_Mmyx%!KR^?3yP;>l4Picfitgr zVhC13m5@o9dEGMw(Hj&c3x!ff#W87e&_8nIp5nGGSq4uK22+5Fcs8~p5eExikzFum zxp5%4-i-auRGX+9{zc&8)yE$jZ?!_tErf; z8%OI``0O36eMB02GgFBC%39awvL8yLk$Ka; zN1PI5uZ*ec)4dkR{okK_)VEZ7OZ+q?`@+-yA=5`rroCYT9TmljP^k&u} z%6f;IsHv7NT~3n<3xY7-a+{Zi_2On$Gx0c*=lo}LOfmp!=2DK zUU#OhL%dP5d5VGPVXTW#qjL6W+>bu_)X;&uA>A1Caps2FcSeay&i0vwu^f`Qh*e?H zC0TV0h0bTBtSIE3i1>ZMY4&Ty&yC{Scb$(I7q%<~@7u}W)Y9FXMgK9>gaer-5%DS0 zPZ@#vS;e!D&4n<$_cVDiFOYqBS=qBC;a$c`e$`2-?N-#pE?cK^1&-syK-V8G^Rdlq zPhT3_xli!`%BFjPetBWWN;KlJs#0)T*Va)~^}@#C5w>4Y=g^;Y8Nwqp;G$7XI$&!F}CmbY{M ze_jB}g`S^IThbPIW$taQUkA$n(#kK_D@BVCqI{P>@Sf%v|Cn&TAQp|a#Qgk4qwR^! z+QalZ|mB*hXsNDB;q^ZtAa}(9ex!msO zEpG$2?)nMa;gXx3{H12BNVj&iR(*-17>RQaUSR}4$Zs3tEknr<>hybeXs;J9g!5@x zZRor^R(L(9ZEkcZOFqT_Wc=?fv(Os1xtz4z$zBcn%Kfc}75?`emXt|$cfOp>UGUP! zItt!G()S+m^ZjsPI_0m}lMC#UrE1ir0n?6`FW^Rso>IcNcXdw?e02;yP3hz;llGt7 zYh9k;mtM3FmL4}WQ>A(-SlqqM+rAMJ^VN#RIV`flBe`+GR1DuE_5D+!`0h**cin1b7sK~k zEqy1gOdT1)`1%y^I%(i_exAN%K$_29w-9#3hkF8Zqr@D;atm1fPp5)ZBW6;|re0F; zF9lzyz-Kq9Akrs6%|ty z96*G7Iv@ytnMBy3AqE-i2tiPGzg55K*!s7;oOW?PoXhD_ii(MGP8NyD_xtPj^L-go4E8)Ow^QDtc&yNh8;HzP@e$ z^CP8Te25PCR+H0clsVko?L_@DAptQ!;IL*aw&6tj zD0pHy8sZ81tN7#6yDRmK+5f)c^18Ip0Po^jng3J-oT6{^iL^(Y4G!2b=ccjC!FS;e6ojQo5--o>!-szEkX* zE)@7*g)2qY%g?Kru2s~prgTjya+kk9JtDXI=Mjs$E@p{9X*+H{Aa{u6h)egQRoqXW z5I!8UX$`yC8mZbbvG>!!CVEr!_7VL554j=s{k6V6ly} z_|ju{K2**tq$cK0{^lW=fLZK}_9GmjA+MOFolqa;qPX&0*+Q;N-b^t_!C(Y(HZW=!#RJwyxv!!>>BRVD*UFQc;k4!=%RmZ6Ymb6#Yi+PPH z_6gS;c0NNqyqkkI(c(Ym@-Du`r%rNFBs0w`=QEoU=g#RkF8LJOvyg=Gh#AhF@-%09 zombK#_Qt<|65CX0i`X+Gsy^*m>VH6GIAk|ZFju+RL*cuI%OO=|pQyyK@x0Wb?}ozP zfyOY16rFr(zxF#G&1H$YQH>jKX6tRQ7T37rUtEJXoR#-`#rrbq89Zc=WO*L%VISBi zWNKd85?HPj%SOyJJEW+2S}PuK`Qimk)WI!}e(2$UqwYQ#lCMr>SN*4WM3MroTAJzg zXT(?0;~|s62lq$i{Y|}ZBvp&5;3VrLyi$Z`GG;7tvub+{T(qA2<}t$=8L$ya^e7AGq<>K# zdN;H#t$+-venCODPS#&|revJHSdl*NE&s+wL+t z)?kQ9ecx9b?AC`{EA7b=ri^xg;&bSJAdH;Y#*%{tPjU`#Pye!vS;-H*C=-&)*dbrD z_~H|HP#-Gnu)t4eFbQP8T~{jE?bkW3Ji67Cy%L`Fwzd;5uC(!066&|2A$mAp?EWyr zj~}0p=gVFF9x_iWbPvbt6EV?>ZPm`s4h#TJOG#mbfw2?BmE$$mlQl3Z*YDeJ7;zdI z5mBHuV@P3f2Py2j_d-P_blfTd)D9T?`02xkx=H_=nD-ufcJw}TTa)N zpz%>D&d*-;?Tpmf@}V9U9ySl+(gG!|YTw0yu`~(Wj79XGqT11|Hm?Eu-lKlIDs^9` zgB8(xq$&u6TTpu6g1Nal3^;^QCJVaAD#jkxrIfq}u|J43LP1xXJ>*15R31!Fp3e()r=5i%e` z@`Yb#zj(xqOK11pIU}c5QFbe4A69@0$vkmZJ*uJ-r#>HWGj*ki#e(I&Kpv(eVnE?; zh^BmI@$2gHZ5a4hA}5m!9X=JQcIcX&gbS7$Vq!M>Nb=#9HOos;j>0+&Bt5LC5Uk}r z++EeHa?IDwm2lpghmlD~W8bVJqN2=hMwteFGw=%zu01(e+`stXZJjA@9v?1bDnL)_ z0<|i!s$!NV+K8&OuUcd`{Yp_I(SL=f&kOUa4d};(>pS&8K!WUv-<{&*LzJVHJX+Xd zb>-QeSD%VjxG&{Zv%)b$P!NsTih0-P!E|gG`o8vS>6MF`nwpAAAIu&n!~516$^vs! zBe-h*$)IIrLXiSPK6T&m^U%7w_;8Ef0dihR zBiH0=m$&-5QT!c`{;o>(hs6ORDS#c!9c)+k^?$!dg4Nz|qGP<0nr?i;+)TrZDP zzHa-?#xR%UsYDMGTq-*B`frXf-n9Yd@Amff2?rT6*a%(eOedn?;u8>f|Lu24NeLOd zD(tbK!F$ut!u3jsQ@iYi*DW*!1%)DYj=4^qZ9Ec-*o1_xwv{*VaJjTfepKHYFduRW z$ro5lY*|#~_|=f(gMZQIgO?xoHWjbm!{tNbkz3UCcSpN8o#xtb%7nBEHg82~E-y-s z#s>!V$>7ot&XA2nTCa}}IpEy0%oWVPv?$r6gEa7(xao_C%p1*BY$r-?^$?tM@<#i89ArXy$7*=s_r7J;es z?A<3m#npKRRd6y(ii=^@$LjZw41A8TL7@vaE0N;8xzAVu6U4t6+@McMOneF|Yl6o~ zxl|HN{n{+?C!BjB6c2;kQ8Rd9h%AGT*wI=eOhRGj;))k@x>-v_pOT#1n2H@kiv=Im z;{4c|WXit>mnT+N_{A@KsqbYW<2NOkO+-lIYA4zxY9*A{Vsn2Tca-1zD5MjAI7+zp z4!`OL1&N~?Rhg$joOEXvqj=R4E6MR}>^6|a<8MXsCk9|uocik^&eb)BlM@qPvnHerF zu8xk*$_?66)-ZY^0`y4jIe>I_%62Q(p70$^R~qYu&(aB9FV;%D@Uq%h^OuRQ-p*td zZ;l>Y2UPE~mwqg_ zA`oL1EgIU&_k4uUxv^>)w!MuNnh-u`_;~;3&6~GQ_6#eW{(QewI2;=pN#R|3KiHdkSLgR*iL%$}l2Ybm~U&r1jT9Mb~0v}cvSY82P+ zW64NL%;{AZEZLjyYXbY(lXL@BHmH*Te5(B27pXY3W)o?9X%>ge)nI?)UTezcY*6;+ zrdZ7V@Smdj&9B#`=%lcGsHY(v!HSDb4G;0H#$0`);L5#)Z6rO+Q1^gowZrtRl20FF z3RT}MTm0(6afIQkj>K_1z6; zpm%7tUvG)ikLTOdVBw-@fYO-e)Gtu$9N5m=#L!B_`Wy4f??BqLmUT)Bq z6&lFRy$va-B0X`^ZaX;O;GSh%5l`PyeUvS=+%+GCnii z$%OuOHhdc9Wyw(yrS!YKVibIqQj&Ry2Dcy<^_zAV5cRlusj4aanF}ct9-l>>IZ<^p z*+I|>l0L1E6TW7v4w404PN~rO{w)K=!~#}%`cT$KDdjQuOB8qiq&k#Yb$pXpia3_f zX-rAw4khdu)n@Ie-QbeUx};x4*!ZEal?YnRYaVQ#2>n|`k* z|0mi8u?L=>k^sVSx0(~R9@0t96$vS5Dy3i9EZ!vB!QB5WNs*MZ|D{l)UmnTU4viwF zuI*3b$R=+MoiEa9#Dg08Nms}7D_YLlzhkQx6rvrPnu8hw6z_QzpgfS7iZeiO4m$kOi^hRSjI-jR;;oncX6L(RMACuvMM%ebjWt zopO1*cr9ncCOtDfrI^i}f2&sfU{;JaF)xi7$rbA;G{3A(SSJ9o&mf-L*?SKYu7{&5gz^E%lbGs4z)~P5}dM3{`N;r(#jr(Qt z;XtDYo)I({L%5Kj@n1JX)tp%=x!B%iZg^_t7W^B`_}Oh za3rtdgk+F5O5qt5_Cv{eoo#t{P0!(CJ?>IgnFf6*Ur?N49sISrh}c_=ea>?1aWS~IQ*O4c0*%W%?d*o4q1R&l#O8fI zN|w;69BpFx%hWw_;!dg?r+gls|Kw*=q*oq3e4OYFE~0G&$DlC&S~IC7fx%CX@p6gW zUr|b>rkNBynSXu?K#_V|`_em9-3CYREg5UOy#6Xd_qLj;0M>Lq`Se46@z|V(n@btp zsJldk{-@vym5DZ!IhJ~kt%%e^gU(N{JJ72=f$bC--w)HT=BnBteI8m~z-43Jnzww0 zzEF|8NYdzGgcS3`l>3pZ!hKoS+LU>y*&zA&@YFZGvc#!KUcDYCoolZC_LNz(ejACztY- zSm^AkEogQxz-A&qDsXyu_u4PeK)j9Vx@4 zKWMZ*QXgwN+Hhb>U4zeJ3=onHz=J~ZyxxPc^7(Bo>a?%xzd2)S>4;R(BNX-L&2-J+j7lK~vlk9Jj3fBCvuNsC;r36$ z2f7|U<;D~Ph|7Ju=04CoWkyX1IS2QXe*PkMs7fzQIn}U#IolTIb?MTJ*0i;aJ**a{ zPO>DL=G*SQRhJgOOH6}u4ZAL~-t+u>W=Ta1Zj9%ESuG^=d;_^IlTw(s=`q>ua z#K~^nT6sBZ#lLi_(pL4&=4SSjzNh_szQne~fACZH)r^w^?6_^jkxeNO=sr~~Q`$`- zEMGE<^Od3HY8ZVg%ntXk*4bc;T@@UXHiC^914Y&8rvtJNUfu=aGX{($g#jH{D z?nvm6>GCX9a53Z9GY3kXcg|m!pK%*hJ*?H3msG$7j$L8g>VkkH3b@sa*W2Q*y;XDw zvR8dwt1ooE67b#wNS>L_R#s}RB8t&1_7(v$mT9jlGsdkR3foz`Jr^0j`FgxQm5yi; z#ibvUc&;BZ)ES!=c#W0h}dB^%IpMJw3ZI%~x8p<73)GX7g8s1H1{Q zr{1W=|K>7RXTpP^t&Sq7!YNqZ)xk`U@HCGv+qw-R>=V!P&Np!Ruu3*o7Ob5GPW^a&&yaFYPgOU^~a>t zsDCU}9;va>>Cnd29{z?ep)8!d>V|$Cnf1*t=L4<1@V{I%w(eTDbe@r1tVpyaz;&IP zr^Uo%f?@X$N->~80WID3#QQFiO07T(RZpJ&6eowy%!-zcgUQY(?AZO_ac#jz|+y zY|?hq@Mk&C8Tl8$O*7QlUajK&GwL2P+obZHaRMRMw?O`U`&wk9O8X$#oo>_vn1geV z)PvW&*sgdgTJ}rHT@Cm}vy+f^9j)x>YPd4>$C+&s^g!Wx5~5cH&tc$H8axIOLqtK7 zd`fmxjpe%z29Gr#*XqHiDeLqVxDWV=bF}lApo&ZnW}M`&`oW_QU8!_*E6FQfIU%9F1$3A+urJ zRllqb@EX0F8?{SkdlUMnS9PDS49OLCLL!Cxc6{m}aP3~8l9VJ8;TXi?Q|WmNd7o}x zdk$4qGk4+YI;bkJbw)T-GY&4(>wRdEvo?_wKaUlXpHLi>D0^C!n0viVE2-3dJ=^N_ zdBLnqg3y7l!|ehOA<;>}%jbR^BBacREHe>s$Xypwa`#lz2%G6`cF3`{sTfNY7x?#p z9-hImc{kpH^qfS7n@gvm(nco9jpyJ_iWNS`=abNr0K76xM+x?}3&;k$knRr8F1M{3Dpb}J=PMpvZoXZ=Lk`R@YW1l9>lj~pAB8%hFlMi~PWbkS`B=rC zERMDj;1@gP^;y>A7LShDE!5jEUm@uk(@Sp0dd<1G5}&_7y4P53CpY%XnuN_liGU5( z75Uy%4>1emIZVO}I`2H`u<~Z#(^=z-@LxvE28qPzE|{Es#da9Bqg~+{1n*{x#*6YP zwqaYtsEQrI9+l=C%(ltl5(i>bjDj7dFhUHti{I@*q9?2S!En{R+i^($N|D_WtI-J! z)IAu_7enM;$!yJcJ0X#Z;L+<|K_2jmAXF8-%MCLV$~*V{I?WvR(P^{SOWre6)8YeJ zx&g(&%e01=wpS?X76m_iucH^&E3|Av$`}?HztFBRogd*tZ6e3aSzvzo0H#5Dxbl9* z4ycEc35!R~_VK=rjXv^)$V^=~M+a0m-tBFg;(~&SNsiz_6rm0L_x3I^)#*N)f3Iw^ zn7hT_PdH)>!kehV$lZRGOZ;?pgsBv+>=ytVhET2qYH*CV`f<+3}+O3KE{?pDN#L4UfC&r)+)B6o*5kMfL4s;W;+r%NO@;0U;T&1O~PrtRr`VI@CmX3-% z(YmlOW6t6pQ9CLxr&}ElPKU7he5jdqZujFdJ28JJE81O=v-`jd5VKgH|4cAWvwI+9 zgq%x6?_}aV8#xJsT`qb&<|CW{`F_^YB6Sq&Hhh!tv)1*dbk}dTXY%)Dym444hcY}ONCo;sIsmDpOB^kvkpzzHI z>I~@0>UIm2grTnS&ei;$Oa5?;t#Z}wiefk8cy*)7gFuE(Vz%>Z%qI6kHhN}zorb!7 zL)=7N*cWkjt;*hC^iz?4Erd&Oz77C+x72gwDYFj*!`o`Em+70n7L2-_%(NY_KVNjM z<-Iz7ladA#bqOf=Xb1wt&@12Uef-Z0pp?$%V9DeYz&5m0xqGLOPgx+-dA|eE;oYM5 zOghYg{q!;GS%3q8FNym5U#TiAKw-x{dr2ywMRUn*7?Ko0Xi2USZX$3el2{+EazD6H z6#N)HVnsW;c4YTR!9JMDK?R>CU5Xi{Vn#$tAc@4j7sj4?dg=S*~4j zWww2ZnEu+mm+XK{-Iu?4sO!z~SeOaCx$&maRhW8~;P)1hFAs_$$fJI{g3Vc{+ZZ~V zyKX~V@qzg{@EK#}Nht-a?DJxd<)gv+@6!mMpOH-P_#b%vw#<-X-k+)Hw>u`w(b^o} zw19vnYGQ4E`2#y)0tph65yCtj7hjMVdd0@gQ+}~v!xzf0Az$=ACR@XlKM_TJrc)L9 z^?y+Z##JSLkagekzj*e6w(G?d3nXHh#@y*D&SIE=89Xb|X3Z;N5}BPbh2jbl1cN6> zEgUzJr9R*wWeU z3yfhJlhD2+^dc4yF~~*NeVQ?ER}mc@os*L@d3v(T*E}t>;>Qx7H@Xblx^ll6pxS3N z0_F@UuA-J!7iwk~-OKEE2TD@nctIJ2i=dn6(JNwSRny3H`!Gix;689LWx|O}M7@{K zOBmk2&Z=Ho~E;~T5TF6OE~*(u9sw5iy%Rs+hk#bX$&-@^_Yk<3chO=%4~ zx@*!H$fZ|PWiiP0@w>fyMzGG(3#sq$$FvJT=Sv1`<%a$2`IkvQDw3U8Fc2K} z%l#(KK>kXJ}gXNACh;Ou)nx#R5Z7n~+8_e#ha(ntCHi1do z@wj&~{-)9d&3y6aWbs>uUK1^Ae%1T4F-!X@iPd;2F8bdbS(M`~Ei7QaEowKV=^AQ5 zB&-r(BgOl8-wqbV_8IZu33Z$3E_UxluwRPkgxYz17Pp_Mv`&S_D$#_-1 zx8Cnp<32eEm6P&aSNFI3TYKqqk@@Aje#77wqb0n}glV86seVJZzMHU`$K?q z`UIAM`h0+U3ri_iVU6Smxl~xS2)iBO(kF9PqjZ)c&1~2TyfhHqF$=d3Hh7}$H_B<_ zM{GM};RwZ2H#)7u!@fanWw(&FwyxR=;I_Wl(nQuJOiAP1yob{4A$(KnK>RJRSy(!? zwc6&c8Edn*r~rg}+|wUfSpqmK?(`s?ysro^c~n-L1|da6q#7`H=TFi*+JnEDxwD;d zqV7kI$vt}@i5i)h^zBT%DlRRB)>-#}UC_4MpA}H?8t;`6y^@Yai%V^-SmrUKVa_fs z5(YupnA43^0p$YnH^l%ihFUqC zwy`|FF)<@W>3?JP=qKR@fK_yvUiXYmqbg~%Q%Z9wY|5xlk#mqBL^YY5{eUuZuSyf8 zLb0tFphpf2fIn>RyqCV2r$|ai6a%o;V6#T1|4ZPVK3)`_UlrkqnQYZeN~g0kb*I&TtAae-TXgkD;hU?__XT#VMi%-4tRFN$a6f|U z#@D{RuG1kC*YQ;s+E^c|0t*XD=9f1@I<&*A^ZzPlK%W3*lO;Gc6DnSxq0iExrF(NB zOB1sjcPnuKd}aa)(D~*S_?;NeKbT5@NYp^kNTDQ*?tLP-!cZU(cb7q3?_!zoc(#1P z(D3mY$Ut$ws_4@1i)@ybB3rl<^(O!*M}9#?VBA~!)qF|>=w5)gN%k&E?YiP#C=#aV z37O5E?dnRwL3!iI5f|6yANFSO>Tt!XjM8=1ZHiNnofo9w`&0DH$r=zU*(z(=H_B-g z`s6I26!yumkG+HDei*;`E*1qjYAh!G7}gd&rB@AuJoqAA&GQd8G}?D#pX{p7b0|to z)=%#y=4QmFLf^Gs4A9mNqc=Fp8d#*x9Y=ILfB%sQcHh!-m38U|^zvOl0{SrDc_}jU zWtWJ?6ATGRL5BuYKd@(0Bo41FF=s2T9*uKCCE5E60t9f2^&P!-#&Ts}girrocJBNU zZtwVNuEGDjI`i~=fjNJ;^PY4ecS3G|n^phpC=+bf5_LcU8=H+0XH z2Q)+jMIy;70j{{?(|FzWs*~M2RGUQw9oRI09cq1L0cqlefa7n#1({wzl4%QZsTV8;s4IwVdAQAh6Ew zD~MOuBuSEMkMt^7xT~iDNi8jgah6SdH6vm&uB`2&|8Ogrnh2R7scuju8_HY_x%!sK z^I}ct0#~|vF%KWU$}WPrb^?wEQwT8f?w&G}P1B`Y=|6OS&I5NF5yifqQzBvfAMPZ2 zkJ1&g4?j+Oh>1479Eei<<@aN=e2XvA$EYJ5<|XKhO2E2b z{n12p%zKZ(0MtYr&CnWTaaPfxSfLkc>zp{oVs{4h^1m*D!7MI+*yT$RR50YD7s7cv z8C+3sL2%rzufo2QY}xIIk&*Fe#i4ey2d$EBii=L}hu_r$+Mt!oY8!WYZ7ZA$4(U$@ z*G$X|a1~F-yU)2>I=U{`;vd*XgkpB{~dYiYIGbf zk0UHQ5gujH>L9)K9hjg!cA{oV<>Ve$SP~06qpO!oMw<-sYsJAZ>qty#YO9160XIE2 zRhGISU=B_cyMKWg&2lC|A)njA(|@~C=@3}%s$u0@rVGmh?2EadMwUBg%KBy|vvh>? z`{f zSMer0l`Z!h-?8Lz_rJxcbazo9iv89xVD7!R=?Z?}BpcY3Z7BGUoWViihR_dK2jk7* z;bC&{1%}J|=g>9O1!R|T?v8}ig&K#U%j8otKLsv~Ql3kPkX3z==oOS&CE25f*1&;^ z48&udC@?n9vL;G?ou_jx!+locFKI?Aa#|xn1Rn6Ai{`Kza#&F&&o*sr# zFjxR&?}%0ig4B7t=6foWN5m|EdM=lD*HpCa))CbaB>OK(r zMK^s>(ZbkFNqw96^w0k&0x*Kh+O`e%4j*0m#+1P0@Uy)3PnR|5BiA(P0&Yx{+s-{g zZ7|36kd)bCc}6O-%46oHU3{*r@Rv1fL<4R8DYcacMc<6Pkp2r{o4*YL`2XDNOVwE zlQR;A5$tRG|Cn%z-6UYbI~C@e>rWU2P<&QNQ1#K(5Q|@oL_|UGNW{vuZ@C}s!7eU5 zlcIUqyGWqW_N*sS9VGEvN1E8LHKGSUzcc)ghGYTTuIsNtYCYQ8MD|fAY%D-{kC>uV?M7M@Z8 z_+U`TY>sMu3VMipo(wWco?g$Nu-!2TzO}*kzi<7>1gHk$e)SUPhRvXg&xaH87|Z%? zJLDY?$E9zJP9N>>^k_{Y^j(8wkg^I2v3zDB3e564ppD z+1~wlZDtxY*z3XYzmO$&(cFi4!ON3v5K$C^j&7LeQJ}UOKP9@co4p#S%XR z<~1FQqL(ZtS5+AG@@luwjm_eCR8~{dnG@Jit2|x^j~6Reu`T zJ9EJ~qAnjQGIjb7qZ!C0E?o_c4C1UFcSgCDo)|^`@oS3ub!Ow?5Y6B z64*_F&Bd)_+lMGCm5P<-KVbR!o@dR_B&hVpmeHClL{dW4#C|==vs{LBJ|E5#y7cqs z+1A>b{RiI}g7>VvtMi$sTq0&ck!HKUJvJtpFr^=1oaGk5qkEoWp_~AfJB~~RNgrq^ zA1oh>)t6z7^PJc8I#%$zL}J88R-%aA^_ruN_IFp^g@}c_=N?{q@u}!l=s*ic2Z(PS zy;ad6NO9Z;^O#aJCAobF$(C!nMuiAFlH%TV%uA?O8RkmL1EanmKX^(yq9|l7 z<<3+K%a`Mq4e^1f%U=ke4XRkvCNg&B0V-$_M^gP|ON6Ty-dU14me>Pt7 zDn9%>tv*>f#G$zGGfG{)uas=(-;p!WK4uR9z|yFFRk1CJFXNc)mw6 zS0NZ#_a)?iS+czQDZiEVfiE5EbHOROTD_}lZvL0secfMlrOXiQp^%a<-Sy6Ss|?^U zY*tU>N85}hlnbf+AW+y@vEs5CA&ku`p8n^QLxa9A<{4#F;UvI|687r#32$Q{k*bi= zXz3Ywc{hs(bwyqG*1kT;B)B597MgJM2PW!>+0F($74FXecz=^5ZoUa1}O%f;E8Jv$M@KK(0v#d=O*b0_y??E)y0eXYFKnjL>~(bFe= z{`{L8mdEDkR9?WoV`MZF=PxDz8BH^+Wr0WrFPdVaZ6}%~y1P>A|l2(RUq555C$3 z3_`I78XCf{mWDXBO2jt4Gr$-+)W$(9*4JEbWX~Hb&ztJ(GRT4{G;8MC3@6gQN(EnZ zeY}BD)s(?>OVa?F#Qv4bFD?P1bY6_K|QJFr`Gn!Z>V#~uDjv;;)$$mSs*&ktA) zF{1TPc`Qdumch)QH*D!J;WP)85Wq8B`qb1^*z&u!G+daiY9S@{`h!<@=>y!YQV#ue z=)Q1_O&!j<$(QMjOAl^#^lI-jJlpJ#`0xAcal>X(Ssz*L7ah;_-E!-QB0K&flAkw} zrgm9tkf~#YW=zb9X~eEIQWB{zpZ$0;l==b74S8PB5&q#h$+{RY=e3>;wgkHkM%&~R=a%2n z|Bd2?P*Fg{gB)Y`mFCYoPZ_at-d9Sw=x01W04kG4%<;v^(LSW)>h6={!_-G+rrhrf zr9XRCw0vI42NNdv_OK6#f;)PDXluOFi2k@oC7JLKhcsLwGWpJu^)>leAKq3L>?uF9vwF6#1^ z2lJ8XD$vdeQvR5iguv^(CVB?gLSdcq&2Y^*R>=%31cSZLV5*of>mx)=O?yHrTjvKC zQO>hYm-C=22`Eqa@WAotqeGW$991to1uzurXwW4VLTtYW6D23^o43ptt9!Q4PToKk z*Z*j{P0AzBi{!g<&JqKqmw@2-0cFC0xCKyigWkfnnIWIJw9qDkUAKwX|>e& z9DWXO$)R}r)Gv_i+BQO>?w?Uc`Y|>5N5y=@gO)Xf_5V^kiY)oy3BExQL*8laMVYG$ z!}ZuXEQuXDZ@+Ubp zf;E&3g@HtzYX>wv%r&7r3$MFTpR*iv_ld_mM+fHqwOx&9J7L9&2xj_}jK8X<31Ao5 z+SdA!9xO7s9wS21O8oin9q;o zX-waLfXNB0Z|u+qrbXuxt^2LrI>zbYKnr!m*+>Pd&Kcww5sm^dGap$C)Tf|hkw2|5 zw{iRwxg2BSWpRK$T0$q*PXKw30?zh9u@0xyOF*YgwBv(lr9N%y@7`^#RX2(6;t{;v zRfJeR!0=Nvbz(+tw+&_cysFgi%>J)@am&wcM}9xF?P`>@e$LhLJoTS1GkpJ2z2Kzu z&)uc@`O46QKJ*TQ&(F+A`I)aREbOt#=e{9SBB?QN;8ve@Xun07 z>kL#epaUgJ(BU>Gd2_T#ac=wOXVY$-A%0sh5L6qDcL_8r^o!V&;@#pUb?F%$ z8#lHKw5o_FVPS32Dkipdw6|OKf4!GdO2Yeyc70%LuanWFczr{B@@8{J+iu2yYf;(B!2wy{7n?Qlmb5C9%z_ zm@RU{+5|CsQ{HdrhN%MJx-YMxDJb@hnz0*}0i9s>=3IV0P1f3L=$VrF#<(mCBC`yb6Z zH?EG-KY1LBxzcC|edA-r1Pv2TML)HGVc>YS)K4uWRNGF`TAU4HYOk*?lz*5CP)S_G z&1{#K$Wz*JOJ zpehuf(e2zfJ_*;1!?3xz$$f37@o%S2fF5at5#NgtF}LK20t0w$Fkx8YTlpL4ooU~J zQj5vZ?(0rrQJpWU#q$nkKZkPZcb>Xm94(y6-{yY3d79*V*3NQ(K~G%w#Wk6Y(C6y0 z>o^8P_{tYz*EYPctEF+g)!Y4Rc=m$l6ltad8VlyN3hif8Lig6*+b+%bhmj^9Z~??m z)7iVa)ndlu$8^KP=bN2cHrTx}nfVmj0qfuJc{sK5IYmUGMg{mDzo@!_Q}}2^!q6~I zozvRFLMzLl=Dbt?$GaDy`R#>}TH&h4DGy$WTQV{)Lj+WnCX(=hQi9mK zAjb~w-qeXW1*1^jR%gJhYd9yvl|A;tfV51w=Z$97PNtW$Z>%q$!8Ds-WPPKHTS!BM zzcMd=#=sj7tDTNM6Pk}WUh3=;8pXb-d$5f|s-$eTw-?I6%NKa2vAd){#2TRzULH<_ zTuQ$kHgD|X_e_@IP1|$XS+VCHB@Wf=Cz)+zbPP)~C(NN!C_62Ui-ThZT90nW^Cpg& z#JI1)B*(g%8b7H|+Y9A-oaCeuc!wo1QVF+NWZPc_!N6?^n1nV#?q%L-S!nKrKIGhz z97eB0bmYFcj)dWnx{6}#1vCytmc=x6&;IM@yGKzrgZxQEsVc7Ci~`6P#D#`BvH?j* zKtLiPx;gf)y1Lp=Qfx(o_B_eJ%ucuzbGU%*C#ZZ>ZvWBIJ^V1C-(n5-Yt|@L$@5{5P_cO zUfmY6ZKXU1^&hp%E0Q)R>ulkLam_q)l^ZuO7#{ys#CzJ=M#w($=s zi|%3kY<~%=;2AFq0(|75ZrIjN7b>t@AJa*vgcYbjVcQXgUe4qwx$sJhq#iT@^%vUJ z1=8DGrH*l(FPxpV>>cb&Ut4p0_oLcC*rw4<`&{u3@#XwYa)?Ho=4}4DZD{-2G`+=~}&Pd0kW6p=jzn&p_n8*ZgMm{O%bS2rd z3m5t+6*@oiFJ;8E+BYwckcOF2ezer7EaFB+hv;e`BUo6(5{L@%#8D<9{ z$3ky5f!jV&vtd_+%BjFrI*vkr>UEH-x0+?0hOP%NFhoxbI4gHzJhhQ-G|kZ2TP0IK zKivrZm@78S4EBWXzBeFFxq@hu}!VVRZcZ;2Dm|ACi5Xe4YBA+PdGl-2xKo{GAm zCQ)KTPrH1mPB*&E^KY;&K?FW-MoFzD8aiW_Z*JdtC{6Lr-EUkJ7>(n_^gG?sq0P&L z2|VP>@S0GuLZpT2Dv1QdKR}^_JPO)qY|W~M&`lchnrrIQgJ)pK!M|@m$VKA<09(md zl~_ikf3aBbr%1tJIBC^%4S(^ZcMt^-_?ITK9!u*=lz{8;3uHqmOGR=Al2Hfz>t8zI zJw<}XrpMb-;+3Kl7qhL3-ghb%OJRp)QR(nse|z&OCC}UWkVjkWe6+((#z6B5rSONw z1UWTz;2{ZF+RG?PdvYx)$~6GyI3IjWKc0|4gT#o5bX|b_je#ijnKK3@>cyiBltAoZ z)kZ{tQvGFng{I;*vR9>lk=Ha*%v zZZ|-E(8{jA`j0sW7d3*z+<1vU%6i%&y*YpSmms&jJm+`5ytBFK%WMtrAKmnhmO{TQ zbgTR+(|{*n1PN+_>CG!^DKE?0UoJ?ins#ks=-$^rkJ1UEBS}B~x2OsCB*FFuBn{dm zy3(jL4eh3L+Ij^_e?gT8%Eax?AB)d5VPQ1GfSu_c>^wT`?v$#DNE2Z`m>wFciRygb z0n;9GA`yQY2Ch&Y6sd@O@50=GNaOX!{OPFx`7H|Ng^$0=LRcmU+@j8Z(07(5M`b4zC|(I+QX+p$aJKH)d%1(tq+Qx($+H317gksy?G(w)_xQ&kAVBmtU1wo{q~E zi5^A`{GD=wMybrPy7h$8nTmE|x4XvEtuoJgTadyF*j65`9#{Whb^3AdCo+tUJZ@NB zUgmdyui?d}5UL2seS+y$=C^-k_!C%+YF_(9fv>*l(~hm&R!Fq}!S$0m_JsEv9B5X! zMH#ooymLbFec0&Sdg}~Z(=sklWy$`-Eq@Nh{3BKmOnx{AhD79bLt(9PpI~6|U0mrERa7#U*%0PIXQg8T+3ypl=c^RK=6YyGic|JWOh!{SUc^68L9Ijf(l|?Mw4Ofsgq|jKtmR{Zm#qITn&sy zOB`Sh6_+!Xz-SR;6&{AqoIE|dsPhca8Zez&6orjg(j4>A|8yuIM2-K-3NXrwQ)e)j z^z>`pJwIr0GY`^< z2s<&h9|#@M0H)=y1OdtPjG?zyZM$>L=1WQjZ5(Ogr#w|T1Fh);xM_hlPeIUe@j9D3 zgF28cwY=1p@3G0hyDP%q<^GaYtU`{RL&l4Og&zM5JP+}g2N#P49Fb`W&VuRYl2*}o z;|X}b9}3`LmO;X}`O9zI9UzHtB1H%!;+_`ONzfxne9eS7x7rj4cKb}^elxl>ONOaSY zfZ<`RgU(-jb1RAH{Y8SMKZ)(_05y$kXZcFs{+TEvg9q``jP1z*757z67@n1?kD;qz zb<*`m_o(yT1G*0|mgQldO0%}}`1ugetv(sc4Rj7)xitFo81}kY z*S?IWxVUlqu$l+Y=VI6vxw-#-8CV?6=mV8mB<`oLSzS;T0q&8uCIF;2aE7k~r|=#E zN34Pr;5RMvcnyc~Yr;1x94w&883+nQhqm9VA`{d6Y2n`zECBnX59+cWP8vkGuq4{0 z`+3nHfCB-~tIo4>c~Xi_JSq1;(w2``N>9HPOE)>N4C^=k5jWu25a+;G_h?*+x3#)^hmpo;{=85dJi8`9 zQL^@c&8kh=!6HA+^-)z6Ev9h7^Fy$a2D7hU9xL_9gJ-I(eAfCJ+BsvJlh=6Q#$!RCd zSbCCM;LaQ$NC^2IS~*aTk$2*z62d^s4{SZp@L9tMFy{tRp}Y?NB+dI8*Aq;UC;xR& zf{dg~KbX2VxV&)jb}|~@P?YZX-%cWD3Ta^_28vaiZ*)e z(UyhRPTmZ+3O(z1^$#2~Qqt=+S7}cX9)&IJP!Ih{xO>^~ozTMY zO4Btycji32=~dh8e=~`AV=DnattEHy@J$4u{KSIu?gG@M2t=F}tR#O$E_reL)E-)q z6PQ(a{UUa~-hDA2dHJ@rBK8-7-rV03XnZ+;nIOE^YNZHmLT)f3iHmVt zA2C!TS|3rIq(146w3$z`3(Fl0(FD8=l%B<>#96=XjK5uaf`HEJ6Fe784w2>)nBI6$ z7{cY4DMGg4F#I8n#hO$EG>WqrmWUXXbZ?yi778^TN^FR@9N{UAYq1$vUYbQ+YF}eZ}-W$I37^jGQ#es#?sr^2zO3(ZmcteZyMA!27 z%|?og@H<0bWI|V}7TN5rBc%r@k16(65Z~)4_u|!A=moQ{HAb#%TzM8DQl?EB%{`n- zj2`cWwE4Jy5^9(`wJRURcHQ*_2fmRE`L&JnJK7Z5CYix119N8nh8+9q2YqemYx>3z z%NK^rz!Ru^#Vuw&x| zDw{xv0u0qf`K!~OJKhH@#YKor{?*ArJ$z)*4V=ke7X9k6p^Tg1<1AwtsrzI4y?zm+ z0*w*6d^r1ji@K@hTQSg7;XsU*g?bv$6Tvc`W)U8(=fP)mt_1%p3~XgU5;6azYHPK? zzOf|eH)c9%C47f*V*wK4Kz|{d0vux5|vy(a~vu!p}`-Uem zBe-<$Zu}j4h<3dJ>1Yh~^NuXYdc0W5^iFE)99cT|L%3{-GNF&tG+O4*xIX_7%P6XQ zycc{ecLEqh&;~QI@NWp^ANT#h9_o;?t0GNQ5zq`>-ZmA`=!0KO%Q`pZct(vP6*!8O zgW*K>KlOiYfzu^|vNO7ci4b+BZIWrg8K>VC??Ck~5Z%Yvx@hD68_%V4k6f$7TurZm z1p3czWjuW+?FVt{#loQZs$u(j(BfS#Iny$%@cGE0JAVo+4k`;mxsRt91{-%y9dqM2 zI5))6vnN*_YZ7y)A`%?8@BSVwm6)R2x^NY}%VH*m8NyfdQ`28RrsC2m?vBNCT+tov z?xCYOCeGsG7ck-OYDgnJE3{M`{p+bF^lKButzX3!d83>ofOK5&+d@4P#vPLAj%K0(CRSt4FPi^Rh@P@&Mw1@iBVz`_GiRXC%B0+6H}v?5@NP;TzkUXlO9@G$G`?wa1*ygc{qxdO|a%*?yofxWatYbjkCP=)W? zbuTGPa7ovK>0+yKF;1eoPfi57^W8l#5+^VvNdLqN%s}g068XU^XzilAv`rO~(~m8) zaC%>Fi>YSba~d~of2#Qw9?sQTcvuD4U@)_%e1CVrETGP|pHxv;zn~9Yp7yU<0!CLh zWpf?3D7v?0aXK+(@NolI?ous{O#qTIkhL0!&_J49TPt@CSr^W8kw z+Og1^C&&CaO7FKJg-|59$4VT%Rd;4({C`_eJ3Ix`jBfv=Qu^A{H`Og!vRACisP}}Q z<;Ztqe8d%K8*gk(6S)Pgvk2XNS124U4(i1#y{F@4z)xGAYW|J`lfanlREE^9KN>#4 zFa~x03I0Cd+#_rJS6z0YTZBiaXl#-j@Z#^#+Yv}7vITty#qBaZ6ENUU;(Hio2C#*E zAXzf1WV*-acIIzGI$Gz5m{U83mj^sbs<%>?{n8-6}snY zJ%Li!gqdOPvo+jK7`}xO8|mI*HuUSIM0Wfros(CFM7don$1(q#WvzbB^4RRe6^b|d z{PZ8B_Lh|<tfW&J%THAUlRMfGsC3E$9 zjRC6Jb8k7Le6QCa>uavxihO?i%RtIBcPk1d`@R&*Nk&oH}8 zstE0Z1Xl`U%bQy|XXW>wtN*&7lHQ@G1%L9hq5K6==6U2F^}>oz|7` zz4Z@d7xjU5t2;P;Fm9}s73tU-uNrBCbk>6`$LLL7xy*|Y%`!e@tuMg=#sETj7o5_4 zAX&~-U*|JyL!=trxhDrxD2ZymdSynBlASwOva;Je(b&Wy2~5sB(^f`_?}szCa2bxe zKlq#b(rasP?pgkX=~8WL&{Wi$WmwmqtTe4unY4-3@&X}>DLiS{>NFUpf8GBD;+|dG z6{3Uf8)(G3SaUOc<`8uUM}lsKC|s;pf(X;r;meph>&wP0{F&>~fv$`HUqiK2b#w-X zhGO2lxeWgSx0*s1QCT<6Xc0QPpYO!Kcu&O%xnF+gzlj?-W4PaWd=z{Ka5(YuE)r#Z zWbb^L?XY>WNHb`!In`3zyb5V9MXFPJf@WPPWWVB(LS;inTvr~#y z!SA-+^J;6)$LsBHtL-=>88C4!c%6VhhypM}e5O{H>juj=7dtEYwYxkvXwsgo75(;1 zjTA(DVPT)sGyJcdG~nr{=1}ej{glm?d^0~Is3+TW#H{OP*WS;pxiBszitYZG%d6C# z(l&|T;J)_KxBDL5^X0@j8*V1QNeo}5f4|I2JQG))F6f0-HGtuYep6Yo?-a)5x+ty z_RY2ZuJ~AR=l0F zq(Poyt3}l8vL!?@kDtFlA0V9K2=kjL;&P8Yb>ie~7A|frN>>LTv&9Q0d>P~W-Rxh! z$v(;QfTLSSi7qh7l;YcOKc0AF7I9}@_eXK3qdE)9Q6{jIb6n0+cd+=P36b~-3@rG= z`vR%@DBT{BUT6)K%wR5E|nxRO`=#PYIz7d_?}YUiWCBde)hlIH`; zVUJ{_o70+AwshH0s)VI>!-5S_#Q#2rfrZHks~lSOtomXpTO3zM_tp4g@9mKdf6g>2 zqDN2pZwHtx;x4t9=4Y$8lw%c43pv=D%S0(4MYacuSCMkj;S;n+hkh4*jiLR>e(sFy z*0paREE<29G5)&$#zaJ&R(Uiw$Abu($4?@?u8w4OCNb;YnTVqk%v_nni>fYOe$kN4 zixg3wICu29MZ6^CXy0>rXZFTASAGK+Q1MBX@ezzmqmbX6? z*%i8)@9VCu+vJkJy!CSIvKsa;t^MXYe^y97E6(6Q5w7>SD^V|F_;(7ZPss|8DzJ%2 z{=It)tR42@@cM0yp6_2Xj8U)T%P~*iFsw%0xGY=bPhjy%*L-}*uX%bY`t-VuC?}(! zUtQUxh~LE<2R|*LBFc3J#2$f8u-N5&2_S6qo*rH=;~NnZcOUh z`haQkBg|^V^N6>Dg7!rl>4ORm9C}-h&wQu2NN*t>mPeQl?w4o@vxf?W&zhJtx0Jp& z+|-@I)XvXGv!wcbr<>{muvCOk!k#Q-Izst$JyM3S% z7+4ZovDvL5#fhq~vg$)}9Tv}S(L~7G>@nunHBB)x;81x#SxTU?SW6!1-|Ttu+lyKE z`%j*ehsWYZzEKc>Y$6Vl&xj!onh-1dZ7RaSSkgM0lUT{a90>9+*d?MgoAkZ)x$T^ zhq^6)G^Zdo1ZOG@bY4AuLks}_>*V%rmNUi4mq%XX5#pyWvg$tid9hUL;MOoN{WBw7 zLiYL5c_EI!NnCaEO4GNh{R6Y`{P}P{oHQsI4y$iobJvsNj@i&ISc#f1-BWp`fDCf$ z5}^HS(7_(*U(9^)`1al>Su#Zhns+WW$n0lpqyz;xT-cUL!{n^K_|AZFvMORDg8Y<( zKQDkfcHCNd9FCT+JbU6l)(8H;`RujDhTPg5{T0g3#uu~UbiJS;q%5)Yb=tYBH>YUd z)bVa<3#MM1>(G*7W?jBV=q^$|y;;bQLS|38B>lXEwqbt_*&=Z!vlLHQz3!l>6_5MMZA!bD)*xZ73mTdZfrRjXLn%5;br5C4`h9H#XM)#l=P;Y6$k5P z%t&TgKv1JA^RxB7oX9AMSCx{oa^Yrl@=#4WRTTk$qbzvrH;X&oEOAC?PEhFXmHQD! z*N3OA-6IML*%1!ur1izc9TxFJVfwoI$oFk~fAWx+vh245P z`Fs9%)yv}5M`wt^g1%A5+RMa029&nDzOpqk-I*Y6dK4RfA+WJUa+-mmmbc%scgBgY zoWFFlbehrN<@s^_WHMrnt=GJMPHA(OWreHcna@ic$XWnfrpKN@N3xBTjox~^z--idhNOH)dj!GufM6)%&a@RVJ5<% z^yI)~UhwiFziTt@_dQ!;8)Vf56%2>NS@tRT$riv~8wnX;o!p&mx0Vb#9Nr=-`Jb&& z9ti2>=i>M5CYoMzXt>o-=8P2RLXGCtFP^g>3}mEP6)TnJ4kV!fCq5`gIxRm?o^OLdm-y3nRBpa;e?Hp^RIgsZI zln^KM+VjiEbot)`O$Q4EOSOHn4h%qbyTo<5sgSa^Qu|%r554yiL)rqU#DbZlS&;_^ zPb6OP6eMhCYtyh;<#OQFtc~0J?}m481(?JZDq-k8M4ls@E}jiQJo#~H)1P&mCtTS`PE$Mou7hggQa8y!ca9Tkka$$5KgrWv;FwxEwMRso z)Z}@@<+W(UFh`%}Q8>IloUf!)^|S)-PDi{pk?&od-CGe0e~~y{qxQOdD|be4vn$|V9!d|y=jRbRcg2=lgO>~~5ew+r4?^Hz_w;vOEZDYkZjl;`+&ice*i zRoo5Rbk!R9`JOte`k_v_{BGx-v@$AJ#?XbLR+2RYteJuv8oQn;Pe1l7pK`(Kr$3Mi z@e97#qC+IRJdP&pHlKe8fBSISTuA-b+Zc-KllY_Q@9Jp2|0w8Mu=KET0Y})(h7xvP z&^V2lnGCeL^k~nSmo2fTF-+*q$>G5xyK;jY?22lGr7B-9otup*T-2&+wC|gG{9lDE zwKU)TKwCn~N+-|g8pUxrDW>^CfMk=gLGM6jgESL4bQBm^ZsaW-1r+c3cdyO=@U48R z?p9-Rhe`WZ0RMxW;mppjgIexpZF$wJ8+(l}+Up=L|E-twrrM4Lc_{MY75o@-5-aZS zl%zgqx8|cB_}GzE5VN)o-}sFdMP$V96S~p?{9YUGr4Bcom2Noa_&zi_6R}uct`hpn z?V*ZZMk3vTYX%*r!zRC@a4+KWC!Dcu8-yU3kf$#N*Wdj-yN4 zGD9053uu(1mhdWd^lc>V2X0YADs_`a+}ohPyIA*(E`jng{dz>4^kcYT>=}7Ul3ZmZ#rEMA=U>0N1hkzK%b(sMLKR)o3;IA3{Jw+lpi$&>N+S(z zOqfikqh&fg)eV^oLQEdJJ6T)O3I`{3AS-%`YK6gDv{kNALriM*wb!mb|+YG zvY-t9qhEcrFf^AeKbJH^KAg;TdzLL~sC(@6;o+XZ*vI1xi+o#ddcWpfTQ=`=m7cfc zpO9)_EARC`^-?vhlSq zT~gI^1y?&H!lxVjJB)FY&o?cIJ8j=XpDTY zPA(bUpPtw@^`6DIa%BS-7uChmIo}Y0*dkXOaE=jm6nW4?rgrxAv4n{M;<1>hD|e*u z>LdKaGXm~Jl0*?hQgDX89m(PS^^z65sz=$(6F^~8t$#ezhCJnowSUJKJSKXLjO@KSG&yIX8egK3(L zYf)SYeMIxL7O}dzdj0x!c$nahd}HB>AJzq8z=sraoTcQq*4EVQ1ZlP#?j4XU~%HM${8mNm2W;Wikqv|?jtOFR7V;z zCux)4UhXC(1uCk()vKd>?bf(BzI|XQrh9o=?mlpkuRFac-Zbv2hmD5u+vrM4O3KRq zNLEVRLe%Gl`+l`5)H+}8sVtWUKoFIqlK!{zWD}n+4OowaS1S$uV)pBLM*W{@uu~vXN#xQGeS6d;9tLmukVaQ!2lfzj$-C4t+e|ZH?7BK)mdj zO(gkK3&Un+Il!6aRH&LZ;}c4QK|F+3c}z^!_hvzR!W2tcj@N@Ig9)3sGDN>ig+~9z z{C=+X6|1{X?64K8_OKKzM{8g4l<#DJJZ1fr(x&Dm84T>PdHgtgz`E-`!HcR7IHI-& zus`D*=l#81LeY(3U^?4msS8K`3Qaj#z~z*}#0dDT2);Y_rsa@lzQ0s_qwL0{r)}S@ z`RLwo^2wMF5Zt7f|HfNo)s^2ACHA8dyEa!VG@xtbBjI0T;A4$-kDloNu@kYFtokL^ zAUiW$;!Ea^tkR692&p5aOCFmihx*aVPm-kb~)xvFBXfm`-xSZQc&LjFuq`*3AF#QwlkuUM~ zApPFttCnK%MaY9e^yc|6nXsQskr>!u0{XO9#&6cvkAAq5z>!h%xPg2!lm>b^I2fUQ zLf_JIHY}Y!I9n<1zKL}8!~dY&s&?*D7s}PNCokMHP^*|vBoMG3yC5=$xPFnm;8%Ra z8viZ#d*H6U>)^s}qU15&Q4VQaS+H-RKD6~-&6of%ph2lJoqOP;a+Brr;@0j7tSWRl z&7)&1ZBISZR7x9zu0ZOz0qf@add(693g$^jKkQ7^=*zc?fZ=KIPKdt##}4zT%lc2g z^zBa9U3pEuCa9j2aeV**i=~|eb>YeYmB2j$i2nbB7`DFiNYdhJ} zNQg;JG~zb`x&7bDHdu%IrSv`SY%L+#wSGZz!(+UsD)o~|K8y6G7NK&_%onYt)TLoK znS2Igvd`tLGlyZV;x$4=UW2ZxWX0N7sGr8mpvXFt$mw+YE)w^@Aa7B^a_CtRO-GTL zP(y(6+@D##4k4)tSvo1e}=+V9@1Hpvvv^sKU z^K1lv-^>?4f2ciCWN|@TrDC<3b~OuCG)bpaNSYxs5V7~;M+px;L!Iicer(}LqKVMW7amK!~?=3)9LVQf~hEtbaKmRZ*N&4OS>X`q1iUVTUp^67N zr;U|Z+MvSYZoR;U=#+25rBq=z1Zk}Y0M(ofNSRW|GhNVB&Vhx#;#)myEGJ?ACniHm zOR=HU6><_OS&nS-P0~l{Sv|o?;G_kO!%ZQ(&+I%CZGLaJz2OdJTA%(edIRBd`P?ea z(cX|M&9*eDsE&x}j2JQ1-O3hOVPXcqN%QYlj)dY0w)RlHma3`RQ1`5cZHRC+e_-I8q8)($~AUt~cCp>~u zLl|4f=kSVl&#{aOFwJY#9A3Ae5E!Sk@GEY4kRK48yu!ZPwP2yhI zk;x_Lo^23mhLA<~oOh1#wZB@LpeuTR`y$p?{HqJP5NwtD6UGDLMB5n-AYGL;`<<_G z-y*NZYcXMu%VUo>0s@l}apu@PKe<=I65O>@;c6@0_<_Kpv4>a7fjzKB?bJg}Kh#cb z`g--uhcc!0M-kO+%_6eG<&9WpkJ956e{q2S#xJ)!I{P<}3+mNcbYFKHS#RIfaEsTQ z__!_aiz@QpSSw7k48DzAy)%@2%7MhDa_rnLt1ei~(sWHJb%i#5$Mi$g1*A?qm@CneGnWeOA;{%Jvf8a4e%c8F|G5B`A&8A%gYLaG}Elv1+0nNd3x@}x(% zS4)I8-4P#W=9%f;Z=aVrLwEI|=I7hv)78(@Yj22SgDzFf>_|WJ?Io+WvMcXXN~sV1 zd8dnPB?q#;h)0L^?E;ZD+VGA68i5+ioej{Bi<{9AvY|73d7ECIy}9GF=W9O{cZUWG z>eH`@ukuJ0zFvs3Vr*PI_T)>x&K8FDo=lfH+Tep>EI=byMezn)t~^HJe;EVl(?O`F zt^yaht#8vnyczt|{-l8D{J2Bp7EH)56RU7VJdWXU$ds(l9v+S1*uN;77c~zQ*U@BTO+m<5`MXU8UBSa_Uh2<+T zj->lL+A4H4(`y;YeaU7KS)6YH0S03g=N_ssKJ9tx#m_gdt`ivu>rK=EN&*mGqW{AE z2D7z0$m>qtvsrIbi%4aK^{NX`9a=>IqTsA@c%S>-(w`eIW?B#mt&h0E4_5KM^Dduv zHKOb;*chE@(-hl2ACIz*o*n6T?OoRt$x6Q52Dwb5d3GcYl^n4YdSG8g7Ih;bs?J~7 zhSVkgR1K12_i|x1LYGM>l>*D532WsU%NJ=lF2~x;^qPmG9T5mXd8B;!Q6-L(n1_L^ z_XD(a=|S~svo!x^U&!kP!GiA=-Bec)L||_UdYEeQ&*cr0+Q8|$RFb_#cq0>Z4u2S< z3TJ9{47>*2A46}e<5sgd|Lcc&l|3JpkVL@b>SwSiXlySOjqOctBmQZA_JhYS2^LdN z`^zHD_>bW&Pz&KI`*h!#a3Lc3zB95Y@SCScB7+T!Tqf2O23TV1{8ATxO$EDd`DeIJ z%3lYzcAQ*ar#LP|2;UzP7pu1A?OxYTIWF)|FkNh4zB2Q zicXIF7hDa12%yff$53bQHx#fO&i$bgm3(H`sEByge)8ufcf?QM3Yf&sxQ&Ecu-ztz zHorJIw=7%off-ej8P9$s@>94|HEICIKs2sTEqrmM*0h3{c+~mIC3ZiGcbiEsEIiiL zCL<8$(((?mL)HEOl=7qA;~qPY3wN+qkQ`vRTd9bxWzL5-zV)%zcjIKPo#D{d>S2fd z+mY}%DO!P%mg;P#PwDHhK_*+#J6u1Or{VxCG=t<|B=MXy8h9?e6r?gSVm5%ciMRyV zrhCVX9EoB^K3aCnyF9Wr)6PqgWMs4edFMdQaJVo^H(vTmouPZb(wJ1K5tOAC(=Z*y zj<}ZlTxc z#94YmVNk0`7L@;##WHAeNCq6+yTrq)++Zm4;6l+_H5ewhH@gq>G*5>xN3$6<9XTeS zA}>uhqc&8kY;iP~dDFR|*IPPUDhVNOYYK~#(AP34yKIlr*~-1-`2NNCRj7IcfYEWE z1A-O@GFjoYx?^@J3_qzx&7QA$Ff-?Co^;~UH`==LDz@60jyC-?Tam=F+-XguOG*1c z2re^9+fU%;(ZQI&!Q2k!G6Sp(GWSv!xwZ}`UtjQgCNkeXeAhE%t6hHjxsQ1eMNu9X zP8TlHOt>C<2=u~do@iH)(8t}(L?-d(M!59Elnd~w1}{3ui#2gw(ai`;=)RY(H3B;R z$iVYsMI;;_Z*&=G z5L!0;I4A2l&I%c_1*l3+&V=u|0FvbroC_&{Y4;_@r)(l!7A!&A{Pe0Oq5W^uQ=q(X z?%1j>#G>KVA9`1Ryd_El1WRl!<*Vf+#n7xnhvlc(kKE&4lo@Iwd3qAcy^(`upOVv+ zWrYFwfF%uyzp0)f3q9tuN7y0Y%HX5nFmFoDX1ShvP144GVnv%jlt7JUKOh2vqc{a* zVcFZR9P`)3<5wL5>LL&#HAhupB60DBxL9)ZA~;I@Fq2E-`n$FncyZ`L<38kEdGaF<2L z74{^Go^oxgEcc)uud#Uu3j;Fw3@9$9t2WanflcJZO8sK(&QSt|nSwD}5G-}++-5;> zFSwWcKo+$!UK3;U;qr2S2rk#A^IDNPvHtbO`2@EksTZ$^^3r{vBn2t?%TmE7^5^=m zJFDFcaPsc5(sN7_K}R{-kB~br0D23!w%z1O0+%V;X@evlH6uOdlwe@Qu(q3#@z&Io ziwYZi71gNUcRvbxrPDi}^dMi{;@exHLekZeBnwY^8OL)NM-Htde#HcQeq-PLPQZqgw6+^kQ2uj>cedNFkBTi|rSGRGPN3$bTuH7JM z#=rgLm^?nxt#D|>53ctw`bL$QNx$XHu&@_O*^JKv7FgXu1A_RiIZPn4joeZ>wB{Hv zBL?EGu4Xaiq@MQ!hJmM zc;>{+n;ZReqa_-dKgXy#5DT>8Nx*S zs6es3ubG*P8>mrYVqzE<$v=pQ6Ln~PiZ)~p_9PlWb|mjjiVi1U6W&D!plE-fyZl3=~%oA!;#UHJb2|7J@?LS zSzbgKe*JmkOPrjR*4AYc;TAAENG(+zwX@t@9KHHTyT=p~77j+>qydJeED!97!RlqN z+GC|~EH|RN`(vux7c=RL2)!5$T7(Ce#vAAn!`_jRv?5>5((pxIw`1k!?|S%~F4RRJ zo`)g`M!>0i(()Sr{1q=(zFxX8O+tuf&U|hvVntCesebwPmC8;;yW#jRAzHls2f+}@ zgZ&E0Xm2(%iRQ;VO4@Ca9bXN~axH1EYrxc;ODh;82?9{LXO;W^h`r8ab(qU5C^&N2 zy292tF53Kxh)y}*EM0xguP$yPs806S&V3HZjTLi_g@#^UL)iB0HtW7w?7?UgBEzR0P+(B=(siMf|N8YF z>w+150a^m$>$b@1&NQt?<7F7K1ib6YnT+y5gDeCbY}aW(r~oYchJFfQcYB>)(0=Mm zO8T$Fl^e#!33lZ*-PJEMMC0(KAC5%!{p@@WxbWmq!m9-Vbw(Qah6Ic*kdu;37V#)%wEw$GaTLDgyaKI|0)c=#-VmLwyu_Ue zr;@z;t0z|iL^@X6v_h3JlM8Y%*!fihU<_t@$x=NG81wxOPkT#`RS}8>yn1!MZ8h$b zDE7yum%cw9Qu7)I^eNGOuMMDLVuXPzB8I{aDi9U*HLOM;u8bxwu|{h#;vMtqU+vMQ zWZ)t!47qJQzvr2wdtRT*!TM86(d4>l9U^ov{()Jg`jx@zbb2F`g1(&WY;qo5VOyjW z@rP>`onTswo1@Q@k}9dIo91b<-3f~|Uvo4E=zMN&Zh5jiYNU(`0xBRs>x zk~AHKRLoD;LWV3D0Yyl2868R8=+)uEF*Fx%K=;-mFBOe2Y)GTCd6#+0F>0{ zyfIT`)HR3!g-58*To}FWo5cNwcS~@$KYnUu{>8_uwO73Y~nQVb>`4c4DwXaVu)uwtE#cg{l z)MIluf-vP~d%|RCT3he^H%`;*pRkWPEutxT2)A>l5uJc!cx(>iE#sIhep-`UNE01z zVv)N$#d`OT>7CIg;9zh85NlEt&!J=B_ljzF4)t+Qdto@oOA`<1cR)YsHK9t}J3shV zF}>#9#Vfi_QQ$uAOSAj2F;0wK-jy(Rq82^EW-hdpqj`W^G2{F9mbrrKXXacTcl)l5 z4!)vXcv6_fx~Fuba2dM>FeLa_zqO&{NTDpa&%oX1zPY)44ADl19AEyiU;v;LBL7h0 zuxNkZnF5=ow%99aB*t1P214<9mro|_JdqUIw!tGu+zEJp2jAXkIa05E=h>WIdns7| zQ(Fm@eI6~dQ7wekDvc(B1|-rCVgFIpq-fID>TTV>*bw9#aQ^zmpNz%sU=BH!Ggm?@zhF$m{TBSVe^i2t^dh z^=8Kf1LrfOI&P2*?MH0H7U3of7j&Zowk9%7Lh_Vn8i4Uce|b!BJa)w7M8}SRHYki| z(HCji7zh_|PU5Z3zbv(i8J;#cmZ$==s~lUI-Db5#s7LA}zotRS;KRsqE^KE;5?&8> zjx~e<@{ni>8ozrH9b*^<$!?_yLw2v9HeI((v#VN-C~ay%r;$x4R^5!7k;e~z2wmRb zS1kR#+R!}r!eggAG4I?^hid+pAt8en8j{gf!7J>3CJG8neqAZVYzNdl*bOC)Hz>Ud zouX7~d=$X3uB#R&TZx$l-%&R2rcSZAKnimD)48K%cdMFGYadoLh$$Jn~Ir~{N;-qTzD;kG??1Ca^Ge+ui&g}bhs zsr&T^Rfo@Jbt$K&f*6V*p>e0SCkb?KE^b?-I$Avj6PmGY6SeD*xAC$xy~v??;Z=Jv z#tc4a?UoYuqz6U?#kK$OBTsRG&_TcPOCoRS_HqQr+0J6`X>^h?Ps+VuDFi+oaE?bK z$7S~>8Db)uMwz`?_1=JPX-(3=Y`F(e(jK@Qmgu;@j;M@4P<&s+IJPQ7ys#IE$qrX( z(@Y|UHlAG(>WL|3tlicw&e;oli2{toXlS`vN8kuR7q95XEEq&NbX2wp1-`9ksx2Ni z(@`Nk57K0V)baXu`j}(~Z~=$fVsjYV(1~xjl&N+*Qh@Q&YP0-AZhS^i^)~G@repv3 z$qn&IGflbI9)NvTwv3Cf22t|d&Cc})g*@cd?y^3hizesw_|i)_0Q`udd5a1f;!&zc z_oqmX{VN;jCUNtj1F#AT(9Q7%BMXRS+G8k}@Vm!Ym?tnR*<*EokP=&% zCHns15N34b+GEWiN*4I9M6VlbdmlfIn`Dm$2nRg+KYlA|ZC$-Nm$APs9Wd#sqF8M;A%5v&w#!=_*X_!(zY8h$wylhEFKwL>(@6*3 z(LA{TlalKnWsZ&?=fWd1OcybGt-`9o%w_ts*FrmWFYCw$P~6FphDP|KPsZ{9h3sRW zqN+^P_qhg@kM~|s@?4z=x_5Yy@XZQr^rtM$Or$K#HZ0%E1UOaNRUDTdBAl}rUArwn z^DGEX!+T|`V}B0aMDPjo_*G-Yc!4YwI!VlEXgLFdrxx~k$rtrxK|lT&Uj^qv3kCX9 zRcygB0bQXcPX&+fiO3CeU`-O(h}m5WXUg>dS7TQm4(0m(kCtOAOCqw5P!v%VSrVn} zJ7sNBDl*ExjG-dQAxVz}%s znfHC(=Y5{%zCZW<`P_Fv&jqB0;+q$-%v1eFD)WeW@gu+3*g|@*z9OsX0D5wtQhJ=1 zLnQOpnsy!JHudi3))cXTb<>2|Keo}GQh;^&`bP8UD9xXvbBSnk(BVwXu5G1yO!+dP zr`m=?T>AHmMmuH867WL_(eKhLP{t#OqvbeC=r_@m+APizAQ??^F9H zJa>=+jhnV^_@=`q@b{AwzCe~y&q6eN`g_qbg*Eu5`%d&E1pCCZUTk=dH*yE}N}ePn z<}T=pi#pN?L+(?rFgUD-bum}oVkjSJ-m_kaX+!X^@iV3un=RV;nTrvMq?MTo4UkC^ zP0M{ZnfEvkoAs|RroFxa**CYZaaIsTlT>v@;(1ccB5yIzrRSDO*?fDBIVwBs9{q`) zFO8yUSU2DEmqlR1HfbnxFb`m6&nLg)=j5@d$L59M&TSlT>`uh&iYYyn!MrMKkFf+h z`nGZQ2`m%{H~=I4jfyi>fax&Y62fa1EK9}Dt!@@y+`nyn2NIu|uB9HwJS_B%s1&8H zYlIl;X4v`T3s(09PVIg@02P1r+rl87)BFDbuPJ9eL znmr++c4LpWcFoI|a;mBe?#|0!J8Ye?rc5MGFv60G_p2}2Ha?wjxDz-ozfb7Qc4=vC z@k4HD?ty0F!iVE*ot-lh5&+}3wYR6*zXg5r|D{;no)%y;-s249^RszaLNJ#

E)5NI5OOd+(ksi^z-pY-TVlbT|$dvNXpk79b%jtFP?} z8qK5LBSxN{g>Tz673RGRoD~p2-4IrGjgkZT;c_b~)Vuc@uEJ)J$>9Uhh?9h8Q{UrR zOY0M;g<0h!F$HQV0?1YNAvwZDRg)#x9^5QG|XTaxS$xj)eauRVIhSk_p4XWRryikLa9<+ z&H1IJKe|gUKp{)$fJSF9Vc=$rn)EMk-mxq^P%hR>S+I3R`vL`}FoKEoDG_%3C)=Kn zXa_xr6Vu0!TC}ICsaLLfy=~LI@H29`a3q>vehQdW-@m(7^%ve1<+>9Eeck>SXUYFq zz<6HnjvYG$6dby-4ro9RKK6wi(-jasm?m`TMjTYj9!S`hFzZA+$or#{N2vkNKl56v z?XfM=E3i=-5hXc-4a3a`HYqqxdMsz^2qk=cG;LV$H6dxu=+S-y--n(G>Kf82P5Dhn zJo{e!Fm-YiEPvM&JB%LZ zZ3uc2prG@i)U>TMYX0!7*`_2`5nL{h_xo>IJWAY0JxwJ?9yRKo_gA`?J=~6Nrh5`_uuiin7? z$@i_h&HnNdDwh%4AriGPYa!Oxmga`F~Spq zGaO13mouHlaXZs|a^|8J(Db#+lZ$9IY4RhV412L|&Oi7`fyL#^Q&rll)GxqX8Tx88Rv9b&0+@NzN#+4^@jBG^Fs@p{NCKv2&`r26^=jnW=`@S>;fm)xpQ2SaK} zuVrEH#NE@lPHGu*>I51Ca5ThbfWvjwR<5XguWwQ7ioO0 z=qOWL2OZZBus^zh#JeQ#qupix-WtQa-g}=ej{x230_h{V;?^p77Ts?5*O*W)5TV%_ zTh|eFfYQF55{+-$dCUN_?I~!tB%bWAjNW)fvy{D2QLDE}e?H`|xxAVe_54*e(AU1x zQ?^#0MB;0Oy*Icd2VaMo43|yGRgP5_@vFEo+yVPB`KGC|Wl(-p_-8S}6_zb^`n9R4 zIgsu-X7>Q(sq%ALyvf3gR}bcZhf+tbxcHpeLJvCCYG{BdcPYyEeA{N32k9>@9lK4m-RRp_P2@LRg9?YRXe ztcbZ7MK4Uax#8W}81+L`PG-wTvz73S^nRwn3l#4|jWHH^c(wSN7ap(XQThsFo(%y> z4b6?r!{t%lR6@!fOSA>>XB(na_3qL4;!Zqn*;ME7sehU0aDI5hAY2pyG2B$)R#mdz z8lu>L-hHAWAawY-67!JRF0l~i3?TCFE{E#3x4(4}NArt_QTW%*(-I2HeUL;9l($~@f0nyeuh@U=|^TneczVdm2)7QLfwNdlyXU@m@dIK+$_jOkF8G-tA5`QyL+x_BXb2kEdq)5s=;Q zXJ2=mR962AV{HidJ#}a0KcZOh2{!M~R5d?Mc|jj;+00=01e1z80U#7gN2<#-9cuUa zw80-ccsq=!H?$x{PpBC+j2yKbP}hm+IwE_O`R2!uG9EK;t188}Ln_6T!L8Axy_eN= zix!2XA_X$ymk*u5FyZy%wLF`Gh8fB*^DEvUb}kvTim2eElM)sAmQIo-{;p}*s`qG;8gRzWjTwF6tQ^W{V20M6GrWSXFV53IYSe3)_-tcdEWg_^ zwiY4LjS(2~nM(Bk;_GaghhLDpHT6IrF3i0h$Haj8jYW#{MTg4C=aQ&w(CswjTM>QJ zY7SkJixX^XiQ_~6!%Sd+E6@@Zy%ODTo`;WcPIhQd9V_k>^kytVmQZB5CNokIbU2P; zIO?DWJxLini%^!G+XcMCXTItGGSha9-Idp9`<3g_i*(1?M#ybFs6Y3EIHfI=UxWZn zSW5ihXd49EZ#{b!IVO!Hnrz(|%QV#cFH3vArkk9y*XKa7n#_DO{!suPyo!E&_W2(tK!*7aQE<^RkQ$D$w1YvKKZek|F2WCy!nN&X_l`@E{w9Qo4@J zO;2V#7?!mavW;?yvIwB7NFu;)0mpD)wX9QOqKJniL{oaoOb?K7;b9@%Jpn1s<+oQE zs{g#zPnekq%J1wmw^eMn&6R)J&U~mGtPV36W^jEu=77Ja=X$;8MB+PPQOD`a`AT&> zEhM4y0;9}v6t*qlVQOlvsi`su$U{Ro6qIQld3bb}=HL5yvldj`Wy#p2&IptL_c7i` z4mt#0jP!oLrEKoqFPY%Q?edlce>?ZD`Od;K@jRsMKX-m&UYtB^yIIOAbD~~=&vSa| zL)ipS((2V~2fFt(d8hF*iD4K!(Uh^|fwR(it1VPhqo3I_|Ja2mT$n_`cq&hP zeBO{DN^4XM{d3vU@hMj|HCu7D3$tpAt2>SXjm)cq6lQ}9aYNZ!f0gC7C&!pi7%257 z07|BR`7#8_Fr9tu8|UE_^h?N$xWdH7g3m{_S&;a((h(EpafThw1b*bE14hdm|Ci3L zw=jS$x13?yDIhRHCj0yO0iakA9{736%Iaa%QIXg& z&W&QbAV>lWqUx{KgHY<7QHKfIIbZtlcs8*pq;cNrs7SE< z$kMEC0r?R8#TlrC5-sxt`)L!BN%>90mFLoXxFgncnvjO#K`F()S5G$*2U;X z4(Y1<$;nF%e5NzG7V%m$wVPoEx*WWXU0oTuwH2rADSOqGHixt<^)s2jdxEEH)sHp{l z#H3A|9lXo>I0pLgp5p+CoZLRIoigvlIOCN4T~>MnP)mJk)#ukF>WBt{PO4y>f5rG3dYrT4Uj<~%S* z5#~F`JMtY#Lj5;hh*4$yXw)%4W-rWPwrbYCWUNtX6Gi!P&}IE`BhtJ^?SPyd?Jq#N zP>%=})NMI)-1Q}i&R$X%cGzrn^w#4$&5Blu)bfzQ&t1_iy{H<3&)Da0-;iB(nOa=W zoF{&t*O+%BgDB-n*|`qUYpV7z>3}O_5a~6;^B`!t+X5w>`Z63Jbd__mN@2E<%eE+ z?`)%InQL+lg&H6PA3=&W1O>0uZNcKS6U7=dQaJ(-i6ZC*6`18-t9;%QIzx?)r^sdzd7c4Emd@XbD!rGJR#4Wn_w4&~w*3r?qc8vn< z0TO@!fjy@ZL>+Yz%*W71v3CDcRn@FbV2`xH^LvYaS)lYb#|S~2AlpiT$dwXqq?W@D zgBT*0wv?2v9+$Y*O12{UjA+zpOH0eW$pK>TPc}~aEyKosi6J0Md(_p{sm}8<3Hwx4 zUze42{BS%mR)9lh9rhb&y0H)0FQz@9&f{Ra)Z{z*DT|?kdHovL2OaA5@5v1eD zJ+dNg=|``h7(Ro%Z~r^OR)^Wz=y@$utvSNE0#2*P8g2aV_5zI{7_ zbJxpLfZ+3$gDYEGT26QE&rsm**oHX^UvYd3J9gPV5N5edPj@CiI-Kp`Q{X_0s9fJPvMX z;Wb7h_CJJ=tPOEvqGDoJ7`u>y!W>gpc33mNZeEg`5n5SY9SZY8yLXTyx1hkNrie%+ zit+LBImAV`5$1J1kb@(dB9aiDKV~_%^Kn0$NtQ30&_AF__(gZv=V}uv8%G`rXK%KI zw0g-otdxGN)h$y41BiC0gTj!N^Y19h7%dR8`+AJyvaia&=#Jruv4`Bq{z%No2O-|S z=v6jhu@3!QFMqts~Gf2nv7YUz(Vh z05b)>&ouj_ADS#l2pH5ap5L!^uL8XiGJ4$0@!O#!v7C2CJpIiw`I{_vnxr z;jl#&?BA%+wlyd;23!YW?a+{)__I?f-34b$A?ykigdA0+(sNio8KZ-rZ}HSt|CEtI zfRGE0SR27m^DnGQ+(}!!u5SPG>JH;nsyP>Mc6HYfP_e*9tiVEPomp~BWG#V0e+)uR z#4e|(*jT?+fCGJgz1M_~czU2vyW;!$`tl1a4QkTe9=l1JiOw2-s3+}u5xYCbaiBp% zBQ#Rz>~ZyP!bxk*jMD@Tc6j@~Pc$V6lLM!Ej%8s8w}w2y`CyngkcmceiGJ!751PQ{nr6gCN7E)t+X}%Rx}^uo6c8^_ zb&T{v=MpmT5J&nYSwllSul_2p?Lfoa+?=XMcQL$cm!J2V+t5^oHD2jE^h~v@cSdui zwI*nO93r49a&j-RSPC?Er7dFU{?E7+Bv!|bjfzxWP6hQ`Od9KtgwqS8if1h>lmli4 z!7$-x>Nvr+v5cik3d4%7C%Lsq(kd*q7&dvOPmQEP-rNPf{{rW}pP5hU22LEKPajmw z6GFLaEr8TUzx;kpL3MRCM7w}7H&h{-%>82m`?%jz8+ z*SD+@$==rdnYBa$t-8{2O}rtbyuq2Ea^e_~Yrqp{Yh~r?>U!Js_oCjzf$}m4m?+OH zSJ?AMKk~P-Ds{cDpAl3llIgcssOooea!OB67vtw2?)W3dIa#pnr?(zAGqn6IyqaT1 z%gH$#S|Kob_iTdBfQtX^%K(0@qk}d$qhYh)qQ+?JQ+YOcxuf~u<^KOKthZ2xnE!>r z*)D{GHwwiGqg$+P9aWGGY(;w*op;8^ukxNTHr}4C=|?z`smvJf@fuL;%nPd=Sx?)t zA;WE*0<#MWJRp)ORT+xk{gy!&11n2`ZctxeT>*K?U*_wn>RMKiB#3`1-@+KPgveGI z<0lUj5=iwesA*c@WJz;K`6I($qnWV@Tb#x7Khs*j-zZzE7CLBgs^8eyIOz2D?c3p0 ze%<3y`5bo(POcCr>xi(hu$Tj;kd3u<-V^XT0-@g(9ab6+$GPtp_?F0oT56l#8Isng zF;YNK*|i0QS?+~C+6DHwkFLsPIGi?gc7$%3T~5K2lgotj^^xEqq-mjPMqQ@RY4Tm7 zJU4_-VX3#bw-bUF!T2nLjnd_a>?+4-}*gnS`R(}j~2E$hQ2%ilQXae$27T` zTS`U6+O~S~&-Xx|%je%W&yxS45itUUJ-CEBy zj~cr`!%}$VPS9bCvC+W+@SW(S5D8VdcMpF7MVAm*S)?{z&GlcfJ**vATfjN5j@!cf z;fBoF0R#*x;|PjqX{tF~dBG`j%DC#+e%f-%#mw8=+vQx&-xS~z`h(!Y=olG&VA$bx zQ(iT2-_OraT_koI=H>0%x29T4uA`X;e`N!7IRX})_vvzl|6O;7#|!L#ls0{-4fv=n zZEcGSm-20}Pn0e+F@OnpDyX9D^<@o>fjRCs|FDUn{Tj*NFhA`2RtOmQdyWb*pA8a& zSa|(7Wc!9t(v}$c<1uc16(1yG%TL9dSj1`>UaGJ4@;0pgX;9B}-Y=U~B;ML2N-{8-glO}qFCtPm+ E2Ti?D7XSbN diff --git a/localization/ekf_localizer/media/ekf_delay_comp.png b/localization/ekf_localizer/media/ekf_delay_comp.png deleted file mode 100644 index 54d934caecc921be967da733cb2287ae2208e8d6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 147442 zcmeFZXH-*L_b=>oI0ugfkwX&@P*gzb0qGE;NRuiZLQ{H4=sgq_kq#mP(gmc38b~N1 zAR@g<377;3y(M%)=)6(SdG7o5e!1h`G5+gAlD)^?tIW3M{LQ%%{ZvPd?lSx33l}cX zJyBQIzi{DV`h^R>TmAVP^^Q&Pbx-OSjknSh!$1H06F;jvL%n44Q8D!~aCh+Wf9_>} z!O_hfVlV7%>t%26=I!L}vq{scc;UjW3s00E83tsLrouc%DcPIH_5LaQu*%g#mwA!~ z-K2^TmWN(8R>6a1^-FqRS|0Rm+6IqxQ>^b3O=YjhC=cE0J}n!*2Wc@rZ*ZUZYLeyY zUX3pFV&4dgakvD!-RPsd=ZfYsjm7@WqRrpi_*NaFUI7W7cMtdTJ+CIW1Ml|JUz}Cs zP6k%*4O5N}&#r4(5$XxKO~Hzy)cOBxW7Px{p7GzS8QO06fBv~ZBnWZ*^Ybb3e{TOI z#s4vyT=j?k5WF94NoC&3W@+S^9kYoTFvO>?rqqk#F-<>N>~qIDHl8 zX;p4;r9n>z9^y-Fo#d%fbKJuv!_Bq{#v{%gmJNX2zrDTMNv7<%pKjrxt-aCRJHVsU z0m0Vlz(v-xFD?h|z!Ju!hhUO9@MMMY)Eb!Evr_z9n`Vq}gb|SOYF29mon1jy-LZ9| z{pLZxN7e1V7Uv@l;m)Q@o$*z68~Z*lpilP6BNN4kH_mB)ilE1GNd7r-m&T0YklHsM z#&%vGuR76g?EyH6IJd9ZX$?E2KP#@9=HvN69EtryLr2HAeV%Rqd(o=)P>d;uEu7Xgg#Q9KIzhpJSPwakHM9+ zG&E+u;i$mcF0_(<*KxjWZQRHZ#TO~ZA#*?so;qU+99wf%J^m4i-o3JYK?tNK$je^FSY zko=*gV;_SFnE3dM(y!hW7VgoK#j;96l%S6%u09HAh)Dt8xKH z-c&kV#1I&hx+As^b98se55Za(Wc>#^KV6t*&+Fg#ii!iVF9Cz(oNyX5qC=H?eV6l% zYb5+i@F&qb`IYWOxo<8HqRO4ft&^j>7PSL^cL5yR6Xi20`<-5XLmLSR#lab}%z@9- zymue5yAx1LLEEk>Iul)c{iag8q2ivr?25cR`ISC_T;xM8Z|vIU{@x3MZ%?>uhTPC< zZ&PK`C}f74sxBJH2N!;On0Q1X^Iio_tezoLVxrUsCx~7fveV;@ z?ICuxeI~h=frK>B+}_51I-jCgnx!>qJ?Kth)fPE-W0+UGJ*#R0)8JSFBO01}T*>(kmb2u z@E%COS1etIBmUYw{fKMwM;Ir6*n=Rs>p{biiq-btSSpomJ`hHKs>;lU*{8AS?gMf# z`T2bAqROYUSm~%{cU`Gqq4x~t<}hRR(g9(-KY+C;Gc zG1!vm=Du8}jkoA#CWHO7_OdEt^^_;NE{Sd!Npc zfVkh`$)SJ${WgVJQ5Rd~1TzPScsFduKU|RQQm*maFNhPd(bx75KF50h=X@7En`bAW z8GwE`Hi=7=E}kx1-(b`F8l+L7vbP{swH&cvna#3=y3Y~Ici8ol5HCLoU%7c$ z1@`IL&V|lv$9x%TL=V554BS0by(Pu#HT!Hd#P?n-=t!K$boxA6VFkajMDoW}`<-mP31Qh6vG{`XZS(|GXLerFM9@q2ETFow&B~fStQq$h@{@ zaeHt&xyOu>6!g5HW((ss$(q|2`qz*ov*Po~1En< z+{*gI1re{DTdid!*H@`N`whg+kMW`DOoxnnP2BC}@A~tMnMwNm4r}=Auv^X>dsmhayCopbEXB z2P3Z>dr+8Z*GgYb@2g2k0qn%sesCj0s4t@~6+oaHTCMvjwjP@SV`ic}=R-qPt&~1& zn%@a^=H72jME*p)T(RGg2# zGrjhJAt@;H_^_>)((Od*7}s!Yk-3B)ul#b4pDh@^M)wicojbU8m`|4bHirljZvJGJ%lMtH&_#v4 zyxnh9hX@hYypuT>cD|)sKnRe0ust3YNO{vXTEP+4=PDJ|WRI+N;ThDwd1j}WJCxYE z{(wU{UC!&Ij(~pR-71qcw7gr&rG5Vdc=i=FYpn9M8Co3-OQV-(Vz77hkjTxwdXY)Z zq%64G$s<#MXW#KklI>SmjA?ELoO2BR$9wzb-Ff$84VYrt#!TE-Vd?;UK^C#aZ*1s{ z@h*`eDFe8_B}t$)#hpPR>s1a1Y}zrXxXXcD7FddD8Y>^y4MDff0_7pB1$mqirr$my zTg(6&1It5x-!Dg&yIq-f+7nWH5UifbmBY?tuSzPeB;Lq^5LfGi_e(DpN|-`mqy&r< zEO5K{KkPuF!jOWp zxbsgTN8e~`eH$@N0iBJO7%AaFuFx9l2Dpf`6P?nelY-RtNp2I2!@wJ6`_Q&=XIO6Zu=;F*E4P{ zE#Df5>vel;U!2gOQJU{U7{;9IU_~kutrEDlD+HNq1YmM+iX93Uqnn$^v?=3-f7cz5 zTi8}T%y`Oipj`USX^!mgy$5P{!qwz0G&S>b1EEewcGIgP8ik)@AelfPzuv=}A;qn( zP%}lCi{)njhp&8({BIv3Ha1+$3!~b~0ls%r1;DEXv)@MTU!rU%Y6%SkJhZj8{zK2; z9ucZ)N4frKA~|iOcrD=VdHY9Y$Xblcb-i+&ff_A=P55edD1DTTt304Dnlm1W?cHAt z*y)~u8n_kCN}q0|*thcky-Ql$ZP#TL$(>u1S&-sTHq1PJSnWfaP*a=UNZ0p3=L<^- z7qlwQS(|@PdW6^{t?9nEjyMSjYB*P^DhL>5E1#|}B8(Tzj*qZa);H3>epB@xGN0^I z?%q4_YzlziylO#@U~wobr^Gd+f54R=FT?01Wl*cXc!+51Po44H`{j&S+hiA`_H>_CCz0bK@ zPrA-4hc*)o03dX?jeA(3^M?1V9IBNla6bgcsG~78Q_Ij1BB(Sb%Gcau=lrni zVo0nC)$U%i#wS~b=Pv9{MDm65;hT{d%6bBF$_<4j1+{1!#F+UhhKyCPE1Q)aUi0zg zT-$;mOZ(7y>XB2o;HIwfH{(K-Q$se*OsUTSPs-6uI_o)pcM|qDh3b5+cbtutV@eN$ zLp1`+*H>5V8!@${Sw~36B~$-54up;akJ6`O&)n#Ar`pM;X87wBd`5>(Rb9ALR#ldk z6Y1IHQ0wjavUcv=^<5LCiViVabMw03{>2>ajyR(lpsZ^ISTUDdSTrnW(L}Qs4lcCP zyE={?=@~xjikZ+cG-3`nlUGo%?VNAdO^b=uq{qg%r&UgUJp)fmJ8D|+<(wI%?*^1Z z?49pagw%E-4^N!R3*L*Hqmx!0OGti3?}Hd>VXi^hp;Y_3Jo?E0el!x%QQVTbQq5|! z5>s!X2+SdQGE3!ybNrMGw@j{<5ic@dsaGA!SD8~p|1UE=|jn4ZVm)JyT_^Dm`jP`*8DDsNcd$yDsJQMnouSm-W3 ztV#9*Mz=-mSd2k0H zu4PGN(A!}FOeV@ zf~KS_u1ON+Bb4_*cYQQ+ch4Z4+uPfTBWVP-1T^PlZP}cRueL#rv24iwlO=Mo+r%{VX*9iw+_6+1MejYE|eXu zdaSslBthlsjV+pMdh`^604W*p>Z;1Lsazv>qvQJH$ocTo5VfFd4aHe#TKDsn1E-@M zbsnjJ{DPfrejPOfXZAFGjGy1`o4gn2JP8}741AF?n@1g zT;5~@UxUv2^%WY_qo0ZYB=&`+A*DWep_L@_V;6wDRnQ$~P66eTnA*U{hyy)kFh`w| zerkM|t+eDHg>7I*q_#3q2U@S7j{eT705Df7?fSyU*RE_|QS7@Y z^th}?wZQR8re&pb?Q$0nPkvKkvwz@1_N=K-_4(qs5^Y9Y=arsZn^CC&E+JN|v`lP| zEe}_pF?+E~rAA(Z4f4Il1~u-|sHy7ECz&V~C7Rs0%LD(iSeB70H_pl}ZI`_Hei4av z^4Tek;&-*c=wwGlnc)|NUSp}C4s*N1u|rzL4qZWpaO&LSjGFtD*rqX1fFMU;jl809 zh$8b1CJY!+;pGG?7PXMGx2EgBu#!m!leyddPv(3S%md`+Cd-Zb$$Y9Z5^8y=7C;W} zN(t6*ETY3~F-k~NC^@XxzN>3vi{WQrd12-n$b+h>?512=i|?ZSF9Su9puP-Hznh9} zsoRkfTm!Q#EPkUe^h5f`(v584WW4|p=HNSW-mgQOs-7;uoDvQB^(*J*JmA-Z1nA8w zjBF@ot364v5l=AESXjgt9v+)o)^N}%+77PNSO=d3$v%-3=&0{Uc4|B+ex&!FL!sou zM@3TkJI>fBduL~nQi?&LriZ7D*})?-7xZj;ePwlNM7eBWp1yFc4Ya|=xw-p&K`z%f zd4&z7D`_NMd4%M^dX;K2GdJsG&dxDXW8k==JI+E#fm6&BLQj}scsYh=Ph-{T`K}Jv zZ$sq`JHY&a{ABz3K2AlRUqUqbM4IFIxB|MIsov`TAMO()r8elbrC z+>R!mHqDV3|EiU3&!_Z1u^r$XgCld1>>%$g`R;R;6PtxonsRF}=4J z11pg>62xWWQ{X}fL!e8CP0bBExc&i1PEg!4wNKY_|Fu8X**1cXX{8{-%l3)&lj#0b zGY&(8$C%X{0H04G-)zMd8 z0Lggp%uk!Km?o;U^YO)Y3}gZ}GIfc2;MJ@Az40U8)8W|Rxxh+M`61@}8t86BPe|e# zPYNiy|M_yv?Ea>ON<~IwY}8n$M)ILDx3B}&zE}sIzB(`n>vgDQzIM7K`iRZgk909PMin$&Y8P81(v)0_5fx;%X(fbV|JVATpr!K`+0WwFW&(6P!Tpds4tjw$| zV;T0g?~ZV{kbC8zn+CeAL(6xA!Pu@y0o_got}} zN%wgB;bzUV6(4c)&^KhQ9V$*y`nl~?iqcY9>5g)c@ET68s&j(gS=6*I(_BYJ3Z>Fw z3`6t9Yi1sL!G&+->MS zb2zvIi5_hwEL%yMU!r`j{MKxbEi}l=)Fir~Nr7?tjQ&jjYzm`aK*wSnm$C(X)c-ck zCiby2!dz+?Y88#wtb-j36MQdAeufxLjPSC08nxW-x+ejvsHqER*?|Jd?U|&A7 z%ilBi3_uPc-_G3R*DOy}x{-~}7&PQmh^2LPmTiNT?$Hf7@){wH?VKn46LVVLwG2o3 zY&S5~7T%~6&@3OHD}@4mM~gRh3x#|e{Ex%8$2@YY0v;DxZC-1!zLBSPtjqdtp4Md9 z8SO8Qc%H(LItXY4L~SE?V*SX=;F_gwN35=(npZMEwr=<~So#qnoG_16EMR}9c#FI;lZCpWmGM~ZXp4+t0(d0tQ z5~M1AY6yN0DwbX*ck48C)eFQe0IRZ|Hne!8r~5V1^&^FHlOMSbXgiIll((%}!G3A3 zD$$88yDlW~2k55aLFx0}}oEF}_EEsNtSa>Sv z|GDVh)1B#g>QdtF#G`9$i8t?;mTng(XCRCI?$EmHRn!ZfKhy4Ghs4JtJ3GnQ5kjM7 z5Psgoo->1kZHbf{G;#|3_0D+iH5P+&*2du(vIIMImWrOSc94`;&Y!oo=?R}J1zCB zuGYLfTYHXF9J7wYV8|c?It9*O{QTSux^Cvj8?;5N+|N_$E&3iDDbM-f2>Km~V1f$W zO*}j)TC-5@~b zV^<(;aSHZXCKVmAe6}0&0nG3%u32nt?6&v-z9Laq2VOhLw zlgtZ?=*F&ib8w`65ZaH=ar|PWHvKO4KZ&;K&PmScmag)l;UCRfQ$@-hN=rI6#_TH= z77Mf%I|WNWPY>=$;org7zb(53sp#3GQTEQy%Zh_&Frk4w%mIbfriE=JoN(;?%b%Ok1GPRoL+Ol=X_I%guM;Qovvrx_pm0p>sHGg6AbP#S@W^H}=QIgBx@A%3 z?hX~ZU%%nBJEkH3Cm_^GmvU&vIH7fr9^NrI-i#sU1ksn^acIFS=4@+w3XBzRd5CNY zFUtO{1?VwBqpY-}SJHQfyYEf;boE81fwa>Njahr_k8-xjXzRdFIiwK8-$O@5`t&!w zlhGb*J#&E`=_cwQg#LV6>|(hx6npFS6;2md7_$#ke1It4Xs8vAIM8<-`8~m zEck18ehk`4VOi(6*v{HZuRN5sN<2AIb+6%vHr6jc)Rwrxpm)>UatT})Qj1*1IF*6N zsX4RFI~mJl{o8@Zp%Z(uf(e7HcyPyeGIT)OdXpq?F#TS2DC-J$@YmH~9)-h?N|=+2 zpv_>FrhLS@pyJxfZn@{ik(>3&$Qa&PC|L%Ja!ocqnfil>g!5gdh4zhqxtt&LrPbDC zCK%i0ja}&3uuLdQHTmo4vh`5kvWf6 zgAZShOih-XdJ1}SWLIztt6b_SVUKIm@?WAekX29LTe?%wW6s5GfBt0M=gn8a@oa%D zYZ=ig_hS(W^&*J`r{no(k%_vdXDW!wYOFD?oX&s(e#$v?En#p{DHrv(4mE$E8@PF- zJ~Z~u!@hK?=FzB>47ek1=$S7!nhJVH<|0$#4Io4bNH(QA1?vcCfVv!S8lBA&>-}C8 zyUXqe*F5n&tkDg7WQiB+YwTWDE8t8hRjKKeITY4R`$Hjw7VSHkEG8=v472PZE z2h<$!Pkw+bRN(3I6-xow=^f_86|ae=FQKf*w8c4vJFd%eayKWfWMH(I<}Ys6#OkWQ z1r1WKN}@uadYYtJyCQS|$|{n0V;oqpe93tTxVGL>Kk}gdZz>vAeFr8A+J3u3O$dP1 zYHs097G}mCc*{0S$(@=TRAr=rAbl0ayL*G{Yir2Wv>lCV#EItfr~QJQI9_dY*LoJw zN;9HH-12T3O6omC7a=F*gd4A%o4O&`3hUE}L%HvaB(@lbUUER;Oq8Zm42sJ^5ZFyB zwvL~3uFt3-Bl>Ey%YAgW^E5+TOV*?pcV_3TWi*JH(kI71F{cX`{I#_w?1z%z--m;4 zNt_IR4C{+ic3+w?f}CzYIyW}=WKbBcEsgD2h_G7&m6jWul_AI-`4`>b^i^$3#4En# zf<}b3O}@Fu!z)jNZOB0T(s2f^tLt?!QK#F;9v4@J;o6>D)q-VJcx}D?(>k?Dq<&|a z49I-*sc_j`Kof9$qDVM9XsH*PbHk9D0m?5vsm;0K8x9PTTQPSO3AJj?(8`MC8{{+S z2p9XAW*R+hF+%7i18zGy1904v5ED9{M(~mik0)m&K~l-hZ?&wn>^0V1nRev}NqJ5~C%%`YP0g)i$-qryiuK1D@Y1Q_j=n(3 zeN-`1?fyd2_oowknvD$zN5bh?84a2PoH?oikK^1B{b;VVyHM7<+F%jENH-+#)K zOanH0tOrfjj1X-$A>HE*y`>PZMydCIjC$9Y68}s*5K(^R{-yxPsneXMVcoYTtG70g zT4o) z9DFVH2F4e)2kAs8ceo~ET#{PgaKv&Q3c^3>pAYntN@{+u;pjW{v4qZ;_!wE_n{mv+ zHPM?vbShs~W-=%CwO4kvznoA?8r@FPT5 z{4p2{73+8PD)*Ok_m*WDQe^don1_8~4n;`IT-R<+*0A>#D_JTW@084dW=_-=zE6gk z)0|eB$$G%_nuQnu@1uSW;P_q9;7QXnf4BjmNEFJ?1Z({4{nK{H;Z%-MsxAL5~X_Q2^;3 z<8P@YYhm@vFJ!y#$*pT&6s3k3_*bRU=B^?fEvzfi}p-#DOhw8N1<&@4eB-CzWFk%|CZaj+`tsa>PUj6= zt*uR(>ABi=*KJ&BCGAxH7IVPu_r1|k{DSBfZHa#t_Rwg#MbsUVMj_-}g{v&o61pQD z7tYVD7h6Le;rdWTtT7e?%lrIU2-a?Y@l{ee#tH!w{+rQkA8>0o2o>gJgOSG|CZLhV zA-{su&%cq!2|bPHcX@UefvKHU(YBE?e(LiR3uizEhQQ^LW<*F!@kben3Pr}iJ6YLh zI=p+T5-3w|oWs}2MyRj5Of+nNQ?rV2 z&IczEdKS-l@3{AM-SOHuh93b32|{~81Bmk-qFdLSDue7cr3nP_GRShRoCNuN z5@nf`61zJ}i5m4*aJ5|CSHwDr#}$bxhgXrJb2Rq5pmnk=uLM;)Zi#1XZC>kSZB&rg z-oL1&}GQjF5`?r$F=RFrNvZApHCQX7GxXZ-1`i z)zo~(MTSy!aRH@5|wYJ0uA)=sP~;S$j0wWGzPUt()2($r5FN% zOfuiwp{VcEDjt@48x+o+v3C9MNz!Kf-ZS~?l>Y6S#M*R z$!kSinQZA=T_XcAM8zow#w6G0=d%IGHeb6E0?JTXIR~=oih$}wj}cBTeZ9JOqg3|D zGm(nznQEzO+U}kyy@fnQEYqC%`t;KNl!b@(6RK1Vii#@7>3jC)oS`Ez={2j}a|Gil^u>9R6&O{xF9VZ+I zi9WIk$!hDOC*4p-J1m-Tmrpg$Ud@|_98(G&MHbU`b&a;k(qdJbD(tIZ2W%ny*PHp* zQU?dM3)f3B7cTJo?Xp2!} z{-cMe{qDAwJUc&^s`bnQDO_4ws75yT;1Uy_{di1yl4Jp42FRWyi11JylX8A36r{J* z8f)j6)F=O12(>?!Sx!fVa~|oX;Vk7(^J?$heg*!ehm+qT9hG@ec80s|XQp;%wP1#> zI~9IUen0+;5y(4z_1;yTAu0TxCw918#7p>Fu=NxZuWo?W-DI}x8%4!D1TwhJERKR< z)8fx|4uW{RujC=iQd#|rN6jqv4$eAD zcVVtaZu-jb^u4c-qN1F8mzA%wTru0{RC);=(37IX1&?{xJJ$StAOCoMw?+L|q4Vdd z-4w*m?2v|UZ%S|mGsEGRwB-;*n1V12C7*b4{vzpG^ufjA227M`+W|ZV^ zoOH)`J2Ca=mR)g8O^EgC@w)H%V}cqY!^Z(o8FO}6xzlMey^gk-gHgn)9`5=!Kk$8#3J!rS=AV+ z@}}u#M zd#<_dapiar;>d8pP9lgW%f)HiExkexMlZzNTRP#f00pius)rf_8#lN)tYg-h?y7lZoVJp+)-y7ph#&uczm&@)W#xP_%=P)J9h zI`1%R5OdFJff+;6f`2v(YV_EpEO->Vpbq*9|DGSE9*)7?^19D1?1vpsMqm7`l*6xz zS`AwDmh_@^*U&5@L>SjHZ3ADAj*E^eAzFgacDnntF&snpXb4w|9Ng&YU;me^zwH1O z`M7hE5|h0)8cffX`onlB=h0E!z;pf3!`+^sby1;rbe6djuMH{tsmS@4QQvVOghsYP zzkE{@?O&*bP0z~c0Hlm?=k^%Z!|7IO)fNI$9~~v5u)+LtBTvV~6*vF)s>z#ULR2r~ zqp-()mGi^Xrx(c(H-c^U^aSWPXePTZvcWiAoA!xyjGB(>1G>r_zMDKew8hZO3Q9!4 z@=|=eIj8YsUa{*MmClsP6;egZ^`f@nLmRcRkZKB1yB$9{AT>%YKpAG7JuotoU+~uc zeJ>UON%U2-jv|?D#zDM6bl9&?oxaa)SCZ%~{_08Um=+oQCoxi8eGc%Zykr) zY=PE0dPZjLeOOydU5}k!51f46T~O3?oVw1|gx_tTu>G&)O$M4&S{!aChMjDnHbakA ziy5ng%;0vIGNUlENtk4-{9putzHZN6kpA!QIGseFitN!&aVmPq=7_(B65p=1sS&9c z;GO6E;OH9!-;9WALJuH(ru`#idH$soOGYxE?%6>XFlT=*MUXmLqu1HVp?m0Vre>;8 zI)Uv*f5L!HA8ECqqiE1m5W6C{epVy0c?}gf7olz0zUe!a&SvbdxB|TX%{bY9;`+Z- zfA;8bI5CtdURC9*o%rdZ_1U6H%T5aLq#bxN6HYH;(cp2kw@MxErebhIK|w)Y-g7R# zJQ+OUYGVo>ukI$}XUvMvP9N6p$%-%b@_*i1@+$P-qZVJbcXQ8!dAhC8LB8hZ_zX!` zuHdal1;Y)&hdZr@nXTA*_uL-4qrFkxu!DB)>GkxOsBVlCg>hgoQs`%8t}`}c$&wKJ z$%i4SUyvi70wJLVj!FTkO-*vH>UT z!qdkGot+osI#r77iT>oAbllzoNTIr_!&z|Me@JtVrJ=S+AmP@ zg3wLI+vFdFTgTTA1ykBCa-X1Dk5ML8fs0fA1kRf`CmTHHmlfN@vE4b^!ss-^-I-0bfI$=9r!9_Uo z*$c2fKnY_nDpe*=TRHmy9VSGTU(vh-;J+RXGE6ADC)YR~7cFh<+TcmskOzXc=?6W} zHm98=Fu-6_gRAj5Gyt#iT7UJr;**U?CL+6$@?A!3ZD}Fpm8o=KaE0;wiu(EXGZYMX z)fL@c3&aR;I!1>BR(8TsSi49Er3Ta}im{p~L9*lz1{ zvb70&EtSI`5*VEAm8=9PAqKFp+8QIjao6+im#kr@fKcP&zt4evYS}GMgiF<+1|Ih-u2RS z58D&LFTYO?yqVMDC`V(iWK|pWDX4Wcv)|18*ru(5kz-@4WsEeL$sE2qnA<}5Uk8VN z^CYifqJcuzEzP~v7rBGCCL6sw+IE$6eE@Tp22vF>q?NQEV-Tcj0k0L(Qwkbv2%SvU#SHy)0#zI`3edM)|e5yFjEFNN&Y2* z`&aVl#UD03@9y#J#9E)^A63%>Po64ow4R>@W@(`1C313&j#MCC{V_-n>&)@Dm&5!g zIwOU7H4SzPvR~%Kg(jo)*D&{i9Lj6VgGh1_njh*~LZN75@E z%up4#T!Iu%ugK3G%$i>BL+7@kbuHox&G5>@yFsL93#R^*jc0rI{vEW~df`K*TJJDJ zY1f=(T-~CvkrC7IJi&GKX4wHl$E}#Cau*2RCi}2*`*vp33Qtp%_ydoDsm9WCxBu>a zEKzUXygA-%J)chmo<)WoMDpbX*o=#%iCD_{Z)8OUlVR4U!Hy;`A0Z$+e&8Lyo2jJ6 z7w*eBEhhL=yaj-xEY+AG4#0)TWJt=K(1ddeYF0TU8l8^Ou*5#n*R0#8u|ka8zpa1(%We_I^h;Jay_r>7aD(|`fc!TCV?r*`ecqZ?3@w?+@1PC0yW@KQk0NYbHIFO zd@g07h^_CgsMacfe&xO&aMsXkb)mzB6X>QXmD0isxA3mu&wV2CR}~It7cpuj8pOlJ zk$KdVGr-bUS%FjyU+I~(3%tE=DwNuQExP}K)9lw_qzly^KNg3P&{iJI0YDG7X0Nb{ zoE%NGvLtDyiJ(vS@saf0XXL6dhy;5pxx#&FF#^H&6v}{ z0(oKYwFzxfoMc`jhMrIQ9fopgmo_PCzA9cvE2daGuOlbqR>9g1Sh5fE@%*XTQg+|# zTqn4~x3NG~s>khu(@+tKfa)-%1&uL^`a~=Xr=D9rPGtBMLr}LyeCsJ*G-Op1c($Dg zJeUc$?JA-SHk_Xww;m3->y-Z`o498>Aq{%PJfdbF;<$AmMRB&CAx>p;uoswHCKR&t z#5)YCC>6h31BD$ss3?DGb8vmT62V0%a4vT71rUk`TF{w#Rn$QFIDvd9#Sz*1Tsr=q z?d(%1prARO%Wa^mv!{zigNRW8wBx zAH}`paEa>fmW1h!t z8(PLDhD54QTbrGI41zGC;mj55)$Re-x6V{=A-=$-($~NkvdxNm2$Zrt({}pEx6~3p z&Ji*Q;ix_OatFQqo2AXLpUZxB==s|T;Pp#4Yh5&hd3YQsNuy$2x5H-a!e$QR-2OH< zmcv`^BY;KBX{Cns`&akV@$?iGU7xP24)`G5XP?~xxG}*3Il+h1$Y1d4FVu#Sk+uM76 z7pj)67Y4JTLt1m~4>k|8hW_z5YX7_AUXYRhH}1Lc;{W2?TVdd-CNkBb*45O^l=XH9 z2xx%8h(+3&S83ayC0?PD{4?|M$?g!<3vDaZOylL_i;Rfqv4c~i5BmL&FJKFD-+zSY zgN3D~rHze^NF)*t*RPtma+_BtYh`0Y@%#LbgZUmE?Ck7@0!G@}+JS+MSTKu{R*pho z^~FCd?y+VLNPV}xaABs?PCUKep*AfoP0R08_%$30zQQ6T6MW!dVPWCm;9zKIxarN# z!NDDRFk4hqg#p_fX#s4i2V1OA8e;q4pDhLoC0nOh8dlQB-t@ zdPb2VySTWRsCZO@1&1E5*C)SwM;rR~vwzc>B8cXK2immWZ3=GR*W24m3%zAh(9&Wh z(3>M>`z9^TWRp>drEeMyZ9QD#DAYI8(-WJa`GGaij^W)~(E;0Yot>R+T-}(G($X4J zA*CpDx5f?(=27mO!NEZ^l)@$J^@&QEq9TXS7yq!G2cOh2%XnKvdN5a{XCTZq+$jhnzw3jrgu=75^aO!G~~ zF&AG4hob8|{QOb*U>V^b9nU<}(a~{rg;7~JR%!qM0HC?gYD`;B_s!F_Sgv3H+iRiw zCHHOW++Xzh%zeFtw%S}@$1hP|@oH3%kqP)-{hS78Po7mFN{HDJk8Q`rQzQxp(iLm6cVk;}F*Y!w(KOXsH%#Q#+syf8PH=?B&asXx(Zo zSRkdWxtZFdjI3i>hRguFtxMHLq>_oqL&7!*wH z?1BiMN)BozF~$W=9yjNdx-m>7W3gDJsE;2%I*%679b9Z7L*X#Z{ySON6+Zp$g>j#|nqAxWirO+7G(IFi=MkJe=nf>hPzCqE|y@MBh zOEW{P7u-Oq1vNi~7;7g^veH?kvP8@^5AdtumEna_r%GTCaNeO>sJnJ`Z zIeB^F+8Pdr150HV7Z>lHY0|IyH1+msR2btim_;IygPB> zm)6$-&%gYB+?hz78GC%EBCRvrwZ`-ZW-|NbkK3;!BfGvvGosPxJ2ZAJL@ z?W2AvRS{4qsHv%`vhr&b3U&R9lZ3H}Nqv1i)lt{g9qR7xj*5zEbiNM#NX2tYYG+^l#TN3?1|X<3;*4CB=pyz(ut zrltm<=nN7{g~Q=g6Hro8^8NdFO^aS9i88~or6q@K9lqqA-)Ly&=jIdu0NpH^VJvoa ze*S^yoN}XuNOo3sHiS@QRj9wXu%K>2eVf{@E2%GQp7&hPc}4Z6&NNF69UOnOiHQl0 zcq;g^GC%K4tf((4ENn!fxMe(UNlVuk7OE5sOGrv~batMdECada{mQjEe@hEB(bMxh z*m`~pmx)(pWMJ5y=ROahLQNWlUU(#Ac_??2L?W%MtdK}q4;%++=oOynHn}SZq^zwB z7Z5^^A>Q8JRJ*0F-ff@@kn~>a-@reRl8{i??SF8Qp34FW#zu07t}HJvZ|Pr-n4_|R zDqivN@k)RC`}&b&7!WnmbB*G>?Ku&AiN zuP>QQ4mn&*i?~je5IsG;uv4NnmY<4U%7jy6H}}?4DLy{6yr&TP5n+!ns;TkZTNxe#P$r`o?$AQVq$B3$=4`tXvSq!C(C8_LT4#w2 zs(}HXY_&&6M^hz|3O@=63R0Q;zQx(JIbb`6S@6@R<2Rq4^6zgFMAuPPW@fVB@72pW zP?7uhd(NJWI@D%Uu@*<*F?Myd*rWnPUdnX$%gy(n`1Z|%^u30P98zUiUGm}d^fXny zKPUuxJ%663Q=BR7Zbi|hqprix-oEhq7Z(IoGS=2ys6;|riE3}!i<>DaeX%}2nwXiH zISb=>@l(H*{u~}3Pfbcn%FYHj4rb+^?G-7Zp)nb6P40D`!L5o43wPRzuzZT*)gxB7lEcF4 z^6$Geh}cJu`rT$n@ZWP_R~24WR8pel)fMtxUq!UU(taE7vx3OHY15`FP$AqVZ-6r% z0eG42DIAISHH?uhTkNvABRR9)*4O8QC!?aGqzYqVW4p10K0i3@e6Ep;mv^nBe0^wo zdL2xy>eEx_*dy$^-j5}}eO`nBl$u$FyKYZON$Fo57XA72XLr8CMtA@EBFT3{f`emp zyY!#4@eevXM_q~(u3k$wD?LA{?YO2k}iw`S9SZ|$`L;jG->|hpm8O7+N zYNkI@Kg}X%Vlps4)}r?O%rY*%+d5ZjWA%6NA>O%}8EtHp#i{NEPjBo_Ev=3pp(W*< zkzYZm+&~yP6g))FKQu6~@5qr7ldAjNU$eWry81ju7!hSL68VVv%^%Eaqe7S@#RUa_ zQ~Umr_3&86)X?wW|N0__W~SlVRDS=qZQG)vqm2eF<1|%O8GjzRB ze|lix`s8bAmF}visTK;Zd&fg=A zS{w&39-hd#G$xqN-dMB1fPgOF-8SuMdu9Io`IDyoZeUx+?d=p49c&@;Io{;O@$qp5 zCXZ`adCeaV3z{p(2wD9eu6HPz4NyeZ`2TB8TeIu#S=()0Tuir*N1YBBk{PJ&eOJGaA7!tqB1HuH%)A7*gH z+-Qc&%9>f|Fp~COaRCC=Fn5v_2lBgm^{1NeO3SBDaRfdB5u||mZ_SBH+}zy#-b)6YInRkW zWRmt$Hc)XZNik8K>l@XcJtY$v#r8kAZuC%~UjFx)wD0=&ccxfbdD}bpAwU)C`^^0K zP|f7UgAiC*DZAsU5Ir_3r<>ES_t}9R>?r2^dZ;)7%u06ck)EmN49Qk zB+=J?zH{desc0etfh0!xjm?oq!NE!wFMf+WWJc;MEq?uaut|YAS0QO%a*Q$PFi>?q z%E}LDKAPt|Rc3c^AT_;KXnZR8w%Qe-BRDvifq@}$TA-$;=CyoC(ez4XQrmcMv3nS! zgxhf4Q}u}ASFc_n0`>796A@YTT_5oU@#&M(d1T+d=D{YUlZA;6-?^F-m*1*-Prj@6 zTva!(k2y#~V=P23Dx zQz>`tD*D_|wRi7cNIlO^nJF$M&5wV%mW{CAH?hHIhoRec=jXi>&qobU{zUQ`8%u7o z1Zl*;`Q?y|c6xh82A{Na`Mv!o7W?jJrKhWKofM@HVUMsv@a!10mj}W!@?L1elvjr` za#Ko)ifXNtbgl`}(nik?R!d_yLnUZT)E#5$;N<7`9f@;41(bLBGPBpD0PYJyT1@~Y z1J5BPOUqF#0xyU6Z2l+dL*A;!U3Yd4zJH(fOF#sQJja|C>)fYLpE5Es=J$Epgasbh zb@#pW=i6I%Pi`pq4%|C|E5CjFw$J=)=7pf;qM{-M$FkMATBOJJ*4Bi?#QHdirIhXL zcBecJs6G2{AhlU&eQIoU_<+wk#8VIzte=be!mc|nUHjdurA2o2HdLn- zM4Dy;$}T7OlIDK@Mm}pLI|r%0t!-@VFLbu>@hMYG^hB96I5@cd$MN~})zwvmbyOzj zy4C;^-eqN7eBG4r=FQ@CP#j)(^ytykr-zXv*9tV=ytnTa$BIL7vxaw!&B~2&A7PP0 zYOB&6Y-?}F_20O0qb^o7Gt3YY?!Wz(4i3_eKm6k3`yU(@^gN?sWR%%4fedMnT<=x= zlgJ4X>?-%~-ShbKGtldq!>OkUSNuFYJRpN1>MCBiP&m#*PI?x6x3~BCacg^q zlj$QYiEjJiDcuZ5-tmbEQHQ?OkGuKjE%mPE>S8|wG2l9Mbz@vk^6^b0()0210_K>L zIBhH}Mu-J6-Rre7ZEn_G`5Ao@Le?6!5x``uF@y>^nS3mkcc|u2aA8dK6R<6Bp3z-#_ z4lW<4(%X9tI6ouNegI0qc@>p7{Pn@oD3qaW3ZcMVAB;~XBqZpYMoAVRBco`2qx`hl z^lKt&X|6~b6QsSxlr2ax#nT8a#nabsa3+64AszYn@ps$2hYugx@FbyhGBYzn2@^eC zrmm@JE)q+9MC|BY5-nSFtwIQW+iSm9qUo9v7!+jI3(`!|J|!6$8K@vbC8kFW;#mBj zh}h{`Sy?TG?GlMiPfJsd*@B`(^7!#YcLRBZJ(QdCE`iYpW&W$XP!JVwVWOZgc1&&? z$EfdRlb_$AEFmubSTV8F_PLOiI!Y05Gd*kKky5F&{O1owquTf+Ml?wyWpvasP&hq$ ztaPbQ@4aP{yXtaLi=|LvVj{5i&5gCCwY4>*kcJ7*h$*lD9>0fGVuX?vdYu5$aUpNt zT9}x;(s<9}zhloHf|jk~JGghR(^9Ydgi8@(B8s<)iV7QjXB3keb)cRy>8Pp`de_ zOn#e~*eTkcm70|F(DS~^(^Esuf(IoKsBnqM64pX7L`*cgXA}-pIQpp>?ZJa! zUNV6lb8-anoq&LnDNdORs3*O!y8`zdZXW!DK$p0s(=c~7?$>n>7Z(>};}=bqNQINR z`BfLWBI9q)U67amoEUA9qQMoXy0lcjvDVygeZ#{80Kq4T1NL0FaA9^~VamI#%{orlMstY``&HfMMxnkGSOsFc`DkK9Wo7Tsm^3F`pzR(r zTbk~b*@4{1UJMqg)8F5pP&AiPa-BySa`W?dvmh_@k}m}&h|o7RHHpXZadC~)*UCZ2 zK8V4st;@!oQZtIT_Vs0Grsia4Tie)FhcWx|y1Q?y45aoQPk!t9m}VzSD6=%5|IFgz zw1Ka;0HTMJlM}AvP_P*?A+4Uujb$Qs*!L7*?}O}lyHl&Tm8w@$7|*y1LeC^L&D}hh$t_ zT{#cjZ*FeJzR7`M668C}+Ze_-&#+dNw zz8{^-G(Sm)YArT47Qo}s;lmywroU%rFQ}^K@vD?R0oODb|#yMMdn# zk9&`(6z6APiHSK6KhR7y$TB{Q)m(Y%cTZ1`*L2}qayZ}sik@982_#)lUo~Tq*v5G2 z{;n>1Yy%Jz?{-LWb1U&hQ!`7IEGa6hUzA3uIfs{7-rZ*HiY=g_@wifr@=)+`6wxc5 zFP01?{Bl^}cd5P~96T{G;qC2>Ov&$?o!T;{8ZVXJG6te+TQ-}s3GsL(B-{zaU9~t- zEIFvZ!k`M5LH>Yv_gW#$O*?M

DdA*J7GsW>`=Voz%@6<)K-{Ajmq&=Wuxj zgHd6s_Wfnvr=Ifg@YuE{U5egFyMO;a%5Fp%AWCZYco;8Xl*h-)aYe*tKdoLplo!Vfy4 zuRKvAwjLByM^DcY5RTg9W1F;y<3x{GVsg^b0Co1CP~AgGS-LuG)69Mh^eh4`)x_DA z3(|IPGuo_?TD;d+JtAscrnDly?$2<^{LKWK>*D3hrn$PPoqf)Qdt(Igkdyl)EF$i* z4~*EZyR7W&=Bs~ZsiYrFfjI;N*;|~9eg5VRdx$)n{|-t@*FP#1cqMUYN6QhT z@S-v7ki|Z}g9uKig@uH`r6Jp**x@{S^v9g&PFowB2=N19bOIlLmU*lt#J^dZnwr9w z(c*GkUYFGV0w-to^|6g@sX8cHEv=E^;i$)tUCxD<3ORxQ2?+`seVcD{)Xd!6&CM;8 zPQV1$S1Ro@zOa&(mPQP|(X`b`I%IWM@i-b2P_D@MlioVy>;8q#BjR=0yoYKLRsCrY z%xGUS|ck1|}pg^0;Q$<;MvhVxZ=B}=kCQB?(Pqo{LK5idAd|0$=DK08Ptqkm= zclq-ELx=LfPfPJPO-X~BdX1v2ANAdk)1lzz3oUCR&|(8uTClCpf6?a*BsBX5{7Nh0)+w7df!) zR4Rx<*RNkE(f36~9l|jgSm5ZUx}brGSEo%p>Ew_sK-a>$1<@g5&G&+*t;U&Ho0c`{2ua0yg#Oiavl zBlYr-Dop%F0*1Y3au#F1WZEtH(f9oI$^SAe&tH! zd*>#A3C0E;=j+!oaAD_e!*+ zKD zc=(Wpv!t)ww_M{Zn`8$7fVj(--d^vI{yTe3T_P289r~r>R28BqEo6z}KubddH~j|S z8k@)+9G}dNbWJ_zT3E$2G&HEbOnu8&R#wvW^7%kzF3E`8`S370+9Fq1R#uik>dnpB zfKHgg<4RFTe)gT&iAhP8*b~;dE1oskn>TMpY!c(h7kR3T${fH=@%(x1TWt zDkeAI#ZC+OY;t|=usM$lvy9DBDwvuMf<{BV{Z8tJ2gDhzT2RWE4Z!EQ*;yUpdf#J^ zQ7oluqyPaUR4jejg`7iBaZCp@AA#8T_)#Xd{tzAv4Bg+pWr2Kz)`n5}Lne<54Iz)Y z0fIu&!l+b!{OFl!e}rz^9TrK+HIRzHvDA|D59e7@6BCaM3SMT9xEmPQt)*tKKFmztUjYHIN)&rsyfd#>p@lwMI+SHE(_we(u&uDdeU z<8%iPw!Jn~+;R0JT^|(2YG&UOg@}iKeiX^d)!p6QKdICZA2KsC@^sS$&Fiw_XMP4U zORfJITohr)cL55ZoCl%P8&43k1j`K;+k1ZBEh%F0yfJ^LO~hW%n03~bB*1w&DKNdMcW4;to&GD)s1b~}vx`n6^2*2IK_^G)NR+ge&%ujO>g$jW;0&_N?P zuclT`o-Stec?hvHIVmX!Oq76$93Z#6ygXtP5+N=I)N9Q(PEJlN)>6a8x;<1>QJOnq z>djNzx(1s-JwZWU=zDSr1MlxICok^??ZckF<=eNJDq5pwl3toS_A)SVM|z2hhyZnf z(`sLDcpM$Av~fwrHS2%90Hb}z3F+x}9T^7ra_=i2sUb4EVqQQn=9pGfS)F@>@+~gga0lh{gZsl7ct zV8Mp#W8F(zllQ=K>b3@hF%JjF_k4%`rLrYS&f30rrV3tO#rk~Il$2B9KLL5-&v?us z&^l}TUs6|Z{`T#t9d$%R1g<6&)EU2Fi5QYVMn;2qPJO)ehImX&z}>qSjtjF#fKG7r z{c`P8x>30lJNuiZYz@RQ5R`Zw6bXjrvYsBf=0rR;)()1*-af=LjPo1SIBQ>=#a^lr zZReXI^YY8ruk@#{|AL%M{*(Am#{(XQ3YGNKRBj0gy+n1aaHXGd@~=-j{`ePZ5h}wa~gxld^; zZFfd#=~{?r-^1D==|3N+j~J!{Izk`j_{{9a5*$fZ6;SR~dChP{s3 zHv(WpgYVs|sjaQ8sVV&3AW=+fneg_lLtn`@s_@#YbHRCb-NO?TUJyaC#jjY0 zgHfGDM?g_=v5}Wo%L~cw+wyhG8<|pj57{EZ~bkY2U7_XTW@;EL2cX0A4}i{NC~s3g`FlUed_$MTap- zdKw$`(`Dpo(7(^c zU9CYifcZQXTMzmSsuI13?f0*d+|tmuz-hs>lBhR6Bybf>PJhjjBfgu%wf#utOrePXIthbIb50JM7WrC^%@uocdo>vV67s<}p( z6=okt8+vjI3g#&2+n+f2eYz_*bx9V3g)~htF&V`kV?zv3TfhPXGWwFc`xQwW=)=&= z(Dy)$AxcX;AMd@`iGcIAV*+7)ad{*@(BJ=jPETJnur*?xZn_A_hL;z6kUs?k1Qu7d z_#lS4J>J|1?H0-5CPbt%5Me-3Ycqk;fEm2p+}-c3B4l1_=a`3R9BtE6R<6TPqV5OD zc@i7~JWKR@0{oSLgUb!+o>Y)Z|` zm)RD+#DdYsCY2ANAIeIEm&pg zF&FW`&1BF8zTI~D^-x@vWPw5uX(2SER;pwWT$Xt~Jt#8dXJ= zFZ=TfwRm;)2`(<{vF1d`f7Db|z}1i*_#tMeYo;o*Lp~~oMsrzRoi8d8C2JZ4MktuI zQM^hpIW#nYhfq>hMkMup`uK5cF^d7S=lb$UN2ZZ4pyq`L_JyfP752+ugt326$D;PZ zBEwFDK<@$Pf!JzBRfDZabY$dIUnv+g5Kg@gVXZit)6+Or6i(ibuJV`U{q zMA~WK6ZcJ}XLohefd{HB;=SL%O|ZJk%Eks#mDCs`%#Eavnk9-eMn-Tb7(^s-12_;!4k|^0bbAOGpKB96-=sc%=uuRZ2tp}95aFA{X2fa* z6L##_uUp%h&MPTRtp9Aa&IM9RHz>w+bi?I?{M+>ETz;<`%98^vUScP}J%~yKSH05U zLRJLD(9_!sJrfm2;uWa(hRGV>ICRrBsj0(QWCONr+h#bqF$z^5O%6SX+!P=wUeCCTV4H@EK87VB=>T1oa$Sz*(zFEenTE_p3X9FFGa<# z#Acfg`MILMVFrd02(+o`rFyc9cpP@YdesOd7kme(X zscrw+xnQXp8#_!-Kc2-Kn~;~cctU#lf}vrbGd9b2(=dDwsi*Ka)>ZT&D)DFLf9*{- z-aR?a$~u51zd>*qePkBU@fh6T1-e3kY+Dw8&D1L#2QcvL5gwkNz}{U(*8xtPodL@b zu*=HI;5UdKwVy?Z-568z1)3ov^@(8_0KOr4FJoU~2g3s})?q!cUYmWFMl&@Ra%!>$ z{hn=*oW1`kefBi3%47_JjExNdm3ltpBpR|;s(P}no*pb%&{}{Yu~I?WUV6rxRS}_O(nfJkQTxsu~W$&{B0Uh-*Nx(bq4rYYJ&btQfM9`|h@8f4icwr<^e+BS7APHhh~|L=Pi z_EC4jIrXj@w6>!vW)8*2Y1XZf$$ z$S^-hr1-~=kJXR!hbt(ZIdjH-c&s!mtg%Y>r$N*Eyn=!P00Ee-u0j;FBp#zMW;w%p z21CY*R{2WgV>4i)MRYVXs^o;>`!`3_2a-gDU`$D}4p_}!YB%W17VeHkOmDMXpZvp2n<2GxqtsU%VHy?mZ1=YSo5 z|Bm3&Zj6(7tC>phu}N&DV?rV#NH?fS<$)~7QeL2#i;B=3b3R_yjnpS;-I}zX6kZ5) zx_|%v&I6c~A1lqBogOf%BH3N74Cstb1OIyAZd)_eLkM^fOs;McTTufS4D4|6;zgkP zQiA}P8}<3}NfgTf40SQW6V1YNS|f;bPsClh7#ID{$|cfK%;V(T>!aUT`1vz`{klf} z@a@|-m`q^X1b3&w1<~mMm{T~L))@ktEYp&cIXO5WoPi<-YV|BF+pu>xz-)4Ga>AZ8 zR`%Qp#y7xk;03(+>J_5@Am%hb+I9XVvVsrEtH1cZ$Wfp)Iyv7Xb`Wr!_TQ!p<=?v=@mbliWJ)f^`R;zw}z(l@u(A zz5L?EQ7hRvSPe4ER>tqr8jhA#UNr)V_>ov<%W>8e^QRHGM>hkfK{CL#68`747g(V{ z=g)ygfEQSWg|YALhQ3BNr{qhy!{`F&hpB<-0CjI3)CTZyu=_p5xCRH;g2CFgdpCKo ztO0C^9RLBM2vScjGq|tO@wQZ;3c&ezD1EE{kqx6^iC_)W;(Z2j|D)3X8H^##5$?FP z7v<#}`_<0OBEb|4?K&%+qb6I02q+A3eSJ_t$ux;@kEoeVZ$C z|L?v4&j-W{#N*ljX;Xtf`hR-e|Np1|8y$>EA=M&<{l5nf9>jJ>?nPLHQVh%uARw~? z+XPhO;-n6sH{9N^SpYs4!MVK%qz>P#c}^z?YSrgwk~O$M=s+idXAY_;V5wL_Yz zuGk=rXMQWgh@sCHk81!>J48>v@|nSbfd3FHxi!W&DD>%6)wSRL-5dyB4I( zzMG18tdFN=!g;oU4qa9r9_1ZC>`h%=);XO(*V`RR@IFzg?8&mL@3ehZTH@DnNn=j> zscql|iwX*koj8H?q9tBn-9{LRL0SMTF>jW_Z;?_^^rH_TO~3Gzq-1IJEJ7@Fq^HV+ z76wT|aXTCkHDHn9QHK#=&!6)cAA8noo!)G)X&{RuB9hO>)&t5zCj!O=_YQO1QAQ)= zJ`Bb-(8y#R4k}%gd#+cV#YVYjgMqg@uKInH?3t zjrGhY)lMsLMRK7Hrmam_Ts-C@!591}dUKJZ;o0fI;b9SzPdnV4;Qyq%ajkO=M@Yem z12L54=uzWOL3;s75k7yF9WpHAE*$vfCt0!60=SGuN+FZCcQ4}zQ~!4QJE74h1rz#Jg!F@>Ri09f8r zaS}YVBB2x6>*8V(y`titJo!G@1m7?4A$Hd~lRR2n?Cqy3l+$o`ehiV4wV}}P0}FuG`Jw%g_RA{=z}Z_csk#NS}r*SsZgF+a8eZ2_ZL z!OAyQ+GdRg25HyvRyY=Mpq61K$!89OjBrJ`PEiu9Gd(Fi63cfRZyc73>fH_k7Ha9` z%a^eexc#B5c>JyxC0Yp(q2O?S2TYDCm{x}4z$f}3819GQnZC3 zGa=y<#y%OW7noz+Y1o z9HL59htjg$hk#3Wf_TWEe>rADmF27_!d(VGvcy%}-sa|y^DqteXne_b_?JrSsN$1J zY+Z_uXr=jmSAn}I?76OWioQ^)vxF%OjMKL3C-E{xM%D3b+amnvv|sEloyCx06KzpRe9V#%K1Uc1w;%|pr>~`Y460eam$FVgw z9VRxMpUqs{C1HatnZVu8$oIa(iq}thxq%xQLQ93>&OApQOWIo>hqQmR)W* z81zUJR4DStaKG0L?e@~39JuJ2LID!iPuS^qjZmpce9|=04rF9z2!wuukp$E`T41B z<7csKdWtVg9*%DRd(H_3 zg$1Pi|DOH-pZ=e5`2TK9Rvvw}WSC?ju49xzneszjUji~v6r3`vA6}@InCPxMsF+H_%KEP~SKY#MPN~ZQ9(xwQ zIsVtJ-Eqx1)U6WO(SCtGgwX*1c;vomy~M=NOF94h8YA{Sg`>B2bX(zi!5i{k&>`>Z zZjdzMnH%TKJj4Dr7g1#N>1~(D`!()Q^FfMFFrYYOSHx}>*rRt%6n%{?4vjio8xzUE zwBu?S5pTrGX(6m~i|%51^^e)$Z3(tBt>&){2Swf&)R&hO+9+j+l(!eme)#r*iQV3i zSd%}vhT7;7k9vJ}>?nSF<3?fe`Dz8q$VO&fs>mnJzm;*p6JhS_H_ukQ2qk{Pq{99C zm4t}flZU5I@SY2#r(F5G;muLeV&m46##7sqZC+cH)}UZcrW_D+5`29g`AR=gnlw!# z^C_@~6hCG~ojo-i=B5_=gU|o_qtx0|0mEM2_qtQURQvvZw)JGz>fnp6-k#@4s~5fO zqnlok)|2orG2f%f%aZ)2Eh~dDpQ&n%L-vcFMo~>s(e@=(KqR@?pJu7CV3g`){_!H( zcAfF=^yS<)soy!!);WYjk5Dufzqv(h#Xo#z^@rjNrAx+~W8YoaA>jTw<^bx7qZAk9 z&T35epke}S#^6p&phpAdH=9eMR2}v__tvVKP7Qvw^1n~FWwmn?gv4EkmtnH}%0)jXO$n`dzI<|=xlxcp~2o;%nkF^|y~v_7oocn@Ku9>c`xrfl{h&JarL_D)=v&kLl?*e#mcg zfoTNkQTuG%*p0hqcU`FQfE9}?J z7K%D~t@pRk-Iyn`k=BoEkxqm8F}I60`Zqka!pEjLLzi56F1ti-h}M=36iq&Rc4Ukh zi5AEZCApTMK5mqP_G)e?RW!ZSs^;ZBlf!+T9P6SfW&Y5TS^P6st@A23W&EW*3V5Cl z1yHM5HVCih|6VBAk^hBadHr`l)%Sm29z&{9MG@eboQSkwKsCEhO%u4pa|d z?$@dTpw7&G+TS5^llZ=kHZ%PGK)bJtj9#yGc<7dZFd?HPYfH<5`TdFeU$M!ocnA5h z{oOI@MYJ~O6&}6nWmcY53H?nYlZ0PK)NMJ@`T3)#QrDKH(W8YlGKue=C+AOcof=d5 z*ikt&^xluVG`W;R?-ANIX!(&HC<;1tifoJT&of)t(2Ex(usO?no)N0;`2KjNL1H_+ zm-C*bP<1Lt#uq#}YeVndJ6y1Lb1wljD5^baZIr`YeQ!kdCs?|ZPiOk@k5<{)VagP{1r$I#d4X)z*&x2^3ibWmC@+sj$#J20d{Qi#o=$J_r zy=i5y*R!z^PI5;IORV#I#0u*N8y5S&c)j)9xDgc}KXTAPXv#6C8jJq#wNq%Fb;!1t zOeddFNNv_d-zn|88)+SzIm_OC*r417dscHxOPh5rm^etwsEng|beacQ6@XjZCZEul zpm1hknWy{kgD^f)Z1g7v3-g%|3B^aY+)Rndt)ko(r=$E}q5OV5)6^03POvk;h1Jy~ zDf~oi?6DP+pNRJ8;w|i=DplF>lbzOTu+&GWQuNeJdAKnkzo(}sRQmbXsC%nSaLW#0 zN(r*(;KAemNtv1asPBl5a#Y&=PSuQe=B+7+jds+(;DJd9>A*BUwM%sEwT-Y+FG`zn zjm1liNV#=@Lr z-9N@u-P=2*(PiBfy6csncGK;xya)DPPX6cqu1%-6UC4g)u#$Y0MSaT|js4#?Nc(jr zbhsNo8dk<_^ms7646a?<-idl1Hkrfo8t4k0?93sN8;IGa2n%C)c05PFnDiiOV=>|N zlLHaQQ_a7W#GPC9L&afcVG%Fw``q_19o-WYbo=)^gOG)F4Axvcs0z>w!+P5`i~lc# z2`grJX68HOSWlk^H^6Ki%|G_qu6W?OWd0Lo~TAd^{Sxp$XB!@quHA!S@?mK`^ zLRN0>RG4;spZ_~B7SsQj%8b^ z(`ufV(@b5!K~Xr7W1P%%4b~%wdBh^_IRP&_$fCC`h_3glOf-I+y#9Ah-8e$Y;q2hh zo)ru=1Z6d);ETU1X|MTjBI{Go9n`RHv3M)IEbS<1&dRE#nPnRzB&o~gyl-DP77e^_ z)J$i-=i8o#s^#gq0_HieoVPaHMBt+=-PxIVHiYm&vwxpTywIsETOqAHdHArRTpuk; z@F$YD{k;Mp5$D9p$Cpx;i(&-z?%BWj-l!Il9V){L*DMbFfG}liWyQjJ>t7lMhFFNQ z_B~=`RfZqy|6Tq84Sit^L&4`-hu?3rnHPKH^~8LuU_+hSz}VT^o-*^0@D~oZ!Xb0{ zu66hhRzj6X#}q%Va;G$Pyr0)d-J`qtTo~=@$7;?~ z6;A(p71NXH6~`=4}qd&=Ga54N3)IAiagY;ycS z{>@*5lW02JWbt?GnGOr{O2+73hAaV!h6Kb^<{XWsuL_NcvF#QjKnon$ab`vtt8EC+v{%1h3zS{0NrG}_| zdn-@EJO^=CEWZfHFaqy%0ZNbxrU_2bq$@OFvEyl|8*XT^5xW{{Gm^j z)f6DjVUUu7V~n+lu}F`C>GfEqv zqD%8V{Yp>x&eH+kiAK-j&)F02U%shQmLstjE*A~(OA+7bx0dS?TP~JfbNa1dOi<8~ zs)Q#zI>NGxjg9E?3)q?MftiOvJD{lYkn>hLkN?KYzo=A)ZEWXawBR)#`%>SsxWhl= z)qDCI##`yq;tx!$_1?wme5>*On-$L93UzDVZ!5FIG~eRy9a6Beswb<&$F=|3s91PH zBqN)FYfS3+g%>h8UeYUSu;8b|_3BL&VW7wH2DXNa_4IuWo0mAkm`2_^=XMO2WC(UV zpp1(OP-Pugd1t12+dZO(=D*)~`Q8ypby+@nc*45D_W1vc7m!CzJtYt)8pHO5D<;yf zYp(i%0u7Y1^4q)fZ)DtY>V=Lek|>9f)@*;2m!`h(vqJNduFnRfJozx^mAm}=5B?af zGnOUFYYK|uWSgl@os`o~mmJ>h+gtN&OQXC}v`R!#7E&sG2xwxk*5jk2H2388-SZzT zK!Y#x<5?0&TeNnGv%8AZdNw0?D`8lo%QEGfBm#keDg+Jm|g#2;(At+?M0?}nx3Tz&hQ)P ze8{$Hp0`Y{yKr6(vOlzVQPCxMD&>wH3WhB7$;1iLIAjf+H=@tS>{toG33Ut2B^U=# zsM*DDGfw!IsKAUZHpd8Wdt7*uONhBQ@AYY)O8(cL(JohSZoaemu>0c6@^@vPOM!*< z{I=(xe^La?#u|6HGE((e57!VAAY6dB1ch{!f>ym&RdS+B%-C_}}!C!DS&+H8A9zpqaz zZ{Oe9+qRO?mj$qq_foWq>HkjbqZlOO)Kwf*vb@G{IKTta3b^&jfq{=<(dUoBcsGXz zCkA?YG@PMFWp9+3PSn)s=#TALJjF0RA_#h&IZ_eiM`V*9x0>j9Mq=xD>0?fno%qy! z^-1{uTbNmgDk4t{If9`K4tE;Ku|7Z<9JZ&aEc^ri2sm+m4Z~dWQYS=fVG2y z2F0ZQu)l)zoS~B=&l-Marg{tAxo?Z86lW+7w2jjGw3hrbT_8~(&VPO~qsG!}t~{o% zVSKb*Z`*^_jJ}z#(Nmc>I~%rln#SENj~mHe>gdBN-+Qe)*s##|ckplatpzze6Vnn_ zeZjFy8%Y~AK>;6mGkNY)&zk9MnwXRlaBEW9i1gA?lWQ&UW|}zZptpG}tZbZ{X2(a- zsFWss`xiKXm&N$D=#<#n+_0cLT% zCmKAhx;Yor`ts9Vsu{*+f9CfswQca(4p-V-{+W8~pZ<$6XI-Z-^)W0)%iC>GI+Q;Di0I7Fn$d2D zJsc!nO`D%v?H3x_`x!@n-I?6^d_ekGv00gryudluLp#w1;x_qxmN+wKWCYGTNJ2QI z#~c1J;tZ{+vu@0Auj6#Ya-1TBE}xedOR#K-W1F}$OKu-!pztPQr?gUj-<(fbQPO8e za`G$s%BQKk|BH*wDYIzTYC`VauTS)hFBoaJ+v843F!T=nr*X|F zn_=%>t6lxi$}N?S-#wA8zwwOvwH04|XYN$)$B(sv++9cMQ`mjcC$Fl`vQLhhDv>JpNHSqx;hSCnX{RCwrzg zt^Ov^;i|^v=&`kujQcj9%h=L3J4wpPd6jn@>KO0W8KswOsIh&=ls+sakyzT?MBdog z9=130UPL{Wng2hV_6m!N;@G$s(C`S@R$NSmTbsbn#r+AAu)jivloL`Or<^G`O9bhe zoRYXUkKvf`pf_L6Ie$DN`}uxQl7VTmwa`$UpxfV4qwG|7;g2&~-CcUasxt@5#bg&< z#Mt(+R^^F$kA037jUKNQJ;JkWEEOM8Ry=!GYcL|;Ze=R({Q%`px$zQ437=Ml(rCTe z>M~>Z!O-_fT4B>&TID9*a&w-YLu({b*%6xZ>7fNF+0yW2kBzs{(i|Du%*t{JS_Nu~ zeVTs)=iksSURmXjHz+?Gd1$@)mNz+gBPz`}C}}yBx0`E0ihq*3Gp;?ht1R*fQ||SR z6MAl?kp&IaC#It(3Y%5B?{l89T3cDZBW3XOvuNIx*jIg$y4hCdq`b!rS|x|2eQQHS zMbe*aoMn|gW*&6jsK`!XJoHia!CNM*tZVl}nsP+qJ4;D*-Ip%i(F}H<^_nQnxvo{S zyO?XeFSaqlC+ki^-$p|~?}Gh3J*CjKJooe{_x|%>tQ~X$8TmScjQNCJu@FRAKmEwLb(vlWkY*8I5yNnn<3GKwou1}Yh z*q6oAo^yI}73BAT_9M<&gIbiX$-Nid^021DkRv9xCtqDY zIX|%_iaL8t)1xt)DnUSd<847KbvD}?qx8*&!H6q{Hy;`p8I>a<_ODI59y(+wV=jN4fm)Z4&TgLd8kL+D8*x@VD zn477ySw5&X@}Twp{RbHqTC&jrt@OEN)`mH0c&Xj1&Q4up#;$`}?2l>H zVM&3A!2#bD!=K?z_5*@#BPk09`n=?i(BbG#k^~lEMPn1{afN#ULBsy1>z;_6pPwZ0 z=?X_ICupn5-Fp7Y*Xy%giZAJ{AJk*Ck%14G<%eMaRE47&|_t?=Rvd+zi3LI| z`Pz{;wb7!4A3b}ZreUIfy^G(-;B?2x^YwFwJJs$OIgw<#WLva+;gIZiABi&3T?bjp478dqPU90%e@J4mN zfMMC@?)+Zwo_nq1?5_QCRrb@`$B8nSDfCUOO~5e)F+(vuP2Zn^ixVmKu7NqRfg{?| z<+EoaEb3wg_`#pF4O3w+8S|u^MAx zZNGKKtkPBQOYdEmrz?kQ1NPoMh!T)nB;j1&bFQ3Q?@I5bh7H^?y}*zfM(U2&(tZ-H z_h)RlM=jsh!$a$5e+!dggyTYB@IXITEBRQ)YGuHuAODJq2C#UK`6fD?S^w5Im(e>! z3JKaqnqXS}F%__z2VZVm>l4zuEiO&{+{Hj3W9tf|39RY8k2{le0z(3ca#=Kwhl?OXL`FXop7-CzgOEpx1Gm&p~g zzufoEoz0%{imxa2k|V=l<;BYu&ik9xVxGpvwtAZMly0+nQl_*t<5kQsT{dlEjaK%u zHV##}1d@hmlkr*?Zis^V)@Ng<$xFrU8)07)PQ3chS%_jJQnBs(cWty8^rdwz)dcpb zmCF4x@=mmy_>jJO7rX$Ja(Hbk`0r}FzA>$d0{sNLF|uX(^JSSNodvX^YcnY@0<+ooo0yOMWd zatMc*z%uQc#g!*|p491IZwW;7d`h%XRBAoYM;eRa=HlO|yZe?jzT~#V`s(#Hmt|$E zyXFSh%e@&>mAG5k+4;D3rT)gP`BDBU2pZzmxz;SWhxnZrnDKvCqwVA#2U;x9xt*w< z>szk&i_FlRyYJHfVQr^QJNQ-a)O-PhKmju-yjL-Olz*%z|h&p8iZDY*dz3=<%twWFuYWu4jPqimFO^&6D}K@eiBr&D-xs?mzGA()}hPe_K+R zeV1mM1#7eB`m-xXNUL7OwDvXJ2c=p|{vWE|JRHlm`yRifQc5VKghHew$xw)r$kaq; zQJFH&WUeSGNit7Krc9Yhh7uBzIkPB{slhD#)}{CJec#{x$8+>_9NqUdoaa9GUVH7e ztZHX|Xv08#<;{2FGfZW_i>MkG5JU+9zTnO&i!WDr)z8Ubo@;zl_9Da%^UT@>H(whP zbJzZJTW8u6^L#7geakc_MZ6Bi$!*3t*_+&w*l^bDw`aeLCHLpW24;_f^Mb?ugWDgt z4LVA1&{CA+vgxi0=sl>^_1Z$-zS8dc{kJ_uZGU{IWoq^v0 z6-p=1SFY|`wST!iDNcN4uu}TiOS!nWvt-!+ZFjnr<#k2HMTe{Ub6j_*XIJ(twKkn7 z_&gnXd2U2G?43V*dV{-17t?9`=|jx}lo}a{)+?bttxDa+D88NS-@3Z;ol-OFgth$u$_O0@J2n$v8rS?= z{&0cm`U)}Xg@8;`fp5J2GC~JFZ`7Re{U+k1B5yMlveKPDI`>dnZ$y5Gg{}Da?Xt3B z$&>=tu<*r`Uw-{m)^_^N)|Z!{nQq*@=5~BgUsvHTf5tC=%k~EqUKw4uC+hgbqiFE= zp|-t}VH4&BUjt^AV#n$a>Wz2)ZR0Q4c)_p1;=tciT7}%!OUr+{J~+9ZDD^Yj7T;#s zY46sP__~`lc0Kp{H1@Cj@}38dvE_|OIeqoWOFy4({CZ8iil~K)@u|*39uuCAoc@;d zu&gi^-=iGt>&xY|s!pVoTC~K2BAntf@{EmBhTfensZ@}8Cu#@+{boD)^XKX4{rDDa z9+P}nBA@#uaOxOJ2^oL|gGVhfA4?8Ij`!)Nt8EKZ-S1%ivO;w9*h37QaRj~xM|)<{ zGD`#Vi6>>y^5Dy_Sh@bZdE|j?JT|TB{=B7POhQdeSdyqLli$S4gS{0HCIe*LyjdFs5w$*0md%_Dhxp~C*eSN)TaUL{KE3Re< zY_1TXm3$i_|9@NnL2_2ecC!>yflI<+ zerJZb=DwFXiyz6?XovDrt!bVD*H*x`EU$YA%vM1S#77zhA(d?f;{i3gMhwTeFFHw3 z5NseJO(cX~=6FUG)#d)4 zy~XVXZa1s5(}IFnAFJGcQ*P5u$@g=Dk)2QC=R*GfYl4(LIkxdJPjUnM@*`iUlh8n4 ztu7Cw&VHyS_#7|i?SU8*Mr;C?Y#Ajr=%>bUzZylNcqKn~)Nj-SrBNXfBzwbkwTbf0 z@d<)Fv3o8gRI#t8I12 z(YN4~?b^s)SMCn+u6{Lhzd^d>;FBRY721_1mHj$woXY-BUZNd_Hi5mZtswJeFm98l z0Y7AA1+IL#B5Fuk{&W>--8`jRas`XiyyD!&vF}Op^MX$2OEU)iYb^gd39MUl6E7>B zn`{gd#HnnJbRPa6M-(u{Qc@i8z=0_vj9*15@TlK988ALE)d*eOul@bInK1Bo|Jt={ zceP$-J$>rs`*&%{Ld268rd`cR4pxYot$ts*$(4MK05!YV=%&jf!^&CzKUC;qiYibt zNZ&Kv_wj{j`MNbHv0N~a+L>o&Rdz*9O-)yqmHs%o?;>tnh{AQNUmYDu@}_~KV9c}(hR=Qpe;=kdL6!C2t&LQRQ{IFp9|d=9XY6}sRuaCdohyC zNbQpzOHEj=%J&4Mh>Mtc9fa~(^}Bc7-}><_kV`s~&~#U9FZuh-r;o;eJCVSjqtlf! zuAIg5pVBPsiyjm*P;j3}QT_ct>9J(x1k{f)Fa=!=@EXs`xStfM&Bj=w--8Fajem%8 zeR4sRb3Vh=g`D3|HFt)B;hq6E-P3z|2Q=R(*?Jq4zdso%tX5q!)QtzwB@XoowN!H2 zoK>!^y&WS?-+|S|&=`@#4PvIL#jta+WI`@D?geU|*eP$WJ>EM6F0QsSif3Idwi|y7 zkXaDVco?J{+yAZ%bl))yb)&8QzAWmf%~iCZ1^gLE{13!tG@8&mfjQ#9B>91a&riCT zt;7TkxmTPS0R8nfsGtk!E*J5tPFZ*8+0Iio>C4eRmLDHHns}y3IktDto-dHE*z@em z;20ibeWWNU2x*F8KP(n1*AIEIA@;Ody*%DWr-Nrjk184!Iri;H9~yf9`PW0U!RVv~ z@!yA_hyi6p$OXMC+q`L$qP%>#n8S~rI*fxT?hnR1|2-KFh@n!=I}_Grt4}hyAW3Jj z@fVBCJF!m>{I=}r8VKjWl?qEi2J6SjWhDcbOwW0C`FZW)_-pI-nb3J-H@rd zwo~lm&~5W{wa7=0^t(W%!eKl9H}9p{(I39hywtS(kT^yjKLdRP9?plCOp(y$?L+?`B!Pp+q~#Gpda$5L5h9< z$B9kZNy?FTf>%Ai*)B1v)3`l4ewr-SuCThc6JKi=kr6E(cz`zarP%y%tB~1q>yD-S zh5q8j5w!F8#B7d8= zs{phOFlmShnO8fE|77TuEkkJf*U5Ytj-tq=J>+}T7eYaHz4Qu`=F}I~V{#unhsAr- zCx+FWTJ+9ePTn6Guc7vBs5d!Z;)tL7p$>oF2eN~hfp^FFWS*9?3`ZbIU_W>eJoswM zb884%DsufZSE8Xh$DTMxJG)(Zg8zl7kf=krg&=RCCz_mYA<9bwW6-M}opxC^79yEZ zXc6Kc$S}Eo4qnOZNaK0-G!hcG2-kpcTysqOc-SAt=4S^=XY>i!?Q#OEAFGngB(~nK z#1}$U08^4P9t?!@zSVcN&yj@czFNNha@WWC{%_w$h5>HqurG;c-#~z&ztS#;pY)Q` zPzk-EqmuY3&6pWdnR_vwD#f;Imy!&=5{&%)!3wUHW$#y}|M(}iUtT=EGJgDjJ1IRe zprzAxuuA^L^*=B`6))40oWEHr?UdObj_~IG`;W@s?+I48E1!x9MsDQ@gMXYCuY(SH zyrH(!GP$T|N_Q6r=K9;|3`=+BXuQ24syY+S=&JbNRVl&z`gJ~ zwdK2aK7Mh@U}<4`wZpAqgJ|7;4h?;9?}`4#Hv6~-zEE@GhIsujfw2qdN7Dt~pOKSq zn1;d)DaeiyQEMBUtPvTC^0WV<0S?+P!H2r~YA^gb^yf)coNT@sU(%sjy2dp9D%qgh zv3t0=(bL%MvLDJkRYBxxA-axgrmjqHw_rW!FT+4jf4J^_Y0kayZJ>W8TueDQL`85? zwt?g2bz$iLj{nJwfCrQ#uE{UnxDDL0IU6?U^(Lxu!INh?D$q?wriMPPo@di6Cu%y3 z@07p6Ja@p3BUSvXtR1hr@2=*>6ec(9Yi-Go@ZI+oo!~E_)Q}(V_Y51z$bYk$LSJST zp^dNb5)Ad#`A=7FBvHq~CjE+@PgY`O6vLO{Nq!EFk0$A+LgT3d*0LPWoPu?<-(yPNhq3#NybK83j438&Ylay&oJPt$bJD5W(EI`nb+GxrUGOGV%um zCdw*k$nBv=CY68eoUV>pvZ;W&u(ixrUdCKA*U+YrV;e7@v-e~BZjd=&Q4#?WKllh? zK!4@-YAcdpqv6gGROH%_%noZlrVtZ$;OiZBNf&n@7Q$XxlzU$>h zXe(_eWLJw70o$I-Ll6Ha%Ww|=o6bcr_>!&R@c^ceGnycKAom8gYs) z-;{kjlTPD2{*JG9OI{5%*~jld-%<8i7s*JX$vPu2ym#XsC28Mt%JHxATf5`7`z&S+ zSLP?6bcJrmJd{{W^TY%M1cZd3inCHGrH>dn)sPKM9=1gLGqzC5(Wq>Z^( z!}tp`?_rb$8?r5Al9~+-3{=(BW>_!m50?2lGExL952zw77Ji3lJ!X24N&21P2&{`a zzId`86a|7Xm;Y}z(7xDOBVW2D)%ZgUwUO`pRgnx#jpEkArADDn(Ao+iZWu?s0;9LI zQWmEMs0s68c9_V=DC3OtPU7W})vLRRt6Psm>|s!SQAZjD=O-wZK$U-4E~%Lw#1Gq| zD8mj+fdjMY?JdR369_y9815|=+DS{Vi8YMpC3AIsp;vD-1#9ybKbp)N5+g~xP-oyp z+yz73#H7CgbFRk_!!W)GS!l2Tp+E{74g^vX3aYf(C1sAQGWoFH*?e`-WRaz`&WBzx zsrlDQkqQBjM4(<~+n0jmvaU`kSiu2ALP+s0nnYo0d>#r(8;d1ZSB?m))}K(rPRd}h zjHH6s0aH#otUQsDZ~T1gjGz^0{fT>)_4U{kZJPg=AVZA53HdHgC-r!j8F52&PweKtra!@{1XDzB@mb3 z({Tj zd3p4KCwAk-%R)6CljmNGYuB!QjT#O|ER++^r>J7El?K`n;0=s76Xm|Q$<%u6+MM8a z*-{8xz!73An4O!}ukCOTfn<$gEyPKk&?#EfxDGRl^d} zz@%GIZSQK|y6^IPZz2TlHaRM5igtkv#|4abV)7Q#_yV(2zklN>!z8@742O;VyXv*X zDmQ?(Gr{qGOJH~Rom~QM;hW-5_kFlikw!7_XYx$Dv(Yi}QVHTSCb-s2aM{^E*4JfoZc zDh7HD-OV{vRa52a>vtx;5tqe!%+|Y)r@OHchxUcI^M!Ev`Fow{r@u+Q5RZ&R{^rFS zx=R3B{Pm_BnyPb(uWB=bb_d6L(Pm$XIS{j{WFCvm>3aXw*0&==a48911DkD4yH4K5zb= zPt2BdhsjwyM3+nIlP(;TA9R>YF!|_rCgCEDR2r&YU(3D*;FJidPa{HNgm+l{Z9sET z`t@nHixkGs*XJFZjLPcLUo!jR-_v(pOE{!dF(#JVeUI9YaXyY`81e!&9H-^%)D#`i z7+ul~%x4o$VO=&Vg6;5oQbEJ`hIlI2dxosT?Kz(xWpOM&O?n_*bk@A#WIS5u9 z)f#fscbDlTOw~Krw1Ty`2@vt2-g!2s$D+&^vRH z`!df^+pVRdqFvyHcxTYy(GWwJikVB1=pRwYgQ_Vnotr~TG9@Q}?q|xV|9Jg=z)gRC z?i$@LB5c%J$Fm%jIr>TK`17~AX4Qot5}~H2+Olik!Gn1kd@^6Ze96L)IJ7|IGF#}$sE%A`>|n%z)K~T=mySd)KW@10-{zRUPIJbjJ@jfpe*RYMA}H_dsCQZjf56 zo(uGtpF`={(A!KdL@#lC?Jwk^V;Ni=P+h@zHVzQ-A%S+6kumYMLogsw)^>h7$HJhV zl$nHfx!&;TXtDiBQ&NnJ!ajyhn`PqX`_GbtTn*q)}jZO4x51u0}aEia*SR4sN;-+Dnw zNl8ILp^w8B4;Kdj5&=MttOs8ZD$BwFK2jnh(S9&IK#>kJsq5{2l;wl}RvFLj8ZlXJ z^HvR0t-69kAw7E6lEQu6bhFCe?>pjluZIVE-w<4c5Pgxy(gKcNKNG}sRQae=E1NiQ z2}JzqyIO;Nk59|s>5;lzLG^N!P&=dz6JBVafpq9no!$5sOcKmJp#_}Izb2P178qnFP%5T6-VS1FZSc=2}0)e>5@9?2k$bH^%$lIGYc%a9{=eL zkUg1My$9V9y`kT7x2k>Bt7`;Fj4e?&Y5Gw8)rI^UV|IUUWxZ%zr8#!ER9Oc+y1H7( zNs8qT9jeWx+V7xq&g#Y_=V2|eWGnx%xS#R`0lDAf&e0S7B4ifazXe$3|HFs&JR_Wb zrG}4>YmMstE}Al_*0%~QEA~C2#nKwmZC4e+bcDX1+7aryWAmE@_?~|zA5lO+h~=N{ zNy5jz+smp<2L6LZGGl%nZL$7ddkk#obLt}%QJh41|LVOwT7S?E*(C>M)IycFv-n@$ zN_V@<>VIhdlu{3li-t3fc_)t1Z{kH<0@MFgf{44LR?rG%yPaKG+=QTzv$lRE4cF3w;qJLmFjbkr|Hy{mA6iIv{xy)H@s zbt5k6dt`6v=Unpt(kcDc3Q0w|A3iJ6drCqv$x@C>pO6pA|h0sj81 z)~Uz}|Bt%p=Jq;076m66zNdDS)|Dtq@^fs@^7REbw2N{j_?#a3>Fa9v%?mKa(bZLa zPbCI^2YCgAejpzOp_}a`pv`$(_Pn#OF=Y z)EIi{^fL0NAg=_TCWyP)*}rE7F)NdrmZk&m80cSvpuU*&8T3$cY#{6quAh*Q>1$=d z4hyC!;T0L(ea8REYq|r|kH9i2EnSAfDMkd;QiFYAUkGo%DOeL8+1%_z1^p@-77J?8S-kY~ZTge3ONP`6YfHXra%*}CNK^6=vg0!H_(@L+rdUAFB2>fWlNQv%Y-Lflw;k&nl ziXT1lHcmDst<^ZHDaz`{7rhVvOVEWUL^#$Uaq8hdO!UI)p$>-b3GO>e;;zXWa2A?#1Zsk>DQjw7K8tJ zx*T|!M&BgMl> zt|f!}4)=GD;Av-{rhtRtA|$-wf!rN^aqasCGy%?{EURKFilv$QgCytsZiy~ad)`=Q0w zppW+2IaOZBm!mN-$pJUKVRnPrz*^F?5@>w!`F(D14Ex8een5>c6W5GpY+oonaU=D0 zW}%TzWaEt1GeukPcjj3hy6G!pxrwDEqLnlM%lF0DAvO_?{rMbZaFASghrJuU5@q?Y z51yxfOIK79e}*t!BSR6$Cp9W<+L3KKqMkNdeQ|jc`x>o}w@v<_aVP1~I?Vo1vn|im zEd)FjSA|Rqjlq4vAFxiUs;j%K9m&ON9Sa7lgkAj^8Dy(N-eOb1vzKTR51kz;rfI9c zp&QzzgqF-DU8Cg|RO9zX1S=W*f;3=6458xS=xFzE9~hU%pr{E|VW6515ea3*$p{*+ zeZe1KYV$MJ?{}6A@`@j2J?lI4#LY%QuhpbiH}MJOm!o(UU2ZYnU(0kK%KAse#fwu?{G?bI7@jP{;?2i zd-d}%#gO!f9m|b}ACB&!^|M~u^?m+J+L?XugqdHM6Ggzr)ZpKK;2D6>K|t>OvICu< zovV*hqoDU0Ni{ll_2*KxpRWT$-A21Qm7S+bSQ%8fM53a{@lV{QTh-n26=fjtgINa| zv}#G)5KYZ_h{Y;$1+?VA{R4u)WcF7P0QL9X&miuIB$HeM9(V4guJ?cQ!z2Epip%p; z4Zo;%+=0`WjKL>6xtWP5I;O)NRwGXBySV3%@wrJ~#eA9D(lq9j=GTOgASE34V4pZX z1Ex4F*)Z|Ckd~O>w7nXy{K}pA;!S?Z*>6nlAM5A_Py&4(U*9WXxL^=kmYo3#gQs4m zIt9Tjpac5t*ChqGgHm81+5hG?lzCQ10YJ9D@+v1-VJ|uE&}IFQyku*s2&=FJos!pk zYn^in;m^{){Rt!$5ANFsye+lt>67bx?^TXk>Qv?*sqhg=2yy~4Ssf3>qsUJi&HB|mcz zOhPPOoHB@#cW3NJzTl}90AiDfWZE)oXAgn)Gjyg@~ z;8D{nM~ex=)k9KcwL&O%DtQ|xS1(Y9rYF@w%k6v`=V6wiu1=!YQyypcF;rDnCL|^< z%+GgtWD`XGT`~aW{`eH3cxcC5Z0b&>Biv$}g|lZ~kvTZ~8@}S~?8m-VC;LJogLB-T#jZz_D6MT=Ni(r z5$7$A$`OP(S-c1==HW6Nq@gyt#X!is#Npn7lwpCsYnGhX z?5B^v80qMidQ7X{$3bM{q-ys}bhK2>j*}vUgyrhH<^C_Ebc7xtE!tMWdcr>*v;|NX z1s{p}+vC~frrWB&FpwML`)tjwAWpV7CxRNXC+DISXlZFt=h3pwub;Ylzj6TQankeW zKTAFrKm!{fC4vZSF5DZKckbK?({Gp1OXNay-la1l;I8%pR}`KuBO`r3h77KE%Rcn< zl;q?zSGx7AKeCo!zOZ_6TX1Up4}^2ybPDub5qm8Z$@MgLKOa&5?Kv&nUN3xbh|JK!bT9nWLh0Dj4JHHm$?|6HEHoZLScP@(@#qH>jcM7~ZyK%#Y{sK>P zOG_wIK^qA>J3s6&`9`}#fp0}8L~PqW&2)f1aCJDkz3X^OG%I)oa|0onjPOmdIC2TW zm6F`IXGEXYInXt}<@vmw1bAFlL?!lk&rce%MgDn($Pl16yu*4vO+N{VM%0ct|0D|* z)PQaw$LqpYVfcgE`AXq}K7AV+Q89CGdrgJb6rP^@fqU@6w1U_+r5ZyKXNVyNS~ld6 zm5>)z{C`*-8BX6>+D<;&$$JCP%^t?3rK?`Aa^eAL?%8uCxfUvR)hhz8)EX!W=iRGM zR0mJARP$Qv=J0|)<+{7j%|lHQoci^i+4O#ghG|Q)N1^-d)2>Nx2%`IK!W{`Qv$V7^ zSOLnwIRY*-LMD|BHr+ADUFUv5lNgS7u(sJv2c+((=jGQYMhq#S?y#Q||xDfiCNl}dvce2DZVL{)` z!9ocAZ4E3dlbVsC@T#UG<9MLSiSVv6&1=buXiH=>k7P4ncXBG|Fn6@Iz1ksXog??3 zVQ5TlnOa(MV~bW^wIPEHjc*QVwQ%If{G}vMXwpNHA2d>Y0KCG35zki=T>Q{FNRYE1aWRTjAToVGX+|;e!?`u^RnF^WBNb3i@XH4>0_Rxc|0Q>kq zeZo)9aB&3sPF69~8P75n@YRyGtRkL(@)lQje)i^lc2q)U5u2sA}Sn!D+KS_wTtCm^csZ@0zzOm4%9TCUHo(gtKxEO^7cJiYqh}K?LM!uEWx8}+VSDf}k^vgB(w4nP zVK{-Txf+_jAM5KO$iS>ux@qk#h{VCN0FD(8eS1Aumf!-2HKT^=GWf&t_H1(4Dgp+c z%T%QKG(SM3tjn43vKxrZgQp&>5%7U%pA1L1#0|l|G1nqdM+=Mevq|Fa zC>@%U{7j(h=3d`<_1A7sQRD;=n8KRy8boia3rEN68-JLfG#+?nj$sj3;HGlyBCtYq zl^=IpU3#Up(s5nc-4y`H_x&z5iF_j))%doe4ZG{O3kMHRQhK_-6bl{QBjlAZUM-zm z=W^qQ1ympLK5}!XaI(4`k%Q3}lH@ywEWtRtLB7Yap&7vf&zw8%-$l0Syt3y#a9|WO zdzv|$F!+JV6&Z79c3I)MkSd48RLsTT@s{nWV2f5-dL?Ug#sk5(pOL4+l|TV9;E3e=AUl zI-{K8V)6gnb7YNq{o+mZPGwsShXNkV(v=-m5tE8y+_(;^($>q3P=}s97%KXIbnvi~ zlT7IUu(O|&LB@u{)=-m&ho?(o1DY;mdfk8W!=)emA}oi5Sorg_rK=)Ny=KL^woQ8d zofrS!y}9HlJ%ZN}L||BeaITO-(b#NIGlf@J-kaiDgKTK`pa_c1)!;*xK;H7lC^*7W zSKDAc;3M;Oa*|Xn#LgiZwK6a$DZm(WsaK?72bjj_q923sMPcFGit*$}$_TNXJ2zv! z=`7E9t$oBQ|Kv0sBi;7oXIC$spucIF-eRgK-ptf>w)I!!^^v;8e3QN#awAIGog-aY z>3J7JZ*8JZW@Jcudg}zE{7Je;?i<%;_jvR5v2W+Rx`E$(V16mMd$HR!R*~V{!|ySq zrzERmN4zwS zF=^+MZLl$@X4ld@1VA(_DEW6W{IOVw$5WtU^$Pgp@5 z7S<&w-1wNx;BFFDDZ2r;=W?;ze6%NgZ)rzjn-y<{`h~{jR~=*Ow~nbgXP&^zl9iqTkYZ;EM6vtGA@rweM{4ziQE|{H;F!;UT@3k_WgJ?-niH7p}5jxOOf@ z6^fs5X8{NFf;Ji}YMGZ=w{8{8-`0#SwAO311uE}T^ka5amFn@wk7o%OOTrO z_fs~*FVeK*;$;_#1Vq=_4E?Sro?;U1AMXc%yH#dvA6x=NVdZnUh|`-cf>|KcpH4bJ zQQFkW&`I%$n3>3UnJO%;2^DfOBc6IbPc3+N|9VBDr+eUYj-F$d zb@eBANvZ4PuY=McwjlQOy5JX?hikFb(f>uHmdxMgYRx6Tru`XD!1(HrrKIF z)gd2T@g8rso{xN4GAY->--hh|Ju|KM;+^hR8y@25uO!>FG)|*+*B zgv#zUYZ&pVsfkn_g(<@6_(p<=J_}794<)4sP(ump#dj+23agdf5LX?nnMin9>kTdW znSW5)UZrFlWahu~kZYAxTgQWmFl^%EMP|q2N4_b z*KjvU>J?;ufasrgxuo;Wn=4a8Vs1J*I=JX-*Wv>YFGM1&vIfhqUU8h9x|{Y!;#Sq9 z7DFE3^Iu@c0_#HPQg`BW$J2aA&o}xP((zw z<$JH&<6T8Z2B+by^F5~t{g=L>*P_8K;RyyQvp$?uu6w#-i%7i-92%p+dn3 z79IbK#dURcFvr6&YGG(7%zZ>|LtN4u?+-}`M03@L;{&D{?sPx}y8Y89f&kd3mvz<0 zqge8jl-t}-v;nZhQ^t2~fuNB&oP*6pT+NLn+-}{zjUyJ^7t&}CFe&XBV|4$>-*$9d zQx4#?+UOn`IHiZLnCw+{jQ&ockKKl(XUEI-o}MN6wspfBRepbzc0iA#4lRLbi*_XJ zrUtB!#!Fp6#C@U9k08ai>54-9>RVt8%ykq=ir6 za9J%JEnyGT=dozv;E<=opVVj~!FEVc&=%H1O5Ao2hQ$AhSabrNL6eirr7>;^i-+IN z5|6o9R`XyGdr}>-_I;lv_I(nC|DHrH9_dBd#3`3{%iG$0*w9yWeDx>&drZxfFGo z6mQn}?0M*Z<-G?FkX4OnDATT9X3bs(YWP7g9n=yM3th}RIc-t;JbplgMIR@RtSm~^ zT~Z#qh?rmc)m0Chrm%J>$d!9e3>F?ZDu5Hmo!=K!0|qnyBD#x^t=)v4<>t+9fA3Rk ztM+|UTv17X-n%vN#LU~g^~#n$rhcI}?+xZ&O*oTC={0A}$F}lg5Dr}Hra8E{3|=0_ zbHd~$7O%aS`@r68UUW*Kb9_=(c6}>*RHq4=3IhY#mOWy?)U%@5$UyjMn+$s|+>9s) zNWF&DLKprNSRQB2KpebbP;W{h-B#~rZtlr-MCm;(!Ww*h58t356*3-aa+V9Ym7Tz5 z@FLF}ms@B)fXg$&a+uN!RuQhQt}EX(iKj~s!A^(9Jj?|#n{d37G3BcNTQSDzwtJ_w zMI)DV2ytE&w=9M5%V{r6n_nLd&_BGmGr;$GCuL}`XqOQ2Q$e7*;^S0fhPdQ~p3}|} zyJFF@Jk?bG`(>s=28tnVRw5n`|#UW8ys+(6zO$ zbw8J-E`2RkZ2CQP`A0fU9U zMF@c3U0!|yDmb_e3NO|D<5JEr4lRRq)9Uo!5A4vgmF2}v+xg9VUIp*`>$R}m3}b1L zrIL?W$BjQ;ZKCL3vYvA$s_IU>8Ab}vwwxC8Y zz2W%!IzvwHm^0A4W@H?3adn05%;+hj1hkMKT=op&2k3HuNec)DET~EFtd?%)?%Hua zEsoZ%o>^##dDE@sd6&pjr?aho@4c9CmaEy%V5jN!>IXBwc3v(w$dP;9YV%+r|GciQ zg_{Os;0R|ImxonRB)!gj~f{NZgM+2XCJbW6;N4cclTxjD+95Dd2FNtrjb8< zLPOgtdU=thRNq9-_i5X8z?bmNg3*{;^7;T)3W=m8`WWWU%aphk!M22NnAB&jKvRGI(K`c+icN_VrO&pB znpG+O>8O3J`QvhHQEY>Ou`yU9O(QU-w)2s;0d`HgGA;jsM-G(E*AqBZ*q3F=cgXbb z9R_hLFMx-~KCXe~is9O$$Byk-ubKOE`6`Wjn3=R_RApPv?&0MOCE6HjA}#H+P$%7B z>``o6G-5gC!>? zr={^hV;QH%lJ*Y-4puTsVnrr@yNGq+&%Js#va0)a5X*;CoIJDcNY*8sD@>a@)o7Xr zTRa>-D8*Ztppv&^$H>G)3_R#MI_AHH>XH7x_?4vqG53YsQj>M;I}bPa z+h}fQ7wX^{la#;ufl6GXwO1F9Mp#BPX!f7QAdts=WeQO3>q72*nTQJSD+nJfQlvN69n}A=t_(9gp*+lQt2$g5z>(>IeHsuO7KEs!bdReH0Qt zK>EF|4(ixR`J|(ftnA0I!?#_EK?X%v6}>5L9-hU81*mxaaefWoHCSxEP|1gZ4w#Qp zMxtJ;dn9HJW%lQb2_oqlj{gdQ{5qR!mRknuY_CAN(tYkq$nwckDk{xnOPqt_ndiCJ zaPaJf*($n*9D&I>IYHEBykO1%#|?Xr6!q}xMhJ?7y3hM{Z0z+*l{-E7>y%GM75&}# z`TIf~MoF>Zfp;i!Z6%X)a0&b$K17ynyK)7fAT%RYpX#lGZf%~EklVvUkcenrt<$6j z`<4REY}uZ2aq(K*Skl#S)sE20%L1+Db^^xK=bTW`rPq)mmMxC_p~bMtfb@LZ+qVPD zf1GdJ*vrk0v~82mTf{)NfbX~jQfd8%*jDnZr*^NNF>9bn>4|b3rV^+Zs^ogjN9*}i zRE2`dM6Mq-dY%;hwl8?cM6GSE;Lp*I`dL-AZDVSZ0i2;;LQVPFnWmQJ9mH6A#X9PMkM#7l%g`LupZjtXp=qyR0 zgK(;^zdw9Dj!0(D4qSy*#kX&J={9_|Jw{j;b<4d*3MO4amO*hm zCt!82#9eIt<<>8qnO;4vzORbYRtXBaHYG0#FFVY=7#lxdyP>Z*fMUxAI|}_bsyV{V z?{~9DUWo!uWudDZ?c-AkH0SQGT+SB|O#Ym84bn-QT16jKUOf(LZWQW3euX?phz#f{ zFtryKQ(~$#^g1X{uXx{!ty4YjG&*nL)*nt=etntw<0dlgG1>LX`PVZg?gNlMdR!aw zsMG3q0xH%i?S;FulRkE*Bql^C$DUmG;CsS)F!+EA4lU{1hP`QdIVMWM!!2*vF%KoZ zuE1XGI9T5j61zfeNx*@D%!~%3mAG+KQxb!IV+W~D@15RHyfkVa+Nh-KZ11Dcj`Fy) z^}vN6jz$iB=A-UBEv6^J6dBEAZtVXpShhHp#4!t$=9hRlh_i9$HLxkVx;7E#6gU=9 zPW%%heQ`F4lHd;(z9WNYGKu;c+O>m0}-t*&DWP z<-zGlnLibV*Q*?g6aYnTh2LEp0bV1AJJ~_j`S{@*e#UZ8Cn?lj*il zFD9NSy^4x%=LkJ9T{*v7dgujh;W8YdQaw=oOp!>NdbTV9%W~XwyW#nrBpSX z?eFKdg(jbq!#&4M<{5AJTzJ!;<$dL+X6oP@_)mKo#U)z4`Ngo0TUX!sYslkM5|~cl z{IVoE|2WdZ^zykBGj;d`J{fk(?M3dAvsKk5zO?4Bc%-gP{5TrXr|&b-ziTc{7Dw4kge9HW;P0f`Doft;{R-esDQz69X?f6$)`rp8 z?+lkLB3?%-6sn~CYLa-kZFXW3CY9w#NbtE^Z+Ia112Pk2Dd@i}$>N{{fN$FP=dM_n zNt0|9EUt8^DK*B1+Kw>(Qpgzz5hY>=qabr^YDv$Cwh-#YnlU}9pqZ)K@ZXr~3k1UA#B zedRhL(k8FtfB5*TS{Q`z66F!f_kXh5*H>--9=@c0XBQzYQP-<$YG`~#P@f2{Z8LUY zml;R*>R#tt1HpN>W&C_f@F%RMxqf3;H&}h*o}qV#d*a1JWBb5zjM1Y3S zX8}GN|KH>2nh=i!z0Tr#8EJwjYjxVzv81fG<#_t;7q`2mu97t%f*z5)jv0Uj6^nJ& zygu6(qlb5_&>mQF{$d%u{Uh6a zW{JCU7GOQ-qwUyo*A9Il5C)VC;;T=p1Z~cX$~dy_CG%*}Zf}AN@;kpzDf+XFAeT$0 zAhz>ISMCxzoA>2YdPnZr@Q?0~M*yr4FZ1#eE@OfJo_FI^!MzsV_+tc6UdDFzikzsZ zsATN9^gZ!vsRkn1hGb=$e=+b`Own3`(>?Wo zRl&I*60`(RtV4HRMHOHs7sucb z1$|-=DFI)ltcd)Y!yp?nbQoU&PzuWC*y3U!mbdj4%gr$n%BL}ZTWeU}JXxpqQRs-0 zDW_1#>T_zJ@@cZPygfv%?IJ|<*ByBjH_;HGJo)5$^1IokshaNPk^be)`4#zDS-;Ry zn3@tg!t%MxK*$~Dr^xUR5I>zIuvLJl6UjIn@yX0Qr=S3KY7lBaV5e{d0y0B{MMR*d zC4km`Z|`~G!!9SD*%E{z)wOGNMec{VXh_rxkK-A0jiHk&qix>vAR3;t=PSgDN0%vN zdTO|=X4*xMD-_4k8|6^Uxp_D{J45QwqjI}DZ{4GW{in!02vf^btm{(rS(Np~e3)NZ z-kvD6dRRg|oZOVfb2EX`|KYrlch&mko>LqA%@*o@>(^&bGnBldIu;k-O2<1%QDlC5 z{N=G-TVfkx4_{l~s`#!DbJ7=&Q^;+({bpE?McS~dNGHSN8fLOJHFpqb!=95;N^ND6 z@^F*k5!rJ?c!w{By8n3utcp_?PWnHmCpJ56A8Dwfk#X3)zgmQoyhWD}7nUfe8)SAG zq@+=LsV8ozPxXd4ux0;_H6b(l3SK&!4+ftPuRdSf8+I{bN}I0d-tvqYdv{-!!TXEB zdoBcAQ&UwP7N>rebn`6l&5seKqTXASykx1Ox16AP`s^mtiMB07xxb$KKs647t| z`Xtxd3(;9@oW$-I2yt(o0qaJIFb+p0co+Il(XJ)7-T1?oDx#i8N0c8~D{*RK;>h>6 zPm22cH=dSznlwGlo4|7;P*%%IYRwOuI)G-&tn1L+i*3lv%$!_#z#ZXiuO;kj3MFd- zawC}zJ88-p%2kt8h~(?L&DyilUUqDdzP5%;UTiE-Da*1+t@T<_4eStQAkMcY7InP% z^-?tI#mDsF1BpLh9ufAaq^MU)&ds}+@?0S&C58uG7<`zRnA{}$!2fa9-Pr2=ZtgTY zlqd1IiF}46m5kciqLf3LN?8sY=DNXOvL@Uvn3>^{C;F|Aa=IV9{nfTeEfr!BN<&Z0 zZc09MEp^c>ocfmS|7o&v{l7Q*V+ZYIo>X&A?v(eXvB$O>rQf-)*Coif zJSFY5oz3%V%U~Efrby)%{P9PaQpY!s5T80b7v{E04{DuL)H9F z=;{}6e`0)>Zp~^Lb6z#9IP-*7Yet)ugmt*vfhUF)akR|cpAzH`sZo@_>KKx>?EqE9 zwy0bGnkBsDkZgchw5*%6cWVvCq%!r&&N|c&{h42XAnza_pKL}FTi)6PG@RilNX2r^ z%4!8%Mv4dQEP;+}JmZIhq}}_4!+LehH+onQvh1 zWyyR%LA)?Z$j-i4=2K&U@C&Q>{myOG1ttTdmk1*4hY4kw%1lKIg*>IdLeiyc?dIOH z?91t=HXOgQaJQ(13H9xd@HDGU&pE;;tdhRbm)2EYc3)RS9X#Q7+R7-Ln%Kpse0ihD z3`1Bz!zaTWtO1~l1N|CvXj7vLUB`=YdzjkxoAfIJBu zcEed)*6{Kq93Kt9U#gd_goV^Np6Wao3rVShCS!q zJmov>jRPIGtDWnU987)uvXD5DOl7ffMdG#S=Ph0J_5KatU2o7_jQ8S}2xfqCx3)qA z@9-I{|4T&vj*})WtHs~DLa923*ms{9-f51>f4VNj!+*^FG^=6_bU3&wQ71sSLZEAH&_V(WR_ zW6iZjb?d&*wEQ{c4%{!(PBhZ|woI<0^kF9St7`j&JkxmY;ePfAJ$!EZEO=SMTf7MHC-KmuuCpXX>A=hzLF@U_uvc5x;tqvbu$}Tl+A6ocN>FiP9 zC*w=?Wzw|Zh$67Ojl@#uEgjLWztQJY=_A-K-R~)j%a=?!F0J0O?S3VsTZo-3cYXU) z@(##lSj?)_zg?%s?%h4Ud#iLs=BJ;dhCaR9!)9PSl9Vd2QFI=xyYS$eWdHbkG z#`-nNz_z3s+qPbGP0vWmjcfl9^<~hUP2h%*bkj0To>kAQOBXKeVY)9jVT-C37)l|^ zB0oR0Jzv`l${HI3EXaHFrsZt_(T_^jR>kE-$3l6h(!K?%mMDtAmsXt3Yodlu^|M>o z$dT)DPf4QVuZC|;4<9;uIVPMw@G`2t*h(WW%Ap{kUK5JmQGLi3c04)$bG(eA{PSZj zYhxda$h-IR%rTjG=<;R)zlJ!q6zXU!7>-f*YsI<6ClUUVnnBhJkJys+aOn(iL%2iR zi!H_M{UnERuyw?(-OLZ@<*)SQ7?kjCQoVSdl6hW!G_@e>4PrROY7AG1YhpVX%+B}N z&p?Ojqw10CdH26ciRbhEc4Qv#EIYVifzPvyon{pmiVX{%pP!>QG@L$`iTwPvXbevZWZto%MWgs#s*C z3vHOpyUSZX-ReEa_(_X`*v;(bekOh@K>ebhdEgnSrza=$Ae@3mQf+YE={6*U9K=}f zSMCh@U<3N&`F-$5L$y4t$4Vq~?7>OQZTEHbsixY~$G0L9RYpzjY&8;NCFCgyecR1r zvK#y*R<{Ui%Ed@EK5_d?ZRwvVi0Jhh&9}Sw)em%8WxwYpmVaK(fUi63kAYoOxN5Nl zRDb^i&7(!90oPp!^HShFfRK?~fRR12eGc#y|4TMY0E1vM6{t?BXY2$}&HaHE*REmq z=@?)0iBnBKUnln-THPw!?nuX(SX$1^&Uz-tV`2j2#VN%`f5C4IDHbo=o@^w9qC+ev zsiupJntlW<&+))Ew*UR!;x9?TPw6T$cL*G?)fdxNr7DB%!O?ok%(Z2y!N9mQA$Zc992RjYXUT4btKpF6~K2@M@AeHXj-Am4JJJ2NoZTBlt7=_W5hbAswA#rYmy zjV$};hhG+pNncy-ec8mRB+h4@cg$7I7;dHTO4;bGY+ND~F!*kKQFt1?Ok5<|%rLZ6 zNBP5=G3tRoVQzzXX){>$MeMsZTucE>AH_p6Gdqx13E#ZwAEXEAF68`z5NxpfKO7O= z4wW)YvzefUN+OBmrlcK3F@@$ZoPw7`f#2a18WLjJnOjpkYI(#g`m8##?tk60-rfu& zEhlk_1AoGmgYzSr9O#?tMWib7a)w7M@^LNjt$cyuLG%OKM>EST`+wi`Bog;BEK#a% zO|D}pY`@ON*FnQXS^VmPpShjgpU}%LBaIWCH8p=_5~xzL6)w!!o7wk_L>bd~|pqI^;*`C=lZ zrLV7VZ=V||4}KPS-KjVz1z?UdxUh)9od)g^zn>^u;ESKO=(fr?dzWJ z5eoTfwOiUG%rK35?$D`G|_KWzRb@KRqfNMi|&nHieXnNapHRJcEL zq)e)=brUTu2p9nM;`gVpH!m+Of+<7j!(I`}k^!D?uaK+)@J(Yqm%~kI-|7o6@oCU8 zG8!VW-F;VuVixO5c&C4O_znc;FZ2HxCmYFmC*;3GKgLQumR#Ib(F4Fo5@#fu;3C4p z;~hD2{Go~o?lq;CL*nc9zP>vcPq~w@t}|&^_cAuNKHs2`=JGelvw<0~jnwS^WX;b) z@agE+SQerAW};yl7(T9gJKjLB16Ta#_iti1>UE5fWKEQ@BS{Ad~ zlR5Tl2_Nak)Zw`B2q~k{Gv1%9-;hPzX8?v7<~F^`2_A~_r>x{pO@2wurlZZ7eOt&R zqsO4#p0Zqe!bL6l(=frdyRNkhTt4_0vE}TG{1K=eZ0_vp%Hr|drX?>w9}br~U{@9t zY$r7M)J#l<5d@2L+&osnhzJ6I(#LRA4&L^Veu;LyI2Qw7pntVSl%pFz=#5 zT)IZCLrw=C!7-y#-m{1Y5Qgw5|9QFkaCg?Ll9J=cj)j}97evETZi4^nF1TCoGzGpE zCl|j_Mp5*Lj=2xr&Q0VFq6vt!D6wK?kbfdZSPwNBzY@?;I-lIHb^FzYwEE%{zM`I) zac=D*g<0L3Q*L`xS}7!y!W6IMbOiM2djBY}tawMK2ciw0>Fqy!WMX%!HWMkE9zM7mYFTe<`l5d`U$ z7LYD!DM3mB0ZFBE(;ati&;7pf-7zl1KhANed+)W^df)jz^Lc&~`bEtt+fJ^o1|Z&m zZL_BGk>iwL*Kb7$0>r2#yNL9e>~VZqT*l=|UtqF>0*1isBw?;X{4hSgmIvn`uXg{F zS4ARkw^3xhdwzkpm(BFc_~``2t-u$D8g@D*Y99yNP^d+X#oRSgx_Mflun1fHWVw@g z$`l9*%ebT@sOQ=xQ=ieJeJ@bw-QeWRnEX9DTBuj!2z`9$Cp;Ct1n5RGm#8W?9>+*LIiMj#3W$HgX*I5+qbk}3_lo_3_eiM z1($Y=zpXOw6yG-dQ#jtIaMx*N`}$MS==Z9{Eo=uU0lJ@*cpn+})&GtsZwia`aam#5 zdg+`tGT)4Z&&>Y^^!DYKn{Apqp88s%yusDM%4W9|gW2k0|0N@lG*Z-|7fhLe!#JFx z;mgNr=LG>8wwl?mo^aV_@O-fD;}ZvV-^M|>_HNgUzgGf@AfC-g@3ZQdZa-Wnpt{WG7Cr(6mR5M=3l(Bp222|PX2o~R6J;>~p zKhihx;2svgeRXhR%Ap_!Z7m4H4p=;n)lOHTmN$EB6^$jaoS4G8^M?raQtImNS0i^{ zUmiLct~yz`B9s4aI3gX8=57v*jud@(fjRJ9U|9oLVHZb{>6w|RgajzA)S*n*)P&mL z(eC#Q7}2bXZ?m$pvcCpBRYTwNJ(zOwv#$?zxR81dtxeb?Amoemo0o(By|`#DmMZ?! z>Hgy8>)KW%XulNScg%C3cf6x>;f+(ncnZtJmBt@ae{L-ZTIvK{Cq@P+_81;*bx>b` z+9zlLpoj0@JM2A-27>8<$`Qs;H_W#Yb6L zS=|bP{$UQ44=EhzKmQ%`CVWx5@piYPAI05JNE9b>vXTY)0X1bNOmIm&$sdAS(>X>N zN&{%PJJ!%6@MMd*EUUY@xxunDGU7hp9S`g0&!0bGU>r=XM2K*oLUtW|UQhvN+!PE7 zeh^ztNF5NTZz1pB;-==};B%E=vc>JIY8o!W#JX8cEdg6TD zq{KmB_(zXvkzUOf=rE@fD4&qmtG8lyIl|j7oN3+Q8LNF>6P|$++LlOBXKeNe&+p6i zg_&w23>ZNu}S?t6TDHDHz z#Zq^X@W@B{nbNNmO=iq&MUxUOE?Ly{$d$b7r>t@eub=+V!eAt9%koaW64sVjdee4c zGzKq@Ogrj5H68!U4wDjAB?5!kI0Kiy4y&DQ%AEFM^8jukmWZ0MoPKlu&}wIwDQ&*< zv*j+K$L@pAPGTF5RKKWr>=)qZ=JYG(Sf48^^m;1fz{|$u3=(+@!Fpo;VH}M2C`gE$ zAN!u8z%&820l2B&8>e$u8YBI1@0}btc=M9igMtL35P|=1fUDV>EWY|0t(BVJ)Y5=j zO%F4%VTvWpq>$LGU!t-^A@zHTO5=;I?QO96V;Dj612@(KtRs04(c$ELS~d!2p^V2I z?}D3{@NwBci${

s-8aaUWOPX;0!P{I$b$#8+kcyUW#%Hd6Mol1J~8K1{VyFtpWP zh7r`u34_E6GvR||4df1XZNj$`LitEC>u3_R-I>l4;~IEqer_{L7agA5a}VjbUf{x% z$&EvUr#9K!nJ4rliT>dbIf1w?O`Sl9GilfuHS@Hjrjq>p578pix$@chM#clbEE()( zOqEb4vA0v6kI6P2bDI(gk^acTj&CDH-z7Iz2?-n?YwOSDyrUmsaNt-7O?q6kJ0u=e zGj?ASMSi=E`Hn52>vI=v==%DDWH!~*f*1)?=*3UdkUENdlAh5M*>&7s2 zl1t09^0KsME#bXeeal@S&w00h{}1uzp<|%I@rl!U(g)JVFV}C$+l4sNOrC)_a`U;% zVoaGy$l-jS{SJdp2V}y-Kq)W=II{K zgu$|7!CDRF+rN~)s-YojZcgA$+5PsxRps4tR&n1#EJQ-qKFLjQ`91fh|JZH9sDQf& zLckZ`T}hRh6T50ahK+C^SFzFO{gLrWak|@_*d^2$8$ofg?zyj&iSuG3a}9j;XW_nv zY-_1wslKyq4F${Z`nArhcZ&AuN62YWNE(mOhOdx`ZMT1@1)cS=Y2;3A>-2TcJ)hJ@ z?wdQ!k)vEjNW>vt7sYMDBU3`AUN7FW700;a$)z&iWV_C1m`%sJk7ok@s!b`3)5TMv z5JZ5TF$;evfH?0E?_(Z81LOH<*K}1|(=@S94NnQSABF(UYlq_jrwdlCO_T??vL`&Z zHlLq2M|S)zsQ2_`J{AAQb=H60TiIHF>rA(oK`wtHVw&!KQ=a@(w9X7I{ke>k;qqS9 zhoHvU@(sbvIfhpbOTsMcyy@wTYon!{l_$P|K%3-3$j;m)B9aVGGz`b%0 zoSBT}1C07>nfQFUe9o<3{PbEjOQPOXlUP05$t+SZ5!(pCJMhB!vq>=d?CA3#ZO1gR z-Hv|l{0jG2U*+8bQI*Iq&HhKH`wKz!D*=Y02_LG(*9WZzlgZPl%oxbo=I8Aaf9(^9 ze`91ruPiL)6~95;0r&eyn3nqc@7x?Hc5@30IVu*AVSryqT8~Fb{dFbH#4#{5fhCLN zF2TTCa~D14ryFdOe6etfZ0Ga31cl~}OB^=KluN(Qt&V5)l=Cx-rjJY$S*xU;+k5Gh zl&Tis_-O{P>HLwoe;*40^ARl#kgy@KfcSlymYKm`YB2WPNj}mX>o@Yn93(rbU2{`w zVbY@JFp_Y>8ludYZxW0*3HCiPTz|%Z;kWV5SMU+SZ6WKJYd|^v!1vzH%)TK?%T@5= z5*az2G{SyKLlsrqs)pc(kMUY4bt`kk+_3dN@_W51Jov1MPLBPXhuHA3mpI-0PWIL=t3Fr>M@WXZB?uPt`G}Hm+WuLUBh>q}#EzjVF_mm%Avu z<;D-soZGQ$_(M^(R#BT=i9>hM#KxbiyL$;?uKqJt)i>N1Lbq-DRxt2VN@pI1dsE-O zn7~rrAxn#}Pe-!!9ponVrd=BW_1`4soTFXQtH$zPU-?h-7}p%p3er)1ZZJ37L&b znRb5Um2bNV(K@)E!F90$;uNXur@?H>?yv*a)O;rW@Mza0{a$-2M$p&^S*picI z@o?|neE3G83xj?-yI6*}RaB5f0{ftksY$EW;`9F3xHy`3&2}udxlyY6aAenF=wFnl~-47%d)D=aj7xSh4y1KoB}bk$@3mu z|4M~lA2q{z5{PwV7zIf^)@c(ZC2l`%q5ypS3tw`6j|w&=BF5411~7NAyc@7~PxCfN z88%Y2&oIug2k{lUhV0ool&}wuFJh5;efy49vcex`sht7>6QpuTCBStb01yLcKmq_C zW_Y=`axUk?5hEXc54kDeU%XThJMSRYvsR;(rI=r?{kP&zmVlzRS=1XA?rIUrK+oyY zEz^2jWYWN7$=K{(`+hJu@ht+TqChbF^iKlKCUsIWFYZpRPXpJWj=Au4z{yuw`1Qu zTQhr{?fc9c9oOrqW=@OsudnOBeSb+%FyFu1Bec(R<*Y^8ZKULz<5NjDt~&BTsWqV`pAt=gWpW*JGU=Mb60D-nP2` z@d9+_@f9W7oOv;M64`;q(*O9Mf}QTt#V=0PwPXCbL96Ap=f2x39Le)k^OgS}_p{Gk z!Pc2SzuDfJQM_j14lKr?qARj)gElDB4kRy*xwXG0b1esf=@htJD%m)7uIH<0$amC@HR67<6uJ;35=$*i7r^9fsahF?dY) z7btEz!nl}L1b3Lj`PH~LkBDkqVoXYOR8(~Q_F8YZ-Tvx}8HwJ@!NYf0s1c%&{^7rY z>wSfZTLB>kqz<_`jO&dK?e)CDM_!B_qT+k+8`1R=01>0(<6o?g3q`VE_%Xc#Poa#o z^oD!go!6{~3+w-{=K4<^^fe|KOYj!-DP~$sEvgbyXF2At!b51+xn@ZadcNNsR_+&3 z{tEDH&M^8sk;11LVEu7oulh?rELwBZe4k%!p@T^%^C4t#qkosb;SU&vKMxF zjapZ)SO!PYU!hT%q1gK6$$Kv$kuN^@m-gINH4)5SF!A$o>G?a4xBS70@l^0B^HXX) z)bmXgZ>X<0P3r^Ciw2XCN4tBO738VBHRnvS>nzChVdIAn{Jy!Ip=~S@jgKSrO^|8F zFfJnkruAyUl}B%CGrh&5@Q%Dt9S*aO2)x|Tez3Zl10R9W_Zbo@Gtu93P;#c@!6Dxj zpd`>Rs?Z@u{!fIcR=(hDx%}>N@JCI+=HJQ?z1-yEb7w5_x%(|{4wzRHU+1WRi~Q$x ze|>2ZGKC(cXg%YZ)<1!(>&V zgA|vS18rWn!3*}t!^?(Vo1p50YdyGQ2CX(U`J-W1pF!M$_)_>;`H$lC-&Ypq7h2`!BB6YF`k&6im%#R{)vATDVAeUo78SF zlQ%w7Pap3skFAd%s`p9C4_H$kHn5>M>f)vfaGUuVTY6M8xxea=9Zas>_)7eCYTMNE zDDm*?RBQ3B?n@&7+OruO9tE(8_RNESRg?JC^loUOnPmT|o}#FGHe&R=E&CUaB)WQRB|A628k8dClDr)L==Jb{bw z+z9Z%%`-hZLak9y>5{~MONjt;+WB5pNP>Ir4qd=J46#QhHeikn6b5)EmU2;YK z{9S~lQPv;vuN0;eD`BL$&;|LkDv8L1uTa}vk#mr(xZiH)Jezq7F^MTr5S*1JW zP}y=EHDetD^e7aNiSV2mmxB?lr&ue7Vu0k4F=H#Vy%vT%~fy$rJNT zp;s?Lt`-ar0WRRps{J(P*~l4@Qp8e0s$FpFD$J~h#ub?2KYik`4E;aCu%{0b^zp%> z1Yl6W({X|P!O2Ny{|Riw4`gKC{jB@(%3-A1(@mo@U$zpvuk&pvk?S*d%L@Yor9rdh zK{mYZSctvUaM3*D$=SEPg;!GsaUD??wg(2b^rJ{t<@9R=*!W%?r@V`c8?LNpOxasL zyX$M*+Vyf0lfhYl(CM9NOhf>&?o2%fQccd=dY4|Q$4l7xxnxiyclo8PoQe)>-}LJa z;t}n%x);f7)$W{8RGp(#eXjGi1}V<%-nnd+m36rS{};n66zAFQBX?d~)R+3aBJ8SX zt=KgZ3aX|$VZJB76Fx8prjEGYSKG=9&{W%(b~odBjXz&@iMvh6OhIRmB)xWz6_@tR zqU~JB7_}_=TEWZlBXhvPyR>yn_AW(X&e>k&-wcm{Q0?J4CiQ4^fuM*V&k2XTw({j8 z1-ZkUd?vD%w1`r93z;CgLDrKhUQE7qvY%Auk(RML$7N z$HK;Q%`eB6N8Ev_;?ov z)X0}!F*!{Oe98R@wUu>rb2wPZkn!8QJwCHrsqI{qI)!JTT|+B5*NzY^e4~8}5JYVz zDfySK9D}z604lhn^1`^Nz5`7e9Rg+b3^2m~`*<6NFiK60Z$Rw3h3Z9;bqsRf@k(#2 zI$y&UGFz>!X64sc*gL{k#~p&c@002$MsCMa+vPD`try8MN7>qg6v%&O-!Nk){Fr1R z>F8eBOYF~uO~N*pfb zw)U@hq4N{Z<)wo9S{=FIzzn;MN?wY}Mprj~N!y);1+^=cY&rAv6H$Hk8wS)>f}HXj zN)i{GY2-f;-eLH5IcWXN*>1kA8>@!JcxCZQO2mj=?>=+PYH#Q6qlb@rxrn~IO?Coxc}^-zx@V@ zR${s5N+tD_XYIq<4#oq8#dXrhduK((G7s@F1y|4P`zmn)T~jo2F{nkF2|dM0m47!_ zq1H=jBbhgRud+J~ACn&iZTF`ZT_r*V?RYiA1yXa`TYt#rzp_YIw-&lKW=KeDQrPwX z-a3$4k^%My0@DozI5@gSN8^8kIJFCk7|?fsoR0L)(xh z(=w=6WzUzPC!4395ElpDfwyNv6*@M`%A|<>U3%Q7J7)uOQkIRKu`z?3c9px=vqV;@ z&pw+LVLNf*w`eb67_S#!vNGqVeJzcNKm+~hPhMS)=ubnItWg%3@oAC|v$o*Q{-0A` z#t%#^EPx(^k3KL}x==$?LxTeQDj9xzW@_5M4gu8b5RTp{`V6qZf8iXNG10eiDJcwv z8VY1Vo7V|sUjZ%c#wC8*9v~_&{$K_+gDyC(NGtbd@R{W!S>*2}+gex%sSSVgh`wAB zyT4we+nLVnLIA1GBA}V&7d2c!Af)SGwQnxoa!X^g5W+qyYinR`d0sY};p^h2S z&>dyk<8C45887%f=xose3^hfHtXK$8OK!cj>)>dj+dhc7umLTN_)+SDFY;|w%yiQ< z53WMw6FWnl>+S(f30pFRP zJG=0!jbp3+WbNDO$5n>eowT?ZTFZuY))zC`auwiIyyzs?}$^slHt}>%VG?ZjBoz+0B2g9sAYN zGWo0|XKDCyr%Z{fCip_jMbudaLTWA+X=OlWJ1s2@s3~8*Bv@*$EiXgS2O*6#44eD+ zTcF_M)&G+D!yIY)`SUhV03fwaIu`#gC6Ax}=c8ep>J;->8W{F5CA_^)+wFucA9(+% zPbGAE+>eIR%m9?8-9L48KN2m7;NJ+9RF_amr=&EzY;J+`sY0#lXM_G?d81?wU!k+9 zn78UwJcqY%^u59?6YjS|0oN`(;pEWj?=sEG#EfCeFU2Vh;c67;k$I*miQTtfG&{L4 zxgh`S#od&omc)hIB+)m}S56jrI*PA^n>z0*;Ib@7RaY5N{CBr-%B(G;u`=SIgY-h) z?_$xMsC#$WqXeL-34jG-F97TIJW$A7Pn+%_!OfuE%jVUmur2 zox7f81X{3xqvlk9z4BW#JAq$V9Xw6(^+MmA-_6{;bO~)uVxV~oUj)sEUls_Y?`nOS z5>47Nc=w(ye6T{8;Loy0EX?qaMhdv1CiS(o3D7GA(5RqC1ZxEtA$WO}(^crjysDwn z1||)_+`z{KGiwK*K*tD-D{v>fV~cu0UYuzspQJ@|rXC;Ok~tBLIP=KlB>I6Lx%o*` z2b?_46 z(P7i00rf1$u>; zzcs=n?+9UBbx}!RxaSORlH!GoOMY{W&EPM~b$!zSmgAlO=bM53R%86^V{G6dG~9nxoXh5EHr$fC0c zglA!T3?yBdb^mb)AngdPVDt!@^RxZNDo7-b77Pv$WU0kRM*ajmhuJf*IX!%M0m;4V zTE%_2cFd&XGJJgH3kA0V`h(bRnr+?XkN@4zGmJ$=oPGiR#q#_dbDr{!9UT`zp@LVsH3xE6p%oXyH3xm7Nt)=Jb9c*BEZiN z{0>|^ys@z{T^*e}{QMBSHmGsLLCh8ZW>4q{CU#a^ zv7gL@Z_D2)Jg3fTmk{vTaY+agHHOeH4gxpWebS6;6YA6dUDxyu$>-1K0OOxKYjr2F z-g4;Ei%_Yldn^|IG^I3&VEoHWz5>=R@6V+UNg9e`Ikz@$v7_&#i#YIzg|R{^gW@&p zQ_y<0F*g3OV6C7K8Wz@bMMH1a#zZ&?vD(j0K@AuNr?EKI+UqM>SST^L^&+wV19No=Do7>)j z(y6K+ZKD7Y7R@vut70?@0a$d90%BsavLO&If#Yd-xU!Mabjx@dIJd#Slbs!W!B~MM za?%WU83yV=6Gj#jQVOm0}G5U^ua1A|M z7+`GPHmKuElxX(g;&R;gEAQ;QiUw)EU^FFVDpeUrj}M;cby${fkP;K&>a=YD`EhkDIzy2<~`mwPksVcUTpScU=Y4}N1EUES~v4Q_7k_HQmwi2*7y6@#Bv ziHQunHShz}KZx8+RXb!r=CY^9ril(q8`ERq<9VyaBTvWctYgO%ftJBj)zP`TcDo~f~dU&62tN`a3 zbUw(cK{7{2Rdur&kI{Oh*cgnw%t@as^^cX(SKrFz@gd{2Jz2PQi+#I^U1$7N`Q?uW zj-?FQ_TXW7s{gPEn)&~x$sm4>jg7FP*4LlHRRP3D=$kjN1i}PLhRc@)wRCnMwdR3W z^!&DVDh2@mz2C~=Ekf=hH)eo=iil1!U_wcy) zL_NrPC#y%x>2nyd3ocSDXlAX|M3^jpn`Yk{1^JvORSA0q$vB9(eylUQ3klWgXm9q@ z^G6~EM6@^=y6uCXs6DcqjV^FSw$HxZ|A;ODNul!CnFclo>=~drgXs>n@)gp<0GS44 z={caJcsMvLEiAyjx8TS8peNx2=4cz8UV$Xf)WFpA+#L@sfpm2aH=Z+Q*t37^>hOyy7)F)3!a*aid{I10S*-4 zIB-Pc4tX_b-HHEe2RGUW^LyO#knZ{rTq28(<>?H5bfiq9KF&_RB8jb*;$a zs8%c%;`iNAYwMQ1N2!d59SZG(oemS6yg8}CLg5Xz2z6ERD^o2@UQ2?}H02n`UESM) zT+=)kBZ-bC*6P(c3gH736nuD?h3RhuBV>`A9sYSkn2D#aD)++)0yT)Q2udgWUXgI@~9Sp(~h}j$u^_SP{>^$AD@9iwMA0>(Bl2cN0!=esWfb zGP2RzCywcYHSNihXq`eR4mSh2myGr5Jt)y`vq|v?B?o(ZfbbbZG$8eoHOHTX3kHCP zJ2n0VQbZYGRd+rpA6E6=i|~&g?rne=~A$QxLtiLyZyOS-CHe^JhF& z!YRiwEt(IJ(B($_4)`+-0-_E5PBE8RD(WEz2RoNeqmQUdv70J+bY4g=_eV-=04GhG zwv1DM(_NM9w-6oktkBViZ~*{XIb^YEW^MXM5nTN~r(g_lbYLMW<$*e;#m-qJx1Ipx zEQJg90CSO-KtB!+-V-_~)ACMJ(a@N>*tXu-v!=umt(NsMkGn{MiF!p~KS$+8?q~>! z3}BZQ78VAUcA$P%ySi#IkR7)EP;t3*_+p5JeU(~`fbP;$AG&)K=`zUY@3L<9;Pb(X zU?IQai8-o>>Gid_cY8f=$~U-6q~E!jwCKKb!!2PtB==2#y`3s~)}dm}%tN8E6xx~V zMmBm)p1%w2RxX!lS&Mu%EdzS*In`}tl0X@Z$V5?PIjl9?#ji&FkO@s2kg%#~?jacevDfkw2xHb0V>6Nra0pvG=6t87JSSJ~X~tJC*Vym31%5=?QcQPGUi!A}u$;F$4x5I7 z0j${q3AKe+paTpq40Cp1;t2e7Y~YB^=StkU($w0|mKD;Di`9Z$prv;1ceq#}BP5Os z1=$P{6l4=2@GR9cb8xVSH9+0j zb8z?$Mfjg7cW^d?T&=6C=qopUAYTXD7rY~S5?2B2z&heD(Fh_vC2{9v zJA&1LSkmU+Bc{dCphZJE@Y+ksY1twE0L)Y^U0nb}POMpo;paW{EtF@|3@j_uFc)7G zOn78>pqhC!U#d9%>tY*;y{R3^?c|wn>wJ+MA>34<0KA0@3|BXo+s?sZ)4i<}n7es+ zushywErtF8h98SOl<2Ak{$B`tPYIBwE*eaYebMjNn2ZE2F$7iW+}&p@HtaukO8fVK zE_M$7{J90&Jy2xofnDWYwQmEqR*ha!0l1A82r`9k2upg=7SzK&4NR{HAO5oFq*3;h z(3qz5gUiuW1%-5zY6;;7~QwqNkWMN9(R(UtFsdWDbW&< zNO@=lv#c$|y1BboB}NH;dcc^k=Z+6us+?k17%QyBkelYkigLF2vov3ppV(AAik)12 zOfm)~#@LwW2unB=grM^y;1tIV^nU~+zjuy3lQWu)ZZ10CLyT^Bhy;U97kjLPg;0w` zOavMuSBRYx{JL1{^gKuGLy+qdJ^! zx-mLd-;N%<-z!^Yy#;l0U*Gn}68 zPvzwR+}i@!Hvb0ypob|Rhl>NP`pHuk5w8vVZ7e?4-nb3CD^I`TahjRuzpT6f`!RZ* zOFudBLKdf9UqL*!Sb|4%)wJl5-1D^s@#h}SqYWRQ#$zB+Be!D_O1M=T8U!qrSFUb>&B?0H*^RkB*H7R)RkJ(e6 ze6hu73jg%-3dtX&=_8#~z0w`L_}>Y8&o1%BcY`X{1DGNh*Vyji2PY?!k`Z_|fc7}T zLJ3Jufy5Udw@UpVNL5knv=9#sAc)qi7B2yMLBv9zP+!Th1PJfu;n7E&M18pMtWhMD z&zJVQ`}mK5KjzJGYu^rrwX+m$4wl(ykYeg$M^oie8B}6-f&gSB-!r|MEbN970t!S~ zif=xSC14%>@}z|*1Gl&YeW~F^q9FN&kIX}+%7{71Bf3Tyah?dU9crp)#E`g}ZZb+i z8P)dl!O^Bcik)R=eGX4>W1}yuI8azldGG62=)htG!6X1Uf_w{f;?MfErk0iuE4=6n z+|#0?DR*mR;uW)pEJv;P`f*4*_Ro`2&roC&Lk=ehii8 zS8m0C!mUh!mY%M`;mw|Hx4JR=(b_Q1Z3KVUbf4rIosiB=0|SZG@0u7A#li~{WKP0m z7+sB`yMvFRxd#S(K#^aF>V&EZ8)A#-A2^o19~^|t)CD3UY@|X5TERWfZXbJPZemaq z1;cwj1@l>Z!UV*hnwy(3{nO5;;hYAtS^m)SBp%SmGzzr-%+BsaaMBQ!sbW;*q^<1T zoPn?0ujISPzg5G-g#FS5utyrsnuHc+yps>O@aCPw^pU@vg8(7&oBtVJ$KgTZp6M*I z^b-n1;XddQ0iggY9{9;q*8zb2>5)skB5U+R(C**|2h$(U?Eqv9X`u-l7Hp2!3MjxK zx~GCcM3twp%kq5S?#P{s|8vF_BZ{lQK%P`p39Ui;=eJwV6eAxQVj4>q*2 zGADS{A!!Fsl#vnB&_PLFo_xj+7}pCw(8ls`cPIL_lGI}g8V!~ogP4@k+HG9RB=NtD#3r64w`)o5wxd<)1DYjIsHRK zJ;TktPSaO=hCNM2_XykFZ~eE?IJj-kDg$Zr|ZF5Tn(;kw9&PyAeO^`KtRnxo9$ND#3JP4e9ulmN6yo; zrVRsJTU~DM4G7!5*IS3M;lehA<}55NyNrm&{7%wGd6DBoC@4Og`j39V__A|@Mg1?) zNMFZ)4;HPX z>VCzmOtmMVmVlsmoCE}-oS!Pd{)Q?mFW|TO*@eU&hJxj97X#YM1ahCJEn{;N&l(v~ z`(YR%{aEHG?8=@i=Bp05)xcddr$=9hK@CVLLHyp6kzYU{ z8U1m!%V6Ein<$jYu&}Zc_B|6ps$olUcYpirlsWx}Ik3h(!4U&Pl+j>2Gza<3n~!^= z;YHVLr{$>4Gb7F^y9pZEgliA)>GcHIQWh&2cYfZ~z4qT@!lkl{WxSzP8BB(#(|-}z z?@Q+#ZCuTAQAj`I7@WFdWEB4?fP&=84P;T}R`8qW;hA*;(TyK9^79JCo~VpzO`%>t zC`&Mnm+K?$>dZR}#X>Cyg0>K?#Nvyq?e$SxYcP7u&+ zwM6fPoC3I!qUO0@mMck+ahs5?DNxV-oB5>Q=3etqm$dmr6JcS9nC3^I`!3 zqWo_}n37E_4N*HtBv;7Ejp6HFtq3O{o-^_#hYz|*<7c31jo54BD!5{FSl7jX0~0lqxUQ`^d(Q&-6^!3RbP-lcgs_%XuwcDln1@0xFT_O>VX4QAY9Xm|{9|vt2_-SvK z>F&+GC1k{^^1~g*axuLML0N~xO(})m@=4b%>rH+AcOI@y91TwyXw+BQPd^$P9p+zi z#6qxZNh?l|pc-m3*~F*2v&WOGBybzr3Yz$uyi=Tdi41NOB}b z>L^<2?(xzg3~5$ELqy5VMwwYzE-XDU+Q0>vcpmfc-2O}(5(cUCz-v^`(niZi9_I%5U_9-%k&J^Mk9Vpc^6Na#xzniQz3$;QWHaHVnVo@yg)9p@Hx91k zE?={~(;b)7{^`mKNy%n^EIb5!jNo>GAbWL9%@Yt$otYEddzg}%ghz!8|kCZl#l8kb~8U3Z|(`MFU2Hj!kE{I~se!j{^g z+;=y{Mq}rJp^s zR$3-)FevV)gIeTMG>(H{0qDtIEZ<&6v@eJnVfGyUC`gbq7_(ziE z&g6Ampuw!5d}YVQq>-X^JMo_SmHH6pgAL=CQj%oSD2YmP`ABf0!EkaFj%dK345Cwg zT)LH9A|gp0Ghq{-`WFYNY$EgL&4Vsc@>uZ8Sm~MISGA&H!AfULzvO84D53c&b11iwV(0^&`CDI* zk3^F#oEOQWI$@R%J|UrJ@fn}_HI>&+V#mX0C?BqTYg?RRssr5M2j^GCTs!Z#IVSe8 zTo=T%(MAay-|IL(vQX61VSh|rDWrJ!yUSOufBmPYGvGvKb9$6ooo!vFms_!eh2$v} zzt~=4PrfWZR-EwtN_pp-DfM^o>rsxC~n!Nw_Kg^ap1%fP|5V*jT~H#ErZB3?X;E(#$!&fcZ0^C}S09q^p!yRA4mq z>-PeLB^M8f{LK=3vsoMyG!*ppYx$wck55v<4H#)yS){e)?RfXY?rCk4RYlLPPbAnE zOWd|xp?CVUa_#+vRfFHrXLFzReeq|*_dU?77{7rJ2p-|$hpR*9qA5S`qGI%`V|wrq zU)fi_E<#A|hc_i7lQ829^kooT@C^PPB#v6@tb^9m2N%O**hwfm$7V$-rBYIQN71cY zcoxO@`9Tf>8zxxIfsu4+;dC}i`JY-#m362tg_Ol*yUq~ zzKh!GJE_+#3BJ$0jz0A#bq&~wZCUnznSC1`dBN~E<$;m-ZpC#RO?4*viHdi(3TY9p z0-U(_=xZw)4{8O7c%?pfJ(bpPR1ge}I$`+X2EQE8F5;P0t}@1G8k(L4c^P;I;FY<2 zIrc|_4o|Ev(Ea|y00GW>$b5ndtzgE*hN+Oo>!hmP2s_$x{fT3dsHdDG`HF3`hjqnQ zT1O4~zgjhpSx~VfUhwx#O5Dq{A1N#6+%BDRp9#bJ76)^=J~BYli1b#s`>!s`0v(li zFTd{BnHN~-@_w>>*DiZ_K`xRd`Q)S6x6eN?%c)pT_tkjmBKa%gDmR8Q74}&{+De|H zyG(gk$>?EZHq`)T$_r0B6ftcro~qx2t^#;^_rE_aV% z(uT3V<;^rms1({Ss|s-sahi&kd8*`joFwi1Y=y7E&A{}TmrR9aTr38X_Nntt_=O}> z$;ix}@-%_d&$K44YfEmXTA-X}W0I}yWc)Cn-O5byEuSCHbo&@Ep4Wz7M^-7ufe(f6oF-p5m*+TfVu?WgPM zl)mS`%Y5%@D7c5fawpSd&C&T#$pa?!JhW^celO~h@w`SiRobO}QOHU~ot?~dS0#*rG zi?4}!FSCt*ByxK}8$C_vc` zJL$m~Voa4gLrDtC-l+Jfth_9Xl>@@6)uV4bOBwv{$G!x)1sr&ZU%e=y8&zp*(fvN* z47G9SD{cj2vsp0G*39pH5m*+-3Fyy_doKN0Ri^#NnrfE7(#yQ}_hV2ovvu`5a-Xf- zwYsIG)MDOyJo6lkHqay%^Ms4V+AYNEb+Fl;`uO}ziALO6*Q?skp6Cyj-(7AGd1oEb zDZy*^_9!*gIN)pf;(cGH@!^;;~PL4X)(0Hh=r9(gixI#vD)96?hOegX21PIKdCM}tC_-NBRVpzu6$nuLAk)X8wLmBho zcsMsZ_NPKarpd6bH}lIP2Bp4lQx~ZoAx(wn)?*$8zeKn;^^O={st0W0mB_!Bv}1f5 z7LI?&kwl90$hxvc=dBt%@U5~l*jEOam9#fp-+i7u5;@`^Z^2Mgb za?-z1Edx(i5gk4X3c~BZj17~8X=X4Hgwa+>cY)3u*H7?o)g#tC_P$4FD>3}9^+y^j zgNW2@??*-@og{Ycx2#5nd!gtm%2V@u$-#J}EO?}WlkZx;`S7PZr zFj7c}V~o_Y-wPKVQmbrx&_H{jxW!gdI~;Aj4PmA@1WF&=1F$Ss*^E(LzAWo4rwSH8GqZC&o)|@K4!1Fr zv|AW{J$@Ubth{{-qY1Zh6G3%;4uUj5l>_tC}dZm@t% ze`cg+md@$i+N$I8B8fXLdi6^ZE5qXQVY0RgF0aL1WxQVquf5S5wK3wm+BH18VO8m? z-OP9`LTPhr3*BN05BH7BQtM#|^IrwQ0`Jw^bFd?wpDc)rA4~_r@iVX)j&J+x6Zz^K z$3)N$INnETazwMp188f>I7ZX}n_Smq{aMmQ|EvDke!m1+d#PzF3AGnx{XWSkMu+Ae zu1_yLnqLh=HS+Mw*bx|aGiK&+XlzS+`9bx#BO0|DEYgMMkdaEt`h$AcpXK;w>?HOC?QRctscqm`uQ+kAmHZO zmF3D%q47*>A)1xj)06^vhGq(J4Yz#5*3L;7mBgoNY4OFqtO^<(BJ^j4SArCCg`zlV z9S=|X3w1A37yXrOpk#mcNjk^LDmZcC05zs*(u}19V}tP1Lt-K$KdRio4;U%87>ME41(}qbj0|0F!wgsJ-{r5F@ZnS) z8Hwim0I%(IcZT;-g~uKI^J`@Zc4@Z=s0s+Dvm0&c_6_InW0$f6c?-Ts&zUem2Ga`1 zniFVL2;!EOe8ERAh*URu>692=Jo&UA?t&nl0XM|o1>#Kn2>8J|ASk!9bbZ;i=4y?E zDT1FY@8hJs*HYAFdjIwi(`O(zX59(N-#qI$&+1p zCBs_RFb@tgd=SDtVaNjXi`T}gz(Y6=1G!*ICCJJEMS?|5-Om%~wccXEfHRRYEUI zZ~!w5hY5eiriq*78LnzVnZUFA+rN6=8xy{4ITh@fJ}_vg&u`S@WRJ!u=^sW-N?REE ziVK@s$Xnp}>G#-OBOvo{`05$#etftk$sf7MKKw#*0}?g= zc3b&4Uf!yWjNIIJ+$Ae11Y4ENM&G7LKmCk!q}(_S@LCrd-zJHT)v%21TdzslAl#{E z+YoP2kn@w{`t;-Lw8M+9yf-&e^6O56uwQ+8AfRJEL?U!t5xMgFJYncu+|rkm{Rze` z&YO#q`+AEr9cD3aKEGDCUnn&Fa&)xEL4SKEw0?UI{e-9gfRor0Lqk#o4w~zRGIk&| zvdFJb)K&q8>^s(!z?fJDS?_J+3XDYlP3SXzdBL&g+wr$?kAt=P5*akD5Jr%1M7Z6D z)v4ca17*iAFZbl=iVy{2KRqy||M34|>aF9V+`9MSK?D>8lx|c?Nf8M_N|X-i29cDO zR9X>Gq*J;z1LoGt?P=irEwh(mZ|*% zu_HCihED#`QUWu`!U$u3Ou4albl7-2I!7eQNdaOo_yM0I&*uU#$=S&XASM{OSerOw z-_zZNzATMWS&T+g@S8X91sxbtlqvB8AkWn1biGNHdIa=mPS*r^FE@H_rzeO8RN=8M zE@)tVAd*gGq?-alJ((V+*ah*67t`|0DFSmTYO0BK7(#Pp$i3u`g>9j251@lXP{lBjke4BRJRUiTrL}-oQ#c zHvSbZbrbN)J11ZG4k?=O2n7w>5i%Ia`A!-4nZ{qa zHO3;wkffv}C=98pUJ0#=*`7!E-Ieov#x3|gymLCFd#^b&^M1yokXt{RpzQ&CT3{ms zFi+_B70h0tPz75F zVrq64IE?MAt??1I0!hkwfNmNa9^PSqGAVku)E6~$>I)h+At9GcmuaD;0#Z&m=g(8& zfxIn94^9I_9_rI=@=VNfQ1wt84q3swfBLvGv39e%HLR%lVgJh=(py-F2Wj_6cZ^ED zb2A^6>fawXIP`jj(EQ!5x;eiV#$r)4rcOm|9OHSLP2||c&0g8bOKYp7r#5GvIizZT zIz}-X1)7UAm4a z-iF-ihu~p&Sy1qVs2|9_U(Tm|c>e090b;}JOvU$I86ESh((kC0_Z%j;tTV}|Iq&@s zX1?f**D1a_A-+04g3=3k6g}8Hmitip;_tW*9V6aUYF&@Satt)c2$lHwnkFxzn6dQ| z1qs`8FTY$OIXsEdYwU6|%Z~)(PU7^hMmfIjoSPtZV=*u^ym-ToL=fd%EB4;&cg1_V z&L=f2ud;94b=w|$dR)U=L^M{JZ9Ja9c6kHwkz>pMb(s$vKMmnPR=%ZNu{&R?r_rlR zewMs0pW=Rm8entkaMMC1o7~lk>3E>*neyO#mXfR1C#3QE!$^GWG>LJLfjfN z`LOXGyJeoBIbU6n!e$ssUjT460viP)i;$}TUM|qh0?by%ql1rFv*6pq{)*vIg@VM- zpWCpXp%=2kaW9$eOGnLs#WP>4#RxL8nBBX5%k<68*?;6aL>118?`NO8 zzpy0yOK|zBc0GY%!alzz&xFq}Pa~&wDpixW4-_tVd*czRix0bC%!$VZd~X#a33SO^ z6OgW{6DxLc$#@eA2nc|L_X&n%Wc4(Jnh%h85V3#g0pXYn875E|Q^M6y6F@|)WCT*H z*W?r&-;i)Lt}|Eztf&A$U}1E{&o;v$umY!;(dXdzsa6*s)g@?mIqEb%i-I02b#-h6 zU`;~8!_m-GDgcGFa@}LIC;KM^on6&KE#rp|OJ&OnER3sqrOS5st{@OSuT&6shJI0f zi5#5^*(Y(*Ja45*f14cf#trwPm;aN!ft}{+2O53nuR4-lMm%0!vL<|#lB92!{2*pW z)v2p2?fLJZhcd&G-qxSRJp*#9yQm!wFWR2`;lV;|PzDBUNJPcP*f!Q{#hg5|?n2Ze zId0wVkAGx%x?dxjvi2|;on7wka%PxM%xS@;6aO3@7*-uE^+`Rl! zdp17kF)N8?xFJ8pe?HJt?U#`|o%|h}hIZ>gg|8_$drCx|nkULCT!;@Kd}KH~Q5fZ6 zy!!(Fa1a<+MIUR6F#riyBE3caGQpHw;@6DgGnptG^jrjEXRm>bp}L@D9@eLCG?sEK zw>L)MkFSMSf14#|zF*;dAMXUnsU!UPm3P8bj@0dkyMHnU9%hSGf9y#uwC3&-Ws5?H zo3)ov#bZ&LQf~X$ZaE{T8~{na?4j6Vi}D5JnHzEzjxv$mSpEL6koIW+BRAL-F{=FwvqY#0?k76$v1lB5P4g+ z_hm8-8q!$~zqqJqncMiwtDi~szY?8vkH7E_O!%9B%aY@yNb3=1VKc0g-%Q}M4E#0& zLX+4~@_2IMjDXdAKbp3!qR%Y-C+*4)sxHHZg0Y5?Fn=FS?a8&9TwBlW-F7`r0ZasR zvPp@FAD955%G0><3Yuc-N^G7yX(*a>w?6ur#_a1Wd|Ekf!DTW(N4b~Br9b_|%kz8F z#+S3$GjfOJHKzQrNrhSDL12;c_fwnfM{_hus*xHojRfbfCDnSz`VP9ws4XQ#cg!cU zNNmstNb<0(yl_x>PwPs0-Au-V-4^AVeRaC>+~+<)Gw-btVy_l->G|G*Us9#L+*^ew zuRi*+GFzr7PV^N$8NJx(U*pAq+~qg*m%KicR?lWv^VK&xsl4>^!RLqpWQ90>2cZh? zBf<%+s0$}I1bf&vr+t0njXl^`&s`ooH`zPXMK%^TO1C=idf&X} z(_VASRPS)A@>ox5$S(ux!v^t*>oiqN*Y2|2{rv&|`8gAb9q@))1Bp_Y#D4rW$u#7+ z{u$7a4|K!VBQIEm2<)Th*joXs2=NpoUcJzpKxC1%RZ$&wE!?>PAMC2I5I$LHhSwtzi1<$P@-}w2q5auyWSujw(Ga(0Jvg&fcHa0cEV)36~HcL-zE}XqGY1 zbq*}L&=FZ0;OEkMiU+%$$MH6(YHZ^10S>sp-U=Mnom&B zcc&6t0yGW)7RbwMQW?bAa7RD`6B=gzT(qz--PLt~{VWQo6}64M$q{0Jw$Ip5^%YoX z-mBfuK_W!}LnI=C%+K$Tu|ENzE1M?%?zIdoZKuUR2%REEl(D^un#5?zvwUuM_Z2asy*GUp*TcA7T7{)b3);eW zlQZ;xgkQAw6$zug$6j{J=vW_M@R$at!2JBhtTfc)TP|*HpQ+k410`@M-Yc?(w|nkX zGTpff?HQ!8{|8X4%5%E#4htnL+f)>m+OtU7tz~`bcuP~Ba6_odU5cTVX9|kHfq}R= zYIi~V0NA@fxg`TnJ@D$bhci0Z+2J5)LTes>dIi86kU*0ulf{IUz{LRy45A>h4#op8 zTbEpFY`>EPoT`!Ud@UL)qO3%+|xLlC9*O1X<2D+X2J4k6tJ&11AK)O=jlj!Jk{Ee%)`9^TR$;elptSaL1)P_o~r54fI)gwZ+yXodaXm zvIc;he|1wMb}nU3xM@CA-N z%PohFN8ZJaISVHtUFJ*N(~uLWV?BnT8m<_|6|q1@IZ$>NfwmGuLzN-%S65}DR-mll z2iqw~K-rJi^|iOlWc8hZA}Vk;r;D*e`!WT$0Tng%h)Dlm$iwU2YzXJNj==!QL9%(k+$YW@xON4C;PFL^j&Vm>eTgR)l6<~Lr$JZY6|ri zRNSHco00bxW>B1O^4zb%6h*gYJF(B512SwZiF^%cH=G3;X{hJ0u$Tio?tD*Lo;+cN zP7%bQqM&sOC^*yFTmMa`6y-dm%c2^HfP=6(Vqw_pJ%wA+a$(<3N#aX1oTO2-=U#Nj z?XL{`qb?e=jj1>z<(G2>-RmFWt^T0;q`cxT_2U*3rY`K!4~?9nYoq^fBHcTh|A>!e zVLk9YHu-}R)w;2Y^Mm1;uZ*;`D9FG0YYe2<)SVT5kdFPM3ZN&T0Z#njO6$@ zNnJ)2W*yEwqLwBmn->NHd+RQoSO)w~``0vkAyg2wZ2=(%uIbBBE}N0KOQi!{m)wg} zaXlXMKAu%{`r?%;>N_Q_taMR$V02Rpx#CgjQNqW|-PHAW%!NMc2zYp*;+C45I6E71 zd#$h@_nL)X`%wcO=i!;1ZV>F)+jAp0jhh?Yua14|?{@-{en^a5!ezR3%Mn_KU?zt@ zHo^Gc(7h86;AiMH0l1zjiiXet%Xw~8xHxM9k&Y)o`q?s}@m`vx&3CFjEzqy;wHOPx z!c;t7vvP!(XSJ(lJvi<%A0cjGN4g?zc~!L4Wm%h%Vu=2OKeYj<)ds>^fLTDV(V?e{XZK6$34H3-{E5hzUgne(RznC=qhgf`P6{LK2Udnp>>Pw6@F z3j8g;A8)*u#_c05tTFUVf3%l{X>I%H&1MrqxwIWcL_{P-Tv=P&0x~p!FK5yv!`vlw zE2l$e(6>k?$Rjin9~~Ur0|iiJW#uMfnoEIzJcIRof?+wmk~*EdwphrH{2_tm$QIn> zBi0l0Rc#1!iUtQ*t)>dO0wHC|sL;5znENA#^05<$TYXXd9~y0=n1dJuR{r6QUo&u6 z_N0nF`}6vK#)5MrRR1a}wni+|3>#c-B3#_v=OG(nX$j&Ns@S#xpA27-x42#I#leiL z(Z+PMQ2aa9f5K(AU~G9KPok@el-1Spun>q?B-c+=+-`T&Oa0JyiTpQlD&7hH`t|c| zU6-qq6Gk!`z>U3MU}UjAe*eA{$qAI#@MbfD)U>qR062oUdf^F>j6feF^cjOTFF5eu ze*6H-A>?&X1}uQ=v4Dt-1Ufn308E(^^L&TiiPge&0eP$FDoE{Roz&gye*Ld=bzu`) zSMPi;uy=RpiPS(1PIx}jchyfa&N;dY21=PK+_-pXg(t!&Kj;1gscRAlJ8_b{MWllo zZ&MQrCgMjE`JAX=^Zi3+)_*T3JOeb`vGIV(2?Ae1hY8!0HyJQF-~gfJa?^ImKLOV@ zcYNorhp6ObZUUo&l-Z;q{9b&-oqfp=$R9-@ zwha^3YAz{o(<6MI_8Ofv=@$qz`W8*6umH%&*_WbF9p7Ag*)wyP)FnwD2*`oU3y@7% z;IZWNSp^Z%dn^~%;?j8m3=d#ei1!dNG8wY`yYKyV$WGx0fRixs(v~TTS-V)zb-E37 zgNYb=Tt+{;&eDXd7kezNkf|Rvyl8|93mxlfBo7_t#Y9tplWZmbElzd-Hwveeiy4(S zUhKRo7EnIyUk#0`SNqnHH@XfrO%%sd)5pdk1)B?9!Q|x7q>Q+H;XHWF&>acO3YrYj zAPjeGyN`hfrlk=hKxnZD=KBFB&A$n71*xlzhrpeC*uB_( zO?OSdoHJTbjOutV`wv2c2yRmFHLO-+?q4-|k_yl~0{3S|gAkVZzS@845hzWmt1ffxZy!#3?j~GKhLqWoEwe5Vjkwdh_NDWPA1)>p?yFuJc^7 zsAml{#1<5Qup1p+QE@T!)RfQulR`Nd9lyhx;{8?{iOF;^@dZIXUt3 zLzo(_O#JP+WJS0yrE9rEGXc`Lbmn}qyj$C&Yn&LdB>^nU) zmK(%z{eMH90740nNc(jKt}#%kjYJ~DmmB`RpUWO(;G@@0`ar6BY;89+VMXwfJoI-O z0boZgpc1N^>X>HFoK$5XPVlm=-N#%uQ4xAkq$QCC`)M3bs_KFWgOWv~l}{Ca2$SO@ zy`g)@%_5}z)-$QnA!9Jfe0)EL7urCAB7oB9y@1{50r#bUBPWxUnfYXWq6wPsmD?{6 zw&(hMXCDfTfhrStEV$>-gGhdjdKz}pdiUGH{IljnO>q-;650> z+vTr~bygJF;47&#^WWg#75p{F#6U2#I#D6hS8eTq5IHUZ0hky1MgLsoN-btVkDs z?|Z~mHbZMVf%+PHb#@l85pXo|WbnS#OVTtPr{+~j2>V&^*MTqtr_Dnmlw?&f-dy~o zU}X>s(fhP)*#G_P$D=#idf-9p$KCrLK5g-(>`z}Tjnsghp>ln0vlKDHW-c-0=}`MW zn@xq}SA$JXz<%6nrOiJ3=OVPDgR%Bm9^}Hn&4FJ7ddQssI*KI!D`RtQN2eZ23Txgn zU+H`U9P6r-ygcPl=+S==%r8ZukY!30 zdIm*}ox2kt1o8fT9V}OX&p(o>(p#-}MyEB2goal%?u(zLuyiO=+}8Cw|C!{iELp&V z%cM9g8k`w*5)T9Z1di(U{$%>)tI|5S=a*WO&cKl)lat9%Ht%cfs?vdtA@)03P4|INy-Ng1OVY$k0hiD0uALH*ZFo2_(Tx zwg=ujG4G=);}?)%k_dtqyZwjOM(o~YtpU&6b=mZX(Ixn2pFZ>&nNY}yuEbFaviEGF z?#V^sKU)RDR9mkj?EDPQ?|_Z*k%|l5E~~9`({*cYM~?3rEsnL)?1$j5P7B?Q><_|a z+a)k4+tcaJNX+dCT{L;&bpJWBll>lLK!AieAk`JD89;nI_0~GwPgDwYvfRk-rVS=t{9cmGLOYR1Pw8X?a;3rR!7mStQ+Zsx&q{ zqw=?kXB5VBLyd8+PqtqMJ{;Ub{9OIwug^Islu~%4!yNGX{Q2`$4iQ{WM=H#LLPsE} z_+bQer6AYEybi!?2ohybk&yTZ%i96E+hGUU;|9h>#Db6*YTD;;y1!}GqT^bJo;Lrp zH~a0R+!qOjkI9kiTY$+dLlpwUqZOg9fb#P8=|E=%NAnK{*>Wj=#Yq*S`t79%ElL|I zkhj<92f|T3!V2%UaK;wfk=vCcC$LEb1_d3L3&WK@%I+Gi!{jKnOdD1=U`t@pwGJmH zxO=eEbW=6#QC1;5q!63gh*fKz=Xfc)@=wxdy-AcKad~=_^^sb`k=mustZq!ux7@X>m9 zpp&xxrn=$I$+y6D1BzSQZ2N()UsLHbzylp#?+pAk`XqG1WbWzEYvl%Zp>Ni=YigYP zKxJ?;6q-z-9+SFO1u^er=+t9@Lhz|2;x$({OU??cTj$ATlz$zEov#aj%{X#dzji+Z z&(a9Mq-}9{aJweoDv(HZN}HXFwd2lq3$Hm=v=rE6%V|M34*dC56mlOX-96M@&;7Ms zl+}-BIJIBNS50;FT1|ntLq2D*t!%mfc#tQV51H3Wp^Z$a$JEQoz`%ZbnDs7NW+R4! zY)I7IAZwz%G+lB!^yl~iMzVO8U4lf%0MQ?Vy z$&j#517{|x+D02D6ObPS648$iQzCDIs|;8g1$jBSP0vuw+kSXxR_i(4UBDDC_J>I6 zV3*BRYF~tBmHgK3QndGd_JU<}L-p1w4|{lhV>8pW)IU>FHvTEbu-lz&Y_{u$5h4)6 zA{8s#3$Kx9D!SwjzN$CnK5a%3Y2(sQ7@l^lErrl)swg{t4b;~&m}A|knn)t?n0}lz z@+(1Y1xj5&>nRAlIwd8_YL6eM4=o$k*p7JbqlT_`gNO(KPZBz3E5=r#1%&^D5!~%m zV~XRD__lAiikr5An$@dp|8_1s_d4eI^{r<2_p?3v?Ami0S{i}|6YaQ~&(XU>>07H& zCCx`mK@1)rpkcPH31+Wfjbt2ZAlY$f5-lzFyIfe#n|`kFPtmh0b0=Fz72l6~w(cRr zJ=Q#%zEWIuxBGG!-;O)(X}7R@QGn^4m~Rj&<)9B{AML z^r=E*4*?|}Aq^Qd^`cY#9>5}iW+%RrWwH5qElXDb9zyutXVcVUW1hRJtFbY?olZ}A z6o~hI@^aiw9!_cFxWcs=&L&Bs6)^ zdWkqTDFN+ED_Dt+=2OF+=e+SsgQK%)c?ypweYGfsmc1qSHtIfls^2fArZO`qr^FEC z0dRg47&LfV;nw!;YEc3nJ64q=oKGhjUv$QCb@ud3f>_L4S5lG~FVLS%c&<0CRCI>q zV+^>EFTo&#i0UdKFS3-^!O1t;^G2Zw-}Wt;86BAwqGP4jYNE-=NbGZ@OEuojdm#EF z(_d!th2h1_l{i!2&M0}!iB!N$x1Xuj`MMFP8{D6_9Hv)VPV{pMwfsGGDJSX8AB0lc zL;D4YLST%NmphQGdP1B9ou5Z)wrSuWV0uGgbDV${s|=|iFPn1U*SYt6V+u;v<(Rz! zk@C&BMq`ey;Nr7YMyHk2KfznM#3_z(@Lwy=YNe3<4SeKY1J;BePg>{q&S)|c5~ua1 zeM~tPR}&_4FBl+X3{2W65)WNvFp?`Tb8mJ?qK|cVOR`e6R2JR?KzP4fWZes(3C&1Q zDr;G-8IumBF&9>HUzdw!m4o(o}(PZ!Wqan^5vF z=Mker+IV4Xblxgz(A>G!f$f*UolQTX z;P_*!4*2ov8+dUe>MMOC6}Fz~H*bH{&{{-!|N0qOxdO;445tqiWOq>D7`(stVhc90 z&|=W(L~Mk^L^m>L#QP=80=|G@sH7Vc5(Ttc`yhAr0f@M3X3!R5M~tT2>t=@M!8CRg z=(IetsMF&r53;SBt{7n4N zp?#H2oS~Xp1w6W_=N^XO4xAOtzXWV`T6|8sPl^EjhM^h;XSo>((nw7}Kuk(XI#vqg zwup37{K^Eofrn9GTs;DR(wMHL=4SQlmej(d2=jwcob5LnOqSwjTrZ&Z)b$fB+x5OO zWM3LdMq}1cr7a;6TW<0t5Z)DXa}9PN=3=8J5AXo?Cp;aXBmLbrNS}#AN)y)nJ|z8{ znIJWXoDLJ=uAhl=D*%xs#KII!X=qO)o}%e`ByeN9m0pAac?6rrckFx<*cQnLCeWup zPW@GD)TdW^_6B@3AI*zYisFALD8Se$Xzykov8{ni6VcpR_y?x}>xS|6;3Ed#lg&1q zQ6N|bsy_g-`+(Lwb96^ca`HX%?=jE?RwIM)Mt8BI&Hsl5kg)7~-nHUX-|Yxp&ugK2EQu#V0t>>@91p@ohPlu_zGH z3-5q|!l2&j>U5$y%wR`Nxc9;dR@Z12W@e^GF9FAzkIxx^DS7L(zzC@yfCsM*}9hH+I&^y&bOW6VFn%)Ik|;RJbDrUb64|$ zsHf}IN+Mt?Nl8e+cjH-vbOStPjSi=2TZk^uIsvcS#R`mzL6NJRLIX-VPW5p0LAW$f zD0slS^KJ)jKkElC;r@JD8&*o7g&nJOa>#kVZ}dgaiF-iK{DMs>gZNVa%$ek>u$7Nb zb2bFHDT^QpArJ}2pt{zrSO`i~wt!aRo`^5c%Ijz0dXzuvcbeLyQ< zNJD;0OScir4M!&Ne&(pdBX|;ZuzTk5d-xYbBW<49(WBThn*3K_viJ9^$zf*|?d=ll zgxT63eVF}b(HYr=bv&`|`-PyHX~@u>UJ|p}I$FdVx{WY}->U#mcanXDB7Agp56m>M zn3bI3Z!{#ci{EfCoUYkobx5&h*HHgm%&z{xH@eyz-3!0AdJq>{^LtD{l)cw=L_1u6 ziJj%<8v8@SM`cpg_OT4T8KsK+?W@a-vTx}U4W(rO3WAtQzQibYl3-X%Tg| zny-#g>ZHBQ8Tq>%1#{9;c1~|L0xZ16!zrvwgGugF7+(tgW1BkFEhVHjj3Z*|vxc_p z{KkIf`s;>7w-Wf1#FKRygKQMi9eCq9p$CJFc%VVW*Mqb#zE)iheu3cD@-vKD>Tyfd zjxwvLa^{CWk?0C=Lohi29im_e7I!^ZLTUI5YAlr`HYwRf9V;Tg<;xS_8GrLPzCj4H z8^>|ISnhtWF~l!I4K~0q(tP^98B`Yz=aRq@MU&CfpMrR|k?Vlw=yTat;~Qv>R%7Q; zWhSIpWOi9I{#NJ2GUiUY(>iEo_;qKB)vL+IkM2$g=MOT=?K%2lLZk++3fttgKY#u} zI~+#5ItqBgUtc6`MxUMV^%s!JCjW8xhh5s}FJfCup~}wzg(Abn0LM zrXWY~%T!XY{E{-IT>8Se^gQymaetXU*+9#+K5o%;!?Zi+N30B0Nn2w7KFjBaJKBem_2K#5%-Ub1 z!`TuzgBKj|@%ggvfG0-?gU<=3;tU!GAVrb!464~{^=y#Ds8Xq0!fFj4YO5DMNyv_t zbki{oHT)KA3wNDfc`KnfxZ&%vQ^84kqiYuf!6i+w2fHzIOz`PyASbQmR*&!5HqgE~ z3a3O}XJUftNJ31E%U)hU>tdX^Lc#EEWX_2(R{58rrqU;sGMIDn-5#N@5Lptfj%}Cc z+~t3H?f2l%)g2h^-qddueGR#u_Y%A2E|Rjs4%TWRVlL9ox3xp_dy)S$4N0b--`-79 zIEkO}doEWB&y-dMDk^KJ7$MS=u6If+z?;GlJwQa_>I!Tq(-;$kIZobj(sr$k)vo)V z&HK{qKgVDq4mPLtNB-{{Z#ZcQL6RF<<>tf1j=t5lPebIg4(b(rtDBg0k2%in#}O{R z+J6p-g}+D3)y}mF7*kNO=(4Cp*<;e{T^7#3umSFpUh?3R@b-0|edHvNfcChDV;&xJ zSZRY(@)P_D%=TSSzz*za0!f%v2o#QL{UGw(yx+8rgNLV3P+Hpa?Hi{1(jmMZ3mf-j zBS@T1$T7V<7URRh@i8CV^K{_9gHqYC{r=)lHV|c>bs{Gtt3$03(hAs))vQL!Fyt2( z+cmUL)4PxJ`kXw6%US*Y_j^RIaK%cA1-MepS3SWAcSpHuo0*wSOJRV3z~&0v`=Gpi z2#w)o?U)x1hhO(A@P6;YRtGtwt53haxdI-U`#TwE;hK~5$K}$k$cD_pty{O4nO}=C zV9XU9F8Dh!3u*v2e59#Ke&x!uF}vDo4-jMe49RmA99&$WVu`qliB{l{$diae<;29r z$5FEhr#}YG`zWZ8p6G#<`+FFi$N0My zo!r|2zm^A!J;B*9u0Z~;Bdok3XImE@$ z;N^{!o63L(1x~{9-`E*kg{vKqT7)1J*nFh5F;NBPn8)~V7m0{`mh$sJ-|7_D&SIb` zAvP8x&$8L~$sZ5%6Hp+<)%xE|o`1)Qv`M`4R83x99+(-H1`1(QJKkC3bDH@EVI?7> z*!V*Kzq3P{p^pdI85|at3g3r%Icxx3f|K{)_FrLa1m;K~`y0z+{+XV|gvoCGJzQMO zM*jP!UsxC?CW|9OEOsyjlv(W%E7BTbZpZK4?yzY%W=}AfaDSndMF4-hB>@*KfOde8YH)%!?miV*8#< zGqQxjM{r>#>5y9u*D;SlX$2_(NW*{&U4OJx=v`maN1j0#VGgSiKxYN8&`;Ok$Dt*d z$NCrm^5nL*TtaYqC`LKIn9PsFe6uQZQIm%dXpInl%Efhc?*m5-5tzaIn9%zOvji4y zTYW&~Co~$B_VG{MgWRF`=2uc_?Pn!tu=-^&kqU&|r{YJLT!qic0fcAw_Q##i7)9^g z*#URDI2#xm)zU9RH*|Tyq!9icRkIR6j zwl{DoLgjM{=9i}0MO^H{T4I|orP&~hlCp- zth`}$oxsCT8a=-T(2&Lc9O(QDK+B*f_M78VQ+;4cO`gmN!kf5pV*%Q&<9DD8wK7`W z2{->@K1Fcc@e78a^!er!boiR!onLDPKcq39U~k9srU@v&e*Z3?MSz*yj;eKK>jpaU zs1C5=+j=v{Ft17)8jfnl>}iEvtd2EZg#i{8siCK*XK1*J?(^JPxI#k%|2EXqTSE82 z2BfGMk_|2qRLanlQ;tFqeSr0O@uD6rQ>#}D>Mc<&Gv6YC;2BMMnVR}(ljzG^zf7j_NI!ghdjl4-+P|yZ20y--QC`!T7*VGI~@R%i+9&XR4t*hf+qMFhV zQ?e9A*yUtq{uv(<0y=5*ntMz19a!qH+f`W_7Ec}3h!{`e;^2Ux&PN(eLbL*}=jiAt zGxIt+oIBrreS+d$>xbnrAS2n>a13vE-dRwE4{izw44U1BiBS)maySFrF-Y+O-ce2M z54ul@Ro&LMC>wOerJ6~uKqoH=$sac);i1^~!-lEOW3V*6rrD&|I@kVKbSFdB5+;i) zBy0|SUGje3yvfYWeD&%_bQaQ}WNFFzT`LI%1q>Wm&v1ZV+`Mz=mo~kahs}gVuc{ zY7N~7wCi3ensh`#Xqk8yh`NuCJd(iC7&#I50RN_Q_I83IutT0P8ukPFqtOVHD1p2& zTE-oTvacPp71&?s`-09&D}`cy%5(y30L{7ASDq7n1Rq`#>~MN^UaAK>FK=H@7OjuB zK4doZ^=%Gz?O*}_u)uDfv|ZVS9+zUChx~g-gC7X)eJOSDrhM*(gbDr)opoH|K-l;Z zRCuHfCuwLopEnszwrfkzvNu2eWL=F(HTmvryEez~gCqAiK;H5z@Zcd3#TST(7&f`G ztT72COr~u+W&L3AK4yD`u;%aJ8vv7GAQ?bf2TP5Ofj3B7>xSE~Wwm)H1wd_`W@M#m9e#vIr;R4Lg11*_R z_6>`ySvDARAlv{L*?|R;?wPD`v4X-v0%GD8ATkXt$#LeRHN>14OV}xbYY{Bp-t&7= zZK1T5e{T@M{T&c5EMRzJV#wg`#&s|e&*MgDCZHE_`?0)xv<4{1@|qegH7lzHNMSMS zazeS6syPC)eYto63=F)K(D;3DV4}@#Cji%=SNuNcU;w?p1>bT=53w&1+#l6C)DVx- z(1&S2{U>K%i-Z<9z$6O`ABjvJhONJbmgONM&*Ch*N0|3BrO^VB85(qO8&LLg-0_9! z=^t$chJO7z;9gf^{RuYP$aA$Ckg!=Ct7Z@lgh3l43-#_5b(q&LlgtykEGEZlbvOgb zE|ZawQBhd|P?@@EbCq@%-Hfu|_h^!C@&@`A&tqxw$F*aGbSUfUqlso!Fo5Rc;{b=g zwbbIlXgqld+jpbF`rwsPlE7*ptvzG_qrhR>1*>1t*yy#lGBSBQv5y%JFgCEwWObhJ z^``dmwy7L}L8xoyH`^g{^0xUU-u!#0w#{e?^U;d0hoqz=E-nE?Y9e?9DJau$Q33Ps zWRny^;D;Z8&^#I(UErb=e6N)y?W03FPk&u-Vf%b3*E5j59Uq@JVE}Q_Fa;rCh zcX}S@U~8H9!CBz0rSz>jGl~tjPbHl#Z%IjAAQeE9K9a=nVd@5B=^>0|n98)BXsj}&P=;RGQiIq$AwoY#dLHTEby0IxzSsg+zC^pD!6!J~v!d(F!L%$gK31`k%; z05tTh7NDk+$S{d?Ux&hlm4;>t&EE%+`Q2Fo>0{VkCZ3lS6f8mZ584uW%WlEQL@;s0 zqJ!lJ3(SfO+zPF0mkL5kE+X{c7cx*esT`ppj*E#oS#|L3?CRn#E9>sGcEPeTt{r!J z*FL>CRGQWo07F*^kGR3#$sp$S{L!OF)4&w~(BOD+@C9)PanqT=&Zgcr4`vn!zwb^d zDv4*T(W=cAj`x85s=Ni#_E{8J@>MxWZ}W?L?g5CatCKA)(7gu@%P>#uJiGwUg8|h5 zLOqndNF9m=f9#ufwXzi8$>+0SeM8f0KP2I4D{X7Xn#?+)XzlAvAcq;Kg_kb1VLl?^ zZh27)-R`pSP?PeGh>?Eo=xw=qGUwwkgai^I$49VtWzWpawE4rXj!BDx7cOM>?eetz zGFZ^Q)TIIq!}KYI&=PD^l!!5fNPONci2-|`wcnq2)+Z;2^uF4Pjo_@sY8#C}b3Vk@ z?$b->5O>_oa+m|ctz{pYy!qKWlILvw1BK>2(?Rr>kdTn9xFNIKLLFhN#T2W76-f-R zt$}faZ*^0Bj-F=ONDR6DA<(qd9@dl|dTF2U(sZxgJY2AW$VL3H^u`B4Uz*?NpfUsy zrun(K27{925@ZR$RV~GjM?kx@9B_TPToB#k5-b&GwtP4-r9W1zHm}%=s1EAmcU71} z?8<7HmnqaGlBG-#@ne0I1AhQAd=T|G00m}yD6RWKZw73~1rRiJM6tYl`BGYY zNcUeDkiIN@Fj+8~rQj>&d7J9-5NX9Q|AIE=PIGHCJkzueZnU0#Tu|%PT?Hml2wI`w zcH@Q>yby4hL;J|F5X!1GsxsOsjkK5Zdkb~)?LtP?W>2MeOSV1XH62{1N1zWN`%r5; zqNb}$O+s=TLKeu;QX8tyOUH$}O%u2ENR9oJqw$f*7R{O*eb!P*;Nr`h(z%0dL zV_svk;SkCVi@qwa5pA7=#L1|+Hhw64@aM(Xkxv(w&R??*7VZD#4uMh71F5*%@Y#&9_uAb(E6~%~5uA93m z)CleRDq0-Zr>eMLK`d0kWU>D)ZeOQbtzVrZt@Uaxw`9rewNf0RuhYEX%FS%nw0Y3& z<-U2K77#AHn)Q0r$8GId4gagP>)V4( zWtiGK#bl$F4B1b`S3UJ)CbbQ7CJV3;2Fw+5=$^yC!-c@!^gF8R^r7>zASyXengPYvs=CN zi7G#;6mE$Mxpdj<? zPe%7P8y7D06!qaEuwmV;CM%>f!BB-eKQ&fge{z(unxeq57rg2ff`^c(?R`S}t(Sv5 zWx`S9sv0(fwoV0e%5VX8PoEf)^ukiH7@tcAkDgqWOHf-?0+DUP~L^|?{*lw*TDNI0kj~cm=!Iko&y)QS+d!if4OMXOI`(!u|*!S=V z>8teL(B=75nq5>i%pu~^8o_ND3L+q(%6X4eW*sdUD({i4!ur@Ve0;@j=Bu`_Pj}ZF z%$b)lXKv;8vXW|DFPvMro1*J(kfEJ2*(?SAOmxM0c*p0mls)f1j`3i|xCUW`PI(34 zH+Jw7IDI&;P=0@+z3?a?JgQcDAV4jpfI#Eyt+fLAui9M|9za$ExsF&d%?~uZ+&g$TDn_fT_LooVzQ68nLa|Zy2K<+iH9&u=vdyR zF~n|o9ThT2R1%xbpv_UH-5K;*=H}GSGMS&Vw)TL0-0EHKd2!~OPl`Be;=%>iK4Ke$ zjP`5&c{(Ji>BCj26ltn2Ms_)W!{$_-2HwD(?*a=8li41+_kYb}1zZwnxSGt?^DMR` znonUuPcBN%L@roa`;mh`0k&TWB;Z${&SyoD?Mnp^@i&mU@U2OWqV?rycGB=2sSF7l zqPJ9BXLu@vV>bTn6T)x58w#JW4QR?+>^3}%oDSi>FyG^BU`{(bo_%C3$2us~u45M1>-cqtd`UHRGQe|7siF4$QtotTe z@8E{~F+L_7QZVyu%3i|?Rh^6-nTW7j_tiS&iMGO)Nc!t7g2QR`|4gsmzl*z%|6Xf6 zRDS+x1pI!bbN`p~ljsNf1;ffX?0eUYLY>8Cz;}}hYn%6PmflqN2%9?H8j{ zt&YDHDekJdbf|NYuKJ@<^y0OT_09Px^Jz=sz)XqGRg_aInCcoNc~9T|xGvK_L+xy_r(v>JFx!%pTJE!)7)tPy z4)^4X3qK5RAct+8vaNbYP(io0Ycsx)=A-1ymclX<=^=L-tt2Hi;1+!9oDhc?4WzUZ zudi%^|JZ714e=Tnhdu=^YOCA3++48uF7U$H($l?%uK`o3T&$l+wTQOm)2cahT>DIx zbjRy#P_MMMWb}CV%c5kI=4S1}8@-&W$WqR%jiw99 zxLZV|qwePw7wvj989CSuCZF$!yCXhtc1=G`zCvyjojTx{?zS8)mDAh7VW<>*F_t8^ z_@2v_uC7YXaQ4?Uix+)!$}1alT($?%Z08|iZN5rW)Hv;sS=={X zlfj*rp*Eq4ta0+R*fEVPIF8Ir{B zuFX`cF{Fv!)vI4G`eDY?EI{cIfZMG)9&Sc^Bi|&{ZK6`R`Qe0zzm3hq{vT|)tzMo% zPcKeA`JW+Uc@Qc`O_JFlPp?;0K^VpK%qnx{%t9q2yD_C+d4wdI#7-&g_MN-=Pb+Z> znV#7m&5T7qVSX{*O=1ardy)DAg)`66EKHj+i^sOiLRDy}Cs)dtSYEtQdU&_~q1`d- zW--NEH>F6TmWeB*s|zzR8A|JXTv!G|NB@~Jmaj$>yc^HRn~Ijs(R-_u_!9+vVXZ}u z-|Wy`iy`~{#%hnu#c{jv&!#-D?J{_bJzK&o{@78y)70l*PK0OzBzRXyKY=5i7UqJ2ZM5N)hxWxDa0q9C70jKySLPR%-X}$+V)jIbcvHQ-i%0N z@_3f6h{@MAPOIKLw2U#*jKEbkV7A*SU+x&Uwz6?%rm3-(f(x}6*5dnOFpV|s-c$X( zMm|lN<%OF!uP>$^ZkINt*9O;++>?c9qo9fX^iga*Y)l_%9-@jiY(|;;nm3+~>`2s) zap}MQat(%N`xjQT?cW_7p(iV^@a$WY`D`$Ko|snEN%f^XTe+;CbX`OaT_fmKyLQ(l zU*ok2Ctd$Po<&-6(kBtmlg8`EoRjvf93A#nKMq~x;pySh?;p0{Nvh@L+gGHWy&EON z`aL>67UdLLH1;AZ_9@{bC`R(`&L(1SN(oCsgCon?xPWT)LRM6v9BJz%GOTPjF&UXHC(JbBlAQ z7GjOYvhiobDJ`p2XHBIU3ds_O*_(TGqmc_dcjtk`BvM#(NvfIPPoRKulO;6IHnRtq;q@)c)Vh%*v1jpNtJ zGDZMH0RLwQ9-1m%cMkx^!KB|#kMGE{ZQ+4b_ATOTxZRvo3@QRhx6Kh=M>W z^J3!s-mB|lp%+9=HZc9v1J}G;>$!EG1s8U`kJ(NI7ehB{J^N$DI&OJAdKto$TK16{ z5>DHz`4GlvQ;pSwiTKR^e$>HP=*GkZviK8ZGi+)jep#F9?&xc`XyOPm(ByhOB|f;f z*J$@weVH^uELm_e(S1~rS9VDEW-sE5SyPENrR5~*Y+W021s~ElG~Luu%e*-@y(XmW zhZ#BG4|;1qr!6vuyv;F)%PvY=mrLk(L_ud|CQfEfDdq#al(SBMwRi>3 z(a@;<_R=(PES56k$hInh#L?~Ku07__>w^KXuKrdc7pS3Mz!)|CmXbu`Yv$9fN*z0% zx8vrwA8k5AH|~z$H=%Aw3`!c15;>J!O+QI|GHSb2ZxF%J3M=^4KM3M$Rs9HTr87OE zw$*_>j4-~veC0qxC?YMX@VU%_?N})9GADp`R~$f9C}~V;21t_5)(e6}5N7P@!gMSW z^8j>Ag%Ljv&+2e&83f(Q36WOZ1EW;I@LW7!wgaC5y^GKWnA1n-l)%JzVg090-U-#9 zE^ZF=^n^b#0Ci#R-uzV&WB2X5?6(WM&v|LXsSyy1>p>428tV-c^(`AB6WYE{V$In{ z-L>Hq=36E(Mgw|+dyA6g9J(FuR_}My$>q!UH*qDMXva~@3gh4I)cw|MEwbLD zRvnT?Mk3PU6I!@8CZW~t)muyjoC6?;6(UH-fs|jR2ZMlUIU>2vep%6E^hy}=lB8`- z6gKz9qcEFu&@B8FLAZU896&6}G!5ciX+>>X80RH&mL=NKF=2 zZDi}z>6UoSO$22o8mg!EKH9gn>RuppsK)!+%BoZPIZ0#dWi!*I!G9xMR(9akHMI%` zu+1ScZdlL*;mWzzx2HR zd_LU3UeTv>ec83{Ljdq`0uGB`I!5iy?CJ_%oFZzNqgom1hfJ#%Ot_RYPA6Q-Dj$g$bs#d)a^XD-3Z%fctXFB7+z zHKLeS`)q+a-m!PcBa~pHg;%SM7d$XObY(LmCj40jzC;XYJzDxeY{|D-Al|#;nviJG z!--JMA_wB|IZtY28IZkrEBAgmmO*3lS?(T&A5#R(i_jny?6gj_uyFKTP>h0MZrq5| z_I&I_GJhd2Syqs5aWr`+#?&RR<5GD|7-^{D2E?(*aS13;$)@?Gd5^YPiw{aLQja_d zoXjs3XDiq?$*lyx0eoiD=^!xT-NiHp&ys+}%%AZRW>)t!x+1Zr$)mfI_Q071 z#<`%8`CmegS3$x6Mm<#KQW50TGjAH1RljR$x7?Zxj{&|X%pGA)4~4|qTKUe-xT{<> z>l|y&Rb(u4r`a?}2&-dfv{pOpHdk-rCfJ5LO(zI?YvyRw?~!KSfYA<0Y~uw1zZ=nd zK^&$i1|(pBtVDc zac(a{_$9pG#0{^FEX2Ase{_Orry6`zgxI3i8+%OZzxG;yqBP;6Y`k-1q0)TdHmP=XrJfBHWxxlVpK2)IT^yEU3bzni~g^ic7 zaZMuavAlehGUbsF;RKUXrk8gsV^hXopFUR4wg131qhiBmY}(GFx`#P30_-{)8zZCBAk+v0kpkTz13Z9FLudo$RHj&B8U(U>2 zk6~<>*kK1Kpg0coll1z*Pq6xOm1qtJQ`J*U0iI%p)s2y*=8TK3CCWc*q&DngPDtZb zfTyp~mrSNH%wJ=_xF`*>7?=t?f{epI$+5a+#;6-Qzo`~6)^mosN(q&*+B$x3GTXVa zAc4*&r)`P#uIINFX`iffD)4ZKoWHjD_%ZgW+b+g7VOdqx*l@Iz5Iv)Xbdz3OP3t0q zUQzBwt?ltsH^ZLOQyleX!%^AS8woQ#8B6+PpTg8eKxP`!O znR@lfK2^&2%^4~UlZ;XhNutk%sR*pKleQfa8y*>l;iRz-xK?=DJE#OQ+-{Wd<7ZIS zT8^ebca5pVpGz|?@%p0bwk|h+(FOMO%raUSW~zytn}o)-wi2?`UXA;JnkMGFmb{y4 z^y3(Q(#=s3JT6UFDO9sQVYK)tAAj1=%6GR!kCzc&yEG z_>Kj~phe`*WLajL?sWO!n?KIza5;?+EzhjyA7^z4egkR2EkhYbZ%;6o> zASKGa!45QP9A46dBww0$mAN1dDIoTsPZh~zqPI$Stp=HO!JbP6MQQ5SvFT~*hpIbw z#a_8oxy0ug6HN1VFF9HO7xfe8c2cAY6Y6@>z0^?)I#edKQ5C15xI7%sFX7@`L%TMT zUY1^z)X=`LkM?CL8ZK=Pa8fLTB9U;$jB7l0MyYdp4xkW_uG~&6}t(t6|S-h+~7jy+H1X z>!yf!7)Y*GJ`B{l$m#~4UM!fX25OLOt#^H*9T+@)!StL1sA&;om!e}~TSFsBFFd_F zGCX46Bvb!ccxK~|=ky9^I%L-W__!*nXZcQgkCe-ucdONRC39Y4;mTn%u1QVCh=%f` z;M@VhaX%5QVNBK5s!x22la^S^3zIwPHcZ?PSnr{F0Bss}T`}bPACBuPFshw-^jLEQ zTxvD<88UUot!A^omZ;w~q7Hz4yw3(@m`x}}Ek?A1T{(S@{JZCrNpPDHrbB5WHakAu zN~ydJ-6GrKgGQcP>xVTtZX{5aI6G(0)VFbQ%z46P@S!BqtQ(iq4rA1yvTu`2*V$Jw zX^$4l=%!P{v^wqurv4pvu#kBIqgz$Y(E{U(ov0m_Z1_IuR(T&-bt~}!(HaA1O8w_@ zTG8m_6v+&7u#5SP*Y%>?sfr42H1Afzj+#%#LH+Y#PcP3?C~!)xp<(jGr9-$VWGAb7 zar*M?j8UE@Nxf|{SAfx z601jQ8Nl6npF9zs8OdsB@3%=X9igVCj1>}Hn~e7T6$3Y>c}6?YY>E+w#w~4pU9dGaDF_8?q~#izHBrpu_TF5IkAI89Ym_3$ zW44+TK1b)caB|gQm|TUVH$=y*4k+5{iVv-CkTIjIMOaZ^*$hgx*cF=PhB+3>hAF0a zA!@CLQG&u8E0gW6TM<@R&X{LpuM3GJ_dtqH%)|OOBm0wer|~jOy`t-4Ut3)CGADAA zt3aH-9_Hbj497&{VKgA>1|LUV;{Y4C&9H`-;kNQ1R4d(vgHoy}Vm`tHaGezAL~aYD z^rY>lca@eT*ftWnh4Hwa@E%7w_g-r#(q%^SGKQ|pq ztC=e)hN>t9h8+)5nw3{}h%g;0?xhOr`K-uA0y(&Zvl|Y1v|uHCHAJS0f8gk%p!_ z^~LEVMRY&y$qAIP&Q73^tJC|sj|}#e?};)qrn|fJLEYO~I`pYS)EJ3-ww`0hy3KnV zDNYZT>=iBRtnCR=xl(Ui8B*fgIZe%R>ydWjQt|9b78k!y#f?`Bd6gfp=WM;j&xpygyu#i4#=KzpW>EQo9MM zXxb|^5H~6XWjKqL#CVEQDQv^+LZbwGJU{WZ*fd9F*tvMb4L?qE;Fv~yd6c>PSX1D@ zlVRN9cSzOn!9q@nQKAE#=YFU`sBX6S7~EjZ(wpar1MSYGf`M%sq{e&@Mi!R7P2I>T zYIM|8aOWbS8$y;SC8ekiC#mqk$-2gPafeBK!zVj2*qyV5=augAke#&zKhJRfm*<6d zlaKfMl;pHl6nj=isMy-#&4Juepy9F&9KuFbFoMrmfLx*1eL++E;mX`=K6FUffdu+7ME_;^#u6EV1ZR? zClpDgaWC$jwYT?9m4DDeYh<%7OTZJyI`|?vuEEgAEqb14K;X@@U zS0?sBfQF`)s5o*S$q5ok>$KZ@5Kzj?v*N`)6gE0r%hM zKOBj)bLV-wxH4H{N*7S1el7#nb5G`RySo7p0Wc3&11zfz5M4-OI;D56yh_gS%@Wt3 zI0b8p==(c`ZvzWi2%i)h7AokO?5V^#qmcvFqpd;tQ<*}=S7lg_Q_N4yEMEIVnVz(n zq!xOI-8XYH5|~@A@66W3ew1D2dIbrRSXK7emV}?8Xnki4g8(^^JFx)m^M`s<;Fmyep1PLgteu3Ocb&o7DoQK_N z=Oag&La}q*K7Hg=^`HP6YZBpPbvUmkpD9VD>C&>UtHYmF65ba~o7!=y$J;&=(U5%S z{N3xWcZ23hf?Peg@SZ$A?xuLPp8u0KLi3y;F|v8Ox7$A&Q;hh4DYcQ@A7lL1L*&)e z*2bJFAR8XE8|4SpoTg|)eL-J-91K)*IF~lRCUUyI4xO!Dewg~QRa1}>(LN1dc!5#vWCTGDW_UYH@G0}oZIu%H zy`yaP@BHywB05*$m8w28VrD65ej4jhAsEUDb@p^c-XdEoD9HWBXC=gj<&-9dWNuQ? z%2I7W&)oU8mn+!VmS8=fb3R_^f2YHEGOa zVzpvqD5q1}EOvQq8LyK2E=JCpxfa@-uV1dI0Ca05(59CM>$7h-*>LK%+y>w1d-BIXo~Oi8gBp6k+9%tb37e%%)^FqDiJiC&<)mm* zfp^5$zW2nE^5lg%Yy~$@ck+R@t8h@(!^~v7nD!sW_ijAlCK`knI?+)-JN(ZRSO3*>XFqL8Kf}W3ZI;3~Xg*H$D6e z$d&p}E&POOrM`Ry5p~VQ3M!tc%31!$wZ+h`bocw;}{3|8{&!zkBCgay0 z4)(I<922?@gXmh2#(70K=ZuU&0xUe>;TNu~5d6B82Fa|PV)d>0qGwYZc8f0ik^Z5c z>#|Q5xq2|cZ^a5gp3kpSMWkOEe|hVXQ5sdJ;6qtguaX#(UIF(I&g^?FrdhagXfU}G zt-R0TK$qB$WmnEgYFj)BegCn`gtV|Eav-&4?7$GH-4WZrIFzT#fu{s(tK057c+g+4RA=>Xwy?DzxSjpz5BThcwh_o;t27%Ge%$WeEGMm-1y@jN!s>K1MM{$=)^=4UDg%ktQc|^O z;zw9sKFktG4RyIjCk#oePRPU}h8#|8o~S@cBSoa)gAY=p(vceT28qU>P1K;Of<(Y*+dTN0{nvP>!~ZYohSYe(SOr1ORV*LiAG~mdWL*^vp;ns z889TkzR~jmv6l_crLkMZH0^e&9oEA$`PPEiouuSp_m`#sg!c4SnK37@sEXIlH4*Zp zHm?Zfq~qK4@U?o#M|r8*qB((A>MIr*eQm*RM$#Af$0?F;9!PF;V4hP_pD4DCos#>y z(2K;xQlB^9uhN|PML^B%rT35lgS={fN8KE5&51R2t92)Qf$t)VvJtCAD7NDpz24~P zITQp=D9nk}K(vvZ($GB0+Q-SlLS!5qT)qeQhF8?b)7|Z|geAWDj8-|nwwwdIE!!B> z{c&eOw1oKqZ56KU=y9uv_Ra3NrI0L5+Q23)XQ4qi15Xw+yV(^JNckh z4^MRaD-M(gC=FI<19_hDXI0OWiBVEJ5!i)Gh-IAhsIS-xZn@IFtj}KbSXO#}&`GZ?x?_4bU6U zyv5F(Xhos)^BiVRPIIAE46S!}&TVM#*2+r72+7I#Xu@TnZu9hZzB7N; zh4Oodk$r=roY?N7@2qI&Qg)Lw6UI6RTZA(c-m7}$rtBEI>HsCCc=Qtr(>Ot9RPHRX ze_rbkQm^_xlaw8C7>~Q2Ya8Lgg7~qusup|vd?+SJO+%|U<=th0?A`%&!0v*?@c0l; zZ(HyN#^AF%bXLFM-Df(nifhx)d}uHL!zK(w;5u?|*^zz6yzHbV+T(FQ`DOm@3?U>! zJBXtq{Q5|=4>$Ki!K;EvfbF`TWtB~&qY23j@A@_+`V{Sn%Sau)@Dp;XkjINK?10#GsjUOSs z!H&sql-ukBd4!&{8C*8T_A6Ouh4+q-mSM*>J{?{ERxw$?*;72viX|gPGJ3e>$|oXp z95%`C;@TgAkE>*8x9V!1nnj?*M2H!%Y1;?&HK(^QiC@66IMpOhk=r(HL`DjgEDckV z_zWMd1?QhV_uAn)nuETfXlc5frffuES4(o(-!Fz?qzMYAif|H3q=!mj;yqF>P4VOn z+9>*CkG}qoJv!15^BZkGZptXq4#J0Zf)l;I4b%JdLftV<*WYL1l8ZVApo_ z;3wWNoWfM)f!^r4xF>J5@0X>5x&Y=W9`x@8><=A_yEcx0P=p>{&12s8Q)0?ko?JP$ zRAut2%|~L_+9^kMA1z%rJsQNP39!RxKO>FNijr_a()*ln=%7YKdc=RwSzr0%!4(l1$Qn zJmR6p=+c{faG6%t;jXwnD@^oc>Y#eP34od3Q{mDgg1u{S7}AA z&z3metECB;YtNkHZeIZxLPT&kY^qN`LWVOBR|lU8vBU5-Ztpn8+j;C_5Bj^R`BiT9 z9&*@ovCiX5!F-HL4+HbhFG0H=J)+e;l_lkbA!j~q#b&P(X0AUk@Xw4rK78dgBbZ(a zvvvi)vvZ59Qp<)lsO{FsmQ5H#nJsKHZuHDmyoub%shB=PXko#- zseO+ae8eV;38I>V7NokmQ!x-v@edD|M%T7y$jLV&N~0hmSf?ZUK^vW}XqW4>#&aBt zO`!;`m0QKjDK2xe@BWYP$Y)~XIb5P$S_I0f<#)Q88fO0yV ztANAZ#mJiB{wKTx8?YmUEO+`*&U`mMNt}pxmZ4Wu!hqLpXwQKV0$fO|!P}nJi<#V= zUkSco)WsGM`Ye^|(Se?$t%ynJAAR$h`64J{aL-uzljXku%8YjuE4uuPy7u;3tIP`) z!u2KZ2e-`g8TSC+w^F!Gv>!$4UBO>s`ye2u)Mabr!;8$eQk@>9+DK`G%0tN;Bj7h< z;+TLk%c%193%Qqv&!raXt*iZFG-i&g=$1oVB=%enLriSUp}FPgs35nuZG=Kc?#Z9HbHBwr)%<0xo>ti#!yWq$v9Z%5oX7s3 z)oOkx(6dY4d{@Fx)L`gC4*4-yNkxrV#ZlCK$*MHL4(7=qsZoTWf7=CpEa&(mcAkorT^zKdeDH@kT*=AT zd`aVyKS%Fq zQOVF?2~oE;<|sSux;r}yi=0u>?!&WT05we206{N)zH>HW@hx<6;Fj!y-ii8Lyn6i=lZ?Yf^n4k1$I>i@CM9IlJot-C-ZzH7O z^{e{l_Q~nky!S@K_ohJuHf0+wI)q_UuT*%3el(XD-VTA6+y7H{Z$l0G{S&)iYuP$b+@OauL{>G=WuzBp>P z{g1aHec%sLD!V!Q0lC~UqVuj;G|A~!xfb_29zC*RMqBiGsAc4LT;mwMBk^)IJ1NQ~ zU16T`CY#s59(Lnv z_4FMUajROqW%2JRmH&9(d=bE4`z6u*^hiIQKe&ODZqN{MxJFN|g!`}~`G!Q@5s=Gn zEEFcoQtmONRgnYwYHZo+ZkU*{J#>HSC4MN0IA@k}KDX*v#XQD)ya{+p;0 z^37H@FaRG<|ITLdQg521xVF(tAYr}`g=Tcg>$Nia@rsb!a14cWbHWGoiu3s2-Ct!Z zdPy^TszDe`fYH&1gw{#3asVPl{9x_~;6iyAN+Z1&g@kp-P|x(>KM3Ae{nM(PHzY2r znsa}baGxQ^X^f@A+R2==uaeeS`&e(7z}V;Sx&nV~6~U6(x~9&83|e3Q@kGZ@=rSuJ z*|O^I#SvPylKJT0gLQ6BI-)dculS$lctrkJhV-cl{}k@w{UNHjB{>wc*JX<%emDvL zp8*a71C-7BNt%_RKZfdF=H3n23i3E~6zx0ojuMc+n~w&dT{%4)H9J1l zUfGp7w|Y0bhcayQO^Cl*7V)pwYdL&x5~D?Y8xFLa3j;vS{xc2Mz%;;XirMCUL$mHk zHETmRiT|fFCVbs@=Y>Viz=L$WE(s2geAh3o8q6hu(J#>Kby0o?1<``Vm?;By`{ z?!#xd_+%2Q@Q(yz0oW6KgW{OFtuMjo-wRO>*=rIYFKWBIjwI|2?)%B^9(`vX5U0>p z@IgA65&^U9o>%c_yP;=|MEFLy8Fg==OwZubIjYFt-Z%Ri>S7@!lG5E@HfZoT$a`8E zuNoS?2~O_rZ7hF<@JaE7{d>aHNPM3!4<&WruYVDq`ujhW1|n6(=wnVAuSbJE9gAzv za^C-2a({hAuio?ju7$tARlCU_5b)pMrszL0{QvI9ZIpb*j?l^N>)gf8Z_inHkJ=ch zEz~w>Fge6!TDPuDR!V{IfUmu1;v;R=b(H(^qbF#iM^|9XJ3iFQ!uJR{rqtB?S}~U3 zz>{;ehr^BFyTs?!j(D1yvKom1(scoA55%|?z@+a9oZWiv+> zik5z$Nx2MKx%C0@NA&bLsvrK(Zp?ahFI4$HebDHxCPw<2GOE-H?6`(^8++7N>@e8y=j(1 zZe7D(TFGuywR>zJtMVKhW)dlNd1a7xMqD4vK}-^UJ9wU!1rLev<=?gLWl{_@>#X|h z;}n}H%f`Cj@{@sgv)^1VFdud0z8ab6Ib~kOe;$E1;a-U7>w|HSq|3UV&HkZ5dUl7dA@t z{#>QKuj@VGpZVj)#L0T5FD9aNg(35LEOW*lcK7A753aU6XR1?Qye1OC%W(l5=uqzR zA#?;4YC_3QT)$Zv8z#1_51nTRo})^cV>z1A&mp_CyKVqg*=?-%{%(pP_9xfS@Fz#~ z?{ev4)qBUy#Dg5fgY5OPT6QP37p-cuo1W{lYH52Nwhh{>?Dz|sWlODldMn3h{64=- zi;J{fK79KSk5le4$jT0{dXXk@6NVQzBx=AB9o?oh8r!G*EXj?p7U(#f^s#49W-oMm za?YeBz0?+84`@tF95#M_A;*wAV^aJp8h4ZXGO`(Xf`#~%oY5J2$HOFFf~q7%X+!I| zR@cCTm9SW=@|~25A3t|^Pc>&y(CMw=$l-FZQu=nE+68c1h1!EOM#Fj2;>t;1h_eWl zySemVE%_QI)?n4`7`|~FB?W_}QL*jg>&fIaZ-`!j@{yie!J-jNSXsj zVvrz9ltEOK-iIGNL8k%oilF_N$MVNiXFD3r5a@EpOfDN*z^S{@f{gUi_Brhtvfi@# zzPbl;+$8Ne(yQ*?6YDR6pM=O3w;a^5Zq{YZ&Zu*Q&?&PI3_N!iIM$!9#X!PTWGs`#3mwlabJv0qxW&golX{{ z4)@g@j9jFMji2+d#(!+)xfRN34QjKQDGS~1L~m1dfge41eBFkZiuTR@jUXV)V31q= z!Q_K)wpg_ti!gHeRK;K7hN$i?Ly=lw@U8O)5P>H`+lVr)`_HByn3yP6W1uf#t6Ntr zp}wzt_yFzI;ds_RLMrPv*&&N=3U2(+*U2UFAYkos+nG!>@3pEJQmiDW#r4`t78wW7 zq2zE_0rsm3m#fE^UxH;;6^caPt`%O)jTD| zUb-L=){fx^ME%`$_8{VSJ2ZnK zHQu66UkMpyzK|*eA=R;r4L&)$Qn6@&ZAZB@@TuLfv)w(%iSW#e%#cs9-e@jCH`**L za#6akEKw64;MaxTsrRee?VJziVio|R`H8h9npO05iwCICx`|!cdj*Fm+=P8yEicwUbJl3RWo`{xV zJeh7K@+=+I!_zj%04ACpz77k$*1Gow|8bOHf6wEcd+!jDnFY?#dT7_#+9-FC2G*SM zsZ8!+V@VrjVxO8vajm01g3aOyevIob{;~MB1y+w~-PWU57JKW~^LbqRU@IjAWVL(L9LT6&2_4P8GavWee0M zidZ7I;XZxHLH)!rp_D^n40NK=fcrvkp1B}%{~aV3SN^y?Wn|$~y%WmT6V*4nx19S* z)vK^jgawH51mP?lskvwE0aqG4hd-YWLc`<_Q;br~S=7p!NfE zPSzVxgXzJ}!fYS)DJX8MhYyrQ9%=`2fEnl8QMLkeZ3aEIWC`%wg@n+%%!A$b`yN0= z@=hs9$G4^6Ty7W~?#=8w;dzL@rOi<1^97U4F?U%@^m?Ex_4-ZR7JlQFmdEi*&>)6pLa-H1#qgX-CkoMNx^jLf_5~(*6NlV*3 z$L)Blf=WG#6KommD4JDU`~iEn-Qu$~D<6>8OyLsCOL!PT<;%cJ2uW<6Ep>M3shK-P zH%Ohj#IrrSw(dd7J9kiw$TcJO+Cz(FEn(intg6|9^jFK~8B6JsX_@2@DXG)W{gcur zg+s+8BjPMr5@(08r%^3oo;HHNE$gds0%w~=82^^S(GJR|03n=f4;gf?{mR|OWj{i@ z;?+FGFF`)2lJxdjlAM0p@E-jic0Gwbd#9ACpfXl|wpl?>cl6~hPD?r=>Q{XfGJ~+04mRZuDsV&#p0Gfp~DcNhRgs_?FdtjdPVT(cAL29 z!qTKx->}CM&Fi*R(pUVKUp(EsVQsUgmk+WfzW2skX%J#2Fo#VRgpO7`8+e~l!$>st z2ZrB%Q7M5OUeD>KSN05PE4cqBQzY%{0fx!u8=~_{Ta182-#2D+tUaTz-!p5))kSh5 zG!4*WcwY+g7OS(Gy^?!npGWzE(x7>YOlWcPOkZm~W71M-s3K120vr1$nB+A*sqG6} z%~z`Y9ES-ycGdUE=5&Ixv^R=IJ4DQMFh4A=;{SY_y0l@Wzu*5qR493&jny!%hs3J}t4(qS$}6Ud)WOPzPb)yjmmfYL(<-nJxlgHZ^2 zzT#nc>Zxo{-qaR8)|>i)zDR>MsnhS`X5_Um9@%`{e1`re#EOD4#q{OFwRKLt?h2M> zg?!vsXxxM=;07892Vq;>%agsyHDB|mQNJk-dQ^O85PE4H%h;tQU}pilQ;&wd0roHN zBU)3U<(YUfBm6N+SsyEn3B)VhGXZOkeBwIJnLQk2k5e8-5V z<;6j6LRRYrb-(gX<4EzlGZ)qK){d$w;$uTijq|!MJFIWo#QQf3MLn~Yr;uU+Iii#X zaB7ZW%7nShlAlLu8ZnEvSJ{wlo%)xsFm7PE%+3zBE)k2(k3j@7`;;eX$N{8VZsZaM%1&FIe37ZqQ zw~B|)=Mp846WH6hTt^;0!{TA_(-F$^2%?jhCLp};H$`(tat^oPFq%d~E6!xzOry^t8U*8@+RSvA~*)Ui;q516K{cUY$^Oia4z_(b~)iM=}FG+qmb4B1$cf}*d4ZQZ> zKyr143AU?;Fj^W)io4NXMYJG?*vXMdQfS(x|DBtwtdR>SU^~!%x+P7adipmWpF2ix ztVhdWLrwlx3-Zf?{sCoSXyrnWk|KQ~ryQA&nWogfnP;>cE-cXiDur|fF{T%@sV(8s zmyR6xY`IFtgm#SWdRONnUfCQ@!$V^@^j-TKGulhT-)OchVSh+KHhr_P2QRW1i~@Ty zXvoe}67feM-TOX;h#KW81yV*pBxT9GEpmUhU9X%6pZCnv9ISU;*dl)TZy)^ZjU2j6 zo$0BQqJP-E;=JxlxABHC^^WbHFvGcuSb|`7IBW1-rB+hJWp|_h7*{u0it`WEc~avq z@fQ$M7v&6tm#Y{U@e`{H6J9Ju+Kx-Qcui8yA5Nle$!Kd#Sao@r1!LvNo?Q2QPD2t| zFdW~!YR(9YhUPv*iG z0Q78O%9F$NKBN`_i~K__{JMf1qX05K|`NXWfNV8 zq;g4_#6Oyvr}A37`>Q9J$)$f5-e0k_=OYlwzy>7;eCY64xW)noaOg@32LKb*sph6y zHGZ7Kf8$^f#e+Ggkm?!U9tL}QXwOX34E|&p(Koe`TZ#XQ|LUI}JA(G==E}3h@bK3D zho~%*#Mk@#8m{QyR5jTA*<$+=stP0BdsiyDB8=!}f9+Si-c+wVSAvNS4ELe%T+^lr zQDmp>?d5YH`7sS`51J&7za3x14wu*k7BchS2F1&xeOT-pN^YDml}^`3I(m#BdQy@` z)wPN+D!vkl$MjPV)-%}nL-0$mK_QDH_-Vs@lw2DCe+^XM7k2QDk3$biZ zN&DjqPQCf#1ulgn6JX0WVH(Y6K5$j`pk;BE)gjLDv-S{SUy@{)nvO#x0c+eR>Vu=l zd~V*IO}pjh2+S#0W^z&DU2oBR`@M@OFY(?nplpYTYyH%Qynv`}Po4HMKD~R1sPsYR7OBknx`IDKU7>MB19;3zVE-lnXf$?hv?8EF_ zid3zS)L*o_b~F^!tzFALe&<-*P8QM_?d+A$SwGySQ)33kl~y@>te=#@b*Vprx=JFngq*>&?tf6u`J z%$J=_jgRxE-+`OMJLWUFa)uFS=}Ij|d+)Mrcijt1&-WZ_7WTxq_pS%3rXx$~^$en{ zMICo07gm0yG`4a!cDzS>Wv6z!Yf=uTbpk61*uCpMa9@|2MAbr3M^)Rh(Vr?l=b4J* zXsA8!>gedeQb9Ue?9q`XeP$mRsw(_{L)~7`ehR>+S}2n>hy<{%AZOzv+ZSHw^Af)C z_t17pqEGi?j}U1YDdrZDw))WlquQ+ygJW=jq^I9NRDHeLmll|1u@R*`OcmT)y|*9*%f%dikNfZXeruMJ4%!&I^W0z z>rpRGClUVA|AS~Xg)z+y(%oqq0BO)=6%JQMk@?EJqEDR5zXocIU7TAePbgh998w?L zf78e2G6VmxywUo@G`JbjbjAv#`&PI%;s*xR{K=U%1zDOJ{mDJ{04mCHaX|j>xz6r6 zd$xUc53Dh&T6yqk-5vq?%l)mn1n1EEtZm*z!_}QD0^r;VO`z_yez~X{=3CO!9+oUJ9MoBt#s6>(l`mAZ49fjUqrS0Ew$@Q=;Caf;o> zv7MMwK&N9XH9*Y-Rqxn0_*w2#+40+55)(5HWTIM?$CvaTFp9hL99Frfy?tf7GekLw zD;{k)1|<$qukYnRJDA(PT-g!bRyTXqH-9mb*L1ds+>kWc&;Q>r(6*`OuG{B+g|D^P z9xy)A8Jljog-V@{>WGYQ>OcoH(Mxmq-4`B?&sAy#eWIeKu;Shb6;PgNjo{r!x9uWHvH%>(G0It9mOss!eaKzI?uK;q%_*uk{~91Y=Z|7H=C) z5_<aE3Z@fcSYWT%K-fSQ2 zX!b4zrq-m9T%ZGY6!{N9^B3lqUGe-c)Axt(<6Hhm3IApPPO1M9M*pAx=$zFZEyPZo zIBZZ%c(^rQ<*675K#;13!6b2M25B6`iFLB8&tafV2=JZQW%dnv;%(SP7>gN53? ze1G}TiBkdHeavj75%iqcYYN~!tvxOF z25p-9^4VWr>q-M?!;%aZcWeg5Zq2DP^Bg3Q!Ia}d^C(jhMf*TMW*@)9t1n(~DkXRVuyUQytE zf`q^DGN%0T{%KJde17MY`am(Yz{8>ulE#YGG`%7E2O4hD8uWYT78JLp2P3xztD|L? zAucbjyhYPXh-0Yz{r?a4-ZQGHuX`5-QBWz0fGAZ%6A+M&RFwcqReA^Mz4t02T|m0D zfK=(dgc77l38D8EdJR2<7T|1t@B9AmId_bEznpWv{rSLP5cX#6wbzlIzVXhF4(VSUT$vS)6kGh63|(EB34@dT<{0pLcVPgS zYbM|}Tk!r(?(RJ0T{_~^S___M>K7Ly%Q{4Lf^0bPu5{OnhWnWlTG>Kw9xk{;gZh(# z33Cn?(zr$N7L7P-J%||W%|N;3W3tzI$s3qr@*m{BMHAP>$eG_gj{rve-rtR*DQDae zqPv|H?ewBl=slN0^~~X?q7siY{!J6==0ilh)dOS$BostkGc6i-OirvV0oX3v#I`OTvz1s z%2)h^>du#jX786o;Xm`{0e*Z#8IljN!p@2N`y%U3dm}HoF5X?4nN=g1gve8VTuuH7 z$eVqO!4^FY^@iq19>y_B)}gnIpsX{?6zmod<@A*$);q1?S2DZYL@%;8n=K}j*2}b3`4g%fQ%TqNDkh+Qm2|u7PF(3BD<#_ zYpWkbN+i-+*~dR;ofnj0K>?$B`q3Q|*)o#fF0SxZ6DeSml9#+YQ-IUvC?qhn_ixyh zU2}b`Qh~QY>CU(9G3-}o;cC6$oO4CstmRv_C1EcgCTkFwe?~2~^6(1=wV@*=fKp=& zJ#Gz)$-nUB$I*mCLSlD_Z^ahd5P|I@B{bz%awJ8_--lm}Eml09ntZN@Gu`_0W8O|tvDDUX}GfCy9MWg%ztjUDDTSM`iNQsn; zSbd_cM;(7LS?j}#wUM`Cw>Hx~_$9d-Ouo3Elp-?4j=> zg)O}8>HWesMM{r++21C5UGRguecYLrHIS8X3u5@`Ul|_SJT%Dm^A!RGb-S(#z>IvT zs<$kBHpL&8u5+7_L!vr3YU@_pnNwx=r{sz0^rcdE(9B-Z5&;J&i^-x8y9GpGH|y71 zp<>PQ2KB&AX2XQvO9f1nxxq>Im!|Bp%$~C^%)sHx_jCfTUkOexjX1b|8d%{@)a`m) zL`YpyGI588()fVJkmxTyvF0{91-{SMwE|!sQQ*@mnZxi>r=r|4wL)vzA&%nPW!NH zBVQxKyOZdgtp=V0q!DO6Jx0J)`^r*H_lk1*mIy7+kNSu3m2b7`T%mX`j;&Rn987ky zCTfn>3T(DL5q(N$kZZGGVt*^#I#o{Eky46N+~rPr>9G2mV2rCCyALa$eRmNW8>a?F zF>w-^I=zEuyuz)RpTN8uoX8{>R8Yv`vvuu-dYmFEI^{|Cb|R_O^UaHtSAIJH@`*WD zsZild?qE97A!UBn7B&^H0jyP6if=f-(ujASCZXbI6a|^U5pT1SZn*ig>JMakwsSce z@4yT85}c;*Y89|7as5yJAW9K%w)>MQ-u8F}s$NYBrdMWnzRU9@2Rb?>m6S){*U(@K zk+&+Ow~3)a=e9fi9r=(B8LU@QvH3FPx=?%CmOI4xzrDptp2f*3Rv={EN2orh?GYOg z;H==kVE+lQjo8b>@d!zlo13uAbw!X67#GBolVwPcq z82QI;syy-T{D!~+XW=H%E?t62hVI5Q(3de-uG~rnHpX8=xXC-McTR!B)y=Y4VRtv5 zMVK5%-5aYj+L%$}qm}B!KDRRtb7l15F|u)vxC!5gtb7pGhxn{F7+TldR6CDO^I?o+ zir;U(GIEO747Pa^`H%16RCD;9Y&F`al>fHQ?^9K+YlI!k4DA=h+t+=qd)KV-3xyFX zc{0WDYD9|L7Nu~|6SWrdb-%t&%i1ZrQ(h%bwIPLSWj^lLe(o3jh|@4w{qx3J!5*pT zUYzeAMo#bc1K>Pgmd#D-IoA@yI^HC|mu$rG=FXy{(r0Il=+*ao`7!)Yyut2(kPQdt z|G|(N%9ONrDk{>1kL8fn~)J;XQI zpJF`>-2AOGcRU~kV!2RmYz~{BzpaX_Js)Dv{2kH8%=j$s1EqMHeBRk->(4Jh7?VcO z5Ba>M%}Eu_056c0wTP7rUihv#O6#{Ic9zS+bv0bMNQTg!QRQahsq zLPHL6nW0GMf~>zk{8BMi#XGbS^g-!K z^31Yr^?BEAy9d(9e)}IAo>oW96Ib)8Z~h|>5Q9ed$zVA?4X4fu+hL9&aIm7Za_oGy z8ojq-sZP=Jq)-w@W?K`JzbaZ%MTs$TM1Kjxrw;0}=xbC`G{VEurW;}eDzE~{`+gI7 z3QBHFIR6EoUHuN2Nsd0BRGC|ufA-yZ@x9eE7q$Q^_oLv7j@sW5@5TxPW+V^T&xnXzs)!!2RJ+>DO7R+@AWWSt?I`TSgRHV+gOxQHJEhU2ZBjhh-(U_K~JZV^TpJUqEV zHJ}{<1*zI5+-9JQSXXkX%N}~`*9Y_m#4%L>(3+t(;JXor!@o9zngYeECCcTqi&ye?2rnn)`$C+shHVUHVt5_@Yrc_c-Mr+MN#-4ao)U2O( z1pb|o5h$vqfIwnSAPv&_FQ3L}2s1zWzAe_O@zd@lO(!@CWi_AmY>XC*IZfurZ*eYO zR%K)@Q^vKiaGQAM%r@!8%w-RKI@Qu@H=^AZ7aM#}c4XYkQDpjL?&He+>JkMK*1dwK zT=ze?3;ceC-=H7%eUIOndD1azsO}9pskc#JqbJjM-mdBXsPq-xtP2nCy{YFqHNi`H z1qE(9Hda3(j}{@2eM7~mCXPK!rcr6AReqKFf~@^T*n!xSK&0JvdRi?Ism7}Py>Y!` z>m2?u$9klnc_l`?JpymP6ws-u1cK0$w+bH5+Re%X&>%R4Bv?cQuDKU zw|-db!2(+s7QeVhFv~pz=<3wVw!za>COC&yN$zC>bqIj{;C8#;REC;Sa-ItJ?hU1a z=Eg0bc!4u&JJ+7g5&U)gHXr~`ZrS^_K!vN7$OO>gZ60_3jS``__tE8K{vYphq(Ga{ z-HYY1t^^NT-5x-ch@SbxB!W4oxdn)oEr*+8Z{P_afR3Ysa68HK4(*iUKeHyLL+WSb zzomE)I^e>X34{T(BLBF=fT&mdjdEI7h_ue^hReNB{?=buJ%eo*t>B)P(3z5P#ik<3DOzv z{D#Nhn2)8at8XG!1wFU`5USj0yS>v3H34*KR9K8a#8~kDj7f-Oh*&?B)cc1Cg~q8Z z-sR;P)D`{ab5T@Mj~}W_>8)d0W;4<}+>>`Ulq*SX-rQ6ePdjq%0KboOW$?Vc`i`<069mWFv6En)Ay92iw{6c#*wu% z1!_I-9s$Jwrf29lz7L>)cq&AtC^qO}mhu>Nv+d$ym}WB1jVBg)3rC&6D9+9NvFj%j z0+CA{7q!Pgae{s_B9^MpWuUhrPf~Y=emzRr4NTNhMdcDq`|7yVD8IRzJHF}rSvfEn zSn#oWN9x_#IA0p_{lif%YoAO*3?9@^6jV~YQ%7@L4X)atGJ!A=0y$m;=>I`B=h!Xr ze@7-sMhN)L344p%7ln8zkZ0LHfW87|@psp!?7O(XEJ~ZxE6@%zUbsb#7vret2SZD0 zpHs}j_OSnwuKvSUKi90+|2KK|2Ae^+|Gx;C|6$htAOCRZdSL!Cq*iS&n%@5oj|YLU zP{4hbSHJRAH(1Hsdhz9w{a+eW_Wdl6zbE(el?a!`de9V`MUlUUPSBj)*Nky4i=xb& zudyWY(jQYU7jr4%r5*V2xpwz{`txri}|nqi`BwT|J8p{U54{t<;;QV#arF~ zs(A}spiK+?PZP&CMGXJ+#J#!Af8YGSr{$mJ^xv!H|K=v5xNi%zDE?Pn0G$7u|LDJO z{{LeksW3+td*UI+2J5-hGrDilo^|bu4risz?lrm|6@|?7-cejPEH> zj4(IZy(`}?=cIwgHP`rBQ2eS#*{lqXi}NQiKKX$1-IY`6rQHBoGYbSNgw2@BMLK!w zy~k3l_(5o|PsTQOnmGwD{RS-$UNz!k;+@L~zo!LuT9GVL3*3@cfxv%>_$%0u9{)TX3DGURX`k$a`4| z(6oq}*$#3!Aw$gV!>lG$ncLN1GCj?whYEJpt&k5_O=((W?yDi^LvI!~=Hv6<`MlP5 zcKA(VkZJs&_ZH3{Ja-3+#lIHzi}X-kGya6{Tvz2!00F;!?sA6ip)Y+ZR#JlE?pH6dTnOcAK5aBH20dl&?8BjF~+2OS^Dg%Umma8$>i(bOD`9myU>gB zC7CczZ-x!-%T&0eCzvl8L>UmFkDu5j!57Ojwohg^`XXJ<3gh;Up#ok%PW(eePF~Yo zc**#4`YC&GMQ)F>JpIu1H)H3xUaz!^OA3B1(9Cx+-l-xZEM}L~zUm|~KXQWFA9e33 zyzKFD>RojZf;`dJj+;eH4VhmE(>p_TIS0smFYWs%q@mtnQ+4lHK=$Ta~Xym-gbraPbnlxO2 z-#7hozJWJ~@PX&-hV66U8aiO}ZFrhmZX+%qr+P8Cv~8h*hrERJGvsq#nsa{Qn#+K3 z^PbO!&9jIC&ss6C>erOd<*>OWIOdxPg|Q49CUGVRo*~8-&6OqzXYRmG$8E57=~5#S zec#3X3nw3Po-B*`4(QTczl2zdW?Gh$3DiO-+0#ivM9`*+;75BH;OV+xkVSg%R`V?j z$_Kf@id++toFUmq1{G=VcmF!%1Jlt7K!*E4PbWkz`JIq?biXTk8=KO``S@G2^A_Iafs8HRw&i*IE?!C*iRg*QfRSqs z^1f9kA>A9hlnjCeSA`Sk5)6uu-;d2yw$4musYgg8oza?^iSs!#hpX+B}zi!Mq zAs%Agl0PCmblnSBJK?dJH>zn*B$k{|BHVG0wd4k{H%68wTCX}^gSz>G+g(KXSoS)M zW#?zf6Z!Gl(Ve0jJ3J=hr^1+&=6$ksuV`ck82PT^c1P#+X!^VH-@Yftp1CEt#(R3A z2RU6kPW7{pd4JuMbNjsdJ(VQL=8g~WtWYr}$lYdYg+zNh4!0haidYr(eD9X_&s^BO zEv>)fL#oW&CmC{=N)+e8+ZFwg{By2mN)8<*ueGP%W_;TIW-jiv$Q@vu&Grcr&(P2N zSOvE6?kIi&C1;og{S2t1KZst|X2(jWRg&m@$GTz1lAzazDkmN=43$Oc# ziJQ%c8qmG&Xiw-u&i9JwGi607y!7YK6p=z3n$+|g6=mS_k-FL#twv-%BIS4jHMsJ1 zJG=by8Ckxg>Xl^aw%zNe{vq`#)+5)-wqPSu4LcSyOq>lL3?FbD&wyz5CvtdQ_oJuU z!lf*|l0I)}e?}-GPWp{3r$i=zVuOhT>qlpMAw>D1BUE8Y>W!jKAHnf^mz|pPD`IL|Jvx^7jSi4e4uYiU?Hh%Xp^0jHY=6l)0{L+AqvSrLgMM z3G-F&n~P@*tY3!`(VloU@;5g0W$W*8m+g(6+4%9gi<3O*q#AFGP$;-yF_(D>4ED)) z+p5iVE(=grl+rBgMR{v~xiIx0xWkf!V~o|=jq|sNRN7j1bn32-c*c35jkE2vS1v70 zC?lLwSI=iApJMB+C2jD~uOwl}38M2bJEsRWVUg4i%mqsJ^sAO;J&^uVsLK9m;`&G8 z!1%0kYL#8Qx$sYC^N5mCsm=UW?O&14#y~dv@jhJ@%2>u#bKY2g?_gnt>&!=-{&iWQ zaJwC?Y$QbAhyiA-KO)}8-!8m%Om{@=lhV6>RPf+Z7Ce1xQ35{R*dXLq>7qP{2vjfN z09OUW*hJX*{Jz=!3JWay=uLpX-a^ZUd9vzj&IC+OT%0)5QnfTJlE{S|zK=#*Rb3gN5ibXp7J& z6UYb#(}f-XZ7W2zMFfY2ioY_j&(v+Q2@Q22;M41c#9K?#Jfj{4ebba)eTZGp1-za>eKY$(PE*!tSITfrXenvli$>2(zF>2Y<^ zZEa|tjpjYPPJ`&ztH1bVWniG`a&403q>=LbjJZ8p)nsA8>y4GmQ!nlwx#(OG<#cq!44tw$f2A8qa%X1xksaPNH=v8SXd)i3b z_miQbvtoJryq`j6s{SMQ+oHWBZn-d_;{bbWc3WR--5q3XA(=u+U2B#9l?)q9Z&4FnDya^?eq3W8UNWgKb69PxI{C zuTz%Z+u%#+>T}p0M6ZU@x)&ZFH1_x`^-ew~{WN}-Ic9chkPf+a`@A@_+ICOm^^QFy z=}`28goOS6Hj0+!RG9TPQ{QyYr2yPr^#n$vUqNZ0$N7z?_kLPUwItq%MCs#kql`d^Kn?z*#jW))5W45p3c(9XCf>GPF{y&wxc_H-hI=K zQMNDK%SOX6>J00|q%pPO!9WSNpws#}iS(C6 zJ!VmZk$kQW6jn+{1Opb+iveL%XF-!~MxfMzq&$D=g(jsHAE4JgQtQ4WNnl%wRSPYd~a`N)2ZQlF&WErQi0jozx_ zKZ>~^#H2*RBgPEWWPPay(?N=JCtf+P-kYir2Ep5Vy{b^^KObDCh>a%RiuMt|?mDba zKX%?~g&rG`M;jd3d zy7@{$;iN^(U~=PfY&DutOV8D(@+Grn;aci_iSQ(1VJun2aQIPC*jYusD``yWF(JN! zROea8w>mb1w1M^QwaR7Vc>(V>ex7S80gruv)_XDV*5vM&_1r&||HiXRr3 zsYC?b5`iDqQWwO*In`1oHtv%bfl|Xsrc6f^@h=;8y}hp#7sY>d-t%_0z1mdPdwkL4 zH#j=eENSqPk_|nO(7pN&p<`c4Pm(I7;?GGmHCMp!ah!8XWau4VY1HFrq(obQ8!74b z&h*rP)#-O;(3WOFE&XnqQJ}ctdS&j+_L%G5szU{rsfHN=M`P_k&_r}y9y2qwXMI(w zFcj6&hss0U-WYL37R6MqvBztP7@Q=&UkG@X6sgSVZNrpd;5SE3dW<$X{$q$7&%cwW za^_>p+34`LaX!=u*b=`Vk?x?+9WpN2G~b8$=_JH8@p|fpg$g(Lt#Rnqi)*RmVAFxN zXvob4&4bc_HK(bwgo<`qu&R!f(KM&w^ICTLQ8@!W0Vyy^{2YgoMrbGo?b7+jE_w+x zyq5mEzTJr5M_MhIvNJWRDE11YVL-ks#7Rg-7(|&*msV2zbE&&9J)&497qL>AgscXG zr+vuO>LRb9uO>M_2~ZSsD$LEqHjme2hqSuCM7Su%urc%nvIZepgu>p@1LriJmrfcn zmF;OS{-x)5Sh|JR`KLm(&ElUOB}b~JK#5q78}Tavxv}bE>bo480~sz~hJy{n~6)z4vAH_^RfK_{>R8>Q(rB)U`N|h&Y%!Yi@r*K<%4*E-|*6!+d<|>!t)HbY&5Tx)U_se2)z4c|R zd%-c|diLWcK?JbMiPtMN7}ohnWAIwvA4?se+TeMi?^FHHPnOJs45h(GYS*>=+-4`5 zNCKTs<{BvKSe7@$C?V4QmqSaTrW$6_l}3h7Tf49wkBhI|rMyQTZLK_J>~;DE6Z<)Wr2Htbf8Z6qZ@mY#|p zczSTNOppBXYo5=zB!@JzF7dr9yIs`co`N@U5&wQox*ARL)K$1C1yRaO*%ejPn;SXb z9vr%ImGn|9u+Q(K%5JnOf|}@ifD$Do?0&RpbG8QK`ZP9>OBFUCOqtpYA^$XfBzXns z50FRC<-&5-*9$X1zt6b7eLsBA&_{Ri4y%IqYd4$;VJ8W8a#!hG*D(cU$nb);P8V{s z)m%Z-$pIfjy0t;)YE4`0oA>pEb+lF$izbvov2yv!sVGcvYz6f_;Fx>!yXY`g0QpC& z$m;-D&+5GCZ_glvDT*;JCTrW_{ARES@LqWJ*;jMoDKMwNiGnt`uj;vhPN(4X=3t2)xg*&7jHnJ_~7o&wmK*lTXJ47MQqh1$5IwTxffPVP}ul8)a4t# zqBRJ5D#(3N5g3#|S(dB9KhRXgDf74`@*9_T(S>@@n($(jU|m=`jVvNvpDL-IE^Hk< zeU8sLN^^(yS3q1!C}T_5OSKYD7MTqUNhyB?q)5zh%IQ$mby=X<022+G5Dn14--^P= z`64rq+wKtlo>PUUAm#r1Eh|v5lXmNRlPsgVvB06uSr)W&duS!)x8$$EMFse^3Zs`! zN5M%(8P$V?z1*-ccCt8)bHdMmhjr0{q(fLPB2}3mitJBNDj;aadUnDH=#%fSBZ}ip zG0Ufbzo71r2|E9jXUazUA=mn^Pd;~Oj(z`_GJG=!OdDU zP*^INTf<5kV`C>G*`p0|WM=_E0?lkc$is`baAqvewTa#FU(?*DRR$$*n8%>cza~!} zTS$XNo^DB$ZwA|SChdiXnrZQK6csOQOGr z&TRRe$k9sbZJtAr`@nuSY5<6JwB-$SqUwXm@NAOMEb8mnupjJMz z#n&#X zj4eb42S>Cat+&6%ln_tN8Mh~xilpd!6&_3=#yf)IC}wtPcH#r+7$uP%U;oswqc_e@ zO=0`JnB6~vMUsJ(w=i+$aS|-b)}X?=z4z%v369<9Ny#0q1QEACTP0L{GrB34ccTK; zSRL!E$Vhuut?(}~^RVfIW;o9bFxgmFDR8ac5pfW`;)wg~!?n4iAWAI1KvajMVF9M`LC>{GLg>k;k) zI;f2*_xZpDU(6}0@0_WgzRg)sO88xC%65Bgj<1-6Af=PYmJkm_lT1raU6<7W-XTHX zf<^&An21<3R2GhDQuB3G6Y+LkGnI2*i$#7nK)W{3Z=(oxX)ar)a#J+6?V^Xp#?1Fr zg`ogg{M5gBt^x^v2}SR1_DZmWKh^NLBj)DRu3;MW*i?_YvU%pYAorU5ST#Xv3vF9@ zt)|hIX7F}%-ZuGcX6*rWbcZI6!1><(1%?ngy~c~+Ux8U zX`!=nxv0C@#t!F!xK#>Hg6q&kcxe6{1E?}lRs%xe=Jd_(Xu)X<(j};yzy4;-u^DmsXiml56X%aXYx8$s z|EwZJzly-qA2vA$-eanlKcwJE_KoVAY0g#(azy zLk^p1=|oE5+QJzBBt_9px2FK~Mh!dHD)w`8n8;pI6|P}kLVKXS64uZj(}Z$r*N@bT z$e4FG1U{3JI$9TA$)=?=GGA{`Kf8ZOGq_D&+B_J;liZt95}C&nl!x}%lJ5Y!xO*S0 zd0o_79Nkgc20=SCoVR;WXzXlcn(u^L#j6MIiWRvHYCFYP8^CJPmVBF1NG3MNO<60| zn}!}qKC~c-`=mNDKy+#l(LWC%L_Rr!r~>#oO4mpMI8~9->n|?eWvXlvh?Wv-6zj&a zr={(6mH{n%k-1XfX_qSaR>dslXX1q`VBOEBGp?tdK(Bbu7E!Z;6&-Uc!^g?F+q}zV z7HgZW74Fh_b0Wg7h10Fo9&bO55TE?r9#5O{ zl<>9ObyEbZHh!k7p0%rU0uI_^6tpULi!=!!+zs>Qy&7EE1qKSeWAp~!~0vG+g zKA%@)Fgl%cj<|a6q_?5R9R~|2 zOZOPA{=x}?xGVDdU7e=`RGkt^_;{}v9NV@nC66DW(Qovt^PfP&N@#!TD-UQ^+uzKztd7b(SbAig?8F?7#T=qN#v4EbX_DZjUWd!B=|~LYY5(^ z$~ntwe;-7p_biKOIxkP(=dM00n>w^Qrq&2(soH@b6MfAqg>|))` z0{Y17lT zii}Kb(g^hy?5*8>e`$VeMK)E{RA=4~Vc%1rwJx1E5ZT?lG90OiYTUpI4&~1DOnOuL zO5_|)N_EOYQ4dW5%bPSQqDL8Ii zdeb#JHgj-RM#eCg_g?tW^d(DH2Fclkx%7=4VRtii>qD85_1)SJU4F{&I~O}}M?OEN zg+zuo_Dq=OL&Rb5*E#B|fOW^{M=>=ng)#6$>xilh7BE;skkoHZWh#`nU)ejMte*A3vDU5@9_u~Dn#2h*4*bfj8xW1hdd@UqZt0~>zG zR%$u7d`7ww1;F@9Y@xh&PfW(P@26UyYtL*FrCj^mIFGL>&$L$T_zv}?)6AaLFAm`M zhHoDTNsTKPT-%OSO31WHtb*gO)Au!{x;a5b$z#(JlXl3NVmWUjy|7DAY92jVS#=<6 z0d71pw7S9-(<+H}dhz%_Tmaee*s4AGzk*r=QNo{(QoY}}IeAUVFV;b*Yorbc%ISPh zmS)oFbR%t77WXJ|GILiG^ThRg!`>&gwCuk^rr%}+RYsNr_#b|M3J{BU*>ST#shy83 zNt*-c7sEX01W~wr&@r4sd-2i7`XeQx#}MiYNhsQ?xmUL) zMNB8y>LA>}U3RU7%y@zqG-Cym_CUYW)OT-7keiA$qS+UHms~y8$j>!Q9`pV3kwmWT zR19BxIX#bx1QnNys@j#qqx`z-@2s&A{uBz~-Pa&zxz~{C{Nmv)+8J-vTNvfUt03as1{?<*6l#_NTQ>PHrz6{uDDmi^)^DQ3uf6f+}Nacv8= zr&iVrsL;U5g6&uyr8c#jBnf}c23~6ISTlW%o&$7dw4p;WFtj(L_<*7JHNM*NtINyeLdV}-=231yP zyy~69^(xrO$jk&&KR^B=Lk+bVU9SE*;5nwv?B;88B`rOT_lq}GKU!pze&cbBJUXyo z%OwB(QZpG{cG-0ewC#g3ls`XoMZIVbi|D)tLMHeX(q^$he-kPvBRsbYJ4kgE&^cX& z`ysBH6Z5uZ!Q+n(3hN^C*O|rTMzP0#UsaY&)=O!d5t$nPv3serX>-E-N}{vAGuxj)v2#mm-`A2=5+C(&^!q3uiNJIg zlc`^mRw$kbjy|BSZVxQt_AWQT`7&Oe7}e~`wx8jl2o@0+K5O%8C{F&817U72{2JJb zTNYb`#>!;#B6FxONg<&$yC?2I)Nwu}ulDZM)mg{rdQ}xNR~OT_X5pV%Zc;Ct*~5YG zX^1ELq;v;M8);MX0ou9WHO63%g})bN$ts5B-{&n$AICD!T-#Oe-K*Q~S=3CQO{48) zwQYH12|JVhgk1ZjmdfR#O&PP2#LGV<&wPFWID|QK6aI%WvN>}pHOBcoA1;2;JN;Ro zIo0TwIxnaaR{-1f%d3^i3>zp)?S>0QUh(=;5VZZe8hjfwYlLn*#R^8eCOwkx)_DpQ zn|&?S?rX@~$RlFrR`t{j*CQteF75kw3fCYtrzI^}F2YZkd{Q*rLA%|afH;4}@5%N9 z{m4soQQNiHij(sTWN5B`L_UU6pPs>19ZAXrIvDtCW=E0K*I{lTvf2_$+l0~pIdN6k zn4i1AXES*hGB(LAU4+zN6VlinApYJ@9vpp;8^e`^^=i6Cd0_2$Vurq#%ty|X@1QpJxtXjt zr;=_ZiAR`+d#9Xvx}CaMY^e*!JXGou*t`D;Gt)Pbn2ltV67WjY2{?iNs8d+cw?Sd| zbq~}YC1{I6o99dylktwbRY_Q#OI;8C7 zs~syhUoU*B$j6c;G1qcNUY@Kt*|(OKqN4(eZQ`~^KC7`Lm`z^uj@NOHc)zR8=f%$A z3b|)6DkkJL|FEaC?AyDHVx)Bj^tJcF?8dNIOw__gi-1qTA2-zgg4JLN^zgnVut+Z^TTq=1_1Pr zhKLW%AWG`!6=FaLNF?W;>|C$+#nN`K56fM1kvBXV2;<=*BAAYlgOLuV$DY|$UmKWS zxVl?zoehpEkeZUf#LIi4RqB*Za;~^s4&s#S6Xf(;_#BuZWJ8K1MDei@k>az+0v2!4 z6CS9J1{Z!;wjkUI5ZqOj5g}$De_AWZSBP0lRT`NEfs#Azvo`rJD4bm*GS3XE+7G9G zt&cC8_W}8@E3dR*{yo%4q_J50XC-@zlyFo6zL|0E9y9-=DWjQ>`4$b5wF}n zcFx8uzs&2MV1TYnv=F;z4qMC(xi)-^rCm9wt2>O+2>YFF%uYdH7Cc}D0x255 zN-Q}w!o*-{8RK`Yg|}|-U2iykoT=_Tgd7=S`;xQEc+Y$@`CcKEH8<7Nnmgu zIGz-XRute~thp|nD~}@n=0C9RpHAXNAyXiL*x-pI@%2Tl_fDkg`HZn~7V_y$%p`>V zmJB>P_>l3)F@-^H`$Ei3Gc5G#@ZFr1R%E0{L~GnI@lmGMH2u#0pig1myLf+LHE8%n zgrpt_G(MA{mO6lhE~$Zrx$8gbhqTDxKd{UlP9;!Sese(eb(i|Wucm28fE9}+Oi|^x zV551l6QMjT{>r}vvo~Jkct)F{PE@PfsQ-Hx@2bb1#YeWI;K5(EB>VdR;uC01=i&hu9E6a5nGXayPv_Z=f$Bbgc_{(X2aDfF@~2@t~LH zEkp3vsSEM|MgecCj?dgnj)M3@eQ4akI>Wk}n)zgcWWf|&LL|vX?tCdY9iop|SD`;o z2(7-;=AUSb8dwb*@j9q~RotF9rDjuycNIntABa<+`$cWFw7@nFu|GUX8OzB7fJ@c= z2pfdE!j6XDV&!v?lZB0EmGfPk%sVBD63wd&Bz)U#D~DFiEq0>MSfi%bw&A%Fc09#w z6t9)#P1*Jm@PiSRExI0aI-zFivNhI)r%mL`=oP10ryjuwx!TRO=Wt;Qi_XjYeoe}- zVzIl0?feY&w1z^Fy?0+{43sHmr~^y^DcNmS{C49-K>!-I66|YF)FP@=)$kOu($H_` zN1B|*q)=DOes*ZIb4mRhU?lb0_4+&|)fSczW}KU;$!bc%v3lf+*K$}sTd+yMvHe4f zh?#%8^SxAB)rVKk{*F01;Ewtx&BkR4zo%94K(6Jqwqf`?d@P~%yn>ck9pQO&c5#Ha z1IqHDC&wFC&hU4gCW)>g84)(2+6nR+%z(Vy`=A3>3EMPucO0MktR2FUefr&GXR^DE z-t{`?$x`_5Y_j7A2_eGyzmWt2QwL*8ctKik&PW8fMdl|Z)8m_-hONF z**0sMc-zEbqdiDM5DScqQ%KfqUllyda*3zn}b~Km=O;7cUqqI}{<8xtD2lS%} zD)D)#EG)IXlBODKfAJMl8uB^{s!8D2Z5=*5sRqOZ@u3!YLt7FS<(t+(*3L{sa4P#BtPf#110HSj=sJtSe%Z3v!gDYJrBQ5lsBp*x$j4)UInaH9x0ss9t(26 zHIB=q_^Dyj*Y|njr|Kkt2UP^GGRDg%wEe|5C%Q%NA)?E>gDlZ?6GxtUy3PQpQ%nRP z*AQ(G=r$Dr7*XX>1o+4_NEtB)8{gv}qdlhUsSk?o>!kU=r6jdHQeaMrh^-vG+4wu3@`!3m!!u*ZIVx*af$t(#!+mbaWDKwdwNFqdcY zctJ#v@61*q?Fb;37#Q@M@AVn5_uq}rqdz3pO)i^GF3B#C*h&6sS;W zr-b9kw410u?>OMBqq-%45*LuPEX2e{G!Hv3HRrf7r~M?{MOSE-JU?%`00^nBK1NIe z=r<7kuOarfmXoMPFP*-LB#rsS9vhtfKL<@VIMG=veb=dSWnrFvKfr(}=8wTgFT1U( z9HHYY%3J=CH@}*E4aj2X#CisTSzrSnQtkIMW-kD-!~R5E7)(sSU1PL0pf&Co5_Jm) z=PD79%6Q}yn=WPOqOK=&y%dtUqKI8kuAaaJ<&8XHPz@{|JyVC}w|TnSG@a`^I5?-N z&p2`RLr;N*r(-{)m;v3+LRkmvlsxnL==b)kU(v=D?BYCtvL`c* zA!A_A_36Kr8aR_gC;uD5p1;gaRRaw)Bq7`MDx1xmy~uV&cG06A)};2uNu-3geUhBI z#(8!~15}Lie`dA=k8C(I{zzrOgN8(7KyIjyIU?6w5enRg9c{Y%i^A4e1oCsX0U-Da zVLUng>KgCN6eLFdwvRfgHOc)2tC`I00vNp6C&)1A$4Y);(|bEEd+q=SvwwX}K!kcB zrs{to+G9xk#hko9!=6B(hAVc8L6B6hZ{e2{K(;UX%WO1nwtb|cZ_@Pk*UYas{C6qF!-I0A z9oJ7(k}|-O@pn$P59Ycu5Y0c6mY}MTeXh$aaQt^;(mbNbTdTSS)=*&~Co@VL5T?Ws zGgZ*aa?-#!X&Yw0M)sQ2l(aiL|DX8Ry@}n7Ygf(%*9CL{ZG7?{7W$Fub?!-4*x&xZpd==7?xt#HXlhmV0LE2( z%?YXtVL3lX{$#(Mdh)2sK1lH=T@rlNtGG(=mFSU5bAx3eBe90ZTQ5sYNko2>i`Oh? z2>gaTzBjd4uopWM73^->wcS#%_W#LYo-L*Plh{a`?!^SK(t(}u8en`!yJF7YwbOSF zo9el2N4ap3`r6lD7eM;EbOH58^wh+4uPUm}ivmT?6nkcACNwy)=?KLDBkhNo3vN&V z)`0_5$9MesC5sWHamAj?&qHj*Nl5sb0v@(vN8}Dr(L;*%Bzm@5^yH+G%^pi1fSGWp zp9NUv5qr|x(pkx=&dXfKC&@RjpnVnd(>GtADx+~sesJ0*ElsXVoQmW!yKZFJZO0i( zw~e}#u{h1nbqSn0tC7c69YhSEk41NZ&&YeR0|(Gbk=xFK!8b|+688=G`JE3g&__=y>%Y_Xfwl-_<_a&}Pz{V@YD@fESi z^Iv=?X*WM-MD%Jq?MAAI0laMgy$vN(|1o*v)&J4nd4Dyvb^YFRJct#HGzAd_=@3+^ zL_i^c(t9T$y+?Wnk%I;hI7pLb04Y)e(g}ee0@4#&fY3s(0i-9?yLp~_-{-yeFStLv zdt{7c?6I@5v-aF;%{ljHepg5|>}07B*0O$XA~@`iyuvey!@K*Vsz9wl{{iq!etyvp zC^7hA~Z&2z9;_S=L^=}G*UbBwcABAG-~>p0VF)oOn=}iwLg`k$kcU> z=bO<=4>0_@+dM1h@qmM?LL2$l8jjq3+48o&!n==u@C0h}QHSjv$K5huQJZ(@a0?Gp z>SSTdmyXQbz8(z8mHi4So>Z`&&U?F<2qfKFys>TJ@w5gk@99{;?L|H<&m36SRiMTq z$~<@hkTx%`Zkz3<*^U6H|6Tl%_!>2&<4u$lD&CLyftd80rtG&UxEpGszx>{A`vpBK!5T`n^(n`->{j-LQ^02CNUL zV8Gj)iKFo=GCKFv>@Flf65%xBjq>ZSpOiC3Z!fA0s6_xiE@AYurihC%#4?Tc21Xt# z2E+($pE!>G9Wu#&WY-Kfszd|mv8DTn*yQq)-ThgT)3BD8_lUDB6MI!uQdrtL#(ALQFO||oVT<VB+t>sKh5n17Cw_{& zQg+LI^&%;m#ou<@>oLwCZOZm`z~c%RQQ9T}x7E|_ju#*RMD$t!j~o1=69o0+-W#q3 zrQ_kO(ZfnZ7$#mx?Wb&1+n%DLsw3ZgJnPy_NXqNP`oDE|8Y}B;#TtI+fH_yy{HSwp zH-I=}_@KG)97|SLJKU4cHNQ$G^p`Jm=}XEg0z5l)KA_6tb1q|TVg0*7roCiy?CjvR zz}zajmgPRxTJTx{uc1mC#l6)FNcv@OI{R#gJp2}k*lrB94{o>UQ-o&T5W&s~Z@`Hp zi9sV{jP+=@595LPoo3AfT7dI4g2R34ge|rLRHbifapn|=gVPni0`8dSWuU#- zea%$!TiWX1F^1%T)D#w2bz-81f18G%gG07Uaw99-mO+m~cfGUkqYNRD*43ZIuwG*! zXsx3UTSTa|H)%Y2VJSv9Evt(oK6?%ZueIC6_Q?RF3OC@mROoO)v9m2l#LeZlh};|n@J=g_(UnERz-gAjAA~}(mQiu}3F!POld%u8(p>QCDYuR0qr=0N8UsM)Yti`(;iQB{M=Wq=la|ZFB7K$1oHe zDCyI{vyB5cH~?h>l&zE385{!ZEr#0Hp2{!+uYwIAiE1BxKStj@$O@ zsS-OsM#=-o_DJ8(5MmD8OX=u)3=9PHe}{?)Is6x%`+J+CttOqlY7AJb*^^Df5||A4 zhktgzM|3pDk6rdZeFspz6lj~!1kM&BzWG>njZUL=gK@TQ=w0SmsY-Mi?#5_;;oi?( z4}OJ2lZt0_N+dIc^9(&6H)f<&f%nUH|(;ts}r6A?M10~LP z6-F2Wxe%aEp{%Q@HkDro7#w6#k%+1zrLN-H;s+2GWB16}kyjS!qbZsOD)GS*)s(Hb z1OQz>c(KLjD3Rj2N%_BFaxzz5;jj887YhhzQf@1_sET}?F575cTN#wTRN)$(vX*i4 zYViMqtLHpYh{})zNMQjJxpV~Mr?&Oe6`R6;1g$?PLVM<5UyH?*arrq4u)ry=C(9#% z)$jO{-OiL}-lbMi*I*(7BT!zKQY%&4{X6T!)9r1Z^82`k$t#Lfxe_$iJILmAL%w*%p=fn7kGsF?3e`%$2mWG!*V>TN~s${1=ibAJ92>5GUM@tjbnRXYlp-|9^JxaTyVQPXVbcfZ5- zY#sGJe4P{EdUy1BI{>hjd<`~^w`EZX>$2no`h2I;v5AL3{8cY;`Di0(T93BT`fbFPjCl#t9`r4|34B{pdc z$YI_Pg)*?w1xLR;iI|ExLcFg#w05dgjrn{Q`rr8QLv%V#M+nnU29R9+J-%9>@vIaI zWfxBW>j;mIs@*2Ki@Kh*#{ecmbSo_%%~=Szt05y(Va_oP=;- zDN^V=UPQZq`hy6P$IO39EF5JCReFBok<_CU)vX*#il;bwSXD?n7gVjWi@yGm&71xL)E`Bi(yyEvvKotJ~@vv9JpZE+mX!ZKjxf)b{F99cdUJl)0(LfNsg zD9KSC_3vQ-PmUSn>%AM?J5MX|(pJnfc`9>I_4V^A<(wkpv+cFym%aG(?ejT0fK&j5 zI^SmspZu{?akk;1T5hD&>PW#e(Qk6jO}vHMZ;ENa=tZU&9O`JY z+`Mq%9{LsZh2BG!GoG5}7NkT#U*>jgAyC$aKOSJW25OM$ zjS1`|EuN$z@ITC-KMMEYHHI4Uf|Y5s3R;SZWG4^zlKRE}gKtl)raGrm*UCR40085I zK-0?Q7<0CCzfh0gMhjhpGx#Q*!no8xdz>7tz{lnY@w)GSa`;8lH#CQpyt@BnJ^I@` zt#-!?8;_fj_o`IrHxe0j3c`lnEao##A9(B3jmbEmE}6{BhqEugreWo5>UhAUllxrW zrcR6I)<0Q)h-5ThW1^hNf3jAs5GH!$m|>BIN+#<#Tu-e1m(0w)zo$@qe6}W-M8qh% zKKaUDKskCBv*^KwG-nZMwT%4TO-W9Ian<-pJB|R{{|SMg1%tOey%tLm-IuW}eS#sI zPZZ#RNeCI1XgDPx{t_+E{;uz1Qz-joJ>zk9{GpsuyHbx^2r*gy8(pOPF?RiGYJ4_jw1MD7Q>GYs%+ zZ8#GqQ_~|Arl&{W8a8MBnYPhIZSknV!AOpRuLUxuLQAtzH)v|l8vDkabIX6K;M*!` z;(bWd@lmSkJB{KFb-7orTAiSuz(oxU24i0yJzqw3xd>UXe`=J-Ectdj@Ll%E2=mg0 zxeCWMRZumBHPQBoaLD{=6)1B7NJHxhnroikL~5rVY+;s545!JLOvZUb7Fci=u)6n!fn=rF#kSIY;bfB;PE=cb~KD5<6xhC<`uO~sW@c}}dMWLE8!K!5i77YBO2O9>} z4c=q8NJG!msf+IsHceOALwq?yYGZvLxXJwi&huU|(JxRBG>$|tW~d7oqA3%>cD5vW zF+8M2q2OosMdzk|+Dr9~4`pK*rJG1$FjDh^?0-E4%i|QBe!YRfPfM-erzD zMtRlTpRG7Naw5yu3bk<0+UV@Cu@{zycsxkbfN)xo3&~?(c1 zU!@M4d_E#6R|VNMdk^w8eIq9_qfV=wx-p`IzKUjc_rDWvF4gmoPhHNtld9`Fon;6d zft8}P$9I?wmma7G>(`f@MkQ9)I)Xvkb{2|d4GPuK2r0p8S3!l`>P@u2hZbSx7D%~^ zH>Yufy$_l}N#zP(YEoTfDGsSnU;h%;=q%@0@|{c$GJxvg!NsdO2FbP(+{x=6^yIP* zQ%EKb@Z$n6Ipyk93MoW(g!eR7>#K;OqJ9UI7e#f8`Ib$75D@MoyGXn(uD#{9C!hu3 zgsCwLk^;g>3?mDB`vRcAMVZY=yxqW>rbE{hZvHB8eJm|vn17C1*GId~WmX4%)Ba1n z5+(1rygDu)l$Bg>x>B(&CL$<(L|b&0xo2dDK}ZqLCW@uMy{>~^B~B=C{;7GfoXlb_ zYY*X^9gvnTZt_|ybFl{={+X*Tk=hJ%3$o_h(G$#LVwhdQ+HvzW=frA@Mk^0S`{QEi`ixL@c z`;FxM%f&n;cFrz2u~%^U5kR0$TgflGGtUs3L4LEp*G@3kecM$mw)2_`i|*(9@QICb z>vZ7MWc+tUWkfT<2=bLn2L^6UuH(zRlKh@dcMnI~I`~yRpAwyyH2o~r{T2v+oJGdt z3qH}aUMJ}x6}BFlv9qtI>-P)ah~GYo{djEqJ0=(d^Y*Q3)SDWGXj5<6`}%E1|3d`h zCR5{oygf>aHJ@ru;Lz+jp2%$%@vg;iYK$4Z7M>4b0>vBd#;#^MyP^2QZ>4OU2Dd3+ zYl}8S$8_yRBM_KDVNRWng%LV6h!b5Vv^CFLZ_>n}SmdS!oO@zbKg+S&qdc)@`+?bT zU#<128+Y7b{K2K8P|{4z)Mad-tcS2U$P~{qu9UJ-3esY6$9Sh8q^RxAv_0ZcS&lXO zd@<(1rU?2Wtx!Spip)h@#T0Gv5%pHW%rF${5x3rT>4h(g^;(i*WM+TjxQ}0K(uPn` zjmbz=(GICoI%9y#WIb()*k3bc0OmHWLt3Q4i-)Aw->mHPx~<9*8@3+02y@5S`uV4o z<+HJ`@oIabAo>BK<5F8`V));2cSuQ*k=^~o^wi^UFY*iN{q;7{_4fyvGv#p#`h&DJ zDR0|$6`MAD_8Jf`F>d=tn37nXkTYHovTUviQK?sycjKYWWc_tOohc_dO4NsN$-HZC zXfN7|Wh8GGd~j&aP2j;@IvO{TGxlEH*x!qzR($$d|8?p(i2+;7wW0{pHmQA0o?Hkq zj#SP4N7Y=@5L{Bw&}_ZfT98U6yd*P}0Rv%fL0P_HBJa)7F#g1IVV44uT(}tff8Xqk4P9nC7IS2Qnx#!S8`(Y0 z-E-zS)vd8=b-0UETi;Q}BA{iz66nc26KZyDcC(wj)s11IOJF*VqC1~TO!v4)jb0}$ z#SLTCa`y{vI2V@$(X{iscujb?q5@RB!*!+tzGY)o>K2N#uzwd~e|wEVb_me&I~=zE-alP3 zbWh@HU4s_0w=;u`;ZIsBRbN@(nVQN+KNL}VvzoGXu~%h_&eL&tYo>FqrQ)+Xu5E6_ zx^l#-^N2{X=WVFn-dbxh7(5k(Y{iA!moBy0QgG@@8i9NIfw<$wrqV)U9xP%`Xqyjk z1%EIn{W|E9i;q049V0qdADZEUxAtX#_R!Ru`E7?RIN?Y3BL?!f z$1C`qrK~;TOKFa1SmjB(I9f(VRAfN*<}(B9KS`BUCq2Y}PE8zktNR?9amS2t__jGY zwe}F4ed!ktwR~PU&Y-k(%IgMQJXvsNy5JQit4Fe(ljY|Z!rTBlq3o0d-OEWVYG=XD zU$gKaVvFKjG89ECZU?Ja?(9nsq)4Cl#c4TyWS-TZrW6GT!m?@}_gnMT( z%5B(bO43A#2BeamFkBmPq0MLZVodFTx^7^#j(y$_KkyOJDkh#Kb3ZB{nrkVd*ElJE z73~sJ9Wn-WI)nQ#dt7st^<}HS1>!YalIMu&yZ)8(roAPN{?~%1fBbA02ol_s-+Vs6 zyR`^&Moi?xe>f>i zR*MvtxUsXexn5PS)QTVJk;FmZ9O{gqSGdlFcCD_*{E4I>`2mw?=zt)VP_CO6s5 z#wjL>d-w;bBcRZGB15phYejBOltIZ9!e`-68L6F&P{{4uP*P%p=+ zL(riC_-O8Xf$l>NNGLycP87<@#z`y}6s5j82RgAWE~rt>4m@_Q*%vtGxdUM&+X&&KRvutg9W zX$s$Ftm$>px`M>%1FI|-b#FI572EHP2_yz4wBG>n?hvTU7eS!lxtj9bOR5XQz9F|@ zx-PuW`~89}1yNoJQq%|&{orOW_|dp=wY+09zXXpf+q1vkE3kQ!)hGX&Z z4v)?U*Ej-+pHssMyf>l7R*L&8W$~#D>naln;#uJTz#5WXsR&&kGu*S$d2j~1Q#KDv4RROa;V)GHt(WTfc329B4cWTQ$eR+c@G5sCc-MAYrHNDqpe z=Qu7SX6O(V^2TQV8<-OfSz)KYDVP9^QM=sX7tP3y6SaIP zrYb2K^mj|c$@?B|+`4;9Z>%Ho)>qx55uRtTd?%%%V8L?ha3xzN+Qx%~NY=;1pj87U zXzs{rsPqG3fWS;FjAm^;d-8hlEx>`|)pu#Xe(pwR=*=3$)F)G)+Ok0P9Mul*j>^Ba zV%rK6t{zbTq*+k>)#zaGfEmy|u+z`rM+*KL-oq`;*R*=Z0^^>Be*=KIM7WSKqht9$ zUWMLyrPs6r9Z@y!iIQAjwEu-gk-b@!-vP&HJkyyw4GLM+EUQPg@D_*YE4aJurHM!G zwzM~-Atqwfdh|CSp|)0s<%sUv&rAr`j@Vy114i!!;nUw9a8dDgT|_*UmB|1vx0s&Zc?~&nCoKTrISWZ zt9I4eh+5ySEy+m|~*zy`<`CNY-mnc1Sw|P3d9up;gm;^X9ScPf zcbC4#KUId7aD@+R$T3Ym=blI{eh!5WAn#2rxOq0o=yJ7W&JK($MAe4&k+?X0$i)t} zD34F^@K3RbfXU6ZDS3fmfg#wJ!cJE7Va+WLqd;a;=e+cmSJ0-?lGPQ#K}Th%@x?O3 z$>yNMUS=RtJUYO4x<)SD1$^r-vbUv+qF?TBcTU@P4y>iJRBqwlg(Hbd1Po*dtHUCC zIPX#GnwTrB<5sde$JMsfz;k-5fwGwts-dxOVSj9I?en54yhVW)sRS7?Qeo|W zvmgT@16Re`KK2rCh)LtlPIx=6fWuz2#%{=ua3q@Lv*{r+hC6O!2-_*g6rZBxG&CC} z8POs+JuM&7YW0jU;@^QX;=}R&jv(|faiy^GLoiG7&w^l;^Pn^dh6`X?>DAd%oVs_H zYPd2fvJbeq&;0~M23FV(qpS0FiScqZCmVUB>XR8Y4_;&lzyyq%VTeE?C?jx%HDM*H zn^|h7e6)e9_|L!_Z;b76G}lw43M*HeToy~o1sjb#oy z+tZ!2Px2wF@Y4iRzTp?iTDWHB(_0yz@%B$1vEwxnflq*Hk7lZ>sO+D~?fk6vETf%7#13xPw;&xqHgLDl0y(%^6{K zXz;klVgDe?b-cVXoENK7dKLMUh>o7ow2DQ9IP{tJ)ZoIxWVtz4M3itT?Qd~k=Uc}= zDBs%;#IQ*r-(OW_zfKbfy}I8+obIR|m~QLj{Iun5QuKiMTMq~TStc-)0kp;&bR~yI4$o+6rbqv3kQg1f*`6+T35hFSg@i+Se47r zLSZW`&Az zUBYz(Ugm}>&_wS5pTn|x#JBJ{G_R=$_f+k$%VZ%Gx_$+p-wsR_wsgFP>p?41^X`?$ zafYG+>XphOjW-SMoQCEmufDXL4fnV(l$WUU$)8}eUOmIs zG+e%x`WDcFwtr!%w)~=t{CiJstW|66&TM-GGrbxUM`bkT7%P5rBFsE-d?4-i0z<>r!w)aJ(JRk2{aaw&l_O$+YT0lh zaRMHhJvAV?7=qVwailgCmMbjyeOFzXd{4AqUic%nhPT1)w>ZO-;UNQcG*k?~+}pZ* z52XD?wW-9Vp;^nyA6@>_gyO#3`Pq4)uIsW|FWn~p@IOO5ZQmO*q|A$7@DXG-DJ>>V zRJfDN!lxCnlE!4BE^Zf08buKnJmFqtw?K2dF;T&Z$|YedQ9%?}i6MSKno3czv1~w# z+vUEss^hSxe!f4j?X#-`iv}hIVBXAKj9V1gtm}RhaN}!bMv(^oP0-#K7Plb1sXBAX z10%o+k`y?@$~IAsuO-3n(mb@!x~j7hz24h}1`e2g<|xs7pUjc@28}32z=$-Kw+oIF)k&eKRif&i=Z1l}~$!OSB!8gjDN^IjUFPTsE&P z3V))YTR22-J@fTmrLM<;XsUAT@Z8pkx7VS8)8UYk2+Dkh`bhdTxnNYb2wdERIi5Cw z^92Zs2R|UoS^5asiPnmu-;GP(zI`ekpUSo;+e_@ak(XP3on`%p!>oqYcKBQ0vTWwc zRH_s;h6nX>ZMH!horJaM9iWA;UkoQ?D^qk3F|+sx(G ze;6H)`B4zIRS@F%N(t&Pj!tt*O_3y~2lt!R`LU|w-xudmFGO9HJD+EM;J1)}*AkEj)Zl#Z3ELO1Y_Y5gkjZ}q-qGYXAgC%S;zo>J6 z{klncCX=?qmw-kxOzz%eV~v|s4Q6<>Y8;f+98%#$ZBHmJ7>^q2DiTiU3W-f!X*|1}uWWzp6ua{lzPuw)KS(z0BRW-FYhtjahm^D@YNjG!}qpP!*P4m$X;)xTmBL=iWy7Ia(&eNeip z3Xx)Ny2CEJ@z|R?+8@*Rn*BaEwXUU(uaK>6$p;ZQ zMO|OJ5BsvHJSNtnzaj2SfF#(I=4>hl?+4PZe}H(oC-DfK;jrk8?Nd&OghcjV97~JA zb3gG+Xn|9O%sqBic28&sb6ZH(bPZB8*49mOZudv)NDEfh91TshGqEECUP&)GEiMbA zJYTOIwF2&q%H51;UOT1m=bHc*sxxpd6u@jW1LN%Zb$niFveM<9;f z{QarM1%MX|0H+B+Ds~cX)*!NY6dB0!3@n58$|DJFm>WT!c^qes-D#{ zCw%2luB3S!8*zf#`qSsak4h^G89DbsP%mUV8{X|aoTc6RFRA)zn!XKo^vx$`8izZg zEK5jlt1k+;lToT14gQRb*x)$rJE}^iy>y}KAw+ij^+QvwFZAs#GI;67BDbvmC1n3w zzAyHp`j?7Cc8=hsp!$u2fd?Tqq!Sg>aSpmTv+k%T3KnXA*MIR&yKn*ji5(JXWd*BJ zu#O*GtkmdEw{pIXUf%g{3jF_W9oU^k0R1-w{(ql1 zu=}lnve17N_!0jN)ctqA0*3$!{K+?f_w&uc``>+b{uvefKaHRF1F-#1xBUNaEeB_R YtlgmHTP>k3pI@?9iW<;TdCPbI3oeq14gdfE diff --git a/localization/ekf_localizer/media/ekf_dynamics.png b/localization/ekf_localizer/media/ekf_dynamics.png deleted file mode 100644 index 63c81261a718e8c4dcc4e9ed6283aa6e9a2bf56d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5346 zcma)AcT^MWw?*k79g$u`2)$l98E+h!jy9E$IdM5-$dK08X ziGXwv5CJLiMepyub?^Jj(vXml&_N7!%}GcubCHl- zav>uno_Y9Wg_5|FF*CN*`}OM=@$mouk^WTtkjQ2THiue}=(c|waTToklyhH>(K69# zn)M11qV_km4k96;@B96|^hBJV7?@Q9qN{Bgn!i&J<;~q6(!ch;UFe(A6zEknf#0HC z)C?ftGw_0jL!+&dhdfoML@|kAf#XozWEBnb!~uLWj@IQ83yNi|u~g>&%9U^#_+omgC_Xfp2< zM-5*oV(R4oy7685BDEP56}-?}ebKqtWTy_di4Y8a7q7G25vp;_HnbgS!P3y>2tO8B0F3D`R$B~@UDbjo*zD@ zg8l~jen*m_k`F`r4}TD3=7!GJgnd}Ny~G{s*OIAlvd@&x6jQ>4eP(RHP~R%Mc`a$r z+U*yf`%-_O+xu^Q?^a`^6VuvL2_NSp%WmaxCTzqFzAItsb z;;Rve(s<+l_~W_QNe=e7_T1Uv6!>7x)-^4vkdHP3YunmEpTebuh}dkCZGoOwTqNR@$bS@ zB>luo2U;aQy;bdq^Ezs@q+T7Tu@Ao80PObOdzi`A5EI~U;Kqw>kTEx!p7Ys#;c*@r zIii_A>Ns^u<(Ds%+|neU&C~oS@!sxES4F41*6|RVrf)}H4$`irZ&NMFJy5Eir8)w` z{!Su)VH5n;w2rMw&MNYLv0ySj?W^^bsqv~_3$QmcPSNvQ=9I;`S&b?5VSLt!ORf#{&0(1^AouR)KaqaHSR)l**a z^GIio%9jexnb8knXA*9^D8Y6`_+iiMWt*lRA47H8q2o8~sMP4z%Y5wUn?I2@XYqrp z)&p|Vq9;u9y9i~ir-dBpL*01cd(p%5lOKw|W)V8_uBpUiry7|=Qd~Gg8y5BaIjZcN z^g^J9mS-U87FPEDQu+ptI=oCaPsOb*7t7j)A2*#*AW4S%{nmtLSH%ICQU6f*mG)cr z4y81v@BADlsR+LgweV{_n*tSCjCm~l`uH|kFT?1I+)kTh`zZC30K;l+rr+2DR7N(t)DCB&xAxaIIn`-c3o7ESYPI@| z{Z3~7IovzCq`rE&p(%R$jjN9<+V#1gjcR8v&!p~|R~CcZDwV>j%)-&98`n!JjRJF3 z%IZ@%ocrmH_#8Nqrm~q!lW~pG^YvT#WueNZvTNSy$B=*O}OHK7@SN-Lo-~ zALgRCi6Fap?dbz15Q9(9p`3U(L8aOD037{e;+D!t$1^u^5jKPjv}aGSFsku+-^0As zL-&!IULLcltKQ8sJwCpXq-VMj@fz=i_GipxmWH*TcQe#aNqoA~`DK${SUJ@#;B6?P zKxGkqEngA7Qd>b7FI+8kZ}7{~lOOPZtxh2#ydK$Uea?uxiTIk!J*`s0dDz5M4f4W! zd^VqvlHCVwJjVgM3HMI$Zx>l(S)_tPpGOs|arE$fHBfr%oG|4-{d6D#RMy&7mY{=^ zeVEHN+a!N&R<7$3L)g4YZB$}TK~(NXe_E}qQdN;ma(MO5EGhPdZ7jShyaaCCaO*tK z*LvA+WOG`z$wvKc*VboiZqdE@ZS9-IsdYz_LDlEl#Abx8y(+8qFb%p=@bsSJ@+|7( z(V-LyW1g5(h4BjXMbDL~idZ5>-za-ATzTnMVu_yD^(Z`kMlG9$DL!Ltxj_5NhMDkj z{YsxYrPeyHQ-be>fC47|H^D6G7;tu5s^YbP@hzCvO{32n2)PK>U<@DjN&+X`G{KXh)u0qg7cLtt( z3Y`c&Z{$g^IJF;rxA+|!g<0T@pS+V68I#xM3^M*ca4W;+D>j4 zZS@HDlp{PFc6OV05E*NpTeGrLrPlwVGOjwhzcb>cxfTQVIB!X?R!!fpN5*a^Y_KB# znc7s-bD^}Gx2Ua2xfbnP(QC0rZcWuly6v=?klQ#{=>b2@O;HoL;tHfsrBYBpw3cu& zP2v#ekuT<(RMoTVK3tEZKZ`$Kr7fHccC(GFT;aZzk<6N=a{WaxER^_$5xA~-qu>*i9uF9Tc7c}b!rP%jIKPD9UhS5qq zS9xU99$j{q^zmp|vQXWkHM5S<{--3l zTD#m>XHF(+VB)BGS%@#8M<0Ch4$mLEr}&bEOq=mvTZXUUU>^-6#}LheUcAgMH@_$vgbR37 zZd~f$e+ea**uz5!83bI0a|1+KzU?v&3jaEI=cAtY(~n@9-MKdnjAVSANgcSpPE#IS zx+OU@+QL=Wt`le1w08TB)CRt$wCUMjW8o*(xJp)ZCbj;l_a(wdHCr@?L*Hr|u9LB? zbPlL&(YhjpPrDX2Z@{;P)sz}_&XCjoJSXW}*99!=vmSMM#FVE7bzVoga-EobWfq_@ z8~5Gd^eVS1H%@PVuY3$1(AwRjIO|k<(HcT=|x#wyb(Uv8$Rph(I@h$uv9Sd%<<^2 zZ<4DtytH*{AHa_<*_#aOmEy-W&tr3#2#G0xOK>uPFbxngh zKma6%eL~l^iat?Gg$2R%_PzM!B`Gf>cZ=3Of68!$BvL(FbKuhxh`U^#A`f#^Adp5# z^(cfg-gTL!X*@m<(yg|Hl5;$*HGlM@vRr4$&#SmMA?*`SsXnjM(Rf>6Vys$ieaD44 z&=}63$PGdE73C-Xhw!-;K`iU^6H|63HH#`$=@&y)0AaEo(zeqI{8u zn4!$YOOnxW6n$d%XsJx8Gu(hwtVIq+>m!zZ*e*ouNCCZsdG;6njr5ZsWH0fJlAW`{ zx4OjSD=HG+Cjcvze?YEI&XE;tc;2exsQV=i;?6Ux^bb5Jjp3EFBT^y6@O&^wnX}FT zPKh&Q6(}<&CZMZanzR+q+4d*Q@XY2hffJ<|Vi-P@qs&p~1UG=FS%Wn=L>o$M5AYZB zZjqPL-~@@Yx3HaMmVLttE6(iOKN5(SoRH$+5s4?Yb4q(j^ zJVMDtw$e`mk%I}27)L!xxi!}L#MyG=XRmwb>Eey8k$u@}mioar)_9yn!M~lTae#d6 zzTS+$zOY-VoE+6yi8ETRbq64xeCGC>ou4@Pp1%W`W;D2R`12sUfPledM>7Qh*vp>tEPFGMtf6QfKrv}0<158Ha%8gx!Gs;gD^RJD$H;RwYKCTFc zhyaql;Xqn*bRJk_aEv%M+XVFS&Ya8a>$nI*kruh|xwz~a*{0o&i2?bpau!<-ly|RY zQ2lC@FU7lTB3}n(A~S#~M0H69Ywimd;C(%m-%tZ3PwwcSNnI;CK|}pvhHt3PHgxnp za5qSW<4sjDPXq>l>h1V8XeuERi8i~Cj0*Ve-;>qVx+<%gg>(~0&hnAtCi!5i63xfMg^R=Bm zZ=xb4mISN@lP(#lYI6us$K7(j9u5%!2?3&s8bG4R2PV{YDg*_K{Ur4!6@)(y9GggN z$#o_tq5nCIkCTSP#4@z%2zt=a=>Um8|9Wcu{SeC#JTNU%Mv-w*mmIp~X7i0dSnvVF zL&?raOKUS2=LH(oO5bEK#!>a``2b=&JcELV6`8?M;X&s5)HoUDXctpfqHQRQe(w#4 zYot1S_1jBTDT%iGGj|t}aXe%338}N`qUR_i;BHg3XM}X6OxLyMP0R=qbM^I1) zBFU(48>Tyu|F8Fkf0!Ff;}cgSZRwjG)tQAL{BS?V$8|KmrF=CRy8dl8xR?SP-f3X| zRnBluhzz`5cJ}&W>$+r1Jvi1>Xh2vVtM7<)JGw!-iunZP|FS915)JUnbi&_#X$zi&^PjYkvgAlMGh5wjrwk zwo&5nD04tWg?C&w(EiNe5)8)B^TC6CDk%UKq;SXu(YOgx;O0+^2eER}r|asl($G;F zmI}}y;zO2N`*~4{N6C@C0nF{a%i0gL*!hjtYsCJYFF*k3s&{kw{Z7in@oq*NMoz28^3Bp! zkK-qxlLPj$ru7yAtem**@`NQ;ZY?@wh6%BCm=S2w``+rOn8`F~Epfbk@0;ts8e+JW z570K@C$2_$1*`#_^g^Ju!@t;wwG!DUOx*9*zJ#jLmW<~L?0(L9n)e(VNhF*Gx2Zmg$A$A+IU7n_6^KE%(pjE^{ltaG+GY4%;)Ga9)gL?j- ryU|P00BXQ{9_I3K{($eI3g=p#){#rCKmoDee^WyApt?0+hnW8YJM!+Q diff --git a/localization/ekf_localizer/media/ekf_flowchart.png b/localization/ekf_localizer/media/ekf_flowchart.png deleted file mode 100644 index 0a80cb06b85f00cce2b295834a9c2fe94c727f2b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 146302 zcmeFZcT|&0*e@ElTSbwwML?yAQj{vvK|n!7ML?H9@IT zLk$pmmrz1)A<3D*{=Re1z5m>G&$;WYv(`6@CGpL??>qC%(|*5shTxaV3KW-aT!KI# z6wjVMeg%PC{2Kx}e}U{TaHTrlK@9vl>n!{1H5nP%*o?|F`0sTWc}*8Jdovd|Lnl*+ zxt+bODX+7!lc}klvxU72_H2VR1acGd?D3=5?un}tzTPM({D3$tCRZ%btE4~~(P5@( zV|D-A^=l4^ZQ&1HojTPhr83oUSF+eGIN4X!EUGTAGDfc^L{810{ocCz_+g9VRl24w zijHp_o{ob?=R3|_t{!Yb`05&`+uWmeFW+C^Pw=fTV!`ew(~H(jv@&}&OlsNM+MWR; z1#LD*W$^6j$De7p0#C0}>lj@-y;jQpUzh$%5+n)ymrnejZwd|;6(|)cUT)Cxu^VH_ z>+6rY_mzIPcaU0ckrK;Sf#f)GF6Y)q8oYK=cg%sOgLqyMxO`#(ej`_!AP_Rc<;o97 zW~QJ~+2=Gr*@j&?hHh16;-I&$GCgBx3W;D%5LmO zVP@t+nCRq3PdebUmRSfhEKbg(w!OWbk$i4em`w1c8lO}fCEj%qkhG2#fLrXn>o zGE!~U9WOfNEr@Z1K>o-pi!XdFD=V963ZlAxpAE+ zr0%hDp2&3v)!Ic9wryW$b-bZ=VPR>fyQ7`uwS-fn`qa1KZ|J$-sH5C$lK4z_nP6iB zaprUe!uPZg=~2cg#k_ zi^RQ$K6y}kPD_1p?2nba9)4>U4)ceET=VdFhlL6)#YnGQpJgbt+#a5nmySo?)f)!|L(M0=)rbD{hszwRb@mh=joWU+><8MxFV9ML=D2@@waTjus_u zdSp_S#a?91kbIES*Tt5BJZn3hy}gZrNGtuZk@_E{c7(3$OB46qCU-&_?UH!1@x}p4 zxk}5>%3*yW$Gri2pMsrMlevEI<59k(QtWdO^Tor9ajIWz#hE6%+Y$}`nW^)tJ$ofe zWtboKc5#P1s|)6Ebl^rAWp~`uoR?rdh3e2A$Xzrsb}n<&T3fZB5+Ur>I5$+c(c38T zArAB6v4g@`=A~EN?dsqMTDjl-&9SAR#!Wqz?XQU{%YiIOZ2k7(QVQ0cd{3J(Vcd^Lv-(ALFf$p)2HL*+Sip~RNHO{d@nc8wk zaUN0jIXO9nqdFlS%)$$OZFz2NOL}fYtLC!5`3mZd*XIpc{i)AWPARlm+Sael=8e6{ zk|Rs=b!=gerZr^`@DNWk^(iYY+WXR?l-pas`XkSmrNU@)KGM!RD&hC~NAF$1;zR-5 z@=Hy9En&OY?d=|{(Kfmg_Urv768?*s16;*Cx~e*A^|)WlS#i;{YOz_eWUQ)UTam%) z8A0^)Y_gq4Sw}6-OFVW~&qVp*g;u(reP!2a>!5{$8N%wKLmWDCzk9gFi}SYLm(4aF zC!&;A43tH9@(cB1USvmw+UFJAwa|4qT=)IlT{)a6v-u9Z_OqU*>t=IaAA1YuLeOic z?zzyV?qbC(wXl7qf{|+DmL}mA#4l{}QnHubVpp8b51aM}UF&1}jgBly4t))KQkWcz z3uhsz`@fMgd@{spwe$28{KU5hE}BCdgAt3}qt!F^to}@ru3g^*GV=2B%F6Cz1XwAL zb*@AFe4hG$rev)&LC?pEs(UY#)>OT@>gr8@*m5_jLC|oJ0-8(xN^y}_Q$w)Eg5SJ@ z`_MuDnMEEpMclL})sU8U32GfUm?3C(EX^cK=0Q6U%Uf$Yvc6{1QL$q7CP@^!+4@;q z#Ah)w9>3;GukBe05m>yOby1v)_phI13c#%zHYr?Y zkT&|&v>nT%eNEQF+8VbR;d|W5VDF7lO9}B5`m=fJLDA7B{VS0(vs%s#2%U@Mtp1PN zzu#5oG@a}#Nq4lbs`nI)>^5}w(0Zn7xXG@Tb=k{&<$0ojX~#kf@S5m)i}nz_B$O-q znyAlu>{O|sq5fzrHbq+EA6c@(_8MophTUJ;t}4S+c3^B5Y<%+m)Oo8 z6f%FZ)~d(SU;Xv2$Z>bE;fF7YReu{yVgK|^EK=*R>)EtPDomUpV_JFvx?o1N#J8zeK+ z-wr!RAPe;vWXTMlb`N$+PWj)*M#k?k*SKz`t0y4>s>VH*l5$_;h_{7@U*y%#NBJBb znEwMD{^$MydAI27Ti~;U678Vv(m&|jQDV~hgKc=NhPp}+jOy7pk8?b-FrXxqjYHuR1rQwxm9+7t~iJr9V zN1O?D(8)PhMg z|63~F3t*mJ-r%T^(7J;~fxa*u7beEstQO}*6koo*g?5yUa;A3wj2`yVw>w-D&Yg{} zoU~LOlwpOe6-5R_C$a!me-|g)``bpFpJ(0dv<_nGXVYh?<7LU(p(_KdY_eo&-xsqw zMu&jGvDP?Xa%Qz?={3R|-g>v3%jmdN7k_hNM;8~XXk(Ko$r(LxIOfWxgXZs1l&<0s zyyJzgab8N7552!ab(tIIzQEqs1JIk7W5;xQeo@>GT+1zhny^>ZfIk{;kjB=pPdHs4 z`2a%6!~J=-+B*V43bo7ctT`uz>Po%nU#|td3pmt+56XOrC1YiheVYBlEctn%JWe84~$>8oSWl({pJm< z`e03q2X1MMgW7eIXX{luOr@ClI9q9W%_Swf&jzoJRRvLpOJH*HiwQ7a|Xn> zuf7{{rn}rX7+@^2IfaExQl2iZKUkKV-jyibfn`9jc_r)mydovR>n05xvkdzZQG_ZoW8dEzPd`^hCjnsD(YM58A!rfADqU^|o z%b)sH{-P3t!PEx6jZRl}9JW!!ud%lq7+Cxjx-D3m&6(o8#qWElXojB=AYNVOfk1lo zdiZxsQC4QKBX$3*VRbhl|_|@kfE^ z>q843q|CGczKkASiw#k$EmAE>aP2PoIYS|G@jk@pn@s{jp6G{W( z3pMB1wsL!r@LQP)*c^Pc;5-BI!*9JSM;nh=7sG#eY%f{_y<>h(0tioIm9c1-5?|Po zp{4QKc)*4D5RsxBui9;mS1KYxrbe2oTFXV9b^32w_V+m`>s5$a@{bJt)PG)to!=dtO~~$Eu`rbE*R%5) z$wjq#$mFaPun8l5OdJ;v8@IVSTqkTq1!~Lk?)XzTwxUO!Ba@QLJP4~TaURNfdD6u` zIxV$2NPecTQO;XAmJQ2gI+-GsOO?ljwXyqwRO;%K?e%X&S9)4|B3_6p%h$`z5a? zOO=T^LkF=-J=%wR%wLsJllNe=XC=904Ade$ke%)GFg>;*nNkA6y4YtvDTnj=)dkJp(Ofdv}S8$bC(RIbwx}qM#UxNE*>vy}C zd(lGH{gvA&*ZW4ELtV?;03dz7lPgwSf*)P|qGq4h)k(?vouNUn)U1b@r6|*KPngD> zAf2SIVNfMAH(w?9WNK#NMM)4#=x;vV8Xv%>)sdQ z=dq?_)$_&q=k3x2QH_^c;!}g&l=)UL2?Ja4@qL2Xe2PIXb6ufauS9iqwDiAOD6wk{ z4M~f6Z3-^WDlYZZ3crB8byZU&<3}dBs*P5JhSGcp)VSQeGW*H?neIIgCnr=FW`<(h zIoeYBXl(SrPKMe=RA&ZBu2 z4Ia<$KL`shWUNI|a!jSMM;w~9fjox0@fid%4LO!`#mU6z1FUDk`L9tqd`V77{$Zi6{JYQmskgYWc}b3kzh~b+emYN^tg5OilB3g9kwqhCy(m3e@+Z7K zdMWxU07t3)N5xQPe>UkXW{1W*UR!RTI`ZJ%)LKL&R+^bnf#oU|@lY>Yc4r_j4 zAur}SSaraw+%xQr4h6{zUveGdhv(GT-To-s$$F3e@6Y0Pc@6MSHgmCIuFL@A^H+IW zc5rvE$dSeBxsD!e&SfxP@MPBb|H>jqGwp(*P`|6^rdzANg<%E%@smT6LL8|z#{l<4 zY7cElUX|4TXD|IstFS})8<#mnbaY5@Wgn%v3=Tjb@Nm+L82^FcR}As&2FH>$P<-=G)Ae3dRITyePK+Fwe5arV>x#@q;tn1s>Nz38kz6T`yyUhD=YoRlCX>l?9x}e$4pFVkcc~zCaf7YpKLcMI;v#4ds z4$avn4>7IsZa$`He(ftuCK@4zke_KcNupIqw;lVzt5s&w9?5?80wtrU-T23UZl9-Q zytexi!ua{|j22OMWGHlbYPi^mMF2AWl0@bC-9`seFfe;>{JOy6T~blu0^siLC!c-#yh-tv#zRDgAXL848>*lufT+HL|sQhPX8mK zyY8EH0db+a zJ>|NfLfNTs7UFr~M7N|O6GF}~as)T`t>q7{@UnhSfQjW|0&A4&CYHF9JZqMNV-u1O zMpv=jNz%TPyi4=)_wPU+E|G+vYVNEi;3voZCCY+$raycqd|pmNupEbck3ikvihf!XL}!w zA9uxi6MN-$Eg^pTPeJMdF=|w5flwBrcFJX{_tH|>RK(mmM2XI5PNXNddnU|lEIL*h zC+|$gTA*`pJ58t6_lE@wr(&YI4_=G40wpczJc*%}eVXWC*R5p0C2lfs76Ok2I!P@@ zVkSRONnhK&TH-5WGvZL9T={?3rNhI+3oBg^xT>qsFxPHA3%_!rq|aufP7j9oqiR0M zs}nw@DR7Kw$)%R<3^5>z?2g{jVgC!Fa0xKKHv<8E`=v(uyk~iMLI{)Z@un*BFKYTx z_Tg@K^NXEghO!Id!7U9>gQ)wF(ovVwRvnP%A-w_8s#HKH9LRQ8hOrd`%AuZ@{JuR+ zRNG$uN3T9cL-+LvV!Xl;KNC*|c{`hbCGP0# zYzt?q18H0|w+3^w;MpDRfQ5{ZT5kd3$oSsSN@0-c4T#_RKR`o`a#B+tUe4f@xFcY* zG5rf5a9~R>?CjPNQxrd8PZM8OS4qBGI1s0SI6U4`0$Y027tWnKx3I7<*BZtk=J0l~ z9MY`edJA(A^x_EF|ggoYTF{bmmy*nq*p^Ax1z2&Dy}tpNqZTNUi1k5%yh*gKn{7G zSZu6#MV0D2r1{Ak9UYxPLC}>^HbK-rS;+F0nNO!igQ_>iDJSqYSVJ;BqTloFqD$M3qBeTj;qS!3&!BZZoW zUAxNz=F>ml#qGxMCS))HW!Y2I(HUEO%~dYFH)0H~c-|qc{l^9xWii(BkuohH`&3TL z(b`H7R?B-jJ40Qs{YfK<`zGNMIk_NdcLDl^5-1dI$##n%9x;@E<9=v;ef?axBp=!^HRwbg4?u?2+0k){wZdlN=or0}&J5O|Hh(6UQ!tbY zw(+4)`7bGwzkoDPr9S!~0dw6L={I;R2?pq*)`az~5|8dEAR$Nqm68=t)Hwib33bi3 zb7J%u0R;F`Tv@rRuuZTx^Vw?WjQ#rcu_Vhy{fu;w3f}m8241&l8oE>_;phM-e}qeEyQYR zW*pSga#_nfiFWNlZ^ntJ?FE1f0y{S5C~LybPQ5tM;QJhS&Qd)1AJsZe-)y46mxzSz zl>@vkm2_gaw}$oHChle@MrslB)_vCxi{nUnY{hNBIjqB~oLYQ)j^CI~fUyz}B8b<3 z=~vu-q!K%XLecF4kwAh}xT25H!w3?Q!n?fzms74g78K@8@_t^S1|G3zI|kbuNIBkG z3YADcY@|nQ{Gx*0Yy5JP`6QkUkCvHscEt&%08S~~JTO8Gcbh((Wec&dAVv#P2~>Wu z-SLpI;tI2lFr$SESpSn+fFn?q~BzITACrq-h4qelfeuSsw~;epNt5?9|alDK6!d3=%6Za@|&!r z%mO}P93cfJOK@olq&V3Q!$NoZ6e4a2Vv!dJ1tEvXmM#tL5dRcbByF;A&`1*w+X0*nE({?8Vo?Je}n_jk)WOKRFXb@ zbpYsp z&$CQP*$`+7wE$t5n3}F_+w#MAUMVXpYZNCtb=<9~sks2<1KV#TBm!V&&^dBCAz@+A zjY?{#S6?5FMc^nWA44D$rU~F*5RDB1n!#>e27tyv>l%dm;_1Tr+~MbsI0io9!jluV zc}prInCfl;MCUF8s8o2Acma}%J57T2)+Th(3uX5pH)TnF7zE}w`udZ_1`TH=_a>&C zE<>jMPEn^z=R4uT_wV2L_xFF0z6^ON`k$9u?s>8O1?eM&XrQ1m>FMd98(zw4yxK7c zJk!ta-*1ZWygDB)P%(=+OtaoN4@s3g9YL+N@BV`aB}uerAe6UGC$N44M5|}dp6yTZ z1NZ#pUvW@PV0BKRo78vkuGJ_~6a-Y>AA)i)t}gr5f8az&32DA{&W@T5Fnnt`lh?Jy zGmsI<(?{b6k`xiTbmt+Atp5r?#lyn`blf8(uTN=%`F=hf?ufmYy&j18nVFeEwqO=; z60-&t#ojBzaGi9&_`mn-026)m=#fS-`u0B{3qG|;#*dD3t0ciJQg#0Z$c8^5 zr{jGGRtLLtNX}osaZlwhND2L^+%Fh`M2nrB-Aj5(o$V~-qyK5|GwAKfxBmiG6EF;XWQcgIZ-gf!1QISr%6}F$vS0^IER;8dEJjKUK|JTa zd$+x3Z@~TIrv?}pISw^AC}clbzm(z&?{&BZlK^0O- zA52HGD@tz$t9)XXl4xX2b30iUi7GIQAQqT=O9(9}X=GAKc91n}UpD`m>}Y1Wd_6cZ zk*p2S{vRV#e05<2$ChkLapG~d{mL-@Q)--+fW7-1i6KUh57l`wzg~TTk~q?RqBrg@UG-0KySQ8E^hup>;+i;Wnh)%vbo8O;VRaGv*-=92M#Co_0 zkE%jc0{$l4JX~`9AVLE__S;z|F*=%d<}J{s$8C&WtL9ckhp~<{1T2;B#;TxF948U1 z?v&?BVah=>Cl@z&1{0O%S&|h`^ETinuHRUPEJmIi4J`V1XJ&+jPMXwpj@66 zk2nc)VFrYb0bgDG?}$bG!b0qQ6~aNA458D2aNn~3`>KshevsU61ClDb${e<8jlg6va12O>_QA18Z~B(d=QNw8Mc8U9IvTjM$i5j|jd)6*CryX-uE;_8yL?_d%9LbA`^XtDPK zH-o6%C)ax)1xT~H>Aj*e<$1i>CdvH9fUulTOlb#35az%J!ujf|^OH&MmEj0U#LaC7 z;Ko6**EXovy0-TE6kYe`S5{VbCyH-_vIFDAnbNk!iLIexjpOZx$C4l)FLmp0&-Pwp zn0kQkqB3FrQBmQI8=IOeGgYimd&EOB^M}PEz$mhlJ-N#HxL{a~Y~S*OK~}I+3`)cL z_(k_a)riK8ZPLje2blcgopgGhfU1Eegn~maC`{(MNqy+LMgw&gJXGhVzg53SN}<*3JW21 zcMnQTgt6dgSmg(sR-XaJ`DLeBA{|E(QWHaCu3V?XcIik2ViaxnA|5-j+@~VS1 zd*1}*Y&p^z9L{IP$^*axaam6MvP8+p)l=XLrl}x#dB=t18GCgAETf5&2QI6A$-mJ8 zghD@f{=rg&2^~^uf1H%L0v*I$f!fxt#a)R7f2QCCsAWuMlWu>r?&|@je zowp~CFthFZo=}X-x;Q=8rr7m2~wo+)1PVQOzGlLzOMT1_UpQgMjS|qOs`;KC3m3h6at=`dlzsIOC&Gsci=S> zK>sTDwV4m9WTuZ2#J~xmKg~4c=MkLcKh$n9-Xo3wV*>~YtmR@N{Pqs2juqg(hx-&P zj;>~NNNPY@KqLH7!TfnTgO*vYER9VCt_5L%Vh&G%+&?09F4&x*fbU<)_4HnHy;x{_ zVS2Sz^=igTN{RUo%=}X_Jt8pM-_&AbGl$1bZ8&cjLfSm4%~jvaSK8;*hpZIKcc@n+ zt%@sN{_ufD`A^~`u-INMC7EAftiteTsrdi=`m8Bf#$g^(55^g-zW3 zhcf&=kk)VSWI&2Ol#EVFnqZ|<3`>9&oYR&Emmnt9AW{HN>Xo~>E*b~)#Wii2zxJ!4 zgTq&ns|p;$3(RS0X<5DiMAC(s5#tCYib~SNtEl_3p88+dYutUOFg9oGTBp*ZI+wht|rF$bJK5G+@rW%K}7WXOb;Ry7vNm zybR%coR=3{nuaIOuIKHU=@ttbI`@8ge z(*75K82X=)X4$*m@+2Cum13NL4Tua@;+LuW!&%Op3@@pb21Q&_;%glYM>5-3<2ePP zxip$i?s_q-1Eag`LV56agRf^GHwUUoWhxJ!bcXNqFp6(ZawZ?{-oAaqTyiKzsjlIE zVJPg zIcCpBKaCY%6Ryv(pNf)jT^TGLdj<~)(sfy&*#D}5g8LR;9pXub4n*I+Kq;1MT&1iv zK`0vbW2M*g7%OO5nY16y%4u_BG?<)i4aNkNH@FUss8H}o!-w0G%4?HGtbdBrhc(P3 zZ_$E1sha7KaPc7j^zhdJ(CGw4r`xu(!ei9VWYF;xR%C1 zP_|H5td(*Z9}m0xsYOEQQ~Kkp>9qTw;4a#xa%bs=Y|&-L5ohHqx3iRLJW!DoUaqPM zD|w>B>cu&CQiS1C-z){05p#`n$!oOg-L+ffqP#hiw)>Cu)1kFS;Y(D^(yOcQ-Fco54i&(%((^Sw4Xt{Gsu1K)$U7Q$l--=2@dm(^tvyq1%0|Ea!-ai^a{f;;$>-lp4qSN+r^)h z?9&vyWcu>rjDw~KCdNnO?;9WCx93=o##)Ee^F@Y&sILr}4u=;gbrBbsJ~)FyU5A|= zNt}GzUT|Dy=M`4})r0A0qI!`bNqP>hcH1CKL(t?T)BV|Jtf;5fG6c7doftL|#lNqX z+UzRGj8^6Gou8M?`ou8U&{^7t+IO{0)O1-pXyxFMcJKHw<@I*lZ=`6BjV3x%t*FM< z4(jtUPqFyWNp*%lYaY9qZ?1Q^HgF@MtsMxOi#ST{f6A`=LL5gtoy^tW7#8FH@hmV5hC+(L4j?uzgYx#W2hS= z!<-j+6xrm+^pLnVNjq`k%^naWE96N|58^PGW1znKs>!=#Bo~hp#Vvhle{4Ehk3N1D z@#ev1ckpfU3s>j&R}92%7N=pK^CfubSlZtAr#1>u>x3QtW>(T9W0jP4cN(n^YTfGs z8*2%GA)cS?j7&tMQh;Bzus_wDP;{AAsAzUzX=CVTBs zSG8=~Av>}REG#u{j3JPkmn*4Uq|)bCvsbpkNTYGp7Uv6M_AD45+X~&+?y-uoJj^+j z*YaTs-z3t^o$K0qQe0R5eDFxuFtxNa#Y}q`+b2n|p}IIc<_I3InxgtKDfku|=mke` z1R~W(mE=SjX|Ev11s94!0!QCWC@3et?48Z>U^ieKvZ1Ht)!TU7l+mcnB)Q(W*pc;h zm5{=$_EnonO0TpYrV-N7p-$mEu=NC%SDksgS>e<5QH%&rja6TiFa^%w<^A+bJbAH? z3qeig*mWU<-oV3U_L1~A5SlC$9)J@MkegBR3Dzh?g-v^XKNgvrWBVj(p|E|+)!_!; zPFw8)hw1C3H53E&lrJaBk#O|ARl(E+WAi0i{q(cIF=l)u1;*5g&<@4gXqJ(z(am3K zpg5#v!P1a*KIK*KaY5dED`q!rF7|nG&1^6}$zm)%P|Kn{ewQKro)~nvISd*m%JC^l zw|7|8J#Q-e}hK8>p2j$zmeWEZSfCQbgOg9eI6xnju-j+ z5^Hm9vrcu>+X{g`F?Db#;!d%2@3tK}k&Kn!pBhue78z#fw4ZQGk{L;n2J=l=wN*44 z{^h*qfCH#>O3gH;+wuddkt^5h9jzdj~~LwKUMa!u_qWD6Vlhh zK3KFBMO9E&KeP5VRI;-#z!;URVhxHU367Y6@jdj zGOQ^lm(^PTY9;0!sQTAz(1nqpEVJ0hhU{?y^m+(=;>9X#&-pvtgX_=|}2(SSv5O~ zzQ@*ZxQ3xadYc?BQp^5v-}BdbepIyuocKdYV>43Xa^a5aWR5DuuDVZ4;ugLe5t1C| zIA<%^k)j(lk}=RBSzMiJsHw4;-x0I^RdYMa1Nq}f@Rcbu$WvA&V_7rL2W>lZ>`B< zWG!6e+3V;@_vPO>jmO|z2lvs|VCm+B237J_3;7MJ?B+SqFk;6z=4b-NL8G3j;j@UT zNvNf#U96JUpZO}uDe{7HY-gmBU85^+TuRTV`~BDxJ#lNLyycFRd$vXm6DZdev^%o3 zx!;3)fBym4-%Zuq>;lRI(Po9U-*(0p9d-?KiLlF6*b&xJw8hFD{seqDT3QIaQ|h>e zF^|<467I_H=wWcQA1!Ptm7;oi?@(ue&f7`b^cF~2;-%8uCwG1=?IN*PLiLNaaE*DG zZq?sC4Et-#c;>sgdA4hp3lBbeb*_6`&g&uBWIyJ07BeBGgR=*f3A3l;c7cZ}|6{s4jxrvHSWScX55T;j7U_;pm9s z-0{lVw>$7{gdnT5xpLF{JLt&}ml`>{LsNMq1IL8^53VnlS)aewc(ZzVP@>s@R3`Q` zsa9~baCfT}6POqJZ*{aoH$YpRF}pf;lC&~bJJQe8W7-@V$UusLRTqrtE2+lvGv z#}+_L6cj76rQe|obz9c!ZE*NgqR8=r=X$^M6mx+pGBjJJw9Mp@rR8CINM5CIW$+!k z&Q8gNu3z-wjG~quA7Q1`S2kPAxc;ehf@#|IHTxQfAE6JO3D%SS*}&&knpyi?ZJ9mv zIilCUXSK5s)k3pF}41G)ZD%etvO&etu74c|L-U&gc8aswPj& z`pbtLFG)cf(#t2c+1ZwSG?Y#{h&b`cPi}6lstS(Z`_T~4fI`*(SdE(sr0!wX)ZMB< z?n^9xcTqTt7Ci-IYh58rDLAde@orz7b?pa8&@d*NTVEG$HNwfqEVx%LUQ@Fiezrp6 zR9@&P7Q(a_@_0|Qj(>T)W;^bzbU#jxMLNxSiEs13akMRyo57)%V87IJR0T-0LeVO~ z)x~S*7ZrLG8XkfQgyNK=p$_`wx|zk|Jwk8L0K*lF>{E5UU_c{ zU)bMEl{$s3y{NVE8fR1!)lmJO6~;8>_AOZFAUsn!EElePmr_^utV_(gkVLAN6Tjh%fyW~&p*`_}p&VN)aCUnST zw}Rt*JypcDccN8xO7?93rdyESEchO#mgq4Xo9l?B@^SBgin{*kWrct7yKVD!Q#^{p zAnJy_#~e6e)R(c`eYS%C-({&F9!K;KrYgoBP>A~M9?V6k*fZbc4ZIAWR*U`gJWKO0@2JFq&-ol(aW;zy(dpE523;bW;jIv*<2eW;*{SvYKj{!4-TybN$^V{iKULYeSf&I{ zs2a)eq^OZfv6|IA!E&c?fXjt82(eU4hY=&e;mYkH3^=nBI>F;l7e>zccZ&fg{wVOe zbopX0<3H2C|2sicHUL5ZXy~vO4L2s8cne3U>&KQ^Jx}@_enyGa$cwSjm)j$lemSt{ zy7JJGv*I>_q>VWLf(V{?^6Agd0&}EGb3KP5x3t{!1S$@?LhVvCXfh=S-*qr=b<_BFZRrJU94+5Je)uC@WpL66fCphA0 z=_&9Q#ZfA&-v$6B6y-_lYcm*K)vdYVv|Zj!=bLNYq;q5fikgpv$<1^n2{h(=__}cM zBnelX!&KUB&T(P$(JYg4uc|u&=C7;fNV>*_uvRBy9USICVDn1B?7fXnMwKk?vZ`Um zQ#7IO@?>Zm+u%9aE9eDXNgP^h);}Bgsn)Tz5skl^R@l&gepfiue7*K(6fRlZdsTfO zsRMoMyqS*XRKyaWx92z??MdY>j~NdNyG6gT6T>{$nZ7e~T9@IVd6kZ8H4bj2cHbX> z`u3M22dcU}bW~}4Y#BMy=+`2K^RbJfUxk7n8}0w#&?-N$*3gqGH;TB#sj88XlV6yp z`SR#zS8zGAkA-)GPf7=EVLZMia*QQ^bjZf0D0fm<4c~PvP83*{l<}H=%a`R!SkrhB zci6QK*Qm(#9G%6OhITT46SqW-+lL`#t|Bjl<}FRaTE32Q@8v+#yP-n~^lvoycv8fD zHs<>kuuOHsH4@E6fY1AMWmh$auWqZ%x-;KxB?n`b2Y!+hCCz``CSOvvTx7C-#Dgla ze9aQjO>R#Nx+v&&E>xsY=ZE`5SqnKA^Kl9%2NhYRDa~`l{VGq532;QpXl9j`ypvw0 zWP@Ifd|!O|m!2gkA5HM;UgGHX@EAVFAySY#UXr!7Stf4G{0)c4OQ+g7x8ODOp;PJc zQrg9V_7MTjW(ueLjD!ld{rPS#Z3YQP8mK5RXe77q%(Pg?Y}XbaGo|JXT-!|59vU z{7v$%Zv@rhl~DUTHJhdJ;O|L<(}%|i*){(><}0-ri0{bm=wRW8FOqMz!?itFq1(lW zJO1KBK%HYWgp786m#eIyS>Qi+~#b0;7DnYdkN5=1Srn6d@q%uDiG$mZn9p#TTm;1)ank%s2`$j*y>S;FcnpnmZn z@9}+A@qCllM*0}tI-&Xj)g8~4HG}FO^%5xT?8Ox3H(#fu9w%6Hv2ZIYeIMI7P#W&K zp)UY!fcC8`*dD*KE%r6-fex6x31}2hYfYSLFz3nhVck_HOS791wc}=TRp^d3h|^(O zkujR}H^grl?ULTh>s!WgiM7-OO;O(VM%Tc>qDV;Fb$E#(p=6wJn?w1Uk3P{o=*}jl zBa^82hA>h&SNDQxynmOC%dWv?u#0p)tahJ8^}g%KsQIE>C_AA(Yb&^ai_<#&NO(b% zYU-+bSAw?7op>d`AE!|r5+py1WLSB{q-j^2Tn8m*Drb-=D^%&y*4DT;yUyahe>5Yt z&%+`TtyGg%07mA*0_z<2aMQ0I(@hFivxmF39w5gn+~r2V{6%}NOZ)cQ$#;faSdWjg zYTSDA;I)986EW*-M1pr4bU`E9+Y+@Js{<9SuRSNK@=VxpGc+4X>|^>+Ct4T}TZt0& zSuDG*zMJ;rIIFHT?6`-$R1=#{?iKX;j_t^I>t7!9RM^qgcl+Xfi457_kJ2a(TuYj&UK&hzVj$&UW2r=@I^>HiM!>8ZgPC>;g;jwx7(2Mm8pk{&v+1Pd9P{cxD)U1FGYO%1Gk=NzN=Quo$z`qv!=4W zInpcZfp>d()n&2XDzenI?Gp?R5o5d(nv(N0TDkO*yt(KA;;|x~`n=NJ1h17zCC#UR z3Y|JuYNsxn%fRxEWn5HbDsjMM?1y9Hm}Kvlx-S-V%-gjc7uTq_Q_FtT6I=T=5nuB4 z*fFB(+aR}&_RGX_MYRD20IC{qff zd2X)6M+#Y{Q@E;tWajfGS5EUeM$gIxHN>XoEikg}Cn|R=39K(hn~D?ee~-iUN$LG~ zs|W5<~%Z~ZkqA?xEX}G$yNJDK}Yl2W|$*7VMJ)vPU zSD9NI;b5ufoUp@JV`ub8u=B!Yo-W{sJ{ROleeB>9nGcQHJA7_RPn$ec!t+LKCX{}C zJNiL}Z^PiTjN00X8`U2g`YFg`iYT*?1GKT$LdK}j7l=TL2~DR0vllF?St+3 z__15feD!&0@UaSa!YkWrpC6rOM-IOq2iIcQoz3;7Tn=cRt-;|+>IMfiZ$<*P(I}uP zNLYXz9!i!C(U4GFwaypbMbpRXzAt;yxRW3zxU zL$x7U#CfV}n998tgu5(5T?a+0ei3$=J@p9)MdM9A3WHI;4}n5z_e|U7C|0WMCx&>L zj-#LO7wRTSC{O-$RrlznkaDGI4C;57~MJiqvD^3 zxVe)pL`bids@5~*QJg&;%Y({Q1+}Bf4OZRNLBe4-lh<19Ypp91^@zNBo<3P+cy?kO3%R-%Ee!D3VVo1HQpNQJ#)6W8)R7D;Mqy*a zkJCz8P?!G$p8iau@8rHAWqLGR%n~={l=gWTZtWbJ(Y!*TG?dkrt+#!EOUW1dE%8ZKie@qz-E`M~l+u`Xn{RbWm$Nj8En(x9c@I-(E~Y z`eT=A-dC<_7w7_-w8KqA^;{~98@iR$#NDbn-Z9y+%s($raGgM8WKKk?R$%4&;t}Da z9#Qmm-W!dmzt39`|7F!7Z{0TQ?I@DkP~AG(RVx?6s(=jREg#>o8QrNmD`PZVzn**6 zuD}cL(9_%zE}CqiI1z(Sv@lNJLdgZz5UVE$2vGI_v$zecpMiD`xWF;y&XNE8gBPbv_Go%?1B!?jnakxF; z@0{;j=bv-ex@+BU|KW0mz4vriS65e8)$_Ffch{$GO;ou;JKV!7HhS^dt`)tjgN_+_ zZuXrlp*ABq&6aK3M^(Knc)@kApm;)X1{xCsMHM>8B9yz9+i7d5Sw{V#qaWRc@dxKt zvx@VCi!y1sDuaTYYkYFXLf!Wj<^?;%#Pr9duY#S%PX!RjL9+PnQfqDWSj&mVQL&+3 zzYl-SHy58NBVXysLd=p5r|LlY58fmcBWG`m<^Q!@wsY4Tg(Rl1$JftBe} zfe}m>Kef$3yw*z6ROxbi=)70O{&bUEz9CYouB;{Y!>zS#$;+QE{N3EO-r%D0wE^~8 zwq^B8VG@KTLksI$fo#turaO(-jaMPlbnBnq*06tBRn<@g{eoKVKp2nAWM$0XiDYGc zCg`lJgwPp#mN0(VnF5kGp{Y}|JCxBp>8s5`yrXLtl+MW-4j}3~pmK+-+sNfr6LCku znT4!yKL`$pM`Q~-I&}nVrkcmhyE%!!O)a*@YWH|~s1v#_*6T9m zy03ZnRbcZ#EmZZ|qe@gzx9N6o`S?#?im{-Moc zUE#aXh|kYsruqz35Kb6IPIb?z_Y(|JGsOkb*TEXa3^GqKh4i>wTZ*EI*-syt26HAg zz}&{KY)PM{su*j`5;enJ3rFauUCJ-SmN4L1QThvlPnU99T)m4U3l^T$!yCB3dL?Jv z=w}C8YnJ*RZ$V5YT=KA5Ww?mdU9!?LR|{dWmspxwd5?UmCg#Syon)7l_wVoyL06;0 zz-j>;k()7oAnb?BVftvLq1Cc{SRyI?efL6@;Mm_t?`rYFPu(d`ui2a`(+ z{;miM-Ew~N>PJ$C+%|bpUKmm1?1*2sd-oXZt+g(?79i*SOl3UnLyWlS{2f|?GTUy7 z7wQCC&4S_pLh@oIkZrz)c-;zTg6(SLlJEB31ltw6hj1^u&mQWJ+YULu?dRyXt}Z+_ z_MB}Lv|S3l<~$;&K3r73ASLe5{N6P1`c@>7tG|)%!Ouy&D}77G?YLQ72|`C}+dVNh zLVFxfuKGo)+-@jk{MPNxb%e{b^K7fX&GW|+55P99&Z_CSW4sTtwPUI_C2%wcOjLQB z;_UtPlcrtn@FZQbAiNM)yNttWPV)(Sx_XJ!UzzQ01xcsssOvKTmu4oPScOwe26O2< z$$5w`K3IV^fck z;|zIb(7D>G1}~*@?KTGswGn!itRz9J9=+(xCt<<FCZ+4T$W$$!$cQWv}j83WTZ~ZAhdGo||*7tS|l3{wgL1uMmlNjf=|8r|VlrZgO zy_br;A>;M(H26`vq{pAd!je=ETqBtdx)#F~Ua#iu@mS8@@D51r_EL&~lnGW^12+o6 zdF@j$u%Gld1SxAbRQNqHWTXmn#kk5NGPb$csDw>dr_pPT|Jpj1=}?1I)@j{uP`(l` zZB*{H)~cc&;?6B%*4L-ps&cSZo8ghC?B);m6qIw^#bo5dqfu|9e)rlMGi{+C&UjjzP0B|FDPaEACt=Y zzeqC$Ko@IgBWi9XyBiUCmOFVAwWz)qiB==-~YuvcH`F-&TOG}Z~?|32Sc{Bg(x z>;I5I?{BQ0vjf!4cXTL4OidQtxac-E{_=zC68IZB{cmKPjUJOkeY_O4au)IisSw;A z5|PttII{`D^y8P$S6q8dkk%NQ2G#s$@pF%*77BcXpL&5JCFZ|G#v|A`s6SITK-Y;O zkO_RqoMv+XQ}7}%R&^Z(SBUzrFB}@Xcr}}z2I{=f!-Vi-LpcTP08&j{&_Y6Pt0ggq zDhT?+|7NS?QyrVHwJfA0Q=j(E5<-WOxx&Ps+z|T*4d*0IqVt~#gN;+xMIIgfjpMJe z9ZX8oJ9qKkdk=0&^gD%toK)5z23eBtv89v0S*B*-GV>8NkbKpO`)@YMP!d}5>P@)Mu}_7nK$(!dJ)mF&*40s*tSvb^so-y9>!~HH^$TaCH3F z{H&DnyD3Ff8@|B*R`W=42T#D>a_oIB)K)7ELT^WQdG0v<O7@!^1aI&QQ~ElZfv z@$-=VaVIy$al@N2eih|dc;;TEz@?R-!T|MsC% zPs>duw*iLb+f@K0@woA44^V~T>gIZdrR0j-F~oBMXgUfjg%}LHX0zAd?`X}wy9Dm> zGy7BoN2nn3f~MaE5?EAJ1T^Ho^kj|ghuaZMk6=7sLrwey4Uya_lp{<(oRXUW5MSH1 z4@CY-%52j-qR!uSGu!;u<22Ni-9J@XA6|ok%5G3CyF_$xEe=0FfBC@TO+k6;>vyW6 zqGn1`*nDMqshZ<4ibCyD&$(>(DPLjKw}2;0SpXf#!Nx`J;^6mq%EeN#vKTzKr1H;N z;`v)t7-)xv?I+946oPNk0ksc!lA)p615{|MIZTR5=A}M-9^_sDtt~!{tk^1rVI#$6x6*&We%&p91xIVeB(zW3Tdp{S@ax z{Oi}l{Z0nyE=>0+pX?`5Q;?JAfN?f%%fgrCem6yCDn#W-XBon6 zQN_a^S27t+tmHe zSZ#v|HIei*tCgPe3d32pP(<$rwZKC`50K+@Ukw4T2jD#n0GdE-fEi)|kgF`vmGhTb zZ31i#n_ymP=_$x>f>8sQCH0z3?p~>rf3F6+L;pZ?{z&Vy#L<({CVHb>Siblg|Or&U{A&)J*7_+Z5#o{CxSs*3T}G$B7X4;$n1Q7 zjTCQKZprX{@v+184$$F=5jKLSN)3Vh^EW}E1k7zM2`zEHr}^HW?T$gGA9Pv1m<1S< zESueqoq15<%?yF>YA>x~vRXxfQnrRGLg;_pI2SIz*Ulp7Xz(pip&{x$@&i99T|o9N zU}GJI=}B>#n(y{kh66en1H2y6T;mJG>!-*vfE1M@4V=4q+h|E;JQh;j=?_N`ULIgn zt+9ca?t)@ZPC?u+1t~s&(%zYW8-8YgBjo{H?Y=_fvj~tAm)QA^0QCUkOA(hq?dd9o zbb8H9(87z^ST(7G4>S%>Pd3RnnhyK{m4=8CAObSSYmZICZ#Dm8bkUbH%>p&`k*e%z z{_7M`-O3TpZ{9Q>4wtsRD&LWR_v~yjjeIdSHU=stoO{zGHMorp;03D+($66H=VVG7 zj$s(7Er<#?0JhD8vixjb0Ny!M%bkwyZustqK6v8`?nF%q(e0+A%!f)4Ht-xhnHtV! zKKv-zNc9Wf+|Hnyni>7Cr{}UvNKAC^l2UPd&3o`t*1w=Uw<&(RQR8=p>#spgQNkltvggM`MhzM=|)NqcuSZ zU77vFvgM?EFF(R?yy_30z`8YxA-(nKr>3(N@i%D9>AWz)6HJ%vA5Xa7{-+keXatG$ zUqQpt(QB1>X=)1L=D6McPa>;_ZC`L#R#uk6*6Vu#tmMp&UHNiW`FMVe6g3~AU|5xL5Kkd1OSe55{^r3c9prciQv;_>8w-~m~lb)CYV}?nD#%QdSr^l zZ*%+b@GvKc;jk|lKcsHE&djtHco_#60?LBVo!kfsX=(qx)v>uBrbCK5t)E zL&#M-9jBoRfNFkQ$J@QR2@L=R6-JJ$m}xim{gWAVu~)QaWA$zMOAh!wV1PRDIGW%o zol>9Q2l3nzr>!)ln8pHtv`jymT$rRLiKN79(IbAZ-DTGwM8XYw`%lkFkbl32#-BRX*B-U$Zf#HjEJJW!XbFeF7wW1S{6@5x#hXSOaOYlDg zcTZGBe!riYnZdv8KEuJU@;2c5i99+3*nEGyi~@2%!vPZzjf@At*|@KcZuW>{vOu*a z41))BqApyB{Dl92a-Sl)7Z(?|gPD>>IT1vDT3uZQy>EOHd{gCgSAxeX`K%MckHA`n zUvSs&5G+N<$H!CqEIwfn+wS5AH6{cm+~-RtzVd;V3*U15_5XJ*+W*A{=6`xQ-T#;_ z{0&b%(#J}lZc9TDCvM8NQ{EW(kO?4S^FJI+*Bf7*WjOVSqL;ksD*`~-=V6BpsgY9S z)8wh+d0$~b$>OP82z1B=I1{u3&p{RPPkZ3w0N^1*;1#07X@y_y?V=BWXLJtTBKUqp zDPZ*+yN;5cCb_8v5bN4!RiFeLIH{+}!*FkRV0k|M)i(4L-Xa8|bx5xeWJTj=EkOV_ zF+F`MS1mno0vmY8nt*`e)A{!o-#Dgfr%U;6ZEq91l7qV8b16>;&`zRmst{fz7&ymt zeZR2OpQ+&FPcQ^a*q(5mk%m?YIUM?Wa8 z0Qc^EOE2;qxFJ{35ZC1)JcueQ^}G?Mp=<26_SrGE}cD)gEO2n7BL`7!=G&@-%FObIX?-RE*}+;D>+>fJGTwvut`zpcRF zHEi%D7~-nO=l!~AO4XJ{c6ne_rsl~*!1-Dbq+vEaOUF@Y`o1{ zkF?UGB{w9iM^%>#plF*iTk` z;3SOH?P3)!AD3BqXqOtdJo?IeE5whpJZkO_(!eVJVzF&x-TZqNvp-qkRddr8maU}T zl!UVt54mi|rTn`#k{{o(yF`zjz-?NT7?-Xjt=PiSLok2hi1TH{Wmr+-zJ6JV8Kd+IiibqXGbKN3190SBhaBx`1Q=JP0Cjbd- z+JAP1X53(q^7->CI#WNKT99pE_`)Jt^O-?jWJt=vBOw9x2eA8%N1JU73iZGrCrHr; z$9tp;SPzit7?=tr?|S)WbzZndZhAKKJBk__v7K{()?dtL-!aP;%-8Sk3ji>l2fivO zxE&4tyAO`7Xjm>NoSB`yZ%7f)^Dj_buxxUGlHCb_fG*6>U-GQ}{P{D(DS7$W*p^}Wx4^x=JLcN}`!5~OCCRN zTy7#4Zw8xzZm_7Ot?nE!B{CcEj!BG3Fg1xtF$Mu~Ov893m@Pb>h2O&|kdmqhTXvo7 z{QUT2Jy0;XVCu9Jwx%;t4QLAtVI1VZU!LRxB$rRM2p^pb>1!ey(8N!j;;?|TT5*L% zEY%@{mDTf&Qb)YTt`}~e0yO*~wWLM(90gL>&k2>UF%AaM`-$=JEr|xyO$Fesj_83UmrBUK`M4Ip(Mi-m&0gcdTFq4GFF*^_ z0KCL>z{LPIDxn#&_3|cGXZjEL2(6Q#fScmt)tgm*e83a$@~lxyP9r~iAiCSq`4${Mls@kaXTK{|KcpO{|>S8uSs2j&=TMk9bHSFBr^ zrR9Kc?|AUb2!WWm%VHlO6VVTrre)XN}u|yuzzIt7qb5i7ZsyJhymUE zS_(LF=FL$grb~Q;7^;t&#cCI z40eAJM#WGy;aQ$|_K(xQB-An-f3-p-0UPu2DPWeodkfEO>S72U<~ieVy34qQJHkK! zPs`}Yk_)28GvEPUJ_|Af=84??$2FO4KQH@Bcx+4qznoG3Hc#!jx&-X|01iH#t5*xD z00j&BM`!8r*v?Z5038c>yrMu6;qB7W5yo97us_@AdjxerQIEw0JPtn-{rBg{K9JVd zP`ezQ57hT?H{&YHvCFHhFudsR3cvapa@CoEn)lV~jW+yd3~W83Ij>O`oh$zhYhysH z(h<+DmL@@Uyg46U*B+|@+69{Y;a|Aa-rHU=tI6`6UgGcU98$byT3C}ERz`bQ~gv~^Qr*j#dxYtf#9Wk*j z)mOYt+vh^1@VZxcDwX*HJC3K^3$c^@e)q}wFNKVknLfeKQ3J=O%gX-SzX0hcqamKj z?E^U1CeM2vbek#hivJ|kKDl=x%u4S2SDEuC9~R{0S<&5fQf-~wXE3}ob~f}s4Z&-$ z^Afkn$e0-MlM1j2-C7C_XbLn{7;)4#VC{d2}yFEKTr%-3s=4C@$w{Dp1A!u27Qa%aosR~nt(T8pB4 zQln^~u^=2vGv*cWHuA5=lKguKm`5_ZQ!t|#A_Zm7#PwBw3eed&z$JGQ^%(#s>=6dR z@LwNt0`#kZPLg93dOTDAiyXKF1Uq-ZBCxvH-{c0u<*&moToF58jh?gsV!wApzILlo zT+|fj{Z3O6QoAMuR^xx(KEmHB@b}hcV2!j44e9KXHFD&kcv~}F#ib^6l?G510SCb0 zzuo)x;#H~B<870p(DvB-`uLgcsF#z~33v=IPdLTW5VBJyVJaq)5KM{7k-vi{&74E5s*N#o4_8Mt%Gn9p&XCZ=4X0V6Y0%+a}YD|G5kB=`^)IJQMAWhnYLy{F|Vv z?+B-#{Z-=Qajy>%5AZjCe>8B&Jz9#u9sc}C8qIly^6Ou_;s^X1-Lj@Lb4vMg{8Tit zpn#<45@qdw{+^U`ndZL2(*6ImV`&0+dE&5FkHGT%xq98j0xFji;PG6CF5$yD0dKQ? zd&_{ymMi<;P5o7UdZasl){^gh;6NT=6-<)TOuvtvFSb0ts@(`lqt(yWmhS<#$;br3 zP5=E4U%*0Hymq#Hm@pAs$)2ULjHtV7vwvCrheA$bL3GI#0v<|m?iOG@lJoV?5XJ;i|7iQuOpR`53KH=l~KLH+m)>*!Vg_DEV?8Dd|z;BPfS zzPRglVPRmC6YKdQl@^c;6QIr|9R^^>NByn7f&+hi4WMd|CB!D z5SO_%F;(TeXU@K*Q}pn7yZmV)SWkF({?h^5qNcly8Dhp<+k0ZEHMI(4!$D(xADyW>!2)NCKxfQXQWE=9jIx*TVG5QQ;cmm2@i|u| zN;0?Qf_;*K7AAeH%WYBc6c-5ZZU*zFkMpmC8KqLuMbE;RF?+F11u)V%Omf|S;a-z)2P{^`k{ z&HP||OYrzz9&1!>GiDr&I-P<2vk&km_byi%Q7!cS(P;CLQ&MoLLitsjkF-tK;%H}=HI@5Z@lmGu>Mgemy#@K4SJ|$s{>eE& zKh#Tz7c%!*{T!`sCf{b9AZFWi-COHPu-SnTw_bvvZHHRm%1*qrE z!{p_O7^r;v)nYknxD2#b#n4CnguTa#V{SS-8-y7jqIx)p(DWBD^|mrdxBXu`oG28r zuWt$%{41<~_k0BJGp&>O%v29YIrnBSY}!|14vWoIiAmpD_YCkwg@p9D40c=S`q%Rm zHB~z(?iKKkXv=yRa+)wYz(FM{*2Y5~9(qlaf zj4Dg@zj$HBXIK`fU=xAb`YAQj!g7MYh5X^KXO(8Vt|Ac|wXSxjxUB+>3^F-c(&+gd z3-#2_5*1@4Uq|{pL}DzzkNRjp&QrfY?87yc0*r4W#ur&K)2!958&%9*@2;1Kkw335xWGT4MKuiw;T1mqx@+;)%)nq=1GzT3OQ?0ZfhF} zCOs8X3+=@1g8YpU%{T~0g%q@Uzo~>mLG~YTUFY_8+9!vVztVx;a%z!uQygly-TMXdFKl^bPkQ8I$S-qf za%>CIIX%99>j+Y1Z><<`C(!dSJnoN^SHI@eQM@%Kbv)Dmq7U~!q8vj5aFm12htCMs89EVO-`nZAG8Q>g{T-{{zz> zTq4cQRteV;81{aRn4nmV{ljkTW&FDe1-*~Wo-$sJPjHpp9ieqRdZ&ODPv3WKdZzRE zO``GKQTea&3^}SOvEhJ+*XEaE!_9)j^cF;2`kW0&N&0=}I&rN26}G!o)0c;+O1;Y- zm4?>4pVSKa%ey)S z>^XKq^1PKheYTx%*Bfi0_TFp+!T8poMXyu$fpS`+-mUf(I=6@{Y^vBYR8?Vov*}zV zT>bY7t|KlDg_1$dHQ10YO3#;9JL&B`5$T`GEehcpiJ7yIB7?HKh-U8F8wpY`92Zu1 z`6m!CWQtnxzf7iw)^#*O6kT8XHcuL+syBtlI+Y}otg30YM^M@)`*HL=3*oHa_7zkG zaXtZbY z4qOWB;qg~lz#cL3?NM|Z?;FZLblo6B?8~>6eQhmAQcO;|^ezvl#`2KxW}#tqtL0xp zLqg{L4u~bYh}_6C^iKtb5Sg!aVh@_OI%4K@`Ex(tX8s(L`=#{*xeZKv9s7J|H9T|U-=c#EYeOH=4(zeFDAZ>z>Rjj*J56A#~A z#tE}|3o;n~tVRz@xvK;^p|>N6wkMcO88d`?{oNF7bwqa~GB^d-YLL+48ssH4ElaPB zgPEI(FFWUL9Y&6POc$J2R$>PTef`fCDapSc3dS%&5L57+L-X)x-Rz!mzAq#;Bm_q> zw%xkhAl{pBy7I3oN0vc6f?5388}iu0zOC?Seb?ev+$*i%p#DMUks`yB{jEvw%I*2y z)yBm3(VZ?T&P~Pcrbv<=mR(#Q!N=D348g1#mi5>rx;g(636EOb+EmV-4*;g@dhTxP zNROJ}W!!@r3Arz(l}zuA z)lUg0cAc6|yxG|%*C--VV|b-mu;1ErNYVxgHu`K50XUEbbHGy*D&4)EaxS$TphKEY04o z)?7zdU!&muRrU#oHY~e-j;TgYFZBI{0kg%VkM8J2?5?6{G0x+^DhMS(YfpO`olmr( z&fd(5;Xr0!OLo(5(l&Fn=ZSR%PjSxSQ>#D1W?NbGI+2QsX?HqIB8NPhEwoML*f}LF zR2ADUK`PAk7U2zu9jVTDjJe!)#@WssT=rg{AI$c>O=u$6Wo;*|H)i=$QT04G|Ix`e zYDi7tLsE?xSg*_--<1VvRmD|5IyhfL_Dd(ig#Xk6P<@(re))R5s@5SfB!rJGXU^e3 zo`&+r1L%t`em{Dgb`&p*+6~k~64JYfX+gtQlJkUOmc@wNZ&5v!*Yl0LZ%@yoeU>?w z#vf(xi*2nth=w0^h*sw=9Sr2TmP#yohibr5Vs9cm z^r$21s;s8_QjBhP6m{-NvzVFucz7YlU@Xx>3Cl~Cj_jO|D28W}ZbeMoeQfEC6ML`J zVCwogNdu8b4UDMEEaithia`U1g>_pO;rF^qmqJyepFbOr;#k5k&JsyxixpGY1h^8C zs)t{bjG&`Vzcn==v5pOU5Ec@GD3Nk0cKx92J#J7ZaL*`fA^Lvro}y@~-?_iaiTjO@ zOAuUq$9I%&_fh}4?Zu2n^(_VCJ@_?FWzDv*i3UbSvF(NlRq2|M_A7!rdlJ*7hh~Zp z7Gg2oDeHZqwUZe0us6buz6q5IOkLb=zcMaIjoMPn%4W6e@3v(WNRt=eR-bt`XsKHY z6WxaH43#g4krO7X3lySjfd zNXk!B4I_QW+(UUJPp}~AX?Vyl#p-ITX4P$n_dllh4qwVOyDcrx#tu~Cyv}r2_}sWr z-pv`CH`K1pkk870qny8h4pwQ38m4Q30S~4_V4}DkKB_id^r3b|geOf~E>vAnlgrP| zsM`4Gl)p{S<+Ftz8Vo-krBJHfR}gn~qjOjFO}zi_%@D@kKB~0nk>p*nCDA!p*;nwi}iX*J0P+tQI?JuNK>Nw^WHC6Iv4BN2}sOmP|fK1cHqMO3&-*nO%7Iz~}g~ z*P}aQG;4#*Dz;0>u3i_kY*X!3KN3w~*InL@<&QW%MegNfJ^492OP^FdzfQ3;8+%*+ z+;Bemj%75&D;2@ln%jJpmY1Hq%bd$5OA7hbKQrK)6cU2=vb0d!maL{G%O!?O5euYA zcxt<@vX8&vxkLW|t#1HrfPsaZu^YZzeIJaL$oA^$oSFkl<3Kv%bZxwxS@=FLSFP-J z{QRF$xTTS~^VIz7P{HG`*`6;XjoadAZprO^;InzAj72mR>xW z^x)==5JqpNd%UbJ_pQ?k0wv{j)@c1FbV(0m;y=c|XfDYeIr6R-*=;;bn15+zn`OsS ziZSSBhBqiBga~iTrGc2tWB}dQ|Lj8+taEaTqm%9b zN#jgT`Q{v{m@Ik!nDka&iP#<7j8)ow1-PvxX4neWyfokU}QV6_P~Kft!8 znqmjeeZz-$&jNJ;Z)FeUM(nRKGR`2dxnzm zAgqJ8OMgMcoK|Bb=FpY1?fUz4<^1;Q^;736*9~ig-go0|ulCm5tpqf@BBPD#QRYlN z-99gxhiypg;2V;{Vq$z|=ES%2!%k(IPJ$=fBr zD(RE>M7_~f37QML@lnT{RZo~~s^tJ*+6@^IAxTRk8DgyiV{YdUFuJOfNccC~j0bAU z_THbEvsEBV#Zdp=NJpf$H*hd({mguQUU+3ky2R?u zgHcSgOwL*HtlSH);j~+lpJz9MHdArYZjvoxmmpQeO;D#68e# zbo=U)SPJ8`4SR#EJ3QzmFqHFSWmnqRn_Reh?fTlf5OPwjm}4(Uu?%=)mxydthNy>I zOT?E}&gSKvzw?qHR-%`DRYt=b9FPVEHx88ADBe<{iLQ*6^w|CSr-L8`-9MMT`UEXWqy<)eR!a9{?Qz6 zM2bCh7kyv>Jkvrw>u#T_hV6bi*=?Po$~n6mt@o6+8oK^KtJJ=TvU65VF)wIfON*AD z2h4kOO0VR|kzMFaS%Iy+9P#d0oxALO;~PIGe4@f6Q+e%<_r4(wMya#HTUJ(9db?>7 zjqO`uS&)k^cPjs;{q@ZRbmN|ORNR-#H1w)Ob7BRysA5(PzAd2yQQH;0bz&7squELA zxWssyDv6nY<(`YpHdH6CtE@U9ub92-*&SMgMrhGNsssFy_o+IKh9D18Nc0rqSz6U|3dQN5FDWeAgN`8+ROX%?~OVkscBQa)jz z%)n{v6*0T?y0eO1O6C~wIl+XlTyan_yb$JN5yTxwPdYY?cEG;3(cv!|(cpV-nvLP|yWv)NqV$hd5? z?0yL9iSZ_4^!3C0OCJdS`b&;Cw&!)zJ>UjpB>lb6v7Y(iz1nahSSo4a>r%GeJjM*K zLfm5Ua#bV{{1=3&{d!fcD&bBgl3W^B6HW%%2eSiKWA6g7)h~E}Gi&-lRM*bSxLsj+ zr`}C4B*d+uxv@YdE;)j@N0^;AKMLZ$NKr#;s9{@}Qk_c7oiWJL%l;B3WU2QocUC`r zvf=R8WW#fXRAxvw4I27(>dtJ+R08~yy;wzttB>f~&==!xecvof+}4FSPh8OnfdwH} zQb?}!!fhqq*0H*kbl*`iAsNJLg~nf<6%1Wf+z)p{LoNwSJA$q-v7Fi0!j3%rUMcyZNT;-hmkjgPo_%B7N#Fkd{)O8CTRq%*MDf%v|rHy453MYu|(Qob3 z2&m*TB%7p2bc?kmNJ1<+H5F$oj6JmUp&5(2C+OJ==Bq#BzEnQ@CU=;Sc^YhnXLfe5+mQXP7+8Oaix+nH*$0!#-K zBL`!mm84`Obv*K=mx7CJN0MMDWz56&F&cv}#0^FU_1y=?S0~fVcH5E#`j^_MXGm{% z4_cb{Bqv5swvkXBaSX^&&r2c{zI;NI4C&5p+lt9ScvKn(#C*HPR&7_iCW#<(5`KM~ zZAkXQo7y8oUNkgAu}KfT;C|swGg)zemaO?LEW1)1&u!7<*$0U1$Y2$vVj;hnFrihe#Y|fY*8582{CtDKndE%*vP^Qf#IX{xD*k`fUyZWS7zEZ47;gt>@@lz|g-*HJJX*&Nl>dT@%&(?otAAMSy(%_;u^v-ifXCEl5&b8|71CP~t3heBIN#A)Y?d-$%ui0TP_)IUjP9XE+ zhukCb^&k&LkaBhLj1BJWF9DCk&a#we9|!{f7Lc8N`v0H>a_5OQ{OkVDAG&+nk*i*W z4S$IhmkAA=<(kiK#hsT;oVDWreD3UP{6GIM8n~Mtz}|aS5iZDBnWZTE6ET&RD9FAv zGr9;ahH$mIo&>~jF|-)tE}3pw`JkmuUV$hq5-wt`t=)JMK<#$QXj7bNHP+l!7~9&` zCQlp|8X3U=NsIS9?TEREOHcj6=9#MZmzU3St0^P+OE<`Bs23}6xP~lKaF&$1dXA3{G8?$U2lh&u z_-klCyJs&waf*r#R1^tv`1L0B{ss<(NMqkE*DkhILE%8R>1uLZi;)oZTs| zo*PQ?ZPc+A=5u85B~1QIz_MR852i<#HD`ZXyI(p)O-ZFjQu8IwNKNYqn^@#?*Lh?p zYo9?@0f>X1ga-0V5oT?QtCaLZ`PMcaGHMok`uNzn43*_AlALwc_>*zf;KW+XrgSrH$B4^EluEj9AhQQsWYWzJSszW_P7_+_luy{qJ(B)tWvVNU~b<yT8v3AH^hoD>Cob>eSW523e%BW;lV38&C+di?}K|Um1RA#a#Un^F#Z`T;hZjUC;TN=RHsR#X#xGissF(GgKhPA6^l&@5X zs;wn-S@Jj`^AA(5js~iCf`h0#p4*Z}+$TF}`dwJ+tEu+~~F8Bnc*EPQUKDS>gGca@Hlsb)1SX!`rL!PFH&PF~98@t1BKWRz>4(n<}6<^Ur@_(rus_3BLAD5F$a@L*C=mrvb z6`r8a$DyIpTDv%(Bac8D9@u=z)FwkXn*z{FS<7D@B^9e&W=BMFu5(i+x^>2+B!dt(;!>N=z^YWj z2;s4l3(<WZmJ9TO>QQ4lW?m65(E$oc96V+E)J8fXU z{Ek#|f+n;`)JwWJCmQQDkPlDU2|3-zC6hvWKJ8ZI?k6N1ef#!cn+5tt>jAUtfrDk! zP9&@OcVk=t)8}yNb@XrFp7HwqRY;lC#xWPC`4?r+o0g{Q458w=#loMp@Q{KK6{n7I_U~1wu zt4E39ZDz($(S@|<$6p&4`b!Mq`S@=-vQ|@Qc0pB4_2H))6xyILodbJS*5xo7(%R47yCT8FEhb1p($Y|6<(V7u^u~zR-f??I(3d}}tJSaH z78GQ2RhF&`@O^vLfqwppqyb74IioY7(oya2`@6@)KY!?WK^!#W)n}NWFAws@erGzT z15C%J5T(+zW)~)wo&yH6+{U*@Fh7B&a)4;SVZFW*(bQuUo9P&+4D$8*>7zre*GNg2 zcwvj}9D%B`KPz2bJ)azrM)x^aO{hzXB39*M&XTNPaz0Y~_eamQ9}%L^9_xt3?wr0` z&SLOg2YsYnhl{6`QVswvLZhbGxTM(_8A&U)*B5cc2tNlmiw#EwI`Ny;z9k0LK5hEL z!P0qv%4;2(p76#~Y4MX3#P{g(g=-%a^)km@*-4_=6ETi!W1Cw!!!=l}oxYgz`bAWD z!=h)l2xS^2Ks~rjIV+b>#@d6bjD7b6as9zEvEWLf+Q}4AtVuTu|RNt}G8Oq?({J-L}Pf@1Sp8K5P7 za{sKN8%W4YmeP&uA*+r%MaiPs>=V{9Z2e90k8Gy|J3d=o-=&;Lsazz3)I9zvn(++!vi?s9qu+vl z+Vs|Xsr~a;olv6T`08)HRR~R;t7_jr#fW`7S_{|7O@lp?Q>@mj-zy;{QGb!c93&>{ zJH7d#1W|MNsH`;cRpZEQXy@STuxus;=Q@3<*uais8?_f&^k#+E{!HiORmO z)LHXQ(e^mYQ|e!$z+8dau$qE?6hp<>#GT2y`IG6gr)@Wwrri;G1`R0P1B$4c5+kkZ z!JF6eCO;>-$KUr)XDfg$j$~D|Cv=71=oBRHbjifgPVsf9Jwv(Nx$Xh~_EfcB!kkI} zhrx$OzVHEullIV%JSl&xPA7S@+8LGyRAkp8c}Fobq_NHBdLJ%jGG=^ynp$J@^8w?9 z(%iXcvCKb%QTaVq&z@(g#sCS3?g|KEFqkmnekiMA`txaL*ZR;O)mnRDVRBb<`%b}FN#1gR~dyysT+H{gV(;n>?jeDAy87nXetc-5*xW zEx+T8SOH4S--FS=gQYygFujkOJuoq!QGWIFlU~*ED83<)8?_V?qeNH0{eEe@Z**P5 zzx=u8A;~5n@?9kTe!^<4rG$NF(sQ}YyAZWq8vR2W{dC5#Rkwm(%Ldbt(R$fE6bl(7;2n_iRSm!M@nrvjsG*@~`y#o&^2WxyC%C`PxPLD@9^`npEM9NM%1Z6}hBaDX zXJt$X=uKr!DqmIUD7wfz==SBtd&qWl=bUnc`9uffd!zPh;XD>;DhhtZojF{z(RY{k zh_inxhdVl9!U($#oV1Q{E5s5O16#gl*D{+_%JmGh8(YXXT*+39sl2YH*LV7H{iy8m zMK(|S5zS}i1b6NeYgXk|hq8`cQ?H5nO4GrLx?a82I-RoDq}=_s#1dtmcWc*}lH(HA zqOr|#BNNf6E|vtX;gsBedH}>0{;t{Jn@h@1$u6$+nf9VsdN>~bdn^I=jEvgM!wTKq zjneQ_<}V7eoI8~eX4m!|S4eYr^U}WCl&1SYRj6eA-2KQewq&#ZlbNJbgGGu=^cGd; zpbWveD#(s(BmQg}0()?zJ+#(k^Cwb8v3i2ZJU^$X4kzhdH@b+Vc*Pb|uZKa+;p|~8 zhBQ~mRP)lh+tj|3yNVpy5BJ8Z5vOLg)74mBO$2M78-Njk=bUT%%`2>PL{9z{?zv>H zka@@VH#bF^zdcB8rdl7YDZUia0DcRmg6%EoWU^vu(>6TIP6gN_oF==K)T^77wpS+$ zSGZ-0XlN7fF&R82oj>CTdcfyed>MC%EF9$|m z`*z~k!0e{uZDr2Fktx8It@ER%qb8WOLS5S?nCXp7Scp-E&8Ux)cj~2`@$)*q{BAyM zmEm_*U;9|f`Y(hw)pb~SFA8F8uax}P3@W&ym+eyH-PHebPE-QJ`TMau3}q(H;;QSr zadVmMeq34ftCCr!@5H62DxPCb95rucZc6bJ$G^TU0$*4$IyUu6(n}x&ES2n3lnK^t z!tBcyX1{f<^ssC<#R#lZ3>vW_%ufk68J9_R%+@mAv&+*Lj zrGg$@UO0sw(LpC4r`~RIOp315h!5E_-JXlOH<^?mphs`gkq7=&Qi;Wo&?49~5q zm6y3mbI^m$CEDpun?L8$%^YC;QEat7xSOBXP*$^_uN0A^-$ZPTI;A9m6)pBuj&FTv zw~5x!I6`XbpJD={j%2&*pTz@tySFGM!Y3nZ&UdZ?Ur(&c_$G`H-lLT?hs!LlSQYSu zHM-oo`3W@>>8e$Hw@G{o*PnU|IFdp zVXY>h6XN3YvKR4L;msEN5LoS9R~XY~UB8=!8=Co)3K#|_6>QcPy|;FK2T$Pjvg}he z=YIc9x%tm!mjs-6JX@yQf?2M3&?c6_)(hIL5zTX3HEYJSd_OD%k}r#~jkE;h*^1uw zkAofNIX!u7^4vKXWqp6}Jwz=>{NYKvt*-iNC=#c5S(;YddT9-DbjB!u`xMoWm@r(RhtOx?qMJ4YUijQu(>5L#pyMZtgDVy zsv%D~PZvqml#hKb%0_ZSW39cYqFj|r!2=pIma~y+04BcLQ#Qq|93PSTL=YEc0Y9Mir+LXH;(GbT_!B2Zmn7l|72z# zM5UFxUWKTfxD_m`7KMiNXkN^1VQX_L({a0|g!}H!ia7#~Tn|)?kFa&ZMfcHaJo?ns zK2x;u4ldNkgV-+Rk!z%# z>Sp&|J9V4uM$WSUHrcerIBXtn?_|1^SrQnmlNR#&K|9Sgn4WYLv&g)3?%C9R;Y)N< zit>|C`|-;~9gdy6t!@MLZRXW4(X_iEtOAO}wXCo0JcHPzXTQ270Iyruw z#pf7SF>d>Ea9FClBopTPSLv}&AH8r{)YK;y=B#Ph_eI-1(@kG9;U;OtA&>poAy1eP zAK$#P>QV)wsrO=PCo0-kyL@v#skv$ZG-5`T_qJJFENyb8^V1VnuiI_m4DZxOn_HRh ztgnlhyT_WJ)Qfr!#g*HG*XZgX8y8>_k|10lgZT*dKaqjJ%JHj{z~&&rX31Jo{@BFi zSusWUo3Hhl)^&-uA}2dRwR$0owdC0>%ssXJj~}~jlRmW1F01>P*j>m)Ab zF*#bdsgkfe*Q)wsy%L?))yG}D?#OhPw&M8{MhEtghpg_GtUR#X&|C1!&c^b43Ct<) zn;BcJkJh*0A+JJG>)+yB4$Ufjot^vO!ZFe0^6%+(_9nH}PM6U<$A9@B1GLA(S>zL&-ksnbC_t}TxwxtMhsq~s{yeGmp?I#!64J_mTT#Cf&M- zIieonIH#_cuG}$mGOw$7eD3jFx|lB&vC1@-;^dyT9TZW%MBi8WeU7>?!@+fEXXa4f zzGa!9s+5`;*4QYFoRoLB16esjvOO0Nq;oCIW?+U5G+&CkHElmG>C?Ej@Db>@ms&_i z5DO3wW>^l642}I9`h6VYF_hTMyPOnf79RGxRbE*EsC%MW(+Ud<*0SOqTQwPdoq^wk-dAs{n|LdMlSwO^$t!Ax$!;-!| z*BbXx#bp_kcxX6h>WIah>Eg+NB>voJC{27__{zR}6(-iHlUfV^YKupM)RYro(P8`h zSpL$<0E??wZxqUyXsH=Q;$6me-vdHPAu$HBg#i72mj6sVOYH`U?%$ZK zf36iEeyqjZVM`xOYs=Fb`QgxU72g#lkxjOl1$>_v%kb~X&hHHSKZ#-fdF%T}{%$`8 zquL>X@qO24W@iBwp>x*C*c^=gaU^Wt!h@`9|S`t)A*@ z&XpU^r{YT=Mmg8STB!a+hbYQPKsQ{%%q=TPpyHf2w&{V?VqAabozv9;RYRC0-up zAP>(k7?gl@&wc{{aj>?riE>ixR5*V=_4Snvzq`BZ>FEIiizQm9GH88#pY<)@KNs{p z&yhBK6C#@2HrT@{nA7*^-J*@7q?BtBQB06bcGSDuNwmf-pg=n@M?v*=+vf#C_ zJ@^-BfK>Or-wSj73j~Pi;w)R(fd`i##`Hcvncy>%f~;<557n3zFrt#XK#ITp(yKr4k{&!3E_%aBT6g( z2@=yZM2(%kAa#!+*EAp&S5q<|h9R`*#kE?OvHk;#qmj`0eL3_a$9nQR5|&;V3{>;I zu>8uE%xdkXZkvX@w;tc}yk1k-BpAQJ9Ms!%sc3LV^x4d>T9Pe2i?>D0b z?(gze+X-dU*}fv*KeZEu+T*ET4EFaD62R*S!dtvQwV1Ry|`3d_Vu zVvE)B1c%S@PNRqd0E7yU!~)%^wf@5LWt($A#{-9h1ET*DuCPSzi;4}H1yJ$9~27+)M-09cAG!Kaf} zTi3QniSa=}MveNb6B%09R#in;`a?@XxNs@sV{5D1pm zhg|sj3~76u$a1}$_C+2BzyB$~d%s&Ste-6XwWa~}dsjVf*JwJYvGtpOs3qkjc@< z=Vy%m%jxoK)vKR`5m=tr?wH=e*Nx}`V}>(s6a7|E+!jLI8gWKB@QYNgRa=MDb zpp`~W$VC;Tw(_Y`r@7X>d&&1zTl_Bm=T9!Vhpmb6Sl4Vazb-L{XP$?np6qaxlh+qd z4uEQ(9~e0pA?fvJwvdWdbIsc-Ak5zPB3wTNaPf6Fy{aN~17S(GrJpBet(-1D%6%1s zz0hly4NoGYhVAdkni~o4sHlYXTYElnWo$bWk+te{!UvE$Z}y9_p*sPzf+RXkbg*L! z+$|99{pwn7-D$uC(9~4s9q<4E0HLL$gZE<6Ng8d+zyUeS{Y>F`r$_a{ugeJwKy&slUyr1+;`Og6Q)7U^U=%`u5yoiZY~M31NJs_0wg2W%K`qXg zd#>JBT2y#o$St($x8{ro;Oy@aWs`ICUtf&-Ba;Q5&NyG6;IfSmfH^GUqlDwT*jsr< z=kHdj7}mb7vZcBA6>s+_XlHZpu&|FKX_i32!;5YnMnep|_!b>I4nZZvdX1L(1}xY& zor$!985bF{O2{8&$Z9yMG2nmuj_cQ@sS|;IxSqlRD{=I(-QxGA{2xLASALd-ZsUR7 zztwRjCaPCHfk4aAf>}2n4>yT7hk}2`mM#bTgTYn0Z~Op+wtfQ7qcL2+eWeTl4-&`} z3i@58FPJF(;qOp#CGx?(=~PU8^A>;rAX3uC*?susJFUGd z(lo^-`*x%?r;K58vuyR4nu_Y~sBZk%>w($J$!OE;d#|Gt-&5T0`yG7OPD2Omw(?mI zzQ3~Zxad+mSze{R4#eWMe zd{B*6Hn#0IT7Am4_lcfd!32&Ne2$R`vJx_RrGDmb2T$->oxsyC#EQ< zZ)F1W@p|d=>O%@wCcO-eoV5ihRFAA z_YEJs&UygAsd@|1uBMsS&<4fK2QT@@K(IEV`a9k`&L3zo1c^52=vhl<`;3 z?ID!(+1<6D_N0w!4biv&$JKgu;i9m*S$2mokF=Z$97(hnePUL+_N`mnf=I3bC?|(I zuO$z2oK051__Vygqlf~2IMeXif$g%PfxY)K|J@wX99^gok)-!9A?`5KJG61?_s%n( zS{dwx>3^|?maI5@H0SgBjV>=F2;?G4#DSfdpRYu6?5SJnn^5O#tNZ27(9jStWT8Xq z+b<|br{}{62q^SAapdUNVZa2+rn_xO^*+Ib-?ff5fYmuG$0hbo29uso2rGP_X%b9c zQzym?E9FMmIq0zH>y7Zu{%R;arui&MSvL1;+O-C!}iZpe}4~*!w0Wv2}*B z=8FP?{zi0(qUl{Qsm%e*F~#2(pCF$vhWn!k?oV26bcCoPz~hfkA|k&;Q+=5>M=Y>q zmGv~M?Esd4G5o0O$sHA5!Cw))`SVR>`;)^fRJ6&{Dke~aF6zZS!n%Plut~G3zJ~qN z+{8b&R@lfpCvP*)6IS^(HJDPcyX`ZEw>Of%)&_T5$OG%9$#ga&;%>G5{%g_H!m$$e zO0Nz8BV7H63VAwY-intBn_mQGDrW7|?(M+`IM83@H7NBal=qKM2}QLR*-sZ45%*la z)UX(dS^S=+Bb?`kB?-0q;gDe?oV7_e zRcmqNp8U0hST2$8j5xG7ScnK6c(IHd?o6XrklQm=auF-!4Fq zytsL=ktg8a`W-YzwF#J)5fx?&TI}V|)s@I%DWidyFPW4ix*d%*0h!ry`x3-YYtmOS zbef5#8aDR2=7W|y38c2MHp?L<3!)^7DBp^k#3Xd- zcE^<(J4T9Kz`WSygX2&VD_EyghXnYaBvdwMmcIHYtxbGN-@~nD?bW7IHV##M$X$2A z=%{0cW4sIsSLFOv@!e+^4eX2VzbxUljnWG46jcZy(Z{=kLyzZyi!t)^O z4hy^0@_tcHAuQ-W=C|6g*PH0El4R~(zp$*0SLKkL6IVYR57oYi&So@QSiaO=p~Bxe zPMc|_r59~~Z1_6~V)=`iO4M649Ur|3f5TX8sZZQU

igjpiJwv z!h(Q(5JKVYP(Ipaz=J4^x~ZQr!039*xd-6gn$2b3oDIJr#J$QV;cmP!VA4(Xd44Q< zkFp(qclPJyaIUrMv2?B~PxMjL7V14A^ToQ)Gf;NnFbO6iJ7Zu+{=M`#>>i~5AMSw@ zP{Z-Z#-GRy!V_$Xc5ymeK<_YRIL@2vEn%^yn0y#9RVPJi+U~Ap{Y9#MDWT#@`E*zD zQAZE1!P_#PjtcKsFV=8bh&i^>D=BB3^~!zd+D5nwugp7MPneB4EKfJwsm~SHQXS8T z_IXtra$DWqq8Iih%*xKZHLm&wXJd@@JA&r##Hlv|hS(&Pu!96x-oD z8dsB1Hci~HyyCQT_15R2<*0YfrRvr$wClup=ZxnHvHdxwopAqbq zC|#bKQ?^!|$r<^8YakcnTqQeYeSLZP?ir5wL`@#IFEfvGCy`Ah?$_>JM}dJ=<4UXy z2hRuKn1a+mx1nL#Fjn1YD5!VV!r-RMn|>@&NH)&JIkzHoYqVE~?49Ib)wp+g+^C)y z>A4vtm&EXy%QsE-<}4((bRGu~#Cc+O`=TBPy!SklVEkCk#`w;AFlrj%-*DQl^65E5 z==|IVI7aFuTBQ1sc_o>|{wu8YI@FRYo@drnAs`c3-ZBAvV` zvk|v8JOQQ;sRDTta#f3c9onSla>OfKJSA=iCE8!iubW2#I^_; z9%fl{DuSg-nee_AX?Hl?v^qlsBqXVt_Q@h&gdsF|@qlLW)c(}@zVsVEm|Ye_nbJWu zbN%vN^90n4igI(AE;1Y{VsX#H%bp^P$#FC<1a- zJmoUb?@;bqXM=Zm)m9X#0EgNjlH5EM4I6P#Hqbu0sTm+Yqu-J1N{i5YlwY5&noQ=*cOg~b^Od5`>#Rba&hhyZaEY=jg9jGa>IJT^+9Z{`t}WdULH0_2(DX zS6zMN#|_4>PrrWjXLlMJrX&FZ`hl6R_g(jQ(3woQ{ri7?0mK*XHPQj5VKb_`Rd$GY zmK@(|u6t5~ul;AiSZ&t*o16@?yYUQn5vrZfQZAb(H_4pB*qo|!hi1IHjb$25I3lzP zk1ly&+LZ@;@PakVaUmLrEM~zoquH1guf=hMJDjfNiq4gsDY%x!HLmxPSvCY-J zs8QuHs-L?^I407)nc0ja)fG{=fYvo$JzKvDE+=pHR~$aH2RUfzjTzr{D&2EO0q5IiaZ{^s**5gg$eg?=AH-mz_Vq`{7Sn~t zYVXm0pQeu}OFd4voGTpH1|=}5-YC+zs)!~!I9GzvEand+W>ii*n$Gd%+?*fbG+G&C z58RZVD!;?bI_6@UvR$33D5=2sDO6@sxE|-n%pD4UmivBbz(?r?4+?N_u&O)vn#5E> z1OFU%~#cTWMn8^{wAfZ6>>kdp8l!!7GasUSYo;pXT?-5hiFL#SMxG{4MK9Ldhv)K)Pie;(hga+I+wzi@R-NxQ z2Ce#UGD_t9mvg&LXsQ0#av8BS<#X|p*T!<2#fo!s4C}tLlB(RUw)gC5uX#aG+aJ&p z?(Tse_cZ-#A~-gr7(IST?B_S-@>7VFG?(zZ${4gB0;!5jMx|FITU*mi^J)XnsC3vi z_U#bel8V_K^ysGPoK z4uMyB!}HdM?fk?&&45Y%o!okFb!n-u_w7m(y8+jsDccsq#I$<(&G+!DvuxznqW&WfQ zHbF(@d^b7ay_N=WCUe-@(Jv0_u%67lx^CuFV_%$&LMD3P%K6M(VA1-*EY_{<=PSC^ySkJ16Lsn4wD6s>78MBbwP-a!>-XD{qxQPjk;| zek@U&N5uI`L5A5!->mhrsMdP?NK)IKNmGw!3I&2!9czV=Q>KzG`tb1r9j5;uj%GIPw2yZ|!QR58^K)w{adhfD!8zH93>&6%p_HIkh2C0*Fx34!zIxGNQYi5I{ z%mJ)VoLYas6)g4Ky18mOmo1eR9wXVd8h{{{Sf^4B1V@#3W`LZh|e(?r{uahx&mzN@F zx^*#eekQ89Op@R!p;`jP=bmxbyN12c`)OAYupn&@KV3|T@@~T+z&hTtvXST0%;>fD zl^N+KLA;;m?CdzQHdAKL=7019dfM}0tb<>O%-FKYFyV$xFcvL?zsZuc%2fhtO%Zz2 z+=B{jOna4yZw z;#uhO^LkaZm{p^OP8*CYeY9s(eE_Z1b5{ks|)LUjeFP?jvZAAJ4q7n`c0V&-|6 zIu}C|02wlGd9x%+2d(9O4{C!$fEF?AAM+s@PIJ%I?qt3ADDs(1j5+BTq>%~B=+MNW zmV1qb>d(5K=ckSr&F_2n`wDO2Kq3X4xJCPsm$HRuaSF&^*thwHph584LF)Ar-BYli zA~xOeGhGM~!Qu|bDn2TtmiqPy7GAUaJCFQ|MTFXdPfNa2AtoUceC#bXii!;NgqKNr z`DHIJQ4|NVvK6hIwNNdo+UPkR1*txGXeSaBxrCo~S7SbZ8Dpo(%>ev8I`cDgI6Ev! z3aF;f#^jS2x&dW!KjXl5bnh%WGOQ!-PXMv@m!{vZOMDDko7J}aXc;J<`+dx(FFZSy zxj`9@8DOs0d7mCU|u0k zP4-Eg(x4c_%kDGlToPqTrL}WO5#QCPhur!EK`4t-ONA?!i-}V6)w8j03Kj!;PS5+3b!|^mB64(om~rJ(6K(72G=%DBv0QsrHapT`7P=}!$M^;lCBt?h zd{1l*h{T_n zGm%Sfx;A=_s z+AyC1EuMi>ya|2%x8{3G+t_OYt+z-ChKamoOd%!zFlkTe{m^{ z;i*W%lZngQ+F0T<3F-f!sI!PC7fi+teV-Y%GO7bxSsE5HFAxX$iOZ|BF%iUe$sF8a^J`n_dnv+ z?rQSmK7|;UH1!R-mafxx^&HJ0~Ugrha97y>C;>aL~!7b?(x z8thsKLdB|xTt}jML*K8Q*F}(3e_@F$gVRik!IUD+ZO#5a*AbSe2T!;bU!9B1wnHo0 z{bU2P}=c;lf%qCSVnJLRX zsyXJ2gohWem+}H@Ks=jPR5$3a_47X^z02j$x&QbO8!{XHt;L-pVHiW(Jz`!qi9sX) zdsa#r1rV;8f1QGjndx@KS`;@nJo|s6Bk#DNVi7)kz2IM>=MOTh+uTfl4h2jFY3Nyx zbW6<*96YHZ+);#GDYNKnqlDJjBm6KQyKUe|ab*u-2Ls9<{PJUhms5yb+J>bPpnf7%F)QzedE+`d+~N+gL#y|P3J z%BH!Hsw!2Ff5Gb551V$}9<{nQ+?JpUgiJ46d)6^9NQACgSNR*N;B?#R&n69$w@Gi{ zXKV5NQ2mU-cSHm^VssXU*it>th5_s|?9T69nN#(xc9Huk^pf7F>^obZwQy{Kh?7t# z*>NIW(xULD2U4QmSG%x?h*D@+BdfUc`zV|%ipdrmq@<~!fquBD(SLYIv5ek@HoyB( zY(SM33=h}m4BM1ak@;C}PbOA@#O6BrAnl-K;xXo@y9JvOQ4M>}x3?go8M!GFe21D& zrN`wXS#R&PY=;)WHAgIL>^Ip5GhSPqYt*=a#sl&J2^ge>>H_;nymOb*Dpd+4;`vGn~UFO zN6nX#foyHINdo(|l>^vCG34??_NroGc=)&m#}oqjZaGLQx(n40{)U!%drGA<=ODae ze#PYbQ{?S;&>*V5xZ^OsFlrqxDZ+_|WYhy*_4)ERBoGl94hoQ454Gs<4l~m#bP7L* zRgnQ}6bh6xeTciudNd$MY9)(X@YS^Gn-_V0KxjN$A^TG1i7|oxv#`vZL>2k0kL6)s zO?B^*$QvUz%@$ZZES`G+7+$b32{;}ti2<3E?qHm-R$5!A1)oqI@~!}5-rr;T^7~&e z+ov7Yw_t@DGComz6Kufdx3RH#7kEZ?kQUI;Qr!iZDiH+HP)pl=o<05%xaq%>b^}mQ z(qRtH7W=r?r8%SXYFkP(AW#o#{H0w^p#@Hjv}QPii%6^ugDfW&NuRosEPlZF!QS{k;IFXY5&C*{r))q^obQo;<_o1QeeRA-sH+FPAfLG2IRK+e1x(a@THR9z5a+t&ryV$vvW*nfG;c? zrH=7P6(HSi7GqBWl@WYV3nIeBN5p(n6Q+V*iN1C2u|V#?>{rzz>If3yz8B%7qaY;c z_WRM;5DAZlCY>LuWi^!%L^F#`5vJR!X+XVes5WjUEtYVI`VNFz#UX2*Pvi1bIN_q< zI);d)zwt%D_^}4RuMmMa7E*W0659k*nJE8DL+;~W*Oq1NfHgr>Kcc_$(DZ!(3+w}= zw6sxo34g3Pkw^oLD*%+f?CZNHp^lY|c#!?e-^RuDS5M3%34t}I&9d8{Z*WHDKsgql zyc|zALcSspztTQtbC^~bhUt>i0aA#~vI=T%$vcp6qpFR&NNI*STU8U`rRvP@{zk^B zvsFu{*|_GurNY}_ZPa`%F_O)^z@HDYUn|7$^pma6q%SFP$5LnSiBzV%Kr0^_g9Ixz z&}sT8FoO>U?b%h?=`$=;xyD^sL&>24_0c5u8kLh07Pyq*qb*Cx9auwdo38#rbjiuU z&l!2&TuB&Y7qJ^a2>K)P(;%hA2BX;{0S^>2ryK_IJI}ay186n2&Uh^>%!o@47fMUj zq79`)bRBwd3QO-t735Zgq+{614=874r=$Wwol3#WPeNjP$v_HKp@^A7blj6-3|pKE z*vx8PS}2fEDdRk*I3TbzPF>ni4&*-tZlsjXp75H+!~Aul`j1c1e}0@$0aKatRy3{K zD_FHT+d_HRFMCJ##3->awaxS>RmoSoER;O1@5yMKS8Fx#NO0?FW?0f$Vm)n%I+s@4 zZl5z+A;&Fajr)+X$hO8_)Z|%ora*yQj z*=3B_eReB$VZCllDF4%dELX({AAei|V#>oxxkF&sAa}(&Gs( z4wIEH7cmEY6ZNkjmx4kUO#YwY0-Unmgd6JO_nJEo;QI9GE_-P?W18UdhIfnGZ;+2B zoaG$1u8hKp6D3*H4l_+!z{cGos;j96e$97N+!LBXBjlJb3g(&UfJdp(D%e8Vd!1kL zkMm2Lm!*mmeQ#Abt&Y~7cxqg#nOWZbgOx!33Mo{&o%o&TQ$j9-Zl(%l=uE8Jp!hl?gtV=1~=@Mq^8UY|d`QX3yj*PSgdHg}6lVgC;EQLE+;|B`UP{ z(^GWY0u$xM(usF>&KK(keGh7UCGyFao>UCNetbE2p$Isl9`Q&EUFn}&g{U@uC^i+l zETA|y-e6X#1@A!1CEn%YHZmIjkfi{M)x!0?OZm^T|DQxS#axX&yZxzP>OHV=Ce>En zvgeiFIrI;aIW*XOo58L0CXWr&S(#B)yhigdQ?rqJemS7kR-H#Cg_R~l4_sX>hvU&m zR#(7_O_HN|7sv_YU4WHKFkytk*3_^4Bc*h6hRJEjl6yIVv*TA9Me;y`#V1>dkatpK zgJzzh08 z4p9(PO`WZb+|$J?eMOHo2^gFy*HG-%TgU3zu(RoPL8*=sDejLm0>M8>kGt_jA_kq4 z6%P`>1<_n9bto68dhN~6tBC>m2!y;X$_QHnIC7>B650}!jA;2j^pbgGck2!^A$JQ@ zB3l?3MH=Q}0*QJvPg`=w`;j_C3oFy(ve5ItGIBgZgwv zD3Jc~mHQtoVILK+qg=qNY7RFT5rc@l4 zL~865gk4uC?e0l`S-TtwgSxe5G2)R81tLl)ELc>K$q^y0Fw*domYAhg)5m1w%XQre znr;wdPgS|KZ-vtcCjK0M;0CH3s$2TP{JYu!J6fb74hnQg-{=ll3xZ-MkTk_t1kunn z_mB!Qbsb7|^QW)rcI!rlomAO=PFhKQ>9a(H@>3|yG%F6r!~`dsU2IU*jaw}*l8G9! zC$d-hVd>`YbEi&}mZ0UmYYXU3_-PHd!Uji_aA+E%_^W!+duk6fiAKX+g_hNzjcXAQ z;zB=z?J{eLh4bNwBayx!+zR7@+mzH7f;i8jUvrNu`)O;*is=%kF@;W@C#t!h{sh%!MR$hf9( z|M^Kc&6MUCu#TWM_~YG<(`||ssDz{-qBP7IGUgbDlyI$WA!+C$LywthXT`S#BuH-^ zD3+G9f1VrW5Hu?OVA(91mtL$Uz>tWVtEJNIb$p5E(!v<9+`~;w%v8cY`KyZ^s7VoW?X!xy6ch#zf!ngHaHf@{F-;Y)~@hB~4F5(Md zwKFPX@K}jz$HWKD;6dpX!?->DR9M?Mu0;#bpmI)IuTs|_JysD0*rfZGdbjLhTu^UW z^HwO`Aq>cGEQ*+9`ck%fDvp_ChJEUXBDIN;P@>O}qPgJU*-)^lb7SGRDV&Y0Xh@`r9(=m#KF&0ksu)|3iU;Y&w(G_iPZhd<+rj^g>L6m_Wt#` z5IikESYQ+zQdUuVm7MfbhuldLtZ5jfBC^Qc$rF`8rVM{8wY9V>A_s5>Dv7clTyu^; zwd$lGg$VKw6&)6X*-9Z@Pkl5B2ziIvRrn!t70`yj0 ze*Dp-?6DnnSIuAZf7YmO)E4W}Y@)%U#U&gR%`x|IBDeB(09~T&fkwxOo7~Aq4EDhT z38B+bNq*z0!uY{AWD26m!1gZi`tr=-*sd?XqI*r~?mzO)Y_7M)a&D z{%@LX;hyiBqK~m$ztGGg2MxSUVx@wQIZ|#2?b?rDC zLb3A)7c4kAxk#w=8a^b%qy}Sy490lq%<$2c4v}s@m_x?MK&V32yp~R(gZ|yUaq27% zC=>7#(_?&=X2yA2``k;eCS^DM_w;xsHM(x!}%$H+gcQVdJMVrOq!XXj18o+Ccvv^wY1 zeuIuJZXzsY9~*Jf5ehkPUb`0GZ*&V3ShE3p_1wIxjv}S(r}>kQ0)xgzjol|&JfQMR zm^i>6BvRtxHO1yPO7eyC6Kr$&2N2%jlJz;jjcjH=?(v?!U6l20Kc?nvW6sOX6Z9&MhFBm2iyD|ii8G`fLrTfz=coFMI`$wqtXKB{PF71(l zFcPZ5gWTRg;b0pa>z{~`G3ia19u%f6(D0@0jUQG+x+JJftz1uj%OK3gFgUl5gZe!< z&GM~bw{Z&!%9fb0b4dvFC7XMKn%yzqQ2lYXy5Z2kXPm3FU;Ide!x1)P(zT5AUE~%SC7?gd{@>9Ja-bZ{A0*X&1}A z1;vclEv@~gc??G&CjO!lm-pdGZ)*yXUtizJh6Q&@bx2sro(~Fy%9un!J!nz5jNi}T zqnPn*6+eJ1V(4(scbam&nRxLQIzT9-AWRWQxub5{jFSQlRUXx=rS2vXH!f}gj!`ea z(QJIGIB1~vJV$guS@O87`3B>v_xpm0NP*a%(k?*>I+@Uw(a zMSNIF*;q#d;TRuEpnZ5ahf%*X6xe7MPamj`+AMra|NJP$!ZWV0l)OJkti;?EtwGM+ zt#fzYs|4pO+_NZG>7PpD4h^Rzdk!MIjpyh^SdbXh6+5qP}kT3XM!(prvj>7cT6@G(7VCQVC&F-uv8x2WJv2%wzsl9OpQ4^xn4pd-U-tp8@( zpj-!p(PJ(K!YqDVSTSo>cZ6nt?e8$y2?+5n-GLalC+c3KF306z8n-J<-USZ>ZnI7Qei+)K=n0FgU`v05 z0HKG=|Jb*0jTN#R4eR13;nwBF!3i_$Ps^d+W*4t_nmWZAeV^4^rL!XO5!s9+xbJn*DLfvK;X;5LLE$*Z4teWawSui+ZOX= zK}jr}5W~T=+{A7YNCnN0U5Zd!##`!X!WLi%Ii!`YodOHFw;g| zNKotCKD^5fdw=Ip%bCpo!^7>ITX@FrQT&*jzn({!e+P@?#;Mc)fqbCfjL-E##E!@n z*XAD>L?D9gkPQ5vgFG$s%7V!n*m1{k9@9ao=HaJ}niaS^Py0(Usoq9)C|-6br^T395aXc*91~U|_D;!|5SQhe3Ayw9x9>v3ge@2XQ7tL?iB7fuSVDrFb74?UZekZws z^H)Z2Y08DQ`@NO>WdBOcr5*pA^#^=U-zDED0^hC32n}woEBGq;05eFl83>)O{>3>$ z{41G-A&~zM61owj{FOeI6XZ2*$GszTKSEi7_y$_fM zlzKr7rkiz9!@hR_?$FA)@g5BXMP!)qs08z*<7MG1f=kYPbxnnd zL}>o%v-Z$D*E)Oow};;KafgRvi!Sm9WBMBdBvv3Gqbqm(+e`da6P@25|sD z2t(jIcBUN)^@YE|f896MnWW};_Yj^KlZ3X-K_4pZy*9zPx-A9nWW?-Rk1JpL@({={ zel-!CW$^tKP#%L6-yUa^E-|@`1A-1DyrbK6m}=98BUw^hD!DiCt+|3Lj1!>sjpp(Zl8Nm;R4Yckullhr-;p9px+ z6g@r;xp`L^V~R&4>Dg=`y+!D%n!tOhRL&#=*}tvvoZ!&teJh{+2@@V@xbV4z8U0}o zlX{f->)rg6@2!Z2DPo&4ntk7p=!Em({MPIZOLUOq-*n(Le4`p_)b)HwT@?P$zH<}vK5sX^A7)%Hs?N{43eX)X0sPHLsf6&H!^<2*} zH2`R^&R>Oo789`-=Ey=H#muvNP)6WbI~~!dPjvXL+QxattQM#3!hbnB7nm-@7956~ zFE4Xz`=A`EI*g*?5M^6z(U#(Eh`{TfMy#fC$klA&FpEm^$tzeM@^#m-wU9FQJ>@`z zRS!%tKfu?yj_8w7 z&q*?bguScT#n}hcqezrYy?oi4Ok^{bD@S*6HfmPudOwi^(j-az=?+n$XXImC9f?+x zilcnW2uZ>t+RfoExcDxV|G^8@!8q3fp8ImxI>&3S0VyjrDlJQTEy%vK~87~+7 zrlcURMl1x*X5EE0KW;`&*yyWCG{({&q($-SXh=|3d;d-S|7->sKy$AUi)spo^pbm( zQFTtJ51D$K`P@aU+&y)l9gVJmy^ci@1h6rb(1K561OlWKxVCfmPC!8RZS?DA1&Z-= zX&nOyEk>|C`I*KIGUd2jEOpq|g-S z3GoZ;GD$AY{C>9raWw$0iF#o!rEZUhgLjOrzXw_2)~eyU>6hH2(%m=t=FQ%V&}6pG zt%)FPG7?&^RjaRSz;{+lacL`V{&@!;2LY;DrXH@|3=SlnZKyX@GG}I~2KD%?i~;Uc zhBewP6HXLlu|x?i7X}I{)WZ(~G<%nFi-u}T%Hb^q(vPwZlg;vNRIUpmGFfmij%W#J z(cE_G$NE1<<~idn8z(2-HIKE=fib@KQ1D`*;#))ENcYezg@j^4q-`pQAh%v6}I3Q}(T!n^(W9vbyt%^&M>oD|LUX42#x~T!e-x)+=MXGEos9XMS{QZ#~5Z7s3b}D)X3C4S6?A-EK8XcRgxcxcHPJeiQ`}AJZPRajO%OO7W ztJN3f1U|om>W#Azx~Urr<06|I$tn-I@CEyj_ za6ZW;hdKGSlM~rzqiWBNm&l99XN?y2E8=%olUYMACMX6;&h+8`ua=+4TuO>Oi(tw zF~xJRHm0ef(TEqubK`CVw+pu?J3xNWa~B*2Bv4}B&9X4_M6@`a*yQXKrONTeBX4lh zrjD1(GEISyfr4ajnXB>NiV-+c_rK{a#l;@OqK{X-V?vfHOImFS9we%_V5yiS;i2@0 zuzCjV)#-1G_7)AL`$+9iMsq6?bDIe<)PW1Kspa{@LXNhz81e=->&B`a?AHjujZ3Dz zr2baI4qL8TKx!$yVmzbk0hHfky-w$+;Qjo+j{qfq|(N&*b%z5^&ED@+wD*+=x| z&+4N|!tVw~{SKR5mlF8x6zGX-2b__dFY#n;;MLf-XXWpC4+1#3*Oe^St!*#}_W$k`N`fkMBt<64twu6@@pQ>(FV( zOVeDlgk+-jQOqC$4yIHLx}fzH@$#i9NKm0&nC4q$o5<6Syo=gz(egM<&~qzga5LqP zj8Orde<)vmQa}R_PrO3L-*EV%Y#UNlN84F_GqXvKA7WY%Eh9KHXkMD?R~(5s2Xriw4GKC#}DC1y2W=zBz)>U;+N;& zmbi`!Wn-PGiFm#GaRXI^i*beBmP&P^)BMus#hrfFr+er_H+lfqUw_~_AKpTa_zv=c zVZJpS7WipBXUj&_aKo@jF6Sb5I}HG0=M%L3`yZ4)_={!_zf2DtNf0k#jbMx?an3i? zhNC&PKUp>VynGMwxW~!3X~K{&sD=+z`+7MeTGW#MeR$v!$=Ph+eQK;2ziR7~&ULdh z2BgaYlvEQffAdG>e|%q}D#c4OgmBl_n<+y+C{Dy|JTqZ=h99+WJJ9Ai+!o~R5kLm? z4lV5ly_ok^y<1)>(UK|!vGtF$TSHdlaiFWO#Hn(VQoAQkJX~$IjPw8<=EWX{0WOOw zV#XQ9RmE^Po5GHd?-ek_f4&^3XiQ4^fsBb0&E|N5O}3lkm2X^4bas_%AW=_D45QRL zY(d47eMfs(L})78msMhon}|unL&&N56CCQBNwRscD>u)9BxxZ$GO=gp1D(Vp!|vN` zZWmUbrbhG^6fc%`$0CC+)ZO7o}egOJe z0ugyiG?R0DOOOfBGsSXZtX;)c0P^PSMgJ`pg+gB z%^r&uX`C@^+D!^YT6^sy5J1dbgxf{<0X5uEudc#h0X0+ic-AlX?BRashj$*{(-CNI z2jLK^zhDNQleTfq;*QoA-&4E}j z=F?HiKaf9=dd>Px>18huT9xeYM1dSq07ka&Zb*A6yqTQ$Umb&(47>hDRquVe4pXx%{r+|wU)7l)iPtcC7Z+0P>x<+-*Kyp3L+#XB zs*cps`bnVpNU`FgZ^uiKVRyZLtdHI(v^Ha=1(~D#zS4|POZouxNu*A-Exfn;LV`(% zF3tZvZCWk2e@x2IDl3fB(JytbCtWXOu;GP7m8I@5OUr;S-`4G-(--?7OKqD?aCu11 zTR1+huNt3|X0du>cBT6{LqFoDpi)&#(y!jFG^y|;?vNt(H`6hCoKG3~=zK+i7`L$% zLpzOUmB$FvH2}tCOy7m+an$l_`8Hg-na_x0s*%%X;}h#D#Cr(T4UQh@lCqGm;BM;C z;3QwStF;Js!v;;FD*u8kBjQZ?bJEd9UpgMo+Kq_O@~5ze;|*C0sa+;{XAYZ<{p8ce z9_F7hZ4FjVas&RGmozlyLWVKVzEb?gkx{2kzl}Q*L*4X+5;(h$Ev1dYf9-adKs2xC zYTjYdBu$Ta$XMInjhSTHEdlDw3(CuUtrLZoe|4E2ed2{IP7KHL&Pr+Y&*tmeQQlg8 zYF8}cjbw5M(-S-mf^E0n$ri4M36jnC8vm|D(ctuKHB&2=Zzv(RmJ=L898 z^TV2c6z4pPF-W~I6YeeJAR(F^Achnp>@ZA?yTVg|V#`$6?5gy9L- zwf@bH)r-HaQ<+}bu@aW`ef3nDRl{5GGVFlr${PC!fRO)6M#TkpkU1rzx*Aj8_6;e-wDmnDGCih}zryPJW#X(27;Hz_UCDSE$ zYZl__WOLBhd-AY9+q<{>_b1xs{)d%ggGOJZyXu!8fldJAeC=p-n=IbF1qM6;OmT-sT zr`q2A?^tX|_~xR?XtNBOlY{Pdt_;_`i(@PHBRIouEuonPYSu)H1a zrj&?Ght-B(5(LJm{YO(9#Xslo>Nz< z1wn&;lvio;UQE&VU1A|TsjZYW?N)b`*~V8aXDn1#n@VRiuEu+U*eFhEL642|u;7z2 zXrAd!WNp%smxToW*wJ6K!UJ@_c3kzLf#++R`NK4Y_9cw5*Zp&)xw+j!sq%b@i2Dp7 zFRxj3Eb=YI{O;$^i{+!Z)-~8!G=jJDrOaue|DS*2gfh-b*A)X)n<4JWjS7$+Cp{N(}B9JxqWzEwTxQRE&07Nl3b%3 z>Y{w4J3@2_x8ZUNXHFM1`cdxtJ}qXqey`GZzJUQWVU@di{`tHeYoV>7&B;^yu1FQv74Wv}iX<%v$d`UgXG@q&qxDK0KnIh&y$g70Ix207xQ~& z*3W$FN6`8l#wY`|nvH3C?UZM1H+Ei1MT^c+Iw|7;tsUvS!$;Y|C?PeGmEExc>x-Y& z-&J{ghi+eU>ldvB)GN~aL(xXDx163UzD-h7K;Oe?_4qqNeOkuF0s^Rg9GxSqG=~n7 zxF-O>s3XsF>pVP%c$Rws^|sPXG^X#q%zXM$3h_q^rVTeYSX)80-=!yQ&a>J_62p?j8}BsTc<)T)?@ z#@L6uh`I$G$efgL-up^?(`o%Tf!oAum27QUIn#~M)v)i=AET7rU$>f}1B%R_@R}gcjJanjqRg z!@p5$)&w$@u0KUuYtw#O{4|~*ts-Hg-nZaX;DbCLTY^mv9bn1Yy)4;>97z^DG&*@I zT;OL!3Fer?sx|Qm>7BkPdY{0 z=_}p8Ep_R3DD_Fkv7DK*@8yF3Aoqt%jyz>gb5?lK&*PQN4L3>cCiP2ExBu*lIq7ex zm+~__3(~^>SpA;fgHD`z^E+C`QQ2_YZe1t1T!#x4 z@4Oxu{TEv+Sd&ZQtl;!3p_sEq8a~Cvz-3d#3O+|GNZ1eUZN}~Kr)`}j zvPu|!m8&ysYE$<*MQp5z31p#kLI#l!J=;^$h$H07epS`deAnqk*#Gbi?r<450Ag3? zRkQLgAt^(fSc{8|Pkewm6t>6G4^jl4L|_o<(*^G1Vh$^ZpO{aCYvBd1 z)ytISV$C7cG=73OSbi{6=0hzhL}zzSsL_*I`t>Uo^5`kW*?g#+%vtN~#Ej3sz?PQA zETcuM2)_ZdBi>SH0ljU6CKNyZIAa_DwYUsrSFv_!UCrO68;;rP{sQOlEND26b`O94 zH@{ZI&uhL2$>pX7x%LYEU^DTpxwv3(<(--moY%#$9J1&H-lxWBkr>^UP;mnyy5>1_ zI}3u%{vrAvte1u@aaCg|j4xux#o6;BE)OsnhX54elP){4VM$)r z^aBvIR8`_kBlK_U%8729jL_VOmrBXtQjM!sDoUY=YOTty?w zq@hfKB!)2b6%y`bK-Qfi`+iew+{R*|7a9&TW#oA0Qc~-lgu8eBA^E2mSVSpM<2mLu zz)OBG8n#EBL9viT1dz^NMj7wB11S=O_hFuOBy%FOmeswIteNm|BRfQ{5PpO zQoZSsYBITC98~1sTP)4mt>dfEYq8K^Rk_CgCH$HSy_iEw&F($c0()U$K%q2C-QSvm zeKr7Kq+g&3spo9Yg1?q@M#Y>Qwa!2rbN=6(3tec2L5Y z)skAZD&iua2?cpraE@7`r{bQwU&s_L1CXJrzRmZD_Y4iC_WPSOwkw+-lA@aXGI|+= zzn}v3^05h&8e65@=5pu*FSAkcFV`tIZPv|ZWkdCTR7i1DUJ~#*R-Mxb|7ml(7FLcQ zq)bAR|L8kX$}$JaCzMNq_*Nx>=J5rn0y5EvYj`=DC@B_%;h)Jp>?H@g8c9uKsPOD< zBep_LGE5EnBrqQkVIh9XVK&b%56^hF@ba;R8k(s&QP5DGxi<^g$ z&}J6q4xx2+&|Db*~~#vjT`sf~QBK%=5(^YUo2+$Oy5z_1e|yu@Cikls*6M$0KyI zDy_5n(rtREk=Gc-zKZWg;_FUt7Rx|}l8<8{5!;{(7}?v|%-zaUug#{V>3~v>LznNh zwxm?e$f5b|cK;o<*~ACAnLI`sC!_jN+`GwE z%;Norm+sKzNQtHQFD7jcd%yZJnU<|aSWAjhs2uNhl2<|mZ~9X@9OYTN=ah%8qK175 zy!-GcrISTmYwiUj4ZFeI(o`v1qVzNOkj}m&@=L;1USV>5*LMeCULz7f=A)>pKtNSX z$q*t?#b8j-i9mMQf7Vfd+k=wsJ++Mi+{rf}LIcW|v%2Gj5u#%nC)3^t0H{--+*DWx z%wkeRUGD9PUF5ITr^ln5wtk(Y`CZQqod^4Me|JDD#(PJ^uz?qp#&EkY-Nr#AUwvNp z+wk^0a8(5Ic+A=2D9U-v8M~DM7Zj2lyVvow@ID-rGocPnms>O)T|9t)dd%9o->ecj)>1OHj;mBX&Pwi{0Hb^LWH~J?8 z!rlyOwNi}G0Q@7qnsjR`lQr!Y#qsttfe9H0(oOGBCCl^z3ty@$-i67!3s?TX_~w3sNMx`gj)a zp>Q#gd1^A-Gnta0C_bd?uf>P;2n=%QoNh(s zJ=Npl@&thF9;Z@#K;);+&+iruo)Gdl{u`d?iwGxiCry!}3#vi!Xap|0bWLs2Pw^YWyRb_OJil z@e_8KdPU|zE1MbZf1YM;u6Su5)-Fqs^!xsvXZ>N|K}Wt`0wwk?D2FZU+Xw|a>(F1N z)%Bp9=8g|a2xKX;jjwGxbL+@2C*1w3uOztu5Hg-!&O>-i+Ed^^M8eOr33rMrW?A^f z{LS`vS$_mGa$qy-3(S`%yW>3Sz`SU3dw(`S#hg>8LkDO)W3-Kh_NYX39R{5rWcAgh z(LE_V3a-=pOx^B{3g(m{cT7ajso+Hclg zJ#&GUtuCUP&uO?8{aduWMSNK66mOG>K{XX#e1=>&e#mQ4-}DqiUE_SaCn?Cq1Qy5W z>H~h>eB*_Q@KWnWPLxq@%fnQ>wji&U%!3ghog3ju(=OK}-(ZGtn)N>UmbY^$e}#K? zq1>13sM&sy@!(8oEsjE(`Ow;7r&cnnRrdXf8E~$zZCf-I`d~%JNI!cT^S;rwKMM^V z@i5x=XwCHO!v<$ZO}B}va8_K*pXeV-{-;Idj950_#1Me=&r?4s`s9sWNtA%E<3e&C zE*m0L&B#Xne`WIt3}fZ7@=Oi0ueW zX!32Wp)x*1ciq6hm$forr@-}>2h1N!+Yu}tm*s`AF6%-(IE78Z~aK= zguh25*>N`M_kq-0?sWZtpOb1L5co7A&P0ufDxgxoFRw-+2oEE&YpFIg7fckua>zR8 z0s7SpYntU@_RQ5`0m_@T!WX0vDr<3<&gChjI9%h#99+vVXm z-S$?az#@nrO5Wo{V@Bcn$M`CebE$g51Bdmq35!4g)6aHL2> zKsLcXzpGI;G5HsSM(nr7+7ja@q2rzj(QjAbm`2TYZMSK3yzpbd;sF=pu4!OA6`jkW z#2L1y*In|IKaaSPu&w6rXxu}t4hnfLob=&9htOp>mW zpX8cQ^dyhbrz4u2hQ@|jZ+JjaRa1vH9Eygoc{#CRTq2N>vgOLDEZ8|D1yNXG1Wp4W zIcob7^F4t8nT(i!xv78Gq78=>_r(}%z`0V`5RBaArYo0fx9u3F(L)QRRr`)-FYdqq zbb95oSz?GMilUEgE!B$X4dx;BaR9V)CtbBq|(#}36Vv4tNAYait zyft;trB1)avl+B{OgISyd8kDU!1SM3e+uhcGxNXmb$E`^mhtl1S#qT%YdvqWD`V?( zyoSIEaOD%C3PVnxC)inO8sxA?&9{g`FswzAJ2%l?u#{-m&Ax^076}AXugh%or6@O3 zu>hz}e7Y33O*ly(yU~e8)$%`pE;C}G%tufNcfNsHzMtkhUR=%0%p4u7`;708*rOOe z?Tv-SVPrXR&s#gshoM`&^S~Iz4y)yCS+_ZU8lBXI00KlzY#ByBFz3+{Ngz^a*+@+C z@i<;Q7csPO%R=|y+be}hty^Afx0LGf6@3WKuX2NC1LcNof_jUizKfUr;U ziG!-m&%*m)+|UF~>YD8;`*Au;Ncc6)pyPU{-G2%*%en^X@6Zj`xh0?1$pOmKSMn_h zrum~XcNAulO%*ycjqip3*dTzfg%6{HNJ^Q-cNuI}1R}|QaBmO6TU!wr%0y=j(vrEgDsX@fO}U#WJF3b z%r~m9`Nmx6=6YZohH__^{Xq$y6axx&5yXUYJhyAdg=#e!u)@vmFSf^p9&Nq6_{^2k zv9#@)3N!cn1={7kRSPq0VI-O)K95xg$&S&#vP9bq4bnlT6zUeH*vIwKWoQlQB|t0z>ZZ|c#v)^?@Y8;Ol5+7S%+7-dPDq)PhF+nS zJS};{bGFyImDqIW=d$pm&%cJ*ZL4dH-t0;RJE20Nv}uMdPFoG)eG=%UF}=^H9csqK zy|cKGnbX*?Q$_-l6|2mI_3RssZ8>Y!zhlZ~UAXsr!5!`y0#ettZ*L{(@ZeN1H$q`#V~q{!TD3#@8 zyx~L2Y^U`nrQqU2O)4gBy(7I;z9j|aJa4|_E|2p^po-=F&$CU<^78gx_r28vG~2wc zn_UmpD>K(kMBqs|xQVJDZndO#?f+n>&%t%0+AdLzU!Eupt0XFOS9&qm;UFhAkR*J5 ziIbIxtIg>{6w$q268AY?X9~r(`$;eBvy;)%?x1`ZFE&8QP= zx6A0T;_Q(#8p%ns!_eY}UDN*4ccX^+%{tuc_rz$$5%mRC)7iJ*frki({$2GZlOeW~#$OpUFCxIx+TwA+gKwmdo6h%MJ2qhRk)|PgdXgk{sBs?x7%n%rAM` zynTzKkO`8XH|tmd!3PCJl=cRNjB9A$xa-HUNR#S~JELDsNj|U~# z%6oTePUrD~cJ7DSjT&vPI~!XLMALeMW#>WCoyGdzL&|rA1$Uto2bB!d(+78*d%s5@ zfnJ%gXjOWi9*6jRrKA~`D*2Qh)soA6MXK`-k>ry(6l5J`~YCZ2D%;77JhTm3ERb2TG^oG>Z(7<%XES@=4`T(U6t7YdLbsTBArY!s35$K#T) zTwH4tv9_Yr&J}+QOR)qxyXq{6_3Zdbd{+xVx11!l#;qTo2{buPLco)cd2Qnr8eclX zBFDfY=3RPu;?fD|6iNFR+3>lKtVDHIX44xc6r=3VzvU66pv9YqQO|1V{vNkVYyk&qnQSU%0oe@PW=Y1RwF_UGaPib zFzf3_waa@4Oi~VN7Mx%Z_7FrRlj!q%J~R-1*vor!BO2{j^Db?X-uw%QOaD&ao5>oe zu}ho7XbwC=?6wi$D^EKKrNTpcv$P6o1`OF;${O*Cnw5b2_pdxTnp6f}6~BIWAp)J_ z^unEj7J;z|vzEVjk^Kxa9PG+spKDYF5|-DYJ@1*@7K8JUvAiEC9Res-2@I;(*bjNH zZ6rKP9RKF!kuPzJeR$_85r&4fGzy!yX>waY|3V@cAVtmeA#7@U+*TEPM|Q7dJ+R1H zzMLM3Q%cy@QNOvnN@UV!lCI?GUd--a@SrXhU*lYJRuTWdFK}Y28y~FL9MK2txpudT$Yy z>O##)qJ8J_AVQjm>udkQpd~%hn0>I)@W-it2jz|TT3o8y{G9Le*5;0EUuW!yS;;gVju-y z?aKw`#w>1_ZX{ir^95x>snBBS#8QN0TF>H3Nfxdl!bh)2(@3%B8ts&aPN9~ssLgR$ zPp7Xhr@D<0Z_$>s663L}%Ihye#|NSZji1yK^gEmW3e% z%|5^0n6b~#OTP=bf$`BoVh9mqV`DqJV_ojusNY~=otxuj^2%3(ZIndc<3sj^p^|8Z zqEv?IRcmdilMdcndhtzfpvn|M&v|PB2`_Yl=WFow{&EI1jiaZ9&3^op#2RnbOUrJS z&3j4xERWX#6v3;Bqm$PRCWe8sjmH-N@Lc!%e7|zZ?m+4F^XWu({H1X% zqP0SB>8y|0?|h8VCfa_W{woA#5L{yMzuIJljx@Xn7m z3I82od5cj&e3$40|1fpt8e1~OG<-PaLjZb*!r$%kpu3HC6BNOZdTXk_g|q$-+y3vv z2_(T6DR;v2nSDGakgqd@b68RCHy`EeuS;F$;f|k#X zP9W6Do;|5hp1Fz|K12ZYwtdEhK0Wpg@oM`IB5jtI#|R3yc7@B|#W-TlC*%Gvm;Nq_ z{7L(k{&zhLD|d#US%Xl$Sd3U~@r3TT;)tL3q?}jZy^VY90j$0Pn%{lKp%|Dw7rF3) zJTHeGFE+3+@TdH*rNXT93P2}>yUUNeBjnwOuPmz;k-=EZ5CD3*hJ8lieEz`sH#=)^gE^WG5^9wLE6UMr7b<+D1)=D2IxiG$n+bS{C*Ulew(-FeY- z1S`VxqoVMm?Gn)fWHLH!|59w9LpMS31K|!)5XCGq1m9<-@6Dn`makid&R1|)k@K^& zoZ%^>ZyMg~`e3$<6&nuxxlv00wc`&l!{gGtMOB;%vDPO} zE%P#&6vgtmHxp%Z2y2w;peZit^>9nK(OC9ndo}KV%jYty4CTfDbyASN1rNJe5`OfZ z-;~CB@$d5G#Mix>*;#_r@|$0>at4p8So+~;pjdzHdJ}ID-wgSfD~)5zid8NOpTkc@ zsfK~@&FDMJRe;X#pQ+b|3%`y~p=RM%c@eP~G=KkW&JYxM@+WG4HupI`9Of2?i<~zG z1!&@b!ta$$NkJj-cvM@aQTbM)ZMT^bG<_W+$LhG|?L^@nJ4HCfF4v}lg6b8`%!KOS zSN6e^UK#$6_Hjjm$AmzI3J*^6+cQRmoIxj!IK`5dYxqnE!T*<=q1u2osIavFbp2cI3)g{DLNL;MGzIN~|04y$O) z)f+_D{}81f!jimAH>ry-qBpay>25O`*uA$ef>6W23IE@RRoKGoIC|$**#F&XV6*tN z(1VC2+-i8PG1G7s-|)pY)ZpnXun&dV!#4c+J@2I!~T(ouKfp1CjqzS$LvQjpe=uvEpk>dO7C9P5TfRl%a3YA-(=+j2w6aeK?kI zjp2FHCb2WYd;j+ zjc_kf9R*o&s~v@4@u zyz;pU*XDb==JIUfzMLH-&$>-{0OOa?lU$}4fXpU!iZmwFobVz4_@A`V#p(Gg%#lrN?o|W@L`Vap#-8ytgN!J&* zI0p)k9%#NJWJ0&vyd^(b>P$@(>rPM0>78$kFRcG!AUYg6Px&3VXJ(7nxQOOt_d-XF zk1&~S-Z%C4SBTkG4GOrqEKH1l#9kyY7d2QFuft9f2 z^9irf3M2k4rxGIeTbK`3%%}h9DdVQ|Oq2cGd+bio;#U!q_ShVqRm1TFq9 zA)7{%?c5D9U$kBN87IU!Zlj%--YG85G#T5|b;T^9e}^_H&Z{T3g#L=5OtP!mwgcZD zQWTPZZP&0}!>}FKx9Wwhm8{Y8$}rSa|Ap}KRcI3Xie=CS)6-o20IC=_<)Dexfd8r7 zQJtCYz2})or6eOMtqizc{Ca#4qNPRuZTUKJgoFz8zs%|Ts+agryTwJL)4rS4D)FJ) zx=rUy8NWjS4(XN`f9^71MJ;k3uH4#w%J=~Q6d@S*o?2z<@QKPtY7XADYd-yoV)~bd z7bK3_F0riKu12>x4!gwG)BxZprsbzUNB5bm4PNZ|tK66hR!j8v>@wLl+WjM1yMsLg zYl!EQlg@Hdq8dJ?(V@m3Pc02YC}Fa37gfpIBMY zf0Ql-feLhImaSYhXJ}C|tJ3xj(-=PQ`js|%Y62TJG`#Wj=vjkhU#bJ^VVcIxn4-TO z3YIIF$NhjH(eF8_SwW`8G#M!Ieel_K^JYN;;tlQe?cK~}ozMx1kaV3=BdJiJx-L0k z#%l`=(p4j(@;-xaeYb7WZsJH_uQiioXmmWO@WRRvD(Q$gHRCI)$e>rl?+&erV zpt7_vA7xFzKuzf%1)$noac;MbP6RNZ3phT$!oue?NigZ{rTfG(i|xGx%nG744;WEP zz^`KdFD^9UgN4wfE3Bi&ifUkq#~D*Befx}j5TPO8#Zpy4=b9~CC2zv#%BI0mS5QIW zE~lNjh9V*$T>lW}T0-t^M(E8gMP?MQY4fmGY`i#FBUWzz<8z#emm2_|{A z`Nw~6>Ghxh5ri2jMiZ(6OpN_M1pEmw$oA+?#7oMF&ocEcR~C_V!Yi)E4u{BE_0#zu zQ2Oe^!e)PDj{UNvM!msv+hI7Os%gyV7sM4Gm^-=C*M8xa(ANL z1*foclm7hzez?@=h>BI1YibxMvV7y{S$@O%X1kA`)zQ9qve5mKKXYL^I4C z-+xMZTBJjPfY(Hdvi=?h3s|RoY(NT_m6{L3u2>{dOdp$%Ky7ya{+y+op6rK3>O$Oo zkO{xK`Jcjj_kRlS-iD@I6!PVc?D=0c?KS#kV;c?v9$H7Gl%~tpo-_p#5TNd3K)wS3 z{5%;unXIq$dH5zN42YyZjS@$Og2Znip>%E@8vz0kvpapM^}Xs1)Q43skW+^75pB00 z2wDlBkzIXXj|z~C)bVIbF&Z&>g2faCa>Uq~-V&%69KKK5k(sA+zMS4WtYwWexQ@l#W#2*mCrGF-M7=VE{0A9Nk zSx}eQr;}KEf-CB6FiJLZVR?&aTH}46Dj3nk-0{vi)sFuR%liumDd(}iZC-T}Y^e{W zQ)HCr+njzC3eQa9i*wk)viL$ZhWi?^>Mx@YfycTq*voQL#9CE%F_@DZ{-i2hw@oc}=XU8dIgoyL#SuUPRMzsW$d4D5F9e_Q8ZnD4Rf@=bjTiaotj zVSzAF2Zy#Wr*`!$XU@c7U8#4CkarJ$8sdw6-=E3>WZ6}h43ZU_aMfaF&O^ijoj+Tk+g*$F37AbkwFBv7OdyrP@IORkNsb)1d{BRs&Y zx|gTJ;zacSFncV*w+iM-ZOiCir%kdNV|hpJSu01D(BNy%%%cecQClvsQ<;AAN!z?% z8RDH-BkkZ$O10AO?0ENpq;9$XXy;p7nszVk}1 zO-{xI?y^z4j?)N+O@i1D>X={!FU%Y=5XL{EgM5ElIBr;`K!JX*JEBcbi2;yLq&QZ= zT^o|4!1(iPws7i6PSipMGv)*ueA(RZv%8?BtOn5ycH;$0_Ex3sU0fEBxCVI#GgRbc zUU}K%u57K_H}e&Ou>v7tpo(A3WmD3{>(bL~=&l2wuol_zjq=)_ zd`N*Fk?tBM=nbxJW$lc8i2~~%OUKz`SHttTrtvKyD6w=hgadp_M3a148X*^`TFN94 zuSi)?OQ0-QvzVTsCi!n0l$wQ+yOzgi6WSyV{KVqux@)%ud3Hau*Ioa((BJqtGxwtYQv4^%l+HMX@g;I-Lc?! zI%s*&=Zte94$2;7Ybs2RcR}#c$t1St0G4?*jOZ_z`K0zv=#+K}HW{5zz>*Krhg4gq z2b9^3A+@CQSw9Qz$={@knH2Wbv1)xs|0DeQ5AFt!4*D1XOP$Cm=8Eg1=n?<4h!l>u z)V66Ai4=&)4C#@1Cs`V0tYpFiHQ_ZbE67PKLOr<5$RzX{)Ir2e`2!!&C%Z=m?-$Np z*hEc?6$|I^ROL*hURCgwvS%;b4)x9@3_MX^@Ld?4ZA5KkJ+ zr}_XLw$t*cT&>GA*@JrL09^!YiEy36>gs_NxR(Mtuo3*8lz+k5lu(o|yNayRL>sk3gJ+=(8c(|ouKahJ(R-mgHsZLZnw z8(QOMed}vYE7x{8J+ueo#jy|@PT8bA@e#BnL_JU_9Dui&J1$aapWcM~7)Z?_o-&-@ zEpz>A8->>T<15n7OP3Suo#pb>=wjB=^VESn<|z`21*5toS=i`TQag?5cq6h42yweP zOmDxx&_rZ63(SkFvn@c)WNu*b5u}0h{wC*U=qD#uH<-E!^K1LtR_v>5v2zav4lk@~ zyN7rFnbUW;7G_=oU+v^|sy+pcoAE%L2O!f!6;{E536>Pu{WZA=Lnd(0J*M+X`T|wN z&u#(CmaU$$`~H1-rr7ccKZl+C`O6vbg21h&vL>SiW68oEAo0l(QOUezs=uFvPKQos#6f{cMT9T@#m7E#BvIx`KO{x;z8N%1isWy`jF>G$h z=#=jA?*8~_IXA9Uu3UJ8%WC0*_Xq<*-)xqRI~&gr5&CPKtWeusd^~X+p!ZuWTJtt| zo#`?B+o@{IwczX4bGM}Q#%|1ZZu2zRAhrcBu`i*QXsencJ?RIl(nhJWh8@%K%<~1M6KW?l$h&IchrzDHgVjnHnn>;Bd&1u@odCA?Y>yx3l z=-1$}3hT*bJM-GS51NxVwudw7gI0VnT_xqB$Cl$nuQK8!tEx6bbuN3YB-h`=e8rldf}M+Vz9m z=9xF4cLngwZ9eQgP46N?gA}T&x=Eq{8!kg6pf7wW-DF00d$CSH!e5CA6X|VeeXQ)T zFSSBECSk3bBkE`E_dAmMPw(!ZW2oPG|EwFq{FVV!;Y?B|aA=|yLit&-@UT(WpTk&L z=S_-^RY`k%5;;WgRb7%=O^tS7x&x8;}bjY}#uw2D}qoY|hg)2mbG z1m%leHooso(q+ggy%F1ivzFqIrk${uu#Gk8#3GaD;%{CSftrM` zf8BTnJ8$qr}N#ZCTvPN5oQ z4%7#w%r8YAVrJfmoMS+hGmuo4k~F89M&Uv<5lOk(H~aS1+UdvUmB%M5CevRt{+Q#H zmlf^xE`zdnvt|bXipEH`GU@)eW1ESg(HP$q)>zDS*zZMi== zF2Z*_Pb&Dk5lIAnF(Yltga_{dgdPy#-Q;>KMEBihhH@y!4I0hg029d z$niOvh9nf|w&q+ZC;DviiM+x%VX&t8tc~BLPzO{1un?T!w?8v32h@=dQ_{XSNb{itx0O42I%y_&+3kj8 zS0UL#n2QNlkyIx`}rsIH?5U8ffdZ-Lw-sVbGI$t2Wr73v}qc337h zSd&X5&Qq88yiI(Kh3nav9G$5FxwzW6JR~wyhT#7V=Y5b?Y-MP^OAmo5Md!Jiu=05T z;?dEvcc8JYZ4$>GVG?@NNz#Iqk>Nv8^Z30Rs|DfiUK54)#RpbVUd2I-N-Uu0kJv|F z(2oz3C?EXCQ!gqLQs1R%5NC8?oI|}k%z2aPf&CW!Z^TX(PCn+R%-2Xz1%En`AnT=U zqK(hRm3=Mm_i9w^7qDf%Tek$66yl)lAe%JHIbI8@iB;W9_n4>y-COKMaOLY*AXg`m z7Xn`)LmKSo{0jBT<^Cu{TaH_^XJ-yt-X*}# zg9AwOe=|}J$;47q5dz-uxxSw3G!xI+i0{#&A`T&f>zLEW-N}To6Iq>(eX@<R=*zBoOO)K5D7VQkh!Xn2XC>1f_-U{50h z=6^CVS{dEZKl~9;uwm=tKeg`!=451eRXPh`%PcOb&vEda+`T=aF3@JWnA)X>UisBoKMG8mZbN^+w0oowKZ&EpS7v100M0! z+kwk}Ray|#-xzHk1sjK+&h(6&Zw-V9@aadl-IuHK`30(bnsw41v&wWRBB#nj<$=WH z;cxr`&>wKxkq=z6t&Aj`Rp`Cy%(a*Kv-5+3SB@Ny*3!O<&3Aub4Crw@~|fh8i3D}DpsX2t%d3qz5>XKbuo&9N81i1 zF6un?{^HY%4Y=;Rq(Ym>>Dl*XY%&!I@CnTVU4?Z|%A+q#kB~;&UN1%Uf8hByzoM(W zoN-N_-F3{I^n{%L*orP(Q42n^*$)oU4W#eONW4~vG#9~ZCf?`%$$v4Srdm{wmf$G4 zo1s5Exsn|bqbrsKjfYBTclr9a4hQIk%67e@i{`SifUJZ^WFA)JwA1T^7n4#cNd=a{nHj;VgmbVA{?y%Z>2X#(!gq%UDbXW z`Hb_0u%xmI1e!{sy**j_GDt1C$sS`}ScdN+GP6`+Ui}pfAx{96;E}WFCqzvN1PXJ4 z45|Ks-cWy&Mzv5g`Hr+?Y}%QRUJapIQv`qhF4D%1-#5JCb0&e1wZ0SBAwfN%Tb zhIc|K)M10DH2B$w@8~FD3j77>95hUV(f+UPX?NYy_2AO0Ne_s6Rx7 z--ba>FkB5kzeK{|{(IDO$0!slHG32@0Z8lnasRuThF=krw^~X98voGTx^i{_SL#%* z^+s|S{R!yh_o`vclJ3HRx@E8neOI=nD=CwMCV=qN-$qU)&x^A)H=`saW_j3si- zrv#;k&tY2wV1)TMpvgbTLSY!NLN0w6G)j~w0ifXKM_$AMrte;&uqiv>vCY$6)pZP6y*l3aMPf*OCFh#3Ski+DEWHF#a}i&9&ZFHe*?711V6l!??&Hk(`}cF^^|igKIn3ZtzjO z1~}J*j~Lin$}P7?W>_CrO3kgL960&N>atN<{8mOVHy+PN?08(3ww(|a-{($(OS>Jc$GaS2P(x%sRH*HJHw_^0lpJq~!ldtxO~ zsgghqvA%9%K=w`8;Fcu7^6)iG@gl`1c)vjr&}WvysQx^ols>q5J`dy}VE>_mp6|jz z8T^5YXvZXl0cO=UYh0%qoDl*AZy2@8>kh`Adf?biPd9^o&f&Ql<$v9rBi#!$t_C@l zt+WDL;}UJ~QZYaAmQtj2qlCT&ff!TM2!G_-TkUXd^t@P9^7=_4FZN|7?%I%xb~CrP zoqfF+l`d7z2IVT0=sB!`n~kFJM)|}08Kt?N=315T!f7`d^$*$u`BVT-8x|b^W6v%- zJ&7l&Ab@rkwGOb| z>;QW@)OZ6$!j#CVPHT`&%6z|oq{ykyd(WwjF5m5R3Y&yxd6jnDPTH}l?zG-}=RQ{S z`2#k^ITeDhxFUSlRPA8bMD$4N({_FAVx;#9l}gc_(LuXQ((-sAy9A79(mDVJcTapl znd>Ypj!(O5kR?rP8@KH@JSM0mHic!m3XVUh6!Kb*=!ds1FyH z9;G)f!zHz|Hoczgixp*>x|;d)coMukl7IpOoO1OpUuEm$#Wncd*GhaapL{zDA&SS2 zNnq%kXAwe4h)tZ30MTyN%smj$-0VjtG%oLqJ6>?8`mCZ5w5#`TC3#&Qt-&%;G|QJ9 zQ2_~suR)-hIfb3=Cn}LexO6%9L;OV8g@XkqBIYK)o1)TvGr7yF{ZduyN>h4_^pDxr zCqUsjvS|xUrX9*?L;-fU26z84=66Z%Li89&t;yhc(IfKU1uJIuL7tz^~7YKQY8~pVLD6;UEZaugn0{o zwIiI*DLWXUrEbzUGa~^FV=^HAjOv@)z!If!LMz{4F32&wD)}8NK}Yr{QzAeJK4aSAN3U$F3rOwXtBa74+v%yn3XX2y{1!C{NInn$VO zdtBT!mUM#)9OxZv+8~{+(JV^8_;G-%h2wY!IvIeC zM9kA~TDw{&XGUgiyy2nW_J0X;33U8ZK;wnoJ+M=?)o5$gQYZvl0Dbr>tf6@M;ZVEdw(jmHwbuJ36uZeKD=y16>{@)Zr3FAi z0yo*{ws8Ni)`g4e@~uCF`pSQP#{f|Rjtq#$8YD#@uN}87{9Oh{SnAHP}aS_`Pr>v(OH?UBHj0g_@mnm z#q@Cf5P=s=Z@gF@41RGq+-80n9rOoO@)L-nNB4_%+tDBSi(-1Q>aW>9c2=%9CcQPo z1X6$qFzH}!P@1~)n?~F9en>&#;zefn@}DF&oNmtP;SM2g89>RN`i5r1(meZI9r0%j z*gq59m~x*HqBK!$Q%Z|zg?WCaq>`57R(8lCBcPibkN9{g-QNa3C&{Ju+BxEDoRqv& zTJ%@4AWhtAR`Eb<>OtC(OvUb;gb-%qD*V)w`whZ3KwD;9DR+2kxO!M#4QyG_fnZ)q z=vd4=WzYLFGNHK@t643d^uRRECiiROaq=6eENy>(vg4YcX2N)t8}_4L`_RXBcIqCV ze#CLZg%aiqoFAdo^q-a5{oDS^vPb1#ey_Uo_@k4Id6O{nKL;0hvt)_|Rl9cK-yPQ$ zj`5b9#Lw7H6nd{;$_THOsT0PaqlHWL&nGZmexm9|-Jrq0|1r37i3FKnQl?D4>n-c* zT2zG}SMD2xyJaRNHR$mRq$cN$t1xg_lZQx z^@E}N4Q{XcKG0JY*+m*l2c$lq={CDk^043(+7Qe!AANQ!Dev{QijL03a-qU!jY}5W zO;6i?Pb)JP6az5|vuk{QPcoBzv%~|JG8O)-wFGr`+_n{T>|MIOoq79)0fP`u38;+b z?qR^Id1<>>EnAVKB_5=ia|>4NkSq(Njp+-W1Xq=d^~>?nL*@RkP&ZTYVV;piFd=?D zaeeK3q=j~2Vh}3RQ<3Si3R|@?6&lw8ifM?(;wF3V^P0aZ3dgf@hf`32inWRbOMQ*L zi@aUNT_VTSNdBva)1EVUdD_(9%dOwam1IRo2`^_STnH`ipV~y)Li^%u%+}E8thi+S z{oa9^xQ3Ac)d)1-v@kyRl3+40`rs?$o9-{ZX@?rbF09ci>^bJRfHeU6ZAaPt_exO4 zy}@-ZLlO}t6O)mnV{hU1(dT>W4HgJmZ| zyYqjr0N0gQa1>}!t|ins-*JKPrQpuTzYi$Y$AP5Js;jG?C&Pf6`hPWLH$S<;?W!es z*9mjY+qQFHdc|E>H6>bm(rCw2nn})3QJ^tpvoc|PxgyBGkN$Cc{=9efp4BHAtNqMF zJ6c=bE3RSHiv=x8;c6DcLgro#|#4@E?VTkUAl)K5|| zL0T-km76=yhOU1+@M913lF6U<(ME(fHidh7;2rBT+8fof8q z43^Bl{h7J=vk;H3k|r=_iw@ca?~FDU9eF?AohHL%z^=pFZhG%d(YmgfIaHCYn6y4x zt4(@@$-0^<@55X)f|dxfHCnj(PIFAQIMfVE@A+jHuFa!8g2nlw?$+k}KeqI|tn76F zGvLaBw3L19A0A#-`-}Vz6AMz4K;~i8bRgVQ+~rE7gYzL%qI^thRpllfA*%*CQEt*% z!FC8GY?~L9`|HAe%+%XT1{VIoaW9XP-4LbX5xFo8>i6iZ7AgBt?Z0^0)dpQefM(;S?B=0ib@B0*99xcOpGdy4gUKN*?mJ+#~AAbRL5Cf%BK@bH2 zE-RPiGHGmvGyK;e?s3>=uk=$7n=o_zrLU2ZC>#YPC04FBupN9VYH2&K`T4zWWha=B zBNe=(K^L^KJGy;sE-N-(hZ{ISZ#jLIYipg4ms|N-TW*k{L8Zcf831y!>W5wplG*U0D&K%#*KhgsVJn6;|3F8$McFm%cY$@A&gVw1%_gdIH|jjxsAv zvzPh&P#JW11osBs(KTgH^(VIuoV}T)`|a9ySHpVNAP&qJePAqKke`5KLVCm2dK(w` zi;IfZIZ!~3q1C2io72+^7!+~@jGsa6ZoYWwVx4o&Uj%l><{Ccg+12wCFQcbW!tEwF z04@;+LzkkfFdXa6)lpRYJjjOn?;@$xSd*#cbob^Mm*y(0u8=Q{PQ`eo0Ap zrzO@d)Bdwx>5~f#$Wi+rl9EkxT@SgN+)6jG2GEqI-sd2}phwsK8a@|%j;r(YWHw8z zcDIbosO)czonOCsJ&;4~>QG40nvSKd^^$zUdlPRrq%@2l6{1u-~(Qq#4<_n7lHbPAutwn#_-ek8#(iBB!mqKZP` zi=a#fq{a0wY`x81Ha50B+kE|*SAz0J{CAW0$7Nf+;3zX7=?ba)1Rov`Pfz>mL`s9wmp7D0`!}{+1dM1 zZNI%pGcFjwiPxHqXMOa0efk~&ukoIc>)Lcrq{h&LzFi;0E$zhC%wvnqK{(BlA7Hot zeA3=?R=fo<@a_gV`sB+$yKVLnHJtXReK~{>ZHT{p{&F{_{1EunrYtXSTlrW*zXbE@lMYEa(Ra8{;5&5Lx>oqyYg5X@3uD_3c(!KjRUXlNV!~=4qiKo}SbB2t@>v^s<+g>iR zfunY};`P!P^sy$5yO*j{%cQWzB_A@BQ%u$>}X!GE3x> zW5S9RsG|``?TZYONhEqSJw+VzdKmA$%k_SZjCXN&P#%fH^lioUHv$n+x@2^|yNhNxZXI?SPW4R3);N$rHBmo~0TKZHCV_>4DbZ=P z2NKa1>TP$*3OPNT`_vnG+6Mnj=10=5(lgi+F#yfh79|s|T@lKLaC-VM01>;Wh#n9N zkwi32cWWdm& z{GO|&eBS9@%dH;rKCILmk1oNxz|6MY(3l&27)=FzM4!NxND`Sf4tPGoXxub$EXnZvejA?Y=~peD(-3l;Ueh;q%xo zt?|)oag7RYX=!=B>WTKGc;#Ey)t(0|%W9KE?gX};r`>dsDxg>hnPGe|;C_d{f%%px z9Av?o#AZ3u)7O^`f1ueLxFq1V&ua6qK|GnSnGDe9?@zHiW94#>@!e}5z$hq@&(f{~ zLkr2r3aP>$P=C@_b4#xI3C2;AP(R7c=hL}M>r%L#?KwT z3%2cEhqIOF@K0XLek1NW4p}{2sYWZc=Ldi`uN>>SY)}sU;&9h`vAJMQGnU5Jt?PMK z_`G9MED<7-cKRHj@Svr{HiSN26iZ`}uF1IFX6L!{YISZr{cV1^<_M5P>2dANuWz^F z{dn_s8qMqeQoCXI7v@mBZkuOglJSa!_hlk1qId+tHV^j6-k9=C{lwGb4i!YK#ewzw z2tMZgMJU2PM*u-O-%-{ts~y3?Z`zbWpa#EBt?s|*bS~zr$V|s#Fvh<=-Ve&hGw8(3 z*4sw%R=(kgB=X_BSZ=Ck_*Ak@&(FD)`MXm8L2MtvyMF0vxO%MAi>9`&Zf4K1Ext|6 zYrO|xZLBvip5oA}edW!HRbC-3X2B?38)+PQ!qjzB)c`i3YI1C@3gLSw}-- z>a==+TT`p#z;VG|=i!j&YjdpYgF^N4Pd<@eVq8xQo;yvSHoA#!JPuia2`A42(wyj$ z1>_!GLTe9E+8jEORaI3lPkjVr9@Xu=Fr0mEpex5{S2-|2j)KSPdS0=|FP1jYbo#=W%~r=*p}Vi@_u6$128YO-@%UH|vg9TI$IO}XO-(}}d zlZLJrdMxtv~uxa~DqRakEn zuFKL5=yxdruj@%q2!@E`{h#`vfX20V4`sf8T?`OtQ74kVJ6MA9T?AtD^Urgo(^JDm zwz|;JS8wIXCm!LLyppd4l`(oYe*F z1ms^DLsY&g1C(=#Z(4p{U9aL6_tjXsz_sNP!EbjY5+!*bqqCTxMSHo;j<5Cf9(2Y# z5#^2x{HB_4Xmixm&fcwFJCKDC%GI(=ulp;Ezx`XsInLCGyMNuT;I#H_3!+z4T%5e9 z|82iBh$t~c@)pF0_t(aHi45q^E?v`lZC!Rj-`76hPid*C`FOeA?wy@Y^1g=t0RAe7 z%FRxDRvvl#mZ0AS%e#Ou#U0=cy)Ey?jpD^X3MFaU_LBsJjAD2`Uh*PB&zq>kPoIu> zW#=~Hw5L$UTt8>+4~^At@3j}EzmXPESNB_$dq-@TMVL$iSggSDzh&6}?Fp&Tuvh4K zrT`HGcZHAMTIVZmQP`D`)jS{x&j`vT{Ox;uZfBk6C+M4q?rMIo1aa^)x9a0bW*0OZ z!qubWO`kOKXaaOYG{9hRua|hp9j*Ek6t2rU@y^c9ylLH!x+8~ac@@57eAXKuPp8*w z8+M`GMHhZB&KB-l=3qa}dqhM5UHkn@?HNI6Z(v+jNZRiS-7Xf}i3HRfhdrlk%8fMP zuG@#?C|004QnJ)WE3 zZJe=Yke~7U%Vrv=3(8kwJ&a)zr07gxW#*cHqx3Oth0K=OG!^BNgvb;yMhv}^R&rvb#1dqwjx ze9L{BAfN&SS?(_MyN*zHcwj+}m}Qt7z<*E;yt5Frm+52(R0=AxcK<`jQ;(XhQH zn$_B>|A$CHjtu`{k$*nyu!g^V3xs}vVu47)B1nGFc>i;81``lV+ZCF*L<8g>D_N^_ zJcEjl2Ed2}5uuCuIjJX(a)wzlA5Pu`j~)0^{1apS`|DLen)#M>W8opwt`N_c_I&P` zG5nv~uF?apz9Vk_oWkb~9+Bob1f;w)$m&0e=kHalD8@K~@s)UCzdTLN+J#7({tYp| zeEEe4&{L|4NlK)sZ(zWxO##9ECi5vdiRkEz3Z&>Eq%JU2rWAR{<`u7W8>uW4O@4v} z*GbTWNxkijr?MQq%q`15(@f+tgoGoYAe=-8^TL2b^n4AJroP3LKtnWUN1Y{->m)GH zu--8$fX`6hH1Jx;u4|>vEuVF#uq!)jt+%|%<$bxM>l+bt$&NS1JuN*oR?#DK7e{d% zjVOX2+_WHFELxNKUtG}4>)1Vs4c8f8*5pRSToarxdfg<(B?AV!sXQ?(o9mM z{r=QFE;x7z_m~2hhF4$3B_^Jggc?vji~QUxLirJFmCS|?N%cd&X1_ixp^x+6mQ;xg z50>B=yNr@^uTQjvK3Fb^2~dm{@_Tq4Dnj@wDzZl&D=P&p`NC#{p;Z~1N8tnN8}iax zR5UKSJ!<+OK~|n(i~}ZhLQ&sz5z-UXU{6vgk{C33@?6_`)_dy3Hp^FEKWsW-pv}EC z>M8bnAO%Os3qCkc0Ri#C^#8CAq5bVX6P=sAP_OvFey`nr z8%w|1K$WPu;v{-wy}XLrxKt!?mhyj^pa{S;noH&$aZU*{y}j1V-}^)@O(=~Gsx*-r zldHniz%xHlRfnfU0)~wJ$c(B9Mj*!4Guj%-=B;9?M~qe>QEYcbRd>J8@X9pML$@Ybqt@&b zRlxRYF^^Ug)}vGL6;>hic4}eiOcd^4{Q9_Lsj6AcJv6}vIr{rtXw;1|>#`AN%-`oS zhGvom2b@3XvPhSV$-ixG`f3RzXs{3ADMzy>X@Yyz$ir}}+eY^`a%LHN{n^lUp~tx4 zlG0Pfb^i)ER}6Y@hY5#1l?o4~thhZ*u!)S&HbSk2ga}wOqYIs0mZl0_yMSYU{Q)1M zDOb(EA|(>W(LJvjt!SH_Kpqg!HKwpl3KnD1oVNJ>Yd>D(mo00x$R?fgNSI2%pm7^G zsI|+23Ab*0H`K~#I$y-{;mqY1EINEFyta!d53MGmAxmhm|3rUmqFtwm2rFX_Mq5`2 z7oAdU!=#uLIVU^QRP*0POuxd$R z!gK5H$4YX+Ght-M$Xk}mRs9(rri+X?Z9VImk+ri+rlm!@EsC=lkW8D+ph-yoQNu`Q z;ht3%Q?h`*!BJ$NZowE|z)E7w2l1CA5n$XLwq+fm)VGtFU{xLb6em?XU>P<}Q-1OB zaP-0nP6M2^X2<1rFx3`L7~i6k&dNt^TprH%BQ5EDI?HuaJ{CN#0S-8>KT|K=_)Lv% zWc~-M@=SwY~kHVuDpa`ifUT9WN$Z}dDiZUHFcZXmgLQ% z-#z*R3zyP;)4-9O!{0-aME477_vR10P}CXyFpD~Y#8ilJh|F9@!%rEt5Qynqzezts z4p)&_B<=LU_YnW8eof{-VtkgYc(XW8+47wh{T!7dq(J@hI_~6Bo#Z2nuCBPFDT+wT z2Tfq+=~c{^*{ZkhHdUJvP^OSVwl-Alnekg28T|VhG;)(%-=_;1Zcj5w>R@aaOD!i= zJ9_#ZuQl4iBeJkg8q|{Y5K4X5BUEkJm+Bmxdaq_BDJRBHlU_}4sH!s?o;3WjMfq>z zdw+#=fVUM_wI+!>gwJ5W!Afq!?ShcbMnt7dJ0N4-!kcPkqcimx@+Yqw+2#wLvbtHR z95|EH-q<7?*a8ktSoI%{9akcbn#|LVwXv!o0BaitmCLF`Di@lH4)|k2?l|ZD*!G>3hT*sdWRn@Q zvcfiHvA|$k)w69eSsXMprn5#|{Ipm!w7KvDwY{>Epj}o|ubw~4zbLVC8LX8Mqf}a% zNvINLx1CS+5!S!NP9z8S1MxHb_5!+<&juklqCJa@jXw$&KXXpqbUORB`I3S0O4MNM z@0djc$a&DvF!Dld@8TLm^bXd^0}J!S#U%%cMQ}`fH>1xA5`U^hHE^V0v@P zgX0iFf`^lpYPXQH(c_ovl+|%kV$RW${uiT|!Nut7`YZC`lGt(|M?}$l)5-O(r#5*~ zopksAh+s3sV5*r|+Zm^En>cR(2IJvH&vp^eo|fRKN2!$zSu3P7Zp3eIV-r3$mJG+> z%`EZ?nur8jCRd_MYj)$OY|d8|X9Z*#4NvH7lmYb+ly)4iY_z)#(M{N^vE#USqKlPt zs?pb9C3}%(yK{>XlY*;kAo~XbT}r8K!Ogm8Y|`Vy8~&lYZiAy52bI=2)T)faA}U6V ztX5vZY@4_mV3P(Vw4#{rAt_j`;}g4;K}cfwXi<(?Qge4bqtZ^t?LV#C$}ZG$_mP|1 z`WGv7mZtxpCzp@ZqN7ErymxS-8d_pj#^~IlgzRirjx33me0t|Htq=H1|7pMRfXVSw zr0h;Aba?1-Qh%!&sKd7u+Vit%LGwxq_w%x01!qWbk3O}iw5+c}Ap$lAU_$i1vh>Je z2HUI};md{pgdNmn>1FTzWvZQ2O5PM~Rn^q!K2kKsfdQ-}`m((pW`UAj?q|2m%zmf$ z9t{;gJfJ6jRAkb%n7Pg(TWRjAaT+1J8~R1gn6I-Vog*p_whF6cBB5ChafJz6Du6@1L+q8`hYXvJF_w8%2d7-Vhqrv1W8(;>;xM+U3Q6*j z4Ei<7$7OkYOR2aK@1iBE&B9W@hy1$AJMcePfS{4M3FhSR*6p9Z!xue0r%gG0>{W>q zrf^#@#aUnyRSeZ4J7znGH-ypN&4DE-1?zk9PeTm{xtTmH{@13OxRa|-ok(bNQaa~{ z37yQE(rZDl2XNMBFk7JBVZ>H($YAA(2c=w8u8D{|L+eGoR53ryZG8u!7+?RysKj7eGGkiB$vWGL!$1nS|4x!GA&RjEwtm9Q*gQ)XJHud~T1;~&(?MO% ztTn`2FmZaOLZaf2?Dxd<96F1gO?t6PR-Qg4`RKaIL3B&L9BF|ZX$o*9Ev-&&5@BIt zVH^ibT!Jq!IQa0jFqE{2Oof!wpIGEyMX`;E zao!19};PziIQb$(VFL1&zQ9* z#o}@F1gN|X{>M8JGoq zHfazK|KGI){eBgrzeJ?Gf=U^OJyZ8p7+?4Ljb-moBQGvAG!|ZZh)O~=HL*z^wN;o9 zzs}L!Gh@3N;%hN}KK&)^0OR~21SfnYy(wd;6@m$@>Zucw7jtSSG97 zN?xQs1kouVO56)&)2#B=t||h*Rt$`W7NWYCr)QN}>8p)1nZYq1+|RJcrWgi@4p`wH zys$FsZW*`N-=ifcm1PxcHe$bJ$9q>Cm}&kh?_ES5+5l4w{wj+l)jY3@DX0jp5!PJ_ z3Ms46v9c_8+7f%+iv2&sb9@U7FMW0lGEF)wr(ScMIiq8p1~@~M-!-F)2p1Q<4(m+v zR&~OosPlf2mJBW$Qx{hp&Yxsy^`fFx!cDBJ<19?(a?bOOkBF}Kjl|o3(&VTL?^#BN zP-x7ZCD*FXa^sZv<*ZS232)ZmosEcyi0^YCDbFm4<`GbkfM?7ojY9e@W-ZA9ty$RX zxC)Cq$LTaI0NL7&REv2(qKkpu>y@^3m$Nf50(o@S`bFm>AyRVbXt`8a+Ev?(U)z=f z{-3c3CTAiYKpAy!>O?E38P(MtM3I>wLg<3Kr|4({&1fiD>s>gQd{l=Ab-LlA7GKM4 zTXW^z;T3uZbjOi{xJr#Fcvw*+DdSN#mcNbY7&Z2$;-BLm&U=Q^)oN&2w1kdq<7)>h zW&o~>h|!#71*+y*xXDf|ayRGMms}MIqv?Z4)VYhhS8>5T7}J9XI^&A8>H_tnKjMqf zF@UMEcNB$O`$IbVH_J5Ljem)2+jLvStuxz@5>YoteOCiEX8vuy_`7f;v=C)~jR*|Z2(K8(&xraXT#8Vk zRg$-ko3LzSv(GcW7(l-(Py_qTnea+W20m9|pk=3&Se=(p&6rp>dLT@R1Tu?=$Q9?7 zblYajZf?ZrI1S=m(s_5!T{bR~3TLwB*cAS6jd9@5Ttb0^jmZ@g9Bg%Wp_;dSKs6J? zJ1!4a7Ne8km^t<$J9Vff-!dL?2FHbm47jPM9S>TSts}{r`HFy}#7*lsu}41Dmt|;x z%Pi-6lmsC5u0gT^BQUiV>Lv-?^IQX_Vs_Rz%^ZBz9*E&mcJBT%>-oXKUdldXZW&U) z=+Fj|n5$(*cn9;OSEd#(Q-4X0(2ey|QWW)w7;#`?;ULMfBW>JJt9Ijp>wXt-{Gp@W z$cvDTVLvyL)fa<@D)!?pe{a-9lKl`8T%eO&S$Io5 z*~BH>=QZ+LTvWcN=YQEty9AWo?yvMU*4HH}e*|kxTF4HQOHU>Z*o?YrMLYW%ONZSV z{B(!t5*55zbH`|=H#Cg4&eS;Xoed7q8ejC6IN~qaGLu{ifBMKgV_-N?$0B(iSeeND z%Y2$nda_zXWc`b(gf4C`edUbsU6<5A?4SfrUSjs@k%1O|d`Rn|En3t_Lb5(y=G@kvXEaBR%8&JPn6qnX%%rd} z^w&sYaPiSfP!oG3ZdDL-Xj{@6hXi}7N*1phU7{GO*g0S(+9qfiTuQ4%%aQlWC`$yC z)Xrv%jSdc1|2}D0jJ3=A=~x;|mQQ79r}P_9$Tqrpccd+SVfMj|RpPZDJVo@$S)oa^@=N zls)>%lcN)9<$kwVl7a23ME+3o_3X#uqa%PP-d3t)g`*%&jE1NM!40$kpzQZ-`&Ct! zSb){eLQd>enYBiOi5P9jE@~8mIu}M2Ega^MHJ!=KG*=>ky=^m%CoS=0RYfhp^!Nr% zG3biba+Fc@$Bz=ZtckD$+;=RRd>uCxTHnSLa5!6BecX?N$KpH#k8g34qc6bqp+H^xP-_tzl+F;YZf*#$`_ARR{*Y^ z7`>#K0{_6~SA)T7^vYgLG)3d2A73LvnFU6QIAPTfW3l$H69D@Hjop;T+rK|;{zsE8 zZu5u~Aj1cU@3_XJ)`-1hsq^WH-OAZ<&|LpPpm4V#IgB58)c(y99R#?v@0%1b4SUa6Pya+=9EiyPj#jd+&elyv)6bohaZdN9y7sQ>UB9ZTP`!_}O=RO$bRe%jk()S@Goq@fISP$aSpD&co~Ql8o`HH1 zUB3@~c{(LI=O8~S1wP6^nV^+U@b-(G2CJ+>nx~D|ywpKQ!PHzht;Y>=2ZJK+SU&u5?t(@76mf= zykVh~)QeU_ZyqFjhvjA*>M?$DGLuurgeF&Fv&#PRn@pACR95ho`<+ox%7x?{gs2+C zqV1Jvb}T0P%c(kdUr@*AdT-b+IvISf4St$83zM+y?t1i zvZm}dn$%WdQbc8X*t0vh_JK+`HR6hh9ARm4_2%tvqE*IzUOTCK^>x1gu`$7w3{i;Ws|YKo5yQ|VO$tO z8!Xeif`tCFL5rYRX(U|s<;(0uH(0hmBCRdg-^D!e!(|rh0V~@t?oXn@>jvj}qL;Yv z2oA=0v!Ar;KdDycmlPNh36`u@UeUVFeMy;1`|yF)_!ol~_Pwo>dE53LuB>|7h(I)c z+z%TzQ>JzdIfjG~`55U@HZ1GSEx;GK2wgly4l24n*VT3`w{c z`HalW*T*E;v(!0!`&b9~?3}JVfMJCi^?brE*_WB0R%D_mY%RkkkGZcLw;h)AV^YB$ z_QehbFURS-}UuW4iC_lwJ}y{qg$r&>oUJBUm=)( zAIqdbpwBYK$?gD->O$SdT;~3jA^Feo#SYlE2DvD5T^iJk%y+^?gai*P*U}lw&Se+H zsfI{OJYEq0*XwaMG7#I~=r5N|{XMb3fAd-5Igs*}_SUvLnRP<8|BU#*uADtmDfeHl z9YCru0^t_RXm=L{Gmg~{{}}*qUi13zP~%=GqMNsP?|gW8O?@~*T3K#=VdAOSxIMs; zVMzN+Ltc!-#26CKh~Yp@F#i?845%+DH;*CVz1T!8Bo}^BQg%!PFw7J&GUf4BatRoE ziD;yg#R}3@M^N@u_P>Go*D*BKPsX+TCdT>xartrjeq5ahrN8sdBPz+9q8I>A777ZG zo4U}f=76#>|MRQ8&XUr3!-$Ai92Lj1gvYzSDRrA4tC2NO(U3GOzg=q*z>QuSP-0Qe zlg^2M>GG@kJv3laA0#UAdykqo``ohums^k@FV$@KGX}m7ct}^L{)@-o3j7+*i4PAE&;-K9;vh12G?gRsn#178Hbq?u;6HI~!&;Us8goj$6W{SIOP7a&gEE5N^lJ z%>cS5NJ7(|RN(;{r~L;u1^&A$0e~DM^=Bb|IUheKtC`y0;zwC(c?jzzmv|dPgiXZZ zL($CwC>IV8Dc5_tJnt4JdN_xh0;1U$#BkZNNCXtbtaKhdG`)g>PC4VxiYzA!_pUe8 zDaiio0C5_Lhfl=kw)AK1hmh~XSu!%8GC;wco9sM$M+Lzl9wj6!B~T_Bsz4GhlHf~t z{k^-oyT7e|2aOw@K$>5HY!Ij;xFo>4P@<8ynQ2~Zr{i9&IO za=uc}l}Sn5t2rL3s;Za1FDJ}GL%(<;1iyETWbl~@)@_zLxcO{vPH`LeYa*6bQN&J^We-SqGe>(4-fnXo4E^c{+D49gM<24=llG}>-d<|@_kp?X@O*>a+Ss$nqiJpK8i1H z8+G|fCRy5OL~N-5YBX;DFEIKtL(u!?UqBqM_s#F_bpTE880ngtauy-3(i(Or+A|Fn zyoU^Uv=y@349OdGIs4q{w>d!`0xql6n#mb?*?N3h zj=*Ub_#D8z3grOQ31Mzad$|EvQ{)Pw4Q9kvhb3R5K>)cs!$!)ENEh}m|Gc{L{21Ae z1JTpfl@-Ib7z3VM+xg=YEFvx-j0@sQ=O>jX=Y@7ny%wzzeI%r&+xfd)hn;~6?hgR7 z!p6s8>av$OLV9{9BPqsksCDb6bG1aRhN`g5PYkL>{bzmHg8{I0CMG7Xv=Q@~`@8ea z>FH?zb8MUkZm{A!Cg=nfprQG*x=N}VB=mlA66v zP6l~MZf6MSR|DynIIQ}`0oV|S=K(Oi{0c{2a~$*yO@&e~7KE4c5QTxKvCyD$m{ti_ zB*5W4x_U;c#$7h={6dA;NN@7&Jt~_NYI)gDy38lV=hH(2&~_sHYt%d-badY9bNAOM zsYt#Y{RY1rztwJ7<6hiK-9^T>#NMAr#<9>fk}b>vvt~9Tj?en14}Zlc?*1<8$;-=#_lvk+zwp}}rm;9U zoVEi+{7-8+*HPufFyAhRXffO`Vk(wvf$5H3zMK$vn{9`0525JQl@z7XK5oWrX(r8Z z8v$#nfzHEVF0P>j=3DNtMSIegH85@>qaiw;3$yzOt&R2ty)>{`+#|bX0KG>V&8O3D z24zk*0PYZ=3rSKd)AaV{D*YLJgMgiGHC^4ulZA%Cm%EHpCD1s^-3K7V4dr$Qh{ z>x5_{>uz#VI!?c|PhBI^5NzxT;Brre2bBPIcsseuBzRBg?)X6d6OhyvH--!5OLf2< zM7L);7tlb53a`s9SpHYbQU(}Gk(mB>_`x5@g2B8fduhkdH+qpj^bF~I3YIj@&CTuY z?c?Y}P@28BXnMz+Pj4SWz#aRlj%YS)X zhih2zI#g;X4Fy)Q_KcfTz}PJH{sPcv!SZ!(3{d;d(=og>1d3OeYj$P^=n})~J96OP zmN@AzGPcNm`Y5v(;O!c0c4t?2 zPj~vdPug}#r7LpbzhxTt{8{TsN(2la+Qjxy((G>qMq%GnfN5rUK33n}F6X|Uop&Dp z4uv-H=^!M_=K$ikIXHM}qfur$Pf~B)Hnsnxmo^dwx9Vtd1c}(>Ms@jA0#`Jnh{JJo zKdN&B2c*ViN4=sW#P#Erdq$86NioW|pHP>*hOOAJ=I&6SzNi)#7i-nq&Ub!;14oFW z#?YdQKY33t#uX`CUR>;O6M{I_ry3l3A|)XiH#de<#RuF?cPGuK2HwY<&BPH+E;jw) z!&#<&JyE{CaD5O%Q9vL%{_jK@*j(n8#~8F|fTW+|l7p_)X~ENU5BeEkm3m6HY2JVA zCiS3!X19mZ11K|p(?T0Mb*udW_t{o;UELvve7AcIh5um90KK+vLLfGD1l?g2^EzqoWiyNRI!#o1ZF_ z2;nlP%Uo#%gdVUHOT9pX)^Gjh#8s*B*bM$QKK~OUbaF2%G@x^nW9Zj!Pi1RV@R)An1Xq zCY;QPRH2~e2&tO7bwqs35O~0-bx_L;Vem3G&2kPJVf>V$NQrfueyjA`%tB)DYq4}V zs6CMEXNVLB%X=CDGB@qus@iF`9{Y*1=okdli?~o260!l}kAwJCwDW}uklExz=SFga zF%0x7{>|rCiwVG8(hr6*?{1+YrPw%cv%c1k5QH6$ehl+Y^LEp~9TLo-pc|49%g@+- zkfLr~9Bv47bDwfXq==VmP3^nkNd9HyAIod%K&!CBIP_m>D^<(FWD8%0oxFDdF)G*A&nwoGGt;@ZS|%=E(-ts? zr*eFKq@|1f^OZ`Rx^P!p_fd3#v8gVMppMNlIjcwV{lz)ryNrD8*c@i7q(x?MTz~R+xvW0+P>pv+`8V#6=W9pS-S~>@*WWvHX_;S&3mWd%Dl1J>0OQOGk z{JZ%wNbsqcozoqVP}VtayLcR@;1aDdEqe2h?bNWVxYByfYl&D7xC$s^!iN4B;O?*Pj1_SrbvJ%hpR;Q+ zLsvd+65_kz7~&)JDNQ_7-RY%raL|K`*B$m|*b!`soVJ>vXPe4W)w?zi4X-h_=rbh( zU+~OQS2D7jm|KsAa35fO`+rAWIcdJ+IIbc4wA-1nx1nQ$f3N45IurY*v0>KlsTR48 z4mHMGV(#`8aN2f;0WxzHmsl?R`?qM)Swnm%m870)laOEpA)~JXDlo%llGk;_-@xRpKJ_dhT{gBBwCZEojR;}v&VGOa9Y{e zH?_s5Bwg<;D){Lb7@lqx9l+=MpF&2`NQZ2QKzofvnNf;yu?&!DsZgO^_aQuo0Co$FcJyb{R++*6YnxTAL|!i)J15HCM`*Fc*DKaMFNl&X zM~zh#6PqasIq}Dc6Nh0^owkFKUEwu>I=H)%QetMWbnpOI(y}q`uV|G|Dixa^Q=E+0 zXn1v&eA7tE14bg_1m$S>Is1+n_fs5h5v^Gwl^wIJSR{v>AhjrEl61>}vVl1(q079E zD(^f>zKwa<_5Hv|x|99?0jV`_Oo{x51$YJ4>eqMPartg+0YOU!^q&=ag7hi{?_%%S zunWvL>m!FVaAxdBb@HpLAC_!Qqz>YRESb%GpU`P>4#LY z+*}j=g3*8uUYhdjmU;PbBq9}AZr}%E2m&JZ0h53GM(8%U+2H+Db83$*J^H||gBG`@ zgxJK-1Kv_k>4fQ#k3FRa2&*Lhmgtj(SGP{ zVJZsrzBmW|@y~1`TH)y04f3*!07jwDh`1CU%3l>jr27vjRBC^Q+b$qd9D|VY1LI8u z;n}bEPuQy|nP;89R86f)`zu>U96oQv{AisuusJ@dtG>CdX`Rmy&QS5^Ou>b26~!FA)y?xarVNdKRpp30s*R zMih;F)SpKL74qV4PO52aRrOwKQb7^`o0{Iw%zZfDbf7>a`M~$ zq-DZh+27}3pnV`s8T3R(>*)f-gK?MQzMS^(pZp+Ai}1fvW{niZ-&{HLe*u&kp=IDW*Sw*${%bE#Jz%T$yuF!W^mtg7(wtH+YTw0X6Q z_c1og?hXkG8pu(vb1^#iep&8XaSOYgdBh<7)H?Xg;AMduTteNf?UZKM>+lE1qTt-M zVKa=xp4&5xAqdr}*A-@DG`E#xYLrPZl&Il^UlR0LqkMBq=u?dQSxc^+&-%vE2H(&0 zn#7ixne#c}E!XP0D!=y~gbS@9Hpy*K4b|N5L`Bf5IJBW8}t0 zvs;Jsms~G@PoEPfdXxaaoA51xig6N@;kxv}%vK^yD$Q`X=-G6{jL7NNM_Vdtfe8>D z89ALzD;u#wrZ;N(y6K~=s18~TPe0_nwDFtl!##G=HsEIY%z5ifa3{!mL27L5!`462 z9^H%4SXege;gia-{zm-9X zi3%m4;^E#Il)-B*{-bV?eMlfF9@Kw{+^6F3E^u`lSIC;@?sMbfmP^hywu8s;$@a0L z`z=rPmi-_jms3!`cxYy>YeAnXECDRYGBKrYv4sTMX;Pa~i>$;bvmwI|9u$vi?*7ZS zJA>>kw|O4Rk<0|^h)h!1;WDGDJltxXHU|IUFyq{o4kz=_%sVN+M~5YGD?LqbQJ-}J zZFm!xF`jgOb&)?wn7{{)CYF%`Gg@`TJe$*TqpG zGkB}e#8(ZYQYmr?zl=eKns7x_Rpa_MC-x=2*r1u+!Mr?ADabDQkF7ljr-5sI8;e?F-eG`z#na7hLJ+>ma73OoTcFaBp zLiWh<3AQuO*3K9PDA{`LVYT4z+bEG-4Bg6B4G=@UrLRphU6H7 zC`3@)WnwHjs_UH^9X!;>IQPb8;I^UcSOVBM9X&OfA`RqSr!sa?ppJa(g(i9~^~O{m6b@a+sxx5L#OTSg(pSFx)#Z;=Ech>dLczNofYeckh}q5b)I74mXB zVTUTdV=P%8n|$h9afvFHvjqJ_#w-4E2JxMFB88ma?{S&W={=d;MN#sa-R#wW2UL#2 zs@nttG;v!6UZ?lC3jN#eHW2UMT%YD3W&RQd>%N@z;&T6OlE_h#0MP|6zsIvL5T9B+ zjh?Wy_>SDbn!X(-lt~|suQPweSXcXQS!E%;nm-K$f=_&+5z;zxlGT#3aZ-1U!%Tie zEK%Upd&w{8)y<9Ag8TC%Kxu1_`c|ij^aq*(WQxR$E=yHun^*bzrZZMjl5cT_L3XA3 zogeRu`wy61JUd{KfDn0Lsljr%+jV{wqW}8 zW$Ne!RD1TNKlw)7rS0E>)@QcF2L=1AySq^tM+Dg?k#Ql-D7-Ttn&*t8f4C)0q+Boz z$tO}fJD*0hQu)vJ@kd91vX#=Z*d*K(Wm$A_szC2y^-h7p3hIPO17j@ft7YLVmSenn z7aX~RTqCDmb0NawF4Tj`QGKCmgF?w!!qi>G>Z?Ujnjnysz16--5llb7k+{I*7Ltga zUYw23UsF%MB-PlnH(!W>WkwPxw*a&j1^MjquX^60Us`g9h~`A%#k}xIzKpM|_}v`M zPuL-e@5B(p&&AdK{i^^jNM?0T6h$`(d7fBgX^O%pG4^gA$1up6M6<>ke19*lqJ`9a zGp$)2F_*lJ$oj-ajCl#P(t%$0X`%#PRf0j#xP}vDi$4wJY|P`(s$;*wHf>t{ALhKUo>83cb{y& z-vNyn9TJ*$>(X2otErHUT`^^2tkU?17vQ1j*#t>^P&{YE0BN*azP~;(h&n3zG>Tp3 z`x94U%3{0l%KZlmfxX`r@l2It)w<%=f|S77*Tt#xo`YNtzr^je#hY&xr}Unkc=mC# z$BBp0n~l5^<--R%AvKM49<3Q0IbJEWN33p>+m?s=eVZ-=C>E(^=JrwzY=c-688jw0 ze0Ys2RA$N)@|YrewsVIOweHWvVT+8-cyt^Ok7PqS2a>Wx+c)1HWy47jEr?pGoKHRS zaz5BrrCwj=lgfjup!tGC!6_6=k2MObd6&CmG4>`jpjSUf*uBT{LEI@{Uk_`rQ9MU! z`01W`Ys{Y@t14f}?m_J3%c5NawY7OP@csDnE`8Oa>ZYBZKs=%L=X=z+Tnn2}SF1(x7ZehagW3%Y2(^(j_tZ`uDGs$n z`GwAV3d3|5Au!U_Zv%{$(}m;H^OKn8z#SarNbA2R)`J^QPmlURMdG0bhu!Q%1A6rn ze@1p2IXJydvIr#d!t&Ln0!6f9O+r_d{dflLe(2~V+wW4dgL*#CjYX%FXh_=lbRluR z;Voa27vVRo@S7+6AvQ+Koanl>Yq_yJ0@7L*VC>j)CGc6JBw3M{BUV0!dC5 zSyjfZIs&Vxv)ueFhH;;SQ@r{YKhXjo2fxu%=UQIz%9;IvUkc0G6^5GeUMWO^gRCnD z>&zd+@8oYuCmozqTDHiH<^>UNP@`nuX99m!~qN zN&1_eBE`xkuxLq#$BRPk#qew1IQb?>w3ddK6V6fw!#=Oyf6CD)eXHFoHQd^O0BoyH zC(vtdjV;V8yXpYTv%!F8_B9; zkQ)KSKEAcodp+9PfPsvR47uwU2FWF}d@#H5&08h{o?4fs>Iwgb2V4iRPriNoXfc}K zhLSgcyNvZ!+C`UdJJCcXr1z|1)A_MwZe^d-X^I<9g=RBFL9&!JQ%yRyi=Ts9F58;h ztkP$S@P(_Hfxn0=^aEsjd|B^6jhrS7cpu%Tt?rqQKd$C?~U?NU@3Hq z@zq#dSA1NNBXpC~f+EAckLJ+Php)Y=KFgavGy&1B@lK<|pE8`nLj{-%anmRg1uZnr z67$$Fd&N%C@Ha{JbXXO+UY5Y7-r=KS^QGC#ycn6Uz7}msmat^}4tl_>Ac!rgcF1QkX zy=iAfH$vpS0Nv^H{FU_It4}#gPD`Aw)_O~*+hZA<8EiT(O+$e2*Q5DQ@Rs|47eWP1 zhF?|3#28TuW0lFL%4Mmd_|S1wLBwT!`*TG~G+2XWP}fL=k1QGH4#)Mu!MMTkydsr$ zOdE@!fRu#8yU$rU4grljcYaYPk>-voZM~k4p=*NLy`;PP)SkDnfuMJ=cbb~}f-fbT zl*%f%ku>2b;vaK{pDWE)pK{`#9WuH;Ug;@efZb}0DWE}G_CGT{lc@7MofEZ4Oy7e& zW8S^@GnjKk_#HjPHX7G+d>%Shtli-~N&Ev8l=`@hM)HPhUhS;u7l=Zs|FU1dJWk;B zJObuND5Q16Hl}FHL*3vaN(0)#z`q|MLy_TKIdVN3dlk6~-F`#l-(O8vSh-r??my0W zYJLC1FN7xVlrPrBzlsPFiCk&A)LfVc`WjyVY0kEmL#C-9?3eg0Ro&<0|QLq7n`FSA~$0n;Qt;aw1YpyIZ8v z0lq{IQkcSrry*ttUlU`_t9Tpm5AeBej5asBaJ0{vKXE9&Qy+~3{H4E%t(52tqae|Z zY^3W*mB(yKhotB44F!TpjL87CoQa8Ysj zz_mxN%#YGob0cmGD0G8j*Mzp=0wOX1H6<=8zP7Rk^=#U|2f?^!kb*XN?0IOt@my0o zFS>-_{K2i;PSY!T89u^`cU`U;5Lb5#5qmFx$&5J<-ss}LlWcp`TwLYkJjQ@8^UN{H zR6i7Bqh~ut*l(!{=O{GX*NT-oS+VcLgk}QmtBh`DGDfFc;2lgy1i(r&n zJoQbWWw>VCs=sqD3x!iU0tnjm1cb)3eJ%^kb5oAXD;e1LXHViHTlY0EApX_tb_HQ3 z4HK<~F<-W$Ny$-Oy{K9D&Q6x_XJTxugJ^1;m%>h=szDgn7HE)^>U%Wb>{<@}L{zq0 zYx64?C*vK$nt0HA68A=qf*G;epaK)C`r8bmJ001u3KFnYi%IP z=sO=J&cH(0#>r!kgTwBAm4WE19w7ud$%^(?ItG|$3fYnhAC_20coD#dwU+f~SUDLR z=TTh4&!INwE(nCuT!Brg2e-`?>M^++YF++FVVW3si!Uya8{QaWlSaA?yck{cmFeX` zK4}UsK<`hPOR$sMPT~->$p4h}6yC}^Fy($1G{a&DAK>8`L*u2uc_oz%v{g8nDqsn~ zI`e?paP|HK!h0rr&hA#hP!6@9l;I#e1>PPppr1WHL}76Q9fT0f28nn<6z5r6$0eW&$_ zp{Y`9BTu<;`m=`@JJ!`Hr)fBZgr%(Wc@Lky^KBqh>jy4qnYH}p`x(=Uj7~tu|b z1=;Kpr2o;JWd!!a&0@0aCf1-I&@-Gkhe0b1fiM|1NxPS1 z=uBtGhJ9|*Gzb~@%G&JjS2Udw6>pD}{y6A^XJ&>g$w{8+&2t$rV-;Ioq%@q&Ns3~i z@^NmB_?fdUpc(O_3~*6JuGHoQ44^;b;PUpXFk=x!Rg0qq?p!<-{a$%j7uS&{UhfP8 zQuAV}DpmeXL@kX$$b`g5v>mY2@iI7T(G{byX55_|dLC~(U`R!;yD~{V%a`UQP_;48 zrM~C^Et10_WTg?(ZXT63GniX(W}mrTC)5eOc=tptYdRqgZv0}GZ)-g)P{XkPj#|Gy zuRH*T=I?xr6Z+eg%A(LiBQ-kMzlvMhre^e(x{vW?yFVyaG)Fv7!$BQRi3!9Qo0Yo; z|Fe$#dpTiC3?<47XPZ$HGOEkCNL@uj+hF$h3BIkIZ`9)cgdd?KyJq4(&99)y4i&&t z{zbFAsRplmTd1(E{fP4Ylev9o)+HmVbpiqz2l(E7@R<5da)NFh`z&ECA1w5M&7vC5 zCcXlG=}gi7MT2fS>f)2w8u#J!cJLA0^@4Xo)o_nZzW!a$;Y-JQ6CM{4u0592mF^fi{-!FCK5n0trO1>4vd)Mc`nvi9#yxm zHBRoC^rz`&1x2*fqKHP-`(a96g2 zvR}Z#L546rw-@04=lRq*8-J^;bG0y9$F*wiw*^+3R@2(fo@iUSjJiY4Ly=2koA{F( z!bAK*XM=4C2ipY&L(RN)l)Li=TVPyIWehzV74sI0Dux-GcqA$BH3kQWJ{Z^#q3SeU zwh2GtC>l>mvXU{p$r~_m(E{2sPw+5LY7xF*<&gN1G${YV5{b;Q^k;(nm{vsduuvb= zPIF}C-lVRwMCBlIZybe(3HZusyO>mZK*uo*PWrcIy`JJ7-Xw)zH;Ix$se#p#Zq1Zr z*#Up5dz{v~C7YwouM53lusRKwVnf)TUdaB?^)3I9+EpQ=yT7h#=HKe1x`S!&C?+7~b!W@={Ui*IE%s!K2-}cYqwniR;8@fW<18KZ zD}#U^Ac#3D#Qap^7cMS|fLiw9b}qWb+^vH2P_?Kg`^VF-kzU$iCe*unYVXjbOnbWC zlvFbgh2O2hgTBYrZ^VJ{mfd8b_$ZM$xedQf8DNm@#fi`_@en6<#b18^ftIawfP0M` zfm`Ml_uOie*gunKNFjFCv~nhKhuLQ-$A4T;?KO7>PQW=%>otH5_1irWr3TI9uO{&C zg+H!K+~9u3-A%@LXbq8V1z{Zsn1oru=m_Z*rrP$SKU$Vwr-v#92=HBe8GBCbqyFrGo9ROR-CACfo@F7ZW*m9KUgSGh>{~EL5C0VeN;RAR z`PB7AU$qDAq)V$93p6MG=s|5`pgoNE{-ff3X(maC$=|+Xltn)IG12ZcZ`%LumHhL} z2l2iJOA`sx{0+{aej?R8_MS17nxfgnqX7l0Q(1x~FJ)Hj-+3H^ogeU8Olm!uPQzNk zeUF?niGg2@60DEEC4T*6-)@nm3=2A-KEAP1_gO0;F|FulMXo{H*zWyHwJP>DWhM z`GfSWLN+DlEMxG8A^e9%mFqWgwpHG5khdv4WAK3+$|M?Lfx0W{qE0@lt|)kSQzsoO z+ISl}D*PPMHf=H-=>s8k1ET7E`03;c&UqF`(!2=F`<$Y&d|%AWmakXj=d{cMU+7EX z-|Z0Yl(f%5muLhER;IEqlGf|dEHG7( z)Ix1XT1CfcT6W3K%>QlOxr0Cd^1HCZq(a_Z6^ru~W0&xidS1m6PcANtm{F>A)I%t(P-~<7^OLQQKqMx< z?FWMD(cmg@IiI}V6ig%X5he7Y>J!gNagh11=cxvH@-Mxt!@V)SkQ&pFr~7Me|Hq8e z$eLqtvzvXp&puf|PztJ$v6pRannV|i?0;AQ_O~9ZK1o%2Fv&rWOwCS3OYwXTKR=Lr zazRAfi{Oldoc1&+x;HC^ZPMw^Y}q$R>0kc@^ws2<2&d6I#jS#26- z0we4g5G$|%^=-%C`CX4&au*4IEqIt8^A4`-PuIRMmj!zcqY$gyi?s|eQQ3iym_jSR zc_Ce#W^viA-sC=c-nPA2eO$S<*V7-{E`zj`A$JHvE`=c%N$o9;*vfsda41B@Wo58m zR()>;FNfLlmebFnkmIEO_1f@Xi}L2Tu-h-PFOohmta4YgGk4{DU#1 zV|T@pVr(Z%KG~(eHj48T(}ML-s?Xy0fwwk?f4EB{hPfAnA%}HikcE@l$exH7*QKsKc#YzNSs!DjkG#Rf%VOd zW!#PeOGZr0Kf^FSSUXvM+^TQ+B+U=)&5A@I(y2WSo@=!RFN)?~{`?^_iaUHCO`Y@K z&B`g@mq;vy(BEK|UAxX?Vi8^Kp(ATjzT7<*yiSSjLUP!Zk~PC&7Nk2HS?j?V7zfdB zz$U>Qb^1?w>m8PXX7!}%DLBw@1&ZH6?bQh5OiDS!IXL)|*~;;kRt5bPx=4bqtEZua zqAWZ71-9Atv;~1r6jY8p1wydd=BdJ8sxeN1bd%9NgiV@6{LR^xRkQEsb{VWz^q|ky z_S5axZ4AIvMndIFQlk0!4vc`Cl998HZH`m{SCZKh^tZC6_w6@%yiB}4%ZO1ftYLz6 zoMo7&$B~DmkY-=D4`av76BG9dzy-clVd04hoZkF2D#M}lUk0<1?<1$K-~L=N?Y3Hzvl`29suoTx69Qo5bJrY*c4V1=-FeQ>lk8WK%izcse1D;WXFDQA>_xc=RVun%9g9T*>}z5O4nwWO9@8$^VdJ)*9` z`$N?^tu$8$COdU#*%vbv2*~wu+43dzfkX~@Uu3f6$BYI213|1vZ?Z@94-Zv^w#v)M zL1_JEh1Z%tJ$j72R`4kTzRK%a&R<=$Jp*l2TdN!%6I-zHt>1#+)r1}NOp>TsZvq+B z)k!nwUWB{&hcKN{G<-dB54thcL!9IG%{hVHQBfs;rw9{^95~(*=|25E z1HzeH-hMNwW%Um`FMrc#9xgJ*OfB}!%$OGi;(uqS`y|~pBz`hEi*2x>~-8W7bfUEX;}u!0NcdNzK1Mw5UQd8TO=g$Wp>rg|N8{vwq*ap-4+7ItNmbvQz(2UQ&gJ(h0;OWY)G~&? z(Hoqo1;bBPyF_WNjxqE+JV^vq6RvAP>V^00<}Vy>7sQxU5E{Q7UqrdXaQabHW{lFg zyEfOuIPG*dK%VmHF8$x7g+nvA$SDu2o&-@G9H^Hbp5_55x-0^J_(ONtP`{Q5dtvB& z!Ccm9#2LX>f;P;VUjyn{K#;6lRn;ZFu|`)aX2-Q2_pe38D5j;?yF7z_j=XF3V{ufu zEo$)lp;)n3x<|zS&o~O1Y~&rm6{POx=*6`T{hC`UeyRPxa;lF=$Dww)@d)Y_4{q0E7rq%8c^Hq@U zzW!bLr~L|#K`XW8wbiVm8BXRi(hc&-Psuf>>z(EPG^;v=PWw|(AWZ>ZvhQ&Z1P$+4 ztad2j1F(uq4=)e*HxI=@pHFvH9uX%AXckYAWCFg9`1Jbrxqgu~u#cXvC8Ku#^l=~u zl{w3^J6{D9s|3!=H-HYHmDZDZo8&Sp27WrG^94Ts>@*vmR+?o6CW?xZH{-t?kwGbP zSh}nM1Cz@eDPf>^#Ju6^QH8LE-{+Y1-tHUZU!VMIY&PA?_3AdYvO|vZ7{}*uECn{{ z7FC-zC?Cu9>`o6c{O6mFM$BGF`ig%@iLT6KH@x^RjvCufeRxa^;&x&W2_I7GoPFnW z@XJObw!|HiIen*lBo5lO=#7;6ZQIwF3cEKTbCjeBNCqJypsMz~cvQAmWFNkA&F=K> z2tZZ9KMh@Q0^c6e%vyM`TF8mKs2;#<{f5053@ za{R@Z^mST1p3BPHr^B_FYol+Nu|$?Jc6IdAP9(RmuCNK`)V&<~3hH2Dn6GOZi^o9T z5Ipm^*&$ypod3d}ZU(6^gYZ*6CnP{mGynGTLS0?(y}%91rh)PGDJU~ljJ_VXSKU~{ zq(dk#i_vwPxvJF&?wO%-u!(CZ%ym(e=*(HgGILQd|CNX>JyW&|FZ#3?EuvswYXCsuKHgFz} zlabYEv0ZhT5W{~!dOw3}A*{3Hdw`}(D3}nHDbsA%Yu}$kG?LwJ`v1_29=BD~>k0EAYsbXogRR-f{dOuUs?~k4-hc4#t`_%3 z6hK;d<FSDQc$V&^{{mks8}22qvx6(WzSpIBju5Lh4fPM2g>jK#L! z)Pe%SjHE*E4m{CYFI~B38n@j~^I@0bUrr$-2h2eiWnaO90`JR%n3Bqvmo`65PA(NV zbE@KD2<&<_e?`R*`C{k2l4yXY1uk#-Ibph!JcXGcN3+JSY;dj|05XI^soCP7 zdx_V~C#0jDbFmLgKLic994WPbTU^R_PMVF+#k0?Aef-6;Mr`k%2n_A<;~fnzPV_Qc zYYe!kO4zHT_6JgFkHo&~e8s)XL($9&ok=ym9K6GnbjIw){VVWf^BjFC0QJkew1u_d zeYM!+)^7o3NIae~VcTfI4Xm)Du9M{}mH1)7q(S;oOi&4BpG%N%3EqsU zE|{TRXT>phl2JQ0A+^{P{|8s6d!O=on`XS&DpU<^^lpRLkFTHr^q8`t6%UGzQI6kt z*h%@u=m>hhTs4R;BQT^)?)#$jf~VNbOzDrEHG|s#6G8KDg7q+*RNw0QV}>=C(2w7l z7~f{7ZdpTWgrwewarP$KArjW#x`d#w8k(`po1!vtO;j2Oec)uxyk|lewksAit|-QR z??pf3NVcRPOW~^%SP`>b&ak74@7jl9(xhjV_b4R}Rs@N@gu9xXef54^f;#O)1E!$^ zt2AOGt%hzX#Y~nPdD>fVVi^Jrz*9`-26BW_p)K zy}p|7DwJCE4)NVT(n>F3fz+4Ze7jnJWzZ0Ae+57DmoD6I&D?4>x3+f58g#3(7*J)5 z`TD(p6olF+Z^;9=?IWdAENAngh*E# zS?00>|#{q#~m99%i=38^0c?Va1A{#8rW z7Ns7hNM|sHL@)P%CMBtTYac6*5rnpSnh`~K(Zo;{+in}8s?nv!i}Dghk~(v+dr>;; zSop?|40h0MF4HSp_hTi#?oC>1#@((iE6>zE9hud4W_8s>M%ZATg=uQlN+yFYr04P4|{qK+<#-NqtI=snI^X{OOA!;i+op%lB9%Xu}S1n zIV?y2bx^&4ZNUz8v|A_&JoIF*oM!Ah z=DAh`ow~-Z*r$N3Iy;1-_Z!-lFoQ_nEF?nEgLSH;}YBizVu(^^vV% za3$>OT<))B9FoOk2uXibr*tWE`R=*BbqtsEHuP4g z=7d(mZX;I!|KcI!;v`6Vd)nA00UXGyNYOk=s(y}qMghuG%<7{Y%>Rg!X_(e_ipj?3 zFC%ig3`7_Toe4@`puZ>;%pEexc9vTTKb>E%kr}oEuXTAy7EZHFGeN1aGR@7f2aR zF92kU1t>en*ZSaWMEH5oOx^@qRqCQ(koQ@tBMb%GVVqpZ4{;A0OVGF=|@v6$|?iW0`pH>!5&yA6GbH zUS76XIwMgzy>8q50-sFz27cm!tBu|W6u{j_E$dP3<2Z?R>_%z9T=MfZ zD_N&?Wp?N=Zo*@v(T@`jWLpUbS(i!(H$U4TNK`@Qe_R0*`C;hHrpoG$uU z6~3SCI}4^IUW>ha;5&nIU4H;bY}KL|AF!7HabLDr7U%crG(?jIcK5e+R3$O%m?>Jc zGZ3PIx$ZwIeO$c9PUYpaOP)&KR#*tidK>rVt;}ur)Aly_KKn{9QzS-gHu@h_IxXMY zvtAMT{cTlpI;=Hwmg2CMYm(4$w0+ydpOQfw%hOBT!)@`|2a)9uFVvmy-Ap=u$o=CN6Xvz2e%NP4lOjvJa-YWfExCYEW5C_D zC;I=qh-vTp0>6{X1R~F~%M}YyNOBp+o-Ign=qv2AnaW!0h^{3>Gh=$bw|D8~tCa;6v@yKRU+=V^LII8NK zT6)%m>}|f7>$^{^_eM>&r*?CDp%Xt9Cep|r4UcjGOf1h>U8!gc+T#1!cI%UEWzK^Ey_cN82lGOU0k5uMPmNC(RC*MJ7qvC4}Rlka+ATa;-$LgP35wW1K z!=LDs7p}KwXIz2|lA}1pICC9Tv4a%R4&7^#<8UX?qDW7(G>vgHQ0QFa==xN=rk>Iq z9Sp0k!cDgk&*T10ay64UxJ?3i;(QGPL9|N|KqcGIKGEuJUrLFrOwQyEY&qk}o=bn1 zGylo>m_?pyDJWH^vEs|<{mg00RQqKf#vMmK;EnAO#rv=C3`ltbN&i(_reEKOGCh3H zYVaXP)xQn*Xy~5Hej*(8Svx4MR*ZDgj_7ttCnfv2R$Z8y)u0KzxeKG5$7W7eDjXZ1 z9Mv_H>M|$`Zw|Vbh>fq*IQfgPi+5H)a>$!{*J=i`Inrh9&M&lb7++yGX!@c$XtC=b&0+B@V_Z;oi) z!@s&M&(8KidXdHy?QYkCeQqa)GY~_E39RQiH*ZMAzR31&*|(3uZxNn2lq{V6DpsJE z=+fnt4)ta_t?fdTXTK@*L7~6*%MZ9-!4RKpAdUPv+AA~kzosgeppqpgL)Pq@vzaC#aKVRc}KTg4+3RulTYV)3nWPFwc;9%uenPSB!^cTts$hL{i>ax_ROktIRXP43lKD{ow7X@4{kNqtrF9=> zw+6|+xt@}_&}CnL@)w6qX3DXCSdFJevbQ#0W??;+7|bVl2TP9Te@&@!um{HHjt{ zm?Xp|n{6S&xFNAbp+SD%t! z>z={N^{|Mt#Xc7RhY4BAYqQ#jv8LE+gQ<~xJGQZFj(3XVdNLTWmjcjs_u4NI&eq{cca(hl~HV8|XMFzz$@o33_-nP&azf4y7N~V8) z2THS?ER_CkhY`O-UmFklk6AHk4`;9T_f7Zg@enD#!vs0t3TSZp!63t0iab`RaWaXv zc3PKVQf>75OC%aKnCQ!4lxD!S;(mS(pb{M?b5)9K{{|2)!}Pr0^FoghTVHaJVWu zu`ZM+>+$Nmq0n$;G|<_{dq);CcpD+_nt4L1YAZ#kMXwa7Zp!eBUD88@@MtO~9T8vZ zbon9kY`vUGAf=?7-1Yhch86DLxzUlMfq3iC2?JCQbm%0=MzgAd|Q2bRvR#54u_D z!F6+E=b!kxmtu9|a<9JJBX+%*LBDkVMLFlj(q6)Nsb?L9jo@#T@MNAph|l4Gg}_Of z72ZkAxwJp=e`I`VSt5qZu4%8021$)`nj;^4^(eHcn@|LOj89>18|AWiOhgaPVcIyB zu^)#m_s2ev65$N^GMAI27-<>^Wxlc0=&YY?Mfe8npzne5T=}e(gy7kX^Ek~;b)lv} zBetXZPaKnX1H8BJy?Q0LZ~@`6Sv-q$p=2T>5`N3ZF7$o{OP=fRh0wJh2GM{ZT|5zx z4-Eub{soH&cmhjD2{C|li}W=r3}jXyS-0EU+Z(GaKB`q&gQaq_w^$j42mWzXu>EN% zi;2&DKlr(3`Ofy$%C@~z7A=_e)_I0N2=izcdo_s{E7-NuyKF{z4kVTF2n$0tJ94(} zsQYkiq{=<|FFN?VCFs>J3kr~4HjKy)gaKi^*1bmjeArs;_zcSuW+p2^3}}l}`-vQA zHH;f3Cc9{{QX;<`M5sIU9m;lH)AhdYZ>W&F@r?a-4pWfF z`T$pb(y^ouDBv>&>yeh{B})*g#d8cgV0^#7lJ|E8b(z#0U~W%3#~6>uzyJ$ zM@87;lCe@!`H>-6d=RgaS1@X$3x7)UTa zh!?#~4zBam5B|PJgOL3vM(}6Uv+1m!W|7?}S#DZapbYfpmUOZW%8U+DnQqDdNA8_z3DIf4O4CNpWC@KW5!(#->^t@p zmoCB4ScV9@fN*E(;vzo&pPimQD>mobbJE1&8*`_1C10#^ikTK<9MBu+nlPEivU9;y z+wE1$11*x!A8Te9uz`0p$Z!T_foRP_6|gD3JP0Gb5oE2h(E7hz04h*+=+y8pvClLI zl~9d&usKrJ(l!+cs3mYU_kA8V8lH^1sj>+^WHy=hTxO}8ra||aK^yWiScYNtw+-vl z#S^9Oc@t{M^vAavy#%w#Ji1<{ulP=zx}yGq)JP}ck}k-g5&x@DJfUa6i-Vc{3ve4o zdj+j3e{}g#^$WI^OpMHPXE9l>^nUXz33vaXq7LXP2~q08pqZssc-&5?fXf1AUeMhd zbGJ0VJ3;Z$Qs+jfWPstcf`GGf@NSI8V7r?1Rq zCm8_yO39OjfJO`+b&?d{bek~{k2Al`Q>ytUM0Sr>uBU@R%T05ha9aF!c)!rxWp4S< z%J*6s4kZ&vFOVSqpE5waz{~k}uz&r7=YnZ=?2He~c0RMpxsu;T9S`M!D z7D|c5zUjGM$cW$%`8ng`n@YM`**nLz$loa#>H7u8En5ww(+wg(<8S ztK(rr01?ukT$6X^PNM~+*y^(qGwX~dQ~$P^Gz0-ofL-c+k~w)$@|8iF8XVq9cpq0y znzO_Yb}Jiu1A>yo^=cXWS=e#|XT6#IvBJ|`T>&&wE0Q>Jp zZ&gg~X?(d)1P-d9tNxFv0r}3tHp|-D6e$$nAoqM$tu{FwPE%J{_>_*)jp-X-XLW8r zL>M1h)SA6AxGno?S7|+KB;GbceuupxB>D&A9T)KrxCCyU~Q zxJ$Kl>F9)C$O}zTxo*zs4<<}@ZG8Jj8cAgf&UWQwLO8%V^WGZm6G|uR@@&fmzo-@c zanD=xw>VWR-!Y0pXKi>CNW@;cKiHcNM0mI}gm*#By=Hi=eP>xBjf}T>KUMDuQI<7m zK8qNM?|-$Xbo$#=vNuF(2$MacR#WsO#SWrA!BDZ+q1nY1g7|rmzt6soEIan?RD#_? zrcXqsw*63+&frfb;w&4uO+MAQZ=3Psd4b{*%M*^SqZ5A7L5WE(Hz}mFs#l%FaTDX> zX^-&-F*2uZm=ew*_Bn-)I7{#CKZgAB8L+t4&!V$2G+)1TMzL7xY9oV0L=NIuE|G+P~bQPel9ott#HoLm(%4=)d>)p$n#kRUzS1J-n+|D8g*Nr&b#h2fr>X@s-??L z)Y?$iNbNZ3-GiRI>B2sHAI{?;xoc;1PE}Q90kUfv=6_+S=)+~xr7LWw=fd%gOMFWP zorGrq$(x7SCKLR1uuNd`fSE-qcbBJ*5R~8j^*RyGmzYZGSIhbDC&HNehr9PViw?iY zgQy*4WXs-uO0w5CxfW;XiZ#?yN@+jSEJ$KU9JXz_^ag>X+y4+58xAIiIU%7;?{r{} z{23eHRW<>Y6inLvh%YA!pk`$J5TI$GrhY~RGINT#^uIC&IPU$t!=CDiBb_s;Cv;9#cs5g<+9dR zUbo|UuasuJ;$^*UIB_di$fHB0Xuu&(+G_bnBLT-zj0|y`Q^Uc2(r{b)siT7pFRcKGo0w_ zHnP2>f*r8KykcaZ07~@c))5d|+fKe-mgM}*FOTC=TM5T9&io&%)(p9Bso{PmN-AF ztm`l&1&*3CA_5i&<~Vc$Lz1))-ESpzYn`xV*q!d%vB=o;i-vHY!E2=8iwnoy?~tM8 z7ff=03dnG^u7>9C&+qz7r%xALUryx}_fHH9AqnLDb(`9O$ZRautX|n za4-CfYpQy(>3%LPaaSJ4w|i6?DlE{(858OODzi+Bh$`<`l>T$^nIb57{WqNq5_y@_ z^|X65SLVDoPH+;un)|lWwy->np4KxA39s%tb3NeY;4?}l*f3ucyNkGr;~L))w>u-{VJFI@(OL0f2Rj_Or8uuze=@cO0|rR6*S*lymso%ndp)?|a=;25xtpfE zaR$!NDTNxG%ba#g*J0HY!fR7yFWuB*@VuYJ5r+UF-_AxJtUH*t~3P%#$RxU-HkBPsz&=ko14`Cq2PkgRPcT zH!E9jf~TtgpfyJD44qiL8W~^6x`#$DjS*+6OEm4ei>FB5!3{luN^15_Rrg+IGHOzT zmTAFVp1zh8FxW>p%t@v<)sO7bQ(78bQzz#b=Xt&S^coFDEEt2`4C5wp+;m(i zlq#yvn7Y{^jf3dFY&LG%Z=h61D+#m&VFLZUW;wetZ&oq~9W;44XV^ZP=Qxff430_u zxI1e$iFLa<-ihZ~j<^3k9Xj!eSt&7z1M!=%P>#M8Co3Y-i=`;l=S`66-`ehr)hs?=AYG>*1F6b>h3HlqbHh29F z%%@Xj?1>K|loni59e;-J8^{kcJ@&f9az^x?6FVMa--1||QM_f@C}a*JIcb<*hNDG9 zk-BJX7a>rs*z}MP*D6A1OKl3@oL=1|3XKZY=@&uP+2Xsg-(7O2x5O}{1&%MNywUMA> zu*Qkb`(oEt(g5HQE?9P_0Af2r$9p^`o0Z0i(NU|t@f1b=^FTRjEZ*Flf|^o8gE?FM zzTsz10&P3%>5Y#ly53@vUV6eurQc?Cs$xAP&K?Ylx=2Pue4DU~HFH}j!ruR&WUF&m z-xFsK?j_@~z(NRsNwQ(>i&G$`&UKZEw}x+KV$LL%pCMNBw@)kXJZfg4V)b3Ai%FBHh=(X(3teDtM&bu@bzAIMt z&-OM^lW214(4}wv1+;ZP2AdoG!)Q@4>}ebP->x}DQf<|T%rp_(HOLnI)jR7Sn`XNg zOj}vdibFX2oNC!*;TT@3Fjev+zwAeT(@I-E$5WKRq0(9erP zUSSzgm_S?|#BmaLTP0Go8)0|-qj@2#&sPS4is0fJIumh=U@5|e*QdrMcXZp0u0xV% zP#YHJYrdkOF)p+8d)-U*2dh^%L<1GsHI4T}p;u^P$IfA;kz#6( z25y+Q#T}z|8J%8_kLG{3ss{Sl?@>UYj_+(?04lO*|6G{{8VPT`+sSfraxwt&Y#?-w zo)fxea+5^5`hkRhZE0O|!^Cdqs3~H!bCrOB0vsz&cRLu=9F@cZmH<27rk&c@E#9~V z3FlwT@gx*vooJB|9Go1HVXyk25ld@$^IV! z4Lcot(lm8(F-jDzrje`kcY}hTd8WUHhN?Z=S{jRUMNln|EcogdER*1IuIQPWa}V*# zqlGQU`<6=)aHiDQmBcO1E*j-9#fWwn=0PBcO#{J*9(*e+tdwA5%A2^g=RRXDzb|fk zM38v%rYSRpm=y6+y_(IJO67NbS^cX(bJMQc2XE%-FmkZ;-<$L(B+?WT(a8RFwbL`s z$$mTBKti+TQEZIwUZ16=<`xXNWBm`9%Z%r{UX~q-9gm(R;a@kF85ySAXehEy@Q!&N zf}HdMSLLaV#QH<2*fg^K9ORF0C-BsK#sp)Iarsr#^loT@sWD|U%-*!P7P+14`OWa% z!?=ZHLEJ=m$Tj0G1?x>{IhdEY3r|Z+af{hQlCmW73)Lk-I82?HUxUc@+nz}7l zA6}!D#SadRS!{cFGjz=F(QdKwbgHm_ynB`<9NmRmRA{qZH6S=^6%-8=qCjA(1Avv0 zNd6VjUX2+Y9SsZ&jQ-Kq+&m6oQv%xZ-@@C^G9dio&r^c& z3HKi`mR45mH#+qW93BP+BJh$Jbq1SWQ~%zcqbVE=DBSp`cK92(;W2wS^!6Vr-rXzs z=PppCbuv7GP0m)tOl=vZ*K5k$`Cu&M(>TYRQ^F|*ZS}O2bel%SZ?a~J=+@{fj|#f{*+ydzvsisb zvstXaR&Z0(Q){_Cqqg&jyt6*XcAwIhd#8ujv{&RTh^aJ8nu(JBs(O|exViIK$3gUZ zgRlY6zU|e)@8?^6YvUw?@+ukt6CDUkr}I4DO0ay)FDSsl#l`$RTcV;-u1W5~{T*%; zIQ0)g)&h{_ffoSFo(X_l>+5T(B7?FGp6^6$p+R!h#rSW3(ECBN=%PdWFN)uOWjBI@ zu}X(U_B^Q^_;)2J^5?&r7x-J1`W+8v{;!Y!aG3xk<&O4t;J+Xtf6)*=WMo}&8JlGS zFgOLwdmIg2Mj_~PQDO}+LWl^50SWO*1q0F#84r(1m)qswSB_{1wL<#A{{H^qArG#e zAPDq~KypgVf z7QtqbfEU9C^GcNZue@ItWLp1dyZsdo*O7|2~@gznSs?@HgJQdnY3KoB8Fo>y=>T zHR&a>#nYZ{5ZHkSWgfpaQJ)7!CFrPaDOlZ5qi0|#5{D%3WrLze>bc^$(qgnWPA^w~ z2wsi&ec8s&&U$h>-@2*r?}`)9?O0ya=rL4c1qEy(j8uQPoAQ6TJZaiM`d42?$QzI8 zO8%7r7Y7c1&+qwqVRTd`C-1;rd*W6k#PC;5pWZ>J;V+ZDGoH(_4?siW=uA-{>gLVz zoLZaTbL%e*7-YMNiPe-DxH6N9>xSg*<`sKjF23W&8VP&>u-!5;7+tV|AD%0(bB(<^ z^bZ_Bpy1|nENcF{KX2p&VDOU}7#K;@S$@yY+wBa;hz!Ako*_?x?;5nDeklRN6BPNk zOd#HZIV=0sW^$k}hosPft$+X!Fc`drNoxbmYnxuwMdhs8J-LCHpif5`a8 zBG)z4Ip6+G6)^u$_^rp`X587InAKPeSjr)7+bkE;rc>gs%MO@;-^r}=Q^A7%G~UIP zrN?om`2LJHz~l9bEoGbmA{PN37*hAjzn9LzM_|5|%gW2;q@)hw^nh9uUY?%!_xIN$ z>prkRdGZ5KJ)K=ea0rR!}!fpea7^*I)f%SU|-f9_Kwd`uHPQ z(1G;{T?I^cz&A0DZihbyJL5$?4uG=_zwy5tyYu+?xV^o7Zz7EgS1kYpdLRU@Ms|== zg+umibaSiQAMa}bx_vtWVA=&36<^01{##>~+3ab;Zcqr&=TCDZOCH}rIo*iIApM4m zO)bm)Q2eZ@p$Oyjz-UBJ_R4?nBT-EWunR%q0*(L})G(`nO_1z2fH|1|xAoyat*`%D zzasx@HT=l%&duXDoMHh05C3lJNsC}LifQF(fRp?QHwMvvnPhPT1{Q?u_TLSt^%QH! zZax`5V*39dTnJT9aAfNhS<-;#CvS6zetpNU9#Hp}pnp@<{iToj-5?e(E+`-eAz>bb zz)e{S6U@)>j&sL>ri*DS6hCJhXhQkVqvw1#z#JbNd%ueg1A0i$i*vrZNGPsHU@^R( zOeVm6;s3W1EIMs9&A4d752aO#)gp*6AkmGtIsc?r03XEC^8V>^swh9de{k^O{+=8Q z!69j`0C6drtqw)50*e>(KqGpR>A;srf0FVcnzgP~Bc==w_%#y{O~A#}n=%5Xi%}#I z*5~N?^t^uR2SAn){(pJkuecG@%e@Jr2yG!yFUzbeOaOVXfRbvI36bH)?gYZ%lxYv( z%u<<>S!0*{JOE*iqZKBbdGR;h(8Su(%zFcXivE^pGpXdxidUu-msR`esfj7>w640g z-or39g5UIa;_-#u#5%7=dV{B>M|Q|QCD972nR+5_qGeE8^m1Br3JV6 zl)3x@cw!6;chkdsB{TKB@p1-%d5!uF*0M=iZ(pT5dp+GKQq!aIzmPDkg4R<%b`VQ@ z&VS22b(09`;RWP`@!h);cum0s!|Ik8H5)OEhlPe(?=W$wLl}^?TNIt4;e$u@RG!PR z?d4ZLqe$uVR(Tm_)#6%q&|(P8wQU_MOLuhDMqnU=-}1+s()s*N6f!=PcyOq!E$#_d z>gQE16#v+T2^97BqR`8?e}1L!%BxhTRgFb=~~r|`-(o@}#%O+Op;2;0RK zV0KhK^!K3EML@Z?>Urq1bm$&$GeK?YD^3H@EbEcLunagbcF#;Y)gG~TWBFe!$b4tP z=6ub1M!W4==kPB`inahoOo#dKx0cT6T1QMPV^=jQ#P}8}-pU#}Ysa7coi;1F@4CW1 zF>tKZ<=kr;-+AFk_InJTuAy5ng2C^XLP!8(o|Do*j!xUg!aEsV*sQY%)m)8{BIpUvQPc9WTH}^CL%<9s0AFV zg68nkq?tO&$6_yaaG-x?d310Q?^`45NKDMU&$unE||qeNdCGkQ*LDv>{Z__8f1QVe(mG2 z3Kv{TvCZ#m7E~oQPItIyIc659sTsvqM+m{FJT|R*NDsPA)%y1xEB?0^;*r<}K#zlS z94@8tN#>pk)zu^>+mBw3AsGiU@nQ5?S-ViS)34r)<%631EF_C7)pB556k;N7qvAcCPv<`lp8_=UXZdg;VOD*g9eAm3SLIxsUh=t zH=h2sPJS-PTyGJwL43tIbWH=|#qL_0{@U)W+yK;>acA&-maX$4Z3Ox;bFG@7bl>=k zGjh*i`%-sPT=^cf%Bs-8><9_10yfi&50t1_GfQb44O4^0>u(XCXYJr@Vd}TYJF2Pr z^g`_g^&^i92CZF7OEbu!G51d*_CCgmy9~qvw?$9IDNc}(SURM ze`^>}(UjWP*UA&h*kF0iN5>5YhfTGLLU>lT!M!5i@B$_KsZSW0rotQ-XjPo$KVUtS zMo#efP|M-Q=;@|+*y`D+ig{>?na-x>cNip^OYpFZa;SQ^pTSHpo&S42l6>!4%eVzix}V%0rI5V#w9Zn^UmeYMaOD`d2i`5EwjrnzEwSn)Z}sL| z3quriQj^qElM=Gxn*Q3SQtLyGqPX#AUChxa!-ebL=Z19WRK5{+s%4k(hNK362uTg2?tF<5f zj^EWruPbVDE|`V7tUT)fMPXramb!F$Hi5ZfRJrM%5V=4V)%;WnRrfN{slmUk>MQHM zY|{Zx^!DuNuU|Nx+9nfN3M!6bDvp%quVKe|D{xdc=ZWSb^Gy$}i_U8BT4C@lJXB|; zZj1+iIWUUUne^_gyu^LeLb`>temC!DRb8?piVjR@&uJ^>E;eBPrJ3Jdj^`V|V*QpRk(NcS55R zDl6ZCS7v0px~A*e8i88XAH3M)uT6-K2QAW#-;mO^)Zc8;EIMC%eEYB!Kf&Yb1&*Qg zh;!0=TtPBkHNLf@yY!%~Q<&N-%1;!d^vr7_0`Y#G`6qCZwIW+KUn)v!*i1ZqWZ+vE zL-kqKmNGZ%Y3^bP#ai3DIucLuinN*;R3^9)#Xdfz=gZ|4ZdsVkW1vX(^fmG@76v$cKO>7x z=c*E?0vO=%tw+<}A5pOv9MiR1KC1GcE(*dvl4($|QHF3==I{#mNzzL8OAY>rW3%-W zbSel7r`f(QP9C|a{w2gkgGk$VXcdkmsJfSF#ACbufbKcd6+SO-zI?3PkM1Z&tdm^* zcaDF}!&6K%d&MJIQ+|`?umy(!qewxgfogH-q~hl_e7TL6$6ud~FymHLm3n6SIuXf! zHAs0hT4o20&?>cqtCz)}+IC(64A$C1@*Zbj5}F@z2SoKWYFeY?NF;M4vZ(&y6HhjZ zLQsCfK74icKdGhcU=15}y;^59RFrGCSeekd%<;#MvIVx3Rt$<-oug-WnV@${?$B1C zo}bBOQc&gU5ZbL-`kq8E{5|h7hK`C>_hkD2w3JC3 z++CIWynLd%e20p90o(z9>&O*nsJ0F@zRs%=ERSJVq+D^yYI8`~LC;)$XuQ6h6id$y zmgqdqYaRj&*0hoBNWRnEB?QA{YX*Jm^6o+IJNn+N)IBgHwVvjpHl7EEHfKuOO~HC6 zG*k>ZrD+NKAG!C?GVpfKc6?0}*-X^c@5QiG8!8*wNC*v`+{IDH!ob+>B%599Hv`|A zzZ|r+s6ukz2J8J9Z11iVsd08BRJ^wWcN8`z7N?C=SH-t*h>3mTVUsX=_(u0GO82jq zS!!Z2^_hcsY?Jxz4Kke#3pvN&hS_> zf4ALG2DUVI#O;N1z0&4nXNKaZ7@NDLNn36z)tukc!}iULwhUe{Mr`kYP_$yNpJlnL zzo=LUPkoA0O<^q14$U>j*74hK>kOpuRT~T^yR@40|1Q%qShU-bm(+ED@z7uTO(NHM zsRf=7PTN;DUm@C;qe?;XpT$4ALNsG#rmtx#XS4Gl7-+{c=yY^7Pz9gZf#n3%+P=M4 z*;`)V_{1gMz%_p|KT~7FuP$R`t6o>wDwiB<4>#@EQ#lQ0mlX)Ugl8wQ zH+WToImqdc4Bz;Nq4Rk>^8HkxpeiK;eB_Ret6ggq&Q*Xg?@QxlS7(1zdE|HRrUT7q?vvo4ErLQhow_`t}w3;Y=f?WKqr&FjJSxkQcYTHjWp6ZsY zs2Yxq|7!=kP5gIZvbO1~N1VYc(b2H@f5cE>oaJ}xL#6gUi_1`HgF7TD_J$M4!KW@u z(l1VQ*Bq>?eEBK8kUOstrFN^AWbuFs=7vqRx`a0Xk9?$B}~ogFBbUTh%* z1?uZ%jE)3K4(8|s$kgz_s>NWdo-nQW%GOr)XeorrH?eDI`_mC&NHGbYJ)}1@loG~2 zeCMpW`Kb129^P~IFzwz>tL7={cG(nY40Tk_FOuLv$Kb$yy_{&DC#i4XP2D;?rHmUD zF-dYS?ig+!WYXY9$2fEixs1>j$m7%Maeu@2Myzox5CelXvu0&Wq`e3cA;e3H$+bgQ z>lS|_S0dpx&Sx8uZ^gVf^r#kdoz3)($*mj1)JK3m6b(*C&@oD8RBGia7_%2FiFToG zYoq_VI;~;A?oalc9?1S-P;${aok-}=*vhQ^CUnb zKRfxM&&HzgjR&(jDJ<)EKW)#3yyGe-cfNTCBiW$dD0>#+EcT1_YZyZPq}EEhaqXDF zTlCe})G#12;+Q%U^Iaq{R4mdzRmHj)r~I#r1=@Xc@t)l|GoC-uT83Nc2u9~f##S#% z!8`Bp7T$3-n%s$Vd3TgDY3P~UHQ4*r@XMwwjl3qzX`p0@>!>Wv+yag%IQIXnKE9!k ze(05@{{pp>yLTWtN7kfL`=5=?%E{kL(sKW#&CDED1EtOEl1%4#j<1DHyvk$L-R-3T z_F*EfK~7QYQ@RKfOEzS~?)T{T-+JP_yBOxdpNM}KXrsuQ9>;DXXE4j#P`F#mAFG=x zEtM8m-mJ=cDU^ny#JT#2G%?E#U}CWP$tE=#d z{%u5Jl`mDuJtmevj}=A<^B#v}U3cp)ls!&u9OKYsKP(*utUcq zyb}}K;O79QMyB@{EUXzvAFgc@f|Z(~bg8Yq!|`MKy-*jyL%CNjP{2zzGc*67`3yl< zbu`TzaE;=4796|&B>SBIDSG3hg{FqLyPJ1lj&gM9%$$W?hGOeHmpM_ureql%zbtS+ z@8sTD8=QqjjvPKwHaV1RVR+5}eROHcj7j;%n8-aMUD2`DG!&cfMux){(vLXYQTSo` zb*H8oR%7%e^QxT`#NNNF>ssN?Wl>lC;4-2I&|E+Y%L+j)`w%MR`q zC%Y!#GFRwnP05@Mz20UGo!=!byANN-Z>RXj%MO-nh=Il}nX<&HQ(x(Rs=WY%s|&Ft zpvmu6MvWJ<@R+vxhvxg$$@z{C=Eh<@E!w$v9cCngYqH4QO+!PQvBYWQkqb|E`05*D zE^ZgWX!gulQ!9&0f1~yW)o+(+)To~DC@wSREpw#IQUzb5b+5ymu(*!E`z>|yw_36~ z>+#Knoo#)H0V_uIbJ}3A@oJH0+Uay1n(|$k{AXwHJ>x!2r)cO+%o@$V$qP|QQoBU_ zen@I2)_)g-;F=DzA@Hp8H7XPtkkbg!D++3+49SydAGg726J92HyIupD$!Uwd%>^Zh zL=g*uB=wn7fvn2*;;W7Bs2`qk%ZuAev($IB`5|n;e{f3LIb2Ij3cj-6 z1f7GI2K4L=8BdeDR@{D6Je7qqva>IVx;rfAUll$_)bxR7_-&p?kPDy_#H!pubA1I6^ zXB?R|{-3Z54Kxb|i z&Y*Xv4OmD`8$Y>toX&=hW0SU=t+}V`j`|LPw@zsC`Kh1ZMS$VJx0chJ=U7}Kb2buj zJR+uZ5;a}VWj68UlUwJ`Q{$miiij1T^Q}sWy2hC=8-^Ao>@I`p!=T@U*p)fl9d)eI>LlX3N*P5eDDSPR%fGQPcef z+~%mv8Z!b1SmlNmbur86a~Lr%?We>_MeIMKKFw)&_GrrTwICg7Ro19&UUL#I(g#mO ziQ|LmA}Q0vjhJVPc<5RE0*Sz$~vNANs)L4pn&z> zGefFY<%838jO6Tn)`=Mf(4DO$r5ayj6Y=z*PUB;+gXk5zOTu8N> zu#br#u_`SR-FWxI=IxZFQgg$O7;_*F43 zmY;1N{N*E(Lj}2qWg_qYs$`p!qlq(JdcqNYKT~>l%9GNymGb5OlO$qER6gVzt;WS| zHMuC&AMj$%V9R-Q#+Q#5eXpy=gNW-=cGh$y&Ol07qsQq zC)Xcf5qM5~sSi$$rc!HC{Rv6LCYBc`ezVqUK{&)1F;Z*;6>$l)*M!$v;JEi|ha3%p z1bbErKHY!yr_Y09tXCBYD>CJ#{_yLlt(|xOwyrn7Hypfwbgu;!H6B2nGklX3k|A*{A0_4WXg4trz#qF0XPu{hRX-zM#qJaCOasSUsOfBk~ zKzi%gqyAuzAl--{U07Mw!-K`TxuhyQP&;m)8@%N*KtR7kRg~b_Ci-y0^xMUMPJj_D zqL1BQ9RV$Xb$SoE4~-aNc2+(fF<8OYjc(L#ep32=+2sePJA;ue;NAnW3c3s1$MJ8Y z_vtc5Mym9Bmk_d(B5@Wg-L+aKX5)&x5k#}ZKCpZr5g5mCy!Td~3vXsB!ghwIErEaP zF~-B@&x_mG@|rlW;@GjIQ!8W?96^ION+-$Cwi@DV;bv3q!8jbHvl`w|4cZ8&psNTo zU95DU$~hmWCWymWdTUgLa&7O{4B)02Bf)cLC1@^Cwe zi~%siP<{Vw9dC=Uk|r$N$g%1}*VfE-qt}>5Y>!RCMFa*YJd0^$BL0sP*^Cd%`>y-) z{Mt3lk`**y(W00J!!dVRc@)ZT) zjpZUHydXgYy|i|$=IXtojY0+nK?V@X7mIXvaS3Ri(eQirGYcw_P2g>#;<)~~YA}CM zoVS`~kQqlmHA=@-Ly(qK`02V?3e1{cGHLDq$GKpp52|WW++;j;+INkKDCyv={JY(Xo?z#oxkMuPH@A^?_lBX*?CA? zT|Jlp6_Lwjydjo@JQCBax6~JZGr@og4MjauYvfB^oSqF*9P$@n<+WlG70Wlbo@(sK zjbJRlXE2oabZxUq9Hyb>6a$07m0+ zlWf)WQCJzD|Hzk>pR7!IJx7yix_ml1*+&pXrtQuB0aKDasVdrWW@`T|1^uC#s6xBs z$M0!XO_W+XinGO|%zwV^yDNVTGU15{?5Q#g=rL};6nhsF9ZFBnGa{ansyg;TbuUfI zaxL}2ioB7v#lDj4IqxVlBoN?wRV;BC5U?^d%xX+=J}#|(TekV>m|xZKyOA8>(~o1@ zBv_3Pzc3t+e9t!@x2V|MC5r&5(O0wYdgRn8#H+YP(004c-Nf`_DT6citf~`h?&*W` zatzzDBDzhvFjdwy>CHtUIRR+IcE8hdmnoCia#-sU(^XGo)-1~en zQ_`4LXxT*&0bz96sMkn=NQnpC@Q}2XXw<&7A|A=)B<*Gw7T^6*#qZkB56u5xdv6^T z_47RrFQOQf0umyipaLQ#NT-yFfQXcoNQrbei=uQ$cPb#=os!bsv2-lWQcLVUv&;Ma z`Tf3sJbymte4leZb2zdt^P1P4JGbwh8IV0A!J1u={QxCPCTMSa#IG&BsrK-%u|s{{ zW{>0u--qTrB?>GlG->~mFc|&HsSugpW<-_rX+A*e`4|A3ji>C0|J$#3cI3C)c)$%7 zA!CgbJCqDGy}_(YSu7oLmnVKtgrvhabMV%t`o!u)U**2;fIs-I8g+Zksy@&t`Qv$A zVt48~q16YqAK^YP@;fI&vUr3S<5?ZMkG@e;u0&|t$?q)x|j3kp1@;^v8& z@v2rGap|;-zC$BBH>UZOl*y?5(TDG=3MXqT2aStp;O#fufj#g`)2$YHS?%Xz-q9gq zTswHs6Q$svm#7KoJ|6uJ?jSb5=J2`wv}j^4w8^P5X>pN`xh~>5so>>iL%MSz<_5{P zmA8c#%9&jjG>x@h8g`iYlZ%j&fsGv3{ zHjAWWBXi#;g{r4M9RK=YDP1fxI%&40|3G7s($CNUC@;%u%(r|b@dJFf`(ryV;Wq}#YiR4;ZQygC^>*JH z?`-{yDYSOE1<03SO+)3$`(w@3#;B+~h4w`*U6RoqGqeEZ!bFn=HN=bR0mgHLIR9m~ z4s84a(EL(^HfBWk?$eBJb>vjmrO52;HwmUCoFmIcM|+%4aNlIPX8+n$iGOr7-0+=B z?oWTn+52&z*3CL)9|ZIL2wL)Cc^RbXGWKpJQ@fO(-@86LVVRMah}bTE-hB1BNPPIf z7R~rx$#?&!wnRnpc;c`~x3Mf$O%M#!>gk{$k%dpzCvUwtYrGv}cQ>1jsqO*oXlMBv z&ZB$wx1plFx0~5rS@ZMUbSO1KbJU_$T82$t)d?u1`==jhQrKxhl8IkjYP|H2o<6l| z zqW$U)PYcForc1S2G#i_g(#;(9Z)36*Jm{ULMT`9FPDPBAdmwpoAbXD4{Lqz2lL7eGFhE^_~703P=yAYg2qQj3~k^z$N4PjC1X&0$B z5kGs9Nwwf*oxg=gOk&&ibjj)%xDiFwP&U9pB_AFat@n*r=C-w0^W`%P&Gd+j)1in6$zUTT5 z=z_68y6^;~G}V&tcpSu%nrR$EB7I7s9&#=pK2I&}$j#xu}mM2f2qLpEJ zIxrk4xe^X_>8|A;`=be;+a{}Jeos|V8L#KBlxY3;fcW|$BAU-VUQ$wX!D(|X^=zu< z291nlfW`*3p9ZevLvgV{sCzYASEg`zM*HGRiU-jB#=C1N$&BRA6=oiX-SK~giL z>9=6han3j?^sN2(tMfnGlM{8mvAQh=E&re4=!3GAn`BA zcs(e1w?`csz>xQNfy%*7O@GXkIP-R)k#Z$fhwHNyvNYGF)Q@RpZj5D5o;AHzhjM3ePJW7k^_L2d` z3lfsIB~P+SqP|ve=w$vDZ@XM~izVuZ7;wqOgLi{{@&AI;h7`aeJso5aeST|p>0S!n zrf*G7K>Q7rJ2isxu@y|Y=lTjj+0Dt!Z_wRZp|i@UHhx4OTJgPQ^M?QWA4B^sT`L!X z@#l9UM#(^KRhmcCe)4Rr=cx1V^Dyh@VXuW4?1RVLIX=3miocA%^pod`{oV)!Qtpkd zff4I{xk!z+dsC#}zl?h)Xpl_*0l9vO%N2$=x}*~o&B;avB2Gd3NTE`0)lNk>tJd|F zT%M2djfYGyqH?3Lf_uj1kwN>WFX5>_-dX#zu)JT{s=d!1M&=);Z09Vm@gwH#k8w^W z7xdV)3+Y77Pd>|qpw+Os%-ew=TmE&w`O<>Gn0Tl3-jM@xL)He1o zes*#0oL_VkCqH>^`CL3Q=(vjQie$5+g^#8jsD9bM6@q{}43sL!7{<@N$Y)V}6v-6W z%PH??yEM`OkCHQEB81gRDA#gmO}_x6vijSUO-=ON|KMqD5zaM8Stk~ms3I|>7Ewsg zE%6|50_r|#N+06V?7vs8@>`8Q?-4sIXRuFnWsgOP?e29;ptUaPhg2V_2p>JSzApPt zCoxVl(Ztoy>e@_ft!jS(Pk*z0*VM0}=vPwKoSmv41b?`$^JlsqXfJ(Mxb914&b)j3 zuFe-$@8rBsJ z_}LvZ;ZCdO7rzF4+03;?aQ=ko+RzBp{nX!*R}OKNd37=eI!#16#Ir#S`?Gx3-qO?P z{k9nxa#xJs3IVnH=a0A_vk0#z!`H(ihF5Ik6LlXf=m+)8pzilFk)gu2ty@T1UlwLC z-4jsF?CMsHh#y&ns|Qi~4*l7^b!3d=M?v;Q-Yq^h%xkk}VPoE5F{?x%sQGQoPnozX zHi+el{#IX(IpBGPH$A4(Ih8L$um7ly!sQEh8T3%yhYfqGWqA~F& z-^BJVLx`NMeca3mx62X8Oh|k=pZZm^@P#TfQ(eX{3t%>MtTR62_`CEOv%pxy{aX0Q zYCMm3F{X-oY=4NxB?8HqWqaU-pLgUc^-jNnS`{z#H3MG-yB2?b}EE^qq6KGsc!*pk#mV!GRDjGr(kE(C=0MaKbzZLpo_m} zDwKdM+VKylwIB^CEq&nB#+K4VB?(F;h**LxB|{5>d$zSalqK+f|Ihkfyz$4&|Ffpo z2|Slt0m@Lk4WE&4eyOe#rTp^vr^Itq3N9Tq`laN;7W6|?dhT=Y!Av_VaNO<@!>#XU zbK?z2h3hmuG;bI?>2#DEZ@px&sRO5{zcYuPpiH}4>udj%mv6tO7IwBp*N(=HErG*k zd{&WixYY_MD>0F+q1T<* z)x*rEk~c$9&sUl?ec}}_;I=f;g-H~f`@MkfC*l%(;CUBu`cnI)v9kEy0BhTreecMo zM(KlGKc5$iH_31L_+koh`@AiGf?t@18?CfYt=Q2Q4su(aI&*U|)FgLj*O^LFKti3= ziOwLqBoMglCi|_F4k>z9Jo3i8A2y%q^q=TG8O|Q*wGp|S6D`>7l=`j0Sx!nk zih|?=eA)M0)DIPKoI9CS?D$ny?}5V0yZ=GTy|7~ofeO`pwNRBVIKP>=;VW^&Q&q>d zEob(2I?|V*I{%wt*RiD8K{fANdr7qu_S?P_pMW1h6xlRn=_F}`1m&{^l zX!zV40&!^fxy6)9gd6eqzN1SBjE;+IrWdu5y_YqCuzMo&(f8c(su3?T{)(T^8;1vt z5WK6Iu3Fm4V_)_iiV-(nv6%F(jY$ImwkAnYZoD@uD(&SY`<>{P7xMyf3Mh@gMtz-t zp4VcAyG&-joV%gH3#P%b>^uVWP(acib!}UA**-xhQaLmA~^M0 zcLF=3*sfDwhwO*RMyb`^5BcyJRIow_l=NEF5QJ05Vnxx+hzT?C}@YOdL0 zO6w&!4SkkNdj@r!&iji?)ubO$MtcF@0pUuX5J7;q)>qM#S>!o-Bg@vNt7_1-?St|yL%h|y~= zenCM5jo7{9kt_CnlSC4|2IL@L=f$v))5nSHVmKyzG_|mCat$V8RUcm(H!EBKHaP3PD!)3U5H?zU?0J!CTRHZ=h?I2wH}1of;jgFD#oLD z5oN2ndb>tET->QZYTg?`?mguh6)w>+G1sYyAyc3j9jvt_wRNRyv(GKbp`oGu{HePs zO<-;aE0yJg^-r=-7M(`Dw=k?ggeB=&o{i1TC2M{dYJPR)fP(EBfOFrM?sI7?iI{>2@|W5Zavs`Q z;lpU%r(49O?_UdlNokITl~TJTy%Ufh`{2CE`70a8`S<>}xer!ui;C_Z(_)6k2Ddrb zeJqmrwD%T>OB-8paaC-%9Fh&p;(ySA8I}L7LUhc1JyAb*$w6xVX6A1Fr_SFRbco)@&9_T>Vanmz;mLJ*rdx z`0T4iHDQmju8`i-*V#yIgj*m6Bd%aB@mYNB<#f~!+E6+CHZ4FbY$}MHhyl82I1xhk zErFX{4!4t>z$_riaoEaOkIAqX4{TO?mL^NzcW)(F%v4xOjQxNlkM294AO5PRR&8`V zS<9gEy2bN=;|}M?=GV|B{i#OwAe8lPYQZkRTQAWHl_25yQave8wBX#ys@~DW#O`LW zXcrj|rNsn>v%J5C_Eg8H{eMKG;HG zcgNMTQA~$`7~+Vn4F~7YeESA&<@{oil*O0ndPJkUfa9SpD?6QnL_LAIFNVkfvx3o7 zs84=23|~6%4#-&5y6g0`0ZOvW$m8Lm?K!1@xlc_RO`RX%Q}-s^^p#Y=6YVaq&sIr7 zl|3JGgy0n=^_(Be`Rdx$R(?TrcVF%P8>e26AHDx01wLKv0u!-02`|`f@Yn-{2zxz~ zgNC7f{&u`NYxDX3T;?)l8e5AFvGuR4MCzdSD10Rw(dx%7{RzzN-QC@d(pMnD)(4*# z!2Y6+PWc_^tF!@8G_tqR>oQFst+4aRU4Y7YJ)J}}(g@6~LgFeqVsZ%Vjsyxw0c>JT zX{uDJ<1(Bvvgj=@7Dc@Qi-uPeEb?ZLuux5?dZ~(s3CN!`&ccxq68b8uh1M--jnh^e z-8Z5ec;8G^^Uc8)xmFg{W6`K5I`>1yu2GXfZ0Rnfr51_rB0Cg`FRJs!M?Nyb{A`li zRKl}B5l4*oyj;F~F0kUW-EDM6M8vR3eyt%!`MmouP}9KJP37fdK2sA@W^z^K^S3|Q z@3rg}izQqq9a>5Cwu>ov5(Rm!7yo9Ef7{!ngZ`dI8dn;82)uI9BWolhZAoY(BdT|WjGa$_A0I%y|BsBv zC4KbT@nBe$^~sZCQK-Pt!n%o$@NvFdG(8^253OqFgN2+fV6nm1*>{2isJNC(N42R1 z?Q;sgh#Ni0&Czz`47Er)-Svj1r%%;5DFGsPPLa=;L>iLRfBaD@xz|+;B@;-ko7?0% z=j3&$!)!2H<81>x_#v6!=41#^!}26i7;R{8B7><=Etlf*&Y7(Lu{~GYx!&mr;DYPa zB-ehw*DBT3nu4wqm~6=(9L7BRy)1YMa-lP1@4--q z`cA-J26CoP3F!NYIy+LGd%KA)TS%LYJ1m82tH~!`F)`yT{!tT?vPe;fZC6C~=hA}v zI0Sb^6Hcv0Ma!s*W=BE|pxO^fe7_N8MHvds9nGgQxx0^n%_O2Hv**9MeX9^mIzly? z)%Kg`0ktoo3bXm2B)QM8*GnnNeha(-an@bbL7%9m=mCl5Auj!dTy(dY^iJS%J^Gv- z{ldluk?9xaO^nLU+S^Z)-S`{AAVuGw%;J5CgS&u`Q1mSM91i=Qr0@140;#>Urqs$! zdCSSgCI5ZtE1`E)zp67cGuQg=OQi5XksF*NBaN+tay@y$@3L9gwR0F#fucVGHuiQ(_E?Uq-du~TS4++OWUu7)@gKu zW6Hv%n`%ojN|R;gpO^XQ@9L`y%}bHhbYQ%>119eY*I)4QzQrIdgvg=ak6F2l6t)M>GJOE|;UVy#8_D6ht{Nkb_wa8~8sHE*IG(zhcjP_Z_ zl=kBmKS_u~cLYn+I=kkosaxjhRyDhj(AjPqU45sbczz%yCzxu-fkn>w(nsN22|({d zQ{0gq%6hE?LHe`=8Zedkvz4B39q6<0H;KYVTkp2-kIC4;+zu7}qs|w)e}Q?x4^E)z zTi0@O-A;~rF&dlZjt9pcG0pLVbzD6yn9p~1g=i*H?$kO?BrkDWzQR$3B5gtQL3cWqYOxkdhRkjqA*$6F2*ad2@x z1ixU7-2KF)q@>{BUa*_+a2sZkb4Pc7J--_WIF=V5Abk_joO+4wCu`%yMhH9i4>t=* z{Lv)k=BFcaE4}E~lJC36c}Mby&YOz43{QSG(cmQmyVvzBrRaDps&!^(90!r;q;lW% z-T6u(^OkI6zN5*g=rJ>c(^c#2#|kn}T%CX&@r{UZHZN;%ZN_b76C>zWd~Pu`CPDih zT3_q_giGkP%^bC!G&3a8^#~RuCB-)JaJwc#R}p6tlKXuYv~}AeE`rsCWuTkOb}fU< z?8?YJn=o_jD%-XB@AwA?6hHvQpZ7Y@L^UUJ4noCO=^l_!i_>5B5YhFriv}e3d{m*^N^>HQCgZXE9XhM% z{XRMda`|xnYm~ReOnA+w-q0YQ91SWQn}5U-v#ft=I`=E@Sh62>stRDlu9|42bLpYMXu7#JA1fsgO|2|kp`qLOn{ApVc88jJ)N zY$Vj-DE747Z&E9zg)cuoXg}sQK8f5xKkOrntWir zp#Qe-4TLSFN$MN%j<`?p$;z_Gg2s~VB6)P}4l{w391tX0)g!l*m1x? zTuRd9aNhqU-bmU^X|jG?Z~lg+9ahhtvD*x1Sqt_qfDVkac5r)2bPoTaA~o@iaxrjB!Y$is6uV5J@GGC47EorVmu z&xxHk5N~+iFrf{~a&w7s-v$08{k0xg?Dr;itNR~5KqU1I4S5cBjqgJp?Z=2xqk4&= zQQu&5o>xT#T?-DJxy}MOJyKrT_6no+#(}+NX7G?)AhJ5J*Y7%J*R1V71s!0ctFQOy z!d9XZ8j*0)yc=3HV8L;X=9__`;WEeC{rt8JC*du(?b@>E-V7WzHjnrgk8r*q6e1J& zcIDb*lwc@geEdH*pII-yV5CsZ&zzyvR`S-p12(+k{U_LhN5#ce>`jwEXKzacMYU{a z4G$|v1O}?|<@usvc27pGog0T&R$kHjqo&3Y@I5y-cjcXhZ(v}bIN=k5rq_rB&Ta>3 z8!lD*`M4yg!06CWv(?>E@Q)nuBgq8BJhVCVo=|!f78DeGpu~5{9J0wO2g;&P5r_y| z3ap_9@aQ?#6eLe9D1e!J^at~vL}fjZV`{?Gp#eq30m|M}wo zy#s+2gY;C@Zl%?Nmq!S;|9)dPH7^p_5HY|#CwTkM$PG6gdWDZDCsp$_Z*h=dI(leV z*!nI}FE1}QN?+o5abf9z11Rn`akL%+cjIyZ#^He^X8>Zh2QsE^`Xq|=Upo}UhnsyR zQ$rYJ_BK2J*{J97=huNHTNeTD>c7kIVU_yXXEInr7pC?CLaE7CKJ?-Nro%;m0#mn4 z&1FdNe>%KJe=RL5Bj+IT_=Arv*Z@zRvOlx-cg$w+_1x0Z1y$g@JGbt}G4<6<+Q9yP_r#i5mQ$^Yp%iE$n>Em)4rii?Xej^yWm zF;Xx)H>YcE-cw%RQlyI+lw;OSRqFs~YgdaPP0BD`QS|;Gd%Y%b5<$;n^x@XCs*b&e(;d=lx+`MWC}Y)D zZ{EB-L~=j*E9)Cm{I5i;V<~<#G*%_b;C>|&qh{Tl31=~y_nGMyg+FO>CZ2ENWT_Za z-fo_|$AtHd*;wkDDQcORLCPL=%m0ua4{}RQUP( zgSbbHUh+%QCV;W!`JCdOj;^lP2~q4CceVj!d>&b>8ay>fL-=o1&?`{wd#3T5)zSJc0 zY&&%bIc3wk2~KUOak&S9p5v@LT|xEhcbr$h>Se^&hC1D zhVv#K7J7TO+WmncUhhqysz(-rTZO^?J$UW@{MY)kN_sny?HUA7_<9MrUv6TsXPBXs zAy24NyEFfF1+7`gHX{r!j+at2GuvDU?s=VHV{Hw1kb0Z;nim#snV&Mj=Ep{5qIKxH z1VM-9YB0F_p$=D8nd!>}cJN}revU_C9L<33llfmMDAX^;(@mi{{KBvdjPItd6H=h;(9(P7hc889O?Q+vDILs+| z{5=xRQtyby^YxXSuUgOZcObqjjYU4t`gIju5>xdiW|H?_Y}X-r%+Q?3 zh$D2F`kOZ#1|8v3Q&Wzr;tiOU^Ke$xvQw5I&VKm_>bR|?aE@}oKE`1(T7#N~qDKR% z*S94s_u3g1VxB%^XJ?;LzR80jzGQ8Ga@M+&;ryUG&mJFG_9hC~JMM=h331exmGR5~ zVf1aT_7h8%%Gt-5A=<404!Q=5YDrsGIm-H8#g@G;=>x5R@318fzu zUkmlxPO2ZqQ(`!;K_uR3Ii?)ueyZg#eb7p6A*onmrg6~a4HeiXR?ymClJ)D|pgs}+ z62J?1;KGN0dn4I3CU#z{sEpW+YB?;&7`0a1h^5A$<^yaGfv~7O81bfaKOQ$qk`pcl zikogmuvFtnsoolS9F!n(Yg-5cxl_D3S$^((n1g0^u|L|HCR8B5eOoS?<32E9TXp*g zu$i0FVIZ`27ut^2N4Ng~6}FyR{#GGR3vmK{jp}JoaC7d8V(T%R?<4}MKcJ{TZUH*H%yj%|t685AcGRninwml&)y0_TIA30WZU!2e6yP7H zxk|KpiKTe2c1F~`=z3S(IS6i$9=(P@=HF>(RPROHmW`^}-y2BVt}S=lj(YX#6|0s^qXD3C>JWjM^n0773EKpA36 zMNWui^j156Fg4)_u`fH(4Ds@F4 zfz1v*^)jEX!te`_Mk2eD*EEcc*UpfLpGmXOwv&sI3Q**U>^U(*P> z(K9kKZt+9f1^^UU+2!VwDq6L6CUyrSX2Y2h2Qud0D$3{Q=X>3@Y=Gzy4iPjKX)a)x z<-r^gCX-rFu+zbkUvswC2@V}9{P5@NL)l0Wp5Hk4ij9pe=do}%K`d90UxHXRg7b+E zR{Qm48@{Z>+XO+$A%TGy$!EDZFgSP$^i{b93|M!{@80DAjCIF8%dbbB0HrsdhzDud zjR3a+bueexZqERGYylxT*pS>$0u%-$=!;73`!sjrQ0EG}^$|j9o*bQe_a-kw5Woks z*LWH;RSCpff}p514ye5i)HF9Yrw{qt)z#J0vjvn|8_I&e1c&s&^$h1DGYqN zEQ?to(C(>WM#Z#0SfIg&Ymu1QgCdGGGbH!&7jxWDxWU-sq*3dw~nNupq&E z7yq*DzyWzHD)tx702cfG&&%48D@oAH&<+D#h*-@(-@Wt()~3UjYX!7}0%+si3o_(; z=j{@s`tl{_uR((VFp2vZRSkwB;`OS0LICkez*1>LN=Hu*8#6P1Gp~_>0U&R&jeo{% zn*HNRyqj=-a?sh+Ba){Ffe^jI68$X4{`x383(NXVm{Uy~z+m{rNOSz*9T7=M?BG3t zU;g=uO2qY89QG5OyC3-NpRbr7Kkn%572R>cBfMk#u@yWYeeoAvY9YrR9PQ1EdHYU) zdEdK0o%dz~g*yi5PeT6yr*SdqntD|?aFs`&<3DTZ3s!C$feZ}|1vrVH<%B>^87`*% z;LrgX)!7K~ke0fb#0z~Rqp0w3*Twdn91MSddUr8&P#>7L=-%sk_w%CSVm+|b1qv5X z$o#%oY8O#1u#y!3@{OP8kXI?*jm$P!|%QA%t4Q)v;;3{5zQbkAJ$d zV5hH;&$3xF?30SDz~ohnpB3UE_qn*vx?5#K1|zEqv@I zDgKUBfm;X&^t&Q^jS7b%h;0Fi7Qnh5%fG9f*ZrcRx?PsnFuuk?*Pw!EEl{f<8v;TN ztpbFXu+-k&1FWf1)A1rNZ%bZBG` zjbJL%d!V5l>JSOk7B#>=3$h~q_9$O!3M1>~e*^2MAmv->=VAEzsKQCd(n16f?;m-O zxmKoKCu!)m$CwWava;ZZn3D zC(1?FVCGfGlEK~=!mcX`4qJ7nTN4u#z&uuB#1L+G3#j%m>WU5#Fw)n5T{YL5%BF>V zln!XRv(|4G4(slp;d7wVN>>c&_JdDw3>7C=R-jR*>u`7~(<@oo>XQiz+mmKkOD#Bf z@$kN|@HqhgGYs`>s0o-~sZ~`1GcWsoVKkdqaRDGNU|(kRB+;HxIe-*qGAH1ED(Jzp zOdC15Zp`s?!08HmgoUj!-~Awa=zhrGv-xPKj|0$=ci#mk*7j^@gbIirO<~Lv;5%_^ zVaV)e9dI?mBO=mzDBN{zf&HSk0#xk%O2;WtjA7^pz^DQN?Ka`7v5zsr@fxfXxc?d& z)KZGT(Dxz`W(S50#PWrF$F`;P_WTesElS(Zf#Bc4!8wj;L>acCrFQGUUk9;;z6AGH zMkVhE7S*k>LWUX6K1u8ZkMDdOGtNl5wGEm`u-Y0#61koqw4Gp86Ci0P=5I+A#VN3}!lqeG(Aa z|6dG?(?a)?zf&a}0pO=g)=-6JGU^^TOgS>>Z&%NY&Yl;7 zYjm{ysVxw(PyZ@s&yImxT91Ungm&Uc_?^rU3T*I^l`b1^A`q=p>#ZT>B7!6{TN_}k zD>2frDecnCRM&p4;P4sOrPVsES9R7J>IPGBKvJ-%Vnsant2N)6#+ni6sjFF0dRA7} z+4{;#=%5)z(8s83r2PJ zupe&dy+`V$_Ty(6hA790fFeJAGAYHDjq4N&TW3>4_xTxZ7ZjN{xFm6LAwi<$FEJ6! zPu3(((|7?@hjsky-KU3@2Rf9In*8V0X-m63mmr_MVRehgBNmH>aJ0kvsjBBg3Sj{k zC$kz)@Ln3MHIU4_&a*`)dWus0o||~IH|bJa;=0$6bAe;~QK3q7(i_23zr)OO1EN}& zX>pOfGV6YcaxE_B4=+dU8JE%x$}L7qj~e>XLdX<~$HWefdxe~g2EPo9ei^JJs)Fk} z9o|KVDhnWEWqYW{s!iGsW5(6NT5VP(I#2Y~)A7y)$-uXXoy0QHZ0*W68Cs%-`sg9z zcA>Qet*h?tUEhptRLw-E+96_Li-K5$#g^10w$!FFMoNJQg?Wx6mtPQ!!b-U-(Q@~A z;GwdMuyUy}I7Ul_)%El8{=hC5ZKZ>4e<9LL$$Gf!rK+pR$zHkWnXTDyx?h&u?Ir(2 z*I)Z(Y!Y=&Fi$0EvW;!hK~lwVO%b!HhrHc0g7FVw+T}H-(|bkZ#1TPtD->Mpg2IJK zqQsEP&#@Z))5OH`0}{pX03h^6?w(m^GDK+ZSm@kQtrDV=^8Gsh#mK(BQ&vGGoL#G~ z=qVM5JPq#+Sm_O{2)S(c)%-;LmJ1G~L-Yo}`(=)dPE>t2P+p-CRTIyYHSxBx&b2>u zFH4{7;b_D(r=g^EPqD-1DJkiAKYUG3`fPnFYl2B}XeFMjicDWddA(Cd`)wWb0iDU_ z#`P%qtx8MyxHTo@vfMvlmepw;xL@k*6g(j*rOT#^-XGf2|Ffg9U2imBU`~i+Qr}(7 z9o4o2(PP?1;lBYlKndxMyTV7#7wA_ zmIkU1*CzY$oRnyMuM)wM3Rr4iTU9RMq@RRbN^#C38!E64^L_xn5ACFd+RlkUyV8p) z{jH^^5OMrUhitlvWOjE1mSn zM=7e(^q!vEQ41d`omQiD=L&S)X7Y7A$#aFOh&zmBy0cg5RII zhM1dzw>qncn6@`kT29f2$W+>lVW|CPm0zih!_Q_e@5F?p6UB&NH?!5-gDcA5xC}#I zT3mm`(doxYFE5oa+c-(cwMi8E1};WS20Ts=?uvEy*=D5_IS4tGp}5=j%(rK{>Mm1h z0=O^U`JFOQr|;A&ANmE&la$uWGhrh!7oe%k4{`x5X^dhHOAy8qrYG5fM@g+{D^)$&P z5oSMa{~9uiI!U1-78Wo;?R9wVMYvYiY!vPlwQZryGjQ}QDo$NgiTQ$b!tfxMv5^(X zr*MHl=uYXW7k8r0%w0aKhhc&+(J~R0IK*i{tRw8V@6p3i_Biy=6w(0EvCRHy^<(=1 zKHbSlAF{VM8ZjvAcc&K$?yuUl0_X=O@iJ?S&??Ql`Wm2K~dAk!lj+Ummzs`a4FHXO(ojA;#lG)4(E*lAf< zOgZmRQ$J!EQKely2wX>w9Ty6HU!b-}AVKOQ-p442I z{tZA}ikR7Xrro|cl6792{keT0ig<3IprZx<@gW+X6_G!T4%pWguBO?UYzgvBm90Z} zryS5Bpt4bP9cg9|F`J7>#pNtB?dlWu!B;9d)3DmhEYS15sdKNQ+6PfxCkJ3)HGcHC z!GU;|<*d3ek;St2kO~`gFJwUQk=*ghWCsynwwe2!qALNUFW|y6`|@~W_$R8mG<8X# zN2@O1<+^z+|L(F8QQCJYMeDheNkfZ?6&3>}sHO_6(N8)^WaSeZLAKU==kAK@ywh4I zeYvoNI#aZ&>q8w^cir>s1m^=GR8%SsL@o;JR^9x)|Hbp_%5YND>snNLW!zzqY-xnS zU~9nf1cQbGop8>|AE=t5Vw7BQtIk>O_-#72cgnKqI#$Ee2e63|a}*^t(QQ+~k8QVHWI~^2af|QS#m@ zGbdofW=S~&3z-=v*__xhe~NoiS8RSTZ;(ABFYSbzF2uoq5>=@n)efZO1aVXzG25d~ z!PC~vrY%}k0khZbUD_)IRAWE&wCP`|y2q+0KFJ4W}qxschlclxGIBq&?tX`uFs{K`d-|GLzVuY3|Efn1Bdz)g;1`{LDY zRyrHE^Civp4g-UFjl(~k-zDnLcXBMEOqsi13(G$ez0(vbsN}sbsomBOb8(g4o8KkQ zeZqcf;505H!dz?lmynCDrm&Z@LRYuPgSkE-?&x6GK}1FSwv=Mg=iyYRZ1VH&$pM64 z+l=#e?Py|x%|6|A$hX&6VR20@b>&!{J)Y~djkwEo4{4B%t||QN@-#$MZAfo+7Qa=? z{$O>!1|X*SR5;V{)LTzY?x{M|O0BwVGgY!z*1g2CK~#u)VU8aWS^r*JQ9a^yFAEdg zu4gvnXI_oHsg<^E&LZLQa<6u^>A*&tJHG=eG%b77Jjb=V=(7viLlUR&S^^I1c0J<^ zUV$`RIV**yl8}3v|B2={Se1YPW4_y_NhTst$$V|#Al&f?cqh7*yI#I=k9nmPZP(JG zf(Vunj|>tmg;2$Pf0>V^a!%9xQ7v=>31AAul%j9=KYTGsQ*< z0kXjRxVAB_6eX~6&Z{xohjor-t*xz}a&alGm`!Fa&;X6%ZK7d!uJdscgy6SH{`HQ) zE)@_w9?89MeTqQP7NqCWdz_q{{*Qm8`sU3KftpHGpkovUkC|#m8D7Pdcrw^DTI1-= zCT$Jms~QXt1>yCFpW%H~cI#f$v=DD>aHer|N5hlQqE20FQy#>kxvBDN-=ljgK{i&S zWQWC#j|7zjfcuuOkR-CUww8%FbLwps1R+-<#idq46K$OY0SXEVOp=ui>q+XEn`7d^ zN-K;jD0>hU#w7VXBzCiPMCy!s6Pf&qii+?EC~qF!{gj1up4BOzeSY`;{d+R0XV0G1 zCn4gnIa%=>=mNVed40Hmj^&>#zLNAa!hN#HHG*uf}p?0Q$tnR(CuPuHKMRECJX9i5a^EFG3LLfq1z6&doiat5xDP z&q1HUzf)+hg0%7-Y?wx~#B9LuQEQS#Tu?e6Yl8l@jwc{suua%A@t$s;Z-YR`35gwB2h(^mM#e z+p6U@Cy^&MdMjo#1ab=?ueStZE>KXgq10Pbwl_SgQWq;wZUPhGEzh-Jz6t@SE&-1l zoAwwc9R0GnnS@$P5;>~uO*mG*iH$aVN*Az$W42z2p3M=1E4VWA@@7ucShwq{m(E`R z%3_oTK?ppeyL=!$3X0Gw%EjJbNd@`p0SSe+Bd`#gv|V>w0GjLeI#^E6qAGzX(6j@w zIY6VhSBcKX+C<2Y$gg38fZPrsBaDf{aesP4CbhJ*M9pJ527+(ta&aIpL4L#y>;RBu z+${`t%Sld726>nvC57(xc3+oU7XtNIEML3U`2c?V=mrouK{4c3nEgqhc`RH6H!*1m z^Dq$Yfix7pQ&n{U(ks1(cgj-2%E}5P^gRrFB0yXM)Bc;sz+mCOi5d(R{!0v4Ec~w^ zhF8I$Y6vuOb`&u{2HDBK*mFXwxaRKPI#sHOYdcZ!di zmmoNkK*LXw#u8kFre@VX_oqt5@tDnP13v@ACABbryNH=t27oPD=5vkTq37#53$&LY zx*gr!!k}nM diff --git a/localization/ekf_localizer/media/ekf_smooth_update.png b/localization/ekf_localizer/media/ekf_smooth_update.png deleted file mode 100644 index 7ac26fc604c6f38b2a4fb4a99af3541237666aae..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 146470 zcmeFZg;!MF+dj_o=z{?WNJt3CAR#Rs0*W9A(%ni9F$_I4Dj^*zAT13;$Izt+f^;`S z*U&I@d^ewuKJV{8_^o%X_bivr;LJH^-}}0*`?~MF4?)U`G6c7&ZsXwK5WJL?QpLf! z$%un<-S_6-;3pmYZ+E~y*Bm8Zs^7eMb7EF$2E3(olGb)ogPS`c-Z+@ySlGg0W*m+t z4rXSyj!?MM*0n})9GnL@FQuNTyC$wr*}Hzi)?Z#C_=`pJSCUi;8C5?Q*F@3UW!(6z zE<8f7Up4SRl;M0%m@jq{YKN8|cgxzSDr6Xv(6%4R5_w(XUZnBh4UVG9`AaKxP0xI6g1FQxnsrnNUAk-L_cM zj0{EO{^5qFhQ9P3_1)StGDJ7uSg^d7)=2#z>6w~dId8HoR997M;I6^W%7q=&(RXVn zxZj_bqat%C0W$77;^}roIduKswRryn2q0djs4B^89A5e1%jY$ zHTe+of?ZgMRXd(X^Shao+K^x^!4|Ik^Pz|1!{pRkRCcN5Q?r^4&A;!fby_1zP|9e# zijLrgS{d1AO2sV`Y*Y~K+5=@KQF``+L?bkb895Bi}JJnP-0%Z#pr!T zv*?J*V{dg`R4!L??{}rx(_gx*76vCZTw1V#hulUqJHujqJB7dXrAcG*OxOC0)6M_hOB190;xfTT zt)AMoLZoBn&nL$7-ne?lB1JN1hwUSq)>p;G~oT()r)7P>`*ryJe z@-0y?Czy9X;`GWXTy2W%Gvw%B&tuioH${C36&8N+sYSDH|6(n`UCVG?uA zbIU4TO4X7ua>9D``nA&*{{e*;CW_&G&{A^pTCD;f;d~2J%8FV`>&5NRIiP~pYBc@L`LB2JEqo^o(=B%v=pW!hb+_D~rW&;QNo#6#=t=H*{| zc^b((W?Eeh-I*f87*((IP@@MHJe)LElcfDMLo7=lTS$i6m$n3SksPGTkdlHc@9 zS4>YIs>GhCq4V3+T5@ZnO`MKDOs(mKRPu|d8Q34rLG;$tlu)GIM*1~1B>r_=oOwW7D>ApMCD)LCHnLIA;FHfap|q7}#-M=rSep%zl^{^# zsAj-1G3s?-v(*r0R#w)am!vgKA-1(aF&)KBlj|K_nnj#Ii==_NE6qpxmMj~{t-WwH zk^q=y2$OIzt(OZP;-BkU3%g#oH<+J-C=?`G74u-_wu_b%xHF-*mD-A8T#gH4Fqd&_ z78X1&8;-ALsJHyWdq8V>Mi|SF$Ux*ecC0lsc)k1$RsF8QvvcY}eT|2lkdL9#5v|gk z&;Z{+tE437HrJUFufFo+oJ*NPWYxcBGb<16jLQt4%K7nKWwY}W@Dso`Z$Agq&QpsRViAlCId2hNiMCS@sjE8 zwR^I6Jv@`iVq%i4HNhejw9+Kwh_Wv$himPJq!T3HRT}6E?cU3;pfs1hyOZ7rjg1+_9Da7{i0O}#@8>Dfqw_WHuB0I7pCF?? z3TSC=@JQ;Df?|9tLSv9avkp2^nDFxTwUnYXQlVhD0QTOK5uO#(AUo6q%3G%OdVqcz zs>xVD7D5~5bkLYQI-y*WQLxccK&_?y&u@SQP;51sbha2eW!~_Q9$TD{xbH8ncgetC zkymAv?36%|*3Fq`X{FHhVMXjNvd1&c$bfS6M6DK*Mp`u@P~Lh%C$kmie{B&Dw{6&|J^KI2i+I+ z*Ft?gVI^YXJ(@*qQKrPv*fdmrMj~~lS zKG{$tYT&?rpMr1VX^F<>69i9tR2U%-uv(FougKB(UZOzj9A?8G*QU zkxrz2*(M8`g376^<`7oU$Yqi&S6Ft?YnS3~VRizU@E+$mi#}d&Yc*TyjJGy~g_(Ij zz5_!anS5}Y(GQQGT8@+c?b>Eooq!x#)KYisn!Ofsw$(ZB=He|+%EdnRsF7gQ`s@}x z(L>`FF(@*SH?V+2LVm697Az+VliOwA@F24|FLCTf+0In^V8i2M)S6>SJy15UkHpav zu8LymgFP*a1agIGfyN$R9}9H;Qm>C=#1_;!mAv49L+uFTbH9$(72Sy)^K>zt-+hqW+eTf%>JmwRU9$NKex)t&=KMIE-u`~Asmykd8xQg5;Kr|ks8I4C zsr~5?6_fg+2JcZuUwqB2fHkMCAR2ftqm72D$$1AYsBm_Fovpo*tOkm4&J_6a zKU<1-{>y@yH9N8e0?1PIML~}T?3!jcf1^Lu!u4`Rks_^}d6P_eC zyn3>|fGM{oeLhi>PWQq}&%WX=(uDfr%cnfVA;yI>BVfTp_qizV zrdBCq6@xSCvvJSuiQYqVCsjip)tQ-5yNpA1#JaKvrn>;kRtArWG}2E@u5~OI6OoJ< zTgT_4S-I?UQ9@a?-c-;yw2CO$(qu~i*2Q5oXY-r#g|D@wryrz^ZcdDjSD=Jevy|F5`$qk;Q3xLL2i9=n-MjgoKL`& ztHU`G=oV^{%Aw%|DdjSWyoBmmizLP^vUJC;t1o|?i>myo>7e2GuFLzwKum0X)HD7? z0{x~RE$G||n$(LRQd~#-_G6dzJf@aMK1exORuJ($#iR=e#Wv)}jaMZ9Gj)``jg>2RZhxp+De`^Z`P@twhs z>s>;3;Sxlc%f8pBuJ#z~jD_*rc>QcbC>h+C6H0*CcvWR+N2#3}dM8w=aMf_a$|=V& zxQy|+7dtPmOISE<*OzGGuq^UtcUyF!G$kZM=5*EH{8dN|k{;?FX6@ef9WobFntULa z%0Y&L(riR^n2KMO&)|65(aeJH=8a-GzH`_N{-DxY7-nN)3^-<|U>vhCvYx#wxh{MQ zMkKeNY!$k-8@c_wskD;7UcF46Nk&YpL6iE4y@=VQ&mhSo_njoj8Z3mCrUkuNhVKUN{~sGf*g~FJnOEV ze?Lrl$99_PcBS+k>GY%$ZAfa^5{nNzt-NzKYKSv#RTO$MlB3wv%W1sQbwX14ZhRW2WySs~Jv-_WkfglV;x= z2Yss{S-nM$JH*#7^-lcP(*#pQn#bU2H5ChT^~uY33-P#{i;oIKqXnU2*F1#3kj@{A zsC4i7%a$M0aTIw!x=&YYdA(ig@M*j5*-DEIPSjux$uj(Rf}2^hCtD`)&Hd+&*1KkB zBQuy1-~RU#B=Z@}i<+JJyECCC*OUR~=&sv4TVGmpiOYIbQeQ~_A#H)+{Md2d+OpN_ zCvf%GL@f{c5jr2QX}R?Jix|Z}Furg3D5LOo%STo8bm&A@PQ{q?@Txig2=ud{?;~}wk6hau9GwtM>cEPV(jI|&=1Y9c@_Uh zCIcUS{KIaP?o61UV5-U-;Vz-&znQ#8fIf60EdP?9WfBm&@hwwN)Ck%a?UjTS!}2Gn zIg;<{V?`@Q#JO!oza~86C$LHIrZ>X>J;Ju&I(oKKPY-u?0rH5j=l|g5IlCkMO!>y$ z8V=f_p0ACdn5Kr_^r0RzPGMukUjE{^y}S`+^|-y-E?z4f=dUL{oPTUEA*x+4FkoQNbnj0OrL?wmFTizz$!98FBNIX1 zRW~-^R1yKVz`wy}WL{};KKOlXSp9KHh1arPb|Z8Dc+`n-k2!VQEuc{yO0Dj%8Mc@s z1EosCwg_Qv4|sMP+Dp>=2IELEU6dq*S$YGF(7t?o$&|L~VVh%_ePyJNZ?$WxSBBvo zKgk-&zgui8v9XDvsP%>~=V`xl=<8xOQTWOoaUB)x=SE9Cz4G+-!+vRkY%31Y=G8Z5 z6J5i^)DdK-knFKYWVRco?b*8u6Ki>-v2$t}iwV0o$P$wjjtZ+OCP@sP^0L<}%k^iZ za9{{-zW#sY{F{~? zXDBRn;NyvLIX{2WRwEHdgM`DI0jb|}rSDw0UiVGY1#W*5wAV|Lw|1bvvXWmhQhBjB zxRUp6P2ZTh#9MhmQ{Wx2LbH`>;n*Op zKoBeAQfZd(Eo~#W0M;{cE#|N~^J%FCae?w|t>}t@I+DhNpXJ z6i;n{>+ZywSMw5!Oakj>o;8Vdb#D-r?ooSiO?~s7>7NO-26V3sMD`qtJbD*Z4A}Hn z-5$;okX^hfQhK6|{mS+6TwWW>C1)@%1y!>frH&re(5i9pN|>|bl-=qi4oMMBmsG($ zcpywglf~v+KS!+PWBw`hM9bs+Mrj7QK`PP%`CJSV1a*~{x7ocZO#0ucdz;rsmMkb+ zn7*_~l`V|5)*40lL@h2E_b_126W-5?MYZ+0*74GA1WFzF`6iq>M-=Lc{8U{rlqgQ? z4&_0Y8SZV@8{HnhVU@SFLN}qXuDhi>munqv{(>neJo1u0doOA*!%yGin0M&Fv2|D` zm##&mx&P9HXU->$b22w5FedOtc=*q2TgRM--vm@QnL~A9hV<=jGPEm<92+qoNuEXM}1O?Ta5h$iq zG`I^z=nhBN<+eKehL14Yz4;H&Rti(kV0tiYmMrAa$H6(8KBtr=k2UMq3_0QPa;sFw zA>MDYOI@#|B)QZ%k{ioywJ!69Ppy!xZ0~+6irtuq2iXd2LR;Xp!{#WTlLh`{(8Kma zK}4p@4nL@v&Bfq{A*(yk%=||lUeDlGt~&M?yKUSA;r#9&28(oIjx^zJ0(uvbZuk|Y zMua2HE7$?*{rC?FEU&%oJdo1qqJl$RA5XLodO*RAcnU# z$Gi-Ar_PEq7cMcRsuL+P^sAL#5LNjtsjwMqZ2j8IiU|ER-ePP6@BV?#(z5{ueDjgL zjpmWE+SbPleLlWv@m))Gp{#hnsM04oEHV^zO6|8b)?i+p;w!w1IvWU~B>Af^Iwe)y zpfY(5|6rVqapH9NESM>Qjv5yYI9+1vK7lTIjW!&Ff0L#r1!hcO!aOPUPTW0X&Rm!n z)@<_+64@rA#T%bVNqw%KZrVI3P;#d^z85c&Q>Gu?Qz7LtT#MK6O8N1x-6?8B#UR>3 zYk;9K2xR9!O2|ki(42mf#6givZFtb@o(mqR?*Q-BHuU4dm3R zXU@*M*~)$8r2+!mTxTO|6*bIrUL$!sI$!yE1BGwfs zfr~*)h00e}JK?gXJ`dgbqISN)Hl6kK4D+7&eE2Q1h2r;WGS0PR9lMs5BU_NRMdxzA14$D-Wy-Pv-~l$+ij`ifkoTb@eU&!Z2m0)+uOK^ z3Moh*R7+BxHQ1_zTzg|Lse92ZS$cSHB)^f)cj(kAWHr|cotHWs?kY*j-(!UuOA0An zzHcI5GF?{U{6=TyI3SCLqkyK*Rg%QlD)|kYgV5BWmh0w9ZFKNstyQBcS&TxUX~(Pb zj6h>HkBT8|I@4tlwXbON22F`;MAkxlL0NEcY*oF)uE?$ot89I`14bON!syc+qukLT z%a`1Xj}%7hLb+Tx4_&o{I&q0r6s(ZR(?5D~e!O;;m{6^QC|^3LaZgf-Q7P?DrR%t4 z=M6e4jXnJfcVb*YFIr~gG(j)j;Fd~(z=sZgiy2&Gh}H9n{2`?y-&t9{)JN6k^4_Ua zv#eA#k3S5ZFSr~sz!ZwEzZccjW$1%GiR$H(RvGfNPAzCF`LUrhTWZi7um0cgQ}DLi zMHf_Y8V--r*ctKr)*d0-ggp+{T}N<2c{id})pR~FLDGa$!fbuEdE%S?o4)PFj`vN7 zqlyd=L5hdj$heTTw3j8~ll=|f9#4KM)!p{S^vBMn30WNy|Jm%1){qoGnZO`JIm$vmItk7V?W?zu7?6F0fFwraRjj};U z!oR9M|GU~0x`OhF7Q0lETBw1`%_hxN$=pAbolW9dWFn68;`(LH_Os@C%dFE zV*qWCV8dOx1q=a(>d#jlrs?*jmP==uWIg`#?avg-&k2SOIXM$;c@*0o zD<AOQJhA|vUcc; zbW8WX{tstS$ssj1O^hw<48NH)c8-;H+u|UOf?xW2p3>nOrZ{}+tkVcT(-}94CD{Pc zdBwy zJIgm!j#Ez3K;8PL(BGzOGDDD(@k7<$G0CaWor)PIAMD}t4FZmLWL^q$1c&4v0*v_x zzynS`${Lf?=kJzTB_|+y&Dd_dMCDWpGGAGQUYGB?ZPVCg@lRgJz`%oStL0Mco33^3 z*@B9=8bbeg0gYIJ4_5J&g-Iio(9gpMj6F+|3_iJV&^XS@smT}Lx2i6H?_cyeq|{c;E$*%@c87JS6LVCh3Vc>h?6E~( zd_`>;46(5W>o;T(T(kwF1c-&lSI~F0$cNyB(RylPu@d!FD}66~9K#$J{r|axD=k%i z{w^l^-LQqh`BvZeA;LmJ>xy3^x>m9K^%WKFX3`}cT6@Jk^=17`5Ca8%>hD2MMp|j~ z>UpK47D|u-Jhc`HvYRbNPhYQ>B;WnbANHE@#m=7)h-0i7Y;VJdXdVlJY@LmK8BU9F zmES|f1Uzk>lkUsX(kmaM?Wv=$m6f^1g-e24d$^+xNE6(3TKtoBr&S@fK{_Ou_O=bo zD&HV3{H~P2g2Pgf%U7}fku>JMB+_<`SCj@5wA0fQ)Oh-@M(o`s zXZT2ejncnVh$`u!mb!l!GnUEG+dF({J&_j%3;0iu$t7shkEwsrNQB;k=u>vC%tP9( zP3tUaUx`EZ3Y}0AhftC+jHoLJsY7j0hk3@f_fzGt8BHc>|y)*gi zgvfZ|mk@G!Xqx{B>77EZ?3HC=;+H>6yyzsQUinTl8y9Q0QQK7;ZxTHC^{aI{dfwpr zf2P05Y$f2I-D$mRJ*O6q=VLFG|Lg@2p@;D7)I2V-D9m;;G{9y(bxoS0pKZz#aPDjE zr(EX4P-8nCUFn?SdxTk9AtBFHJ)Zp>ax;sjPLw_-XVg;p2y39z;Ag}gXD$1+*1WkU zmRivDZ3gpAxvbGWr14-371qUnug1s;nf;8BLQ2Y}gLTTWr^_L9_&Cea@D*lg|5X`I z>)rq1=~#nJg5AI3UTOK1rjSdgDzwG@@r6i!u}T9W(RS=>S-U9 zRz)=>@Sg%d&0NgvWC|GS&mC0b11ynWmaFUb^rwGHVen6BchzBqdG4(PC!@l9tS6!` zoeuHa?*;Jabq46!*hT2ZcUEQ}m z$~b4ksFttN-)DbBUK0!2*T0+Bg_K>BS|uzNB^5{8ki4#o{Ie&b4N|1MG|3Ec*d_>S zqmK>#%DkD*B+^uhI3mvxZyZ59b zH>RaWN=iyaf!z0D_=_96{)Nie_<%30A3>W30*Okwr?=iReJ?G}fElv!m{`6+nmFo7 z9=}os1F78B$yaGl%vs+aCtDd<0b&eVieH0K20hoxu}W<*&AWLJ7?^`+(5?T{X6JYy ziJ9Rd`|mzSk87NS{}a~Q3A$L2iGu>y#~uz({5XTfIeZFiliBJx-P-T*_#&i3K4ge| zuYUNe|ChqW*HPAv#4$|{9<-X?#AJn)n)J@uR|}nzmQm`dsln0vedf_xh2=qkLQghz zE^26o3QNEIeA6F}vh`won0JleEi+HR-_v^7nr(8CP~F4FV9h5d$4)-ix^T=iQd>r- zijlO(aj3{8Fpwg6ip{1WyLpH)L@!n}KfqPb(Ztj{8lj1TFLad=gs&MD5>$_zHW&@o ze6JrgUpp@rE3bYunJbdQj==h}94G&}u_mc>gN>ZLGM}Y_>Ml%_N{@qf%O<7q`NQ@Z zPEJuz#^1e+(3ObBDkrt*9t3_**MjfZ%(u{mQ^j3$n2e~QSwAh_m zHy_X1li*vch2&0#F(-?|d3os?agkV2(LI^2rMLOHxA;ahV4C@5Ayb(5Lx*G01{w-5 zRB9Kt;mHR?oX33k#sRbEJDA?N=-e%pK~KG%U-2jW(S`3XbQ6{Ma5IoDYVrfT9C8g) zZV^7G=?7Vi{2$k8+@=`7Vn#=IS`D+;JDQ7lh4=+sn>{g9Pay}_%dM5KLMiyLBwd|z zjPd~98x>eL8S0yJcP~$4U~6Gt75-wPn1@T9^>2@1H+G5v#`&JZ(qI!C33CU>VMkp` zsF4B=C&Rxxc{oS2={ka3fJba+``ms!Z$R+2jeok24Y zCue7xC$4sNc@&I#PqGpd<0AZ8Yr{i`>d>Eg-@AnwD$?VogOVH<= zh#Q2oPrOc?&};+QN-3gkYJj=$CmeDEj<^ls0+B5iO1pQ z`7EK2kk`q6NkP+Vm(Qen0d(Evql0+sjKuDR$gJ#PkBF(s!|xx*ho7U;)n?lcaIJ=q zllDN`Vf=U77WYT=*^*$YvaHlArh&tT!+L7ls#$9EQR~k9&%-TrqvLY7${zn~Aocsy@~#U9WHCWhu(6lBuFEcO~ry;zN47y%3k(qY|Ir?Sr@Z({9U24aIM! z>)fKFqxY73QUqY}eNc85mZNWk-rH>q5no{)e7>#Y#4q%>Gw@xsEwD6+Xd^;FPrgmmfE7ac4!M@@CjpzUL- zu+~-S%n01{mr;eqTQVVd*;HYl6nO6y?ru=kHK}QhUdmdQz-H>mdi>_R{(8=%{-&$s z32FaFdvubpuyAXCtlHLw)n3sfjtZSut@qO{&7-U}rYcq<2}#iv(`CiIJY!J4E_Mek zLFdroVp8tzFX-Qs{~)j7!E6Avt#-A;Vzo@RLc&4O2y7BLF$@{TG*+p zkVb847bEu<$uSN}$KSP~YR?CHFz^WZeu$;v|? zGo3wJH0K@}z0q`^o8|Zm{XA9K$r^*3ZOpQtpBEd8^b-AXY!`NF-XdZ|MjUj5Ee5oh zLY#xL>pHF0ZP7K4lo!XT+y%<9?=BuujEA!>A7UW537F(xbE~bJUSW%jQJI29-{o)X zqcArv2cp5!y8eWds^I2TWzW8hsnb9<)Faebb+PQ&RUJrMNo!T>(}WPcUnaI`%el~8{;?E&F2`}O%TJLAaIsE3Po ziIK?ZL?_b5D#vL_I>EcaYUh4PyK4FVh1F$vl}l8%s>9H;MrtVsGDdk5V&XnXk-7(Y zHy@>A=qH7&T=I~XIXAP6uq2cedkiV8gH^5jHK)&$M?tQjqa}qvsD9RWw&M?ev;~nM zw9Dmg{GHyLws-gTPQ8V^&yLD12TJ)xz0X|D=j}}mHEZiLL`u_3a)n8)?gSX>(s||< zZhm{ZqJtPFpmqv*QeW<>Aj>N%7NI4AmyblUr1__?7EDKBIf9>&636LjR(HB@s?2u@ z5cf&(5id>>PcE!P-w9>?ALev)bR>Y`2azyeoHky1VAqD4D^^!lM$0TB0zH>S(beTc zW^a^X@^#j+t|PXQKWKf9y~qf-)Q9rzhPbHggTKdS`L7B1-Nltr*gHU#-7r+B>*%@Rs4Y|l1d9;aNo zZT8LojJRA9Y$T34J3DI$xo5OC7qAi}b3mvo_7e0d^$hYKnnYb=D6q|thfrbeKC-JZ zH`Ba(J3vOi)l#!WOsl-YPQGVm1SJI#^ZI7R#urF#8D^>oU9q&ZtR4L)?XA4uzXhWv z`nVgBsF)qNK3(t896)e-xFzAXn-S>bT}|isNUJa ziBH1!i%>Gg@y{M7XhdBM8I}{0l&I)`WElY<-GTBY-G4Z*U~MHC4|!Qo%bfltV>n6n z99aW)MD$bUxbZN=%C;tG-qXn<*VwvC97UbcB zw1+MjT`U?gDa7yBg5-X*GtX7e=alsIky_T-_6Lde2_1KQOAZtw7Pl1Nf)y|C8sS9! zrOM`|w*fZod#^*RNr3dnsU5LztuSKeX9^lY5XeW1vc;EBAFt!{662vY_q2XtPoH}X zBda>LFxTAFx*wzNl~aQxmX=mFafT$?1I7DM%688+3}PqF-ws%@sXrXtceRurMRs!) z=~z07&F%$=U8D%(A>1bM3bJ~P3%bG-Jm!YU{@QxqPzYO$a6dzwQg3pF!|g?P85@{K zDNr6-QeFxBBLt!1|6*{t#Ad9t+HtwzWGxT4msgEKfR0yAqa%hRfzPu4i&kXlhe|#( z(Hx{9acyaiKzXxfSt@-MgYrEkXs{Iri-VY^!MSW)0elO$MW;Ho4omEFMCRiZGa@Wf zc3*vji&}6=a|m`j--txnVl;`(Gxg_G1+BH4S}i=HQIoy%deBe#sNy^Ai|BQFK=L(}HFU zwgr;nWW7!m)}horR%Y?D_RltRBg&uQG@`&G?XM1SNq6GRRMI!tU>fBFOG-tY)W7SHLDxpMQ{A7`HCsU}34+ ztig1{Tn^U9F3-`INrG@g9i6e+<_}zMaX2Se<^Fc`?BVHF4W_Wc$I55%zJzxj+@Tp( zIc3gA)dP!s#RTpcdu2LS*Vg8^uCDjmNkdC3_VZ_OK_gWenGb;!_yIO-kFFeIu-|zR2Y>*64HTsum(jhCm5bS~K|raY8)J``0i#bb&Z zlN*V^*>N&p6BQiH%rYvU_2Bi+qqrs7?017G@Nvt=o;a@!%Inj<<-5wg+)Lew!UMy@ z2YoVhQ=WTWptc5O=yJvJ(R>8jZJ8#$?+YyW3Nvr>l;Q9#y33=V)dU#Dn@TAJbUy$l0p~ zu~(kAN`GUz{&X-`jfCk{6{fH@0Ji<@2Hn{P+=nEJ8eX?EfxbA%EV$G3;Hu&Cx)X&$ zB?;L}O4&A^AAnD9PU5zkI!si+AjW)D@Y;}tu8|~0=bS%4?Hb(gv{E3opp+m08+_d1zEpf@%*yW892M4Z>c1gC}GeD|Y=-JyL#5%Kftqr2U=Q@jpz07pO2 zc^|birv$cP0gdLv1ecbUHm7PUYim9FGhTusRuN8q4)Aoizn@|4y4NKr{V?v;3$RI@ zj}>BcIzD1sy%_WI6I0lU44BobGe8*t_A>xDBhQ_dk%j|QrvxRRf~e<_osv?|a*B_* zWq$^6*L8JuJB5c<_JBc~o0|x<*C7~6J2=ih&4zF_0IL7+*s4c>QYkSp5$-up4QjaN zV$7xfOYxJHbin&Waj)^$+zZRg*_Xv~n2ilFr+>TJ+q$KA>yzYHHNa#yo=$BYpg_NB-{|sW1WZo()=0g_A+3_M_wk8| zQ$uwPX8_a@{pRN3CdR8r^Gq`H@-PLJ)9&D}E3yD>@IG11zB)tWVf|M0=g(mF>`xCi z-~cV)>Z1b#BoRO1fK5J^hdz~KHfJU)cdvL$2dH@^Nk9idsHByYz~0*G%ZpRcDMAko zVXrXQ^zK@=ViFi{1b~3^Pa4D|h{^Ir`f)G_PmtiWE5rReS7_R5IJGr2oL(EsyT`5_ zS)I8DK6cpqoX}q~wH64KR^!PKn2-+}Ygd>=S&t;Z8z@6sq)fp{s;jF3FYJWwN69V# zLR^gt&>!n`de6``wZ8rw%mq;tAiax|6F~OleboJ$KsyUF>bR0I8Z5 zmsk4Iea`0TfW{uqf{|YwFN=wZUG>+%-Aw<3N4~$m&nF;oaDKX$9w9FG@NVUlOTq}| z3azeMUK&ss%nQH|K-6_@FqaD`cV`^$RZmeXUt2|4*>0sb6@7Ve2*$eklg`HzFa?y2 z)6OFXz^JQfIM?OTvi*#p^VvX+9BiR4fvnJodme$b;RYnrqANby)(+snpw>l0Qa$eRWj)8Arp^@#Ti;Ig23JT911lNv2XZ<=JOx1fJwx;WO;?@NlkGo7F z#LR7NlcS<`K1iIUmY47MralKnE;#2{jdNaOX;QMi3#Fc#4sV3VoDpz=G{7CSD<- zqi4Q+;L9mK7uDI>%WOq;JeK_rbJb4(@vc%gxKGSTQBPaj*MU`_?#4WEz`%@^n8+9y zBvn=-Y;4veJKgeE*VoSu8!xA(r!QKm;YUYDHsj@%%iT#NN92^{8zkXeGnxl@~-QB$+&aY^;l9Cd5!|~FOAd;@m&O7&owt>WVCW*$@*noy~ zK&7jzt0zz`_4Z+Kc%2?xb^C!DBnZOq+`2{Yr>(6mBrHrnio?B21Rg=AaKG&j0l_}O zVyuVrQyYXC{rvp>yS_Z0A4gdOCxcSVo~U!%`|gj&!NGx8AGP0IcDO$rz zXDgX%cX@HnteDsf680o50&#A1#teh7j(z)%4;H0W?=C#u~Ph@PRLVRBfQf|=RkilWDLbxlq0gE0$fX=(NM z`Hv{@Tm5d42*9V$p6&$1#KeFUC@3y|0W2IZzcC!%2)J3)aKg&K@ciN3YM?tn=0VWF z*)P}fima@x_^863KH#>mFc}6*6?sS`n07p5Vl2>e-GZz;tdzyt`MtfpZ{NO+kEe>3 zla4mnc$qh3ZeekWF}kb)!>@712*AcobE^0E2b5xCV|}ngT7wZ{34&kZ;@sTbRjF@; zy?CBvnE+hMTuTTI4b6uQl50)p^dJRt@3XS9UM0Psv>u&AHeUf+xG6&AV>!hx&-T=^ z6;b8o5B;1Fh=jN}a624&75Q3yo&}nEAk%4RWUA)Y)YeW-P8yq-balR%m6&p1m!iD@nFgdf$B-8alpedNwwT{x1`M_5#SWMi&}2PH*!I`Xg!f zueb%~axmt3(FpjOwKWDLhVD4t>=7@Z5TM1Vr>mPIrvn5BA0Pid0#z&`B2rpf`rg+! zJuMA5Q+mH&zMH4dJUu;uSo%CU-yg6-)xa%hfD!uq`SZ0Kcfi8)6EL#+3sv);WEdQd zo|@WNU%yXEDs^7Ag#n%>YhX1%>}uhssc0Cq4Uau9@VM%FF?n`uY;06vE+BJpHJ*Kx zlODogr>3TWP&|0>b!6C=2=b{NM3Rb{I+qaxgppY(`3bAMW{^~xIxC2k!n)QyBBJe1 z-ku+=t?}N9A>;4;KYWnrt##R)w1mUqHwBbeoNE02rNM}&Y7u}7O8gGJKqQj7zkQ?U z;VFe*@&bL*)MSd11tHg99ok*&_&Kk&0N4nm+~@KXJ!T`oFNrn5VBwwp{XDF!YY5

DVKZ*K5)vBvIJ~Tu|LNZYK z{5en)C#U_zj#w`*FOP79vvblDHwO?zfLeh2jkx(&so!nftAt5oAVI6NE^74;ZoORZ1$VwZ%mJ}v_{H@A?G>&%B=rlmS%=9Cplz}{He*bG{s&S{E+Lqoxe$J*GsV$q0}mX^=u z`5~Yc@GE_NeO`!Ea4zGLFYX>br#T?OkVtlRcAjK?yn@0R^5*sTGcz-wYy}dXJP(PI zeRy}(sb+iIZtc1l{g2L0_QzL8-%0_{zF2mhv_2>ji7eMG2np$U&ZXloIlDTLZDL}= z{OSw$5#r^;k3h@t?s3|n8^qYz*Q2!zA3vVvu35uiv3e%6ll^( zcze#&j*X8iCJOB|L}!7z=&E#l-tZk5EVA4GgtX|EnJb_}z!fB)Ki6T`?C}}ZEfC=4 z-2-6ai39C*vx|!huRVC7VZ9tIikwq_6wN0mCwG&cmX;Qj7PPM2INX2#$7dM3xVYT9 zbqlbnz7?>mV|niuJ*adM_V$#W1yH_tUtizGMjtJ$dkJ01;$Ah6NG3oUi{a42rG!@j z7Xxfwi?O|hg~gjUZ$O$YQrno1s;oTR^11YAKIohQ3Nm=NqLG2u>oEmBXDnuBrgv%z z+_jDStp};ft}{*V_V=Aox?)XcU{W|^eL%9lCX@W-)e>+ySN)fFbX3H|&(iyHi~@BF zK<8m;?--KsYCPVen5Yq44>!Z_CY6aOw`}r4+j=c1yp!O6qArmt* zGb6sjLRwlHZZa=GLsNQK$D%k$IbLOwMFzE5>Z~s>(KQDxuem3urjnA9qUFr&?1~>@ zj)6n)ImZ}*`1pnjCW;~ob8>R>^5h{=`ZZ3u@b-%x7JyYy3Dx78@#v_i5Yzu?Z@1h& z<;TMdX=-{}pqV#h1u&z)t}A~tHzx;l#kg!Is~+2B<}NLnqjc-t_LkmlEp2R^_serl z2~J0T`LZ%MC#jJIdI;jK+YjjdIu@xEevM$T2L}iBa`HnXBPkL-4He**MofBwga9Ve z3+;NcZ)p`WXv9>m&E8-?k4yiftE&L6NrV&ng85L$Ycf}DwLFzenhOa!-6sCnt5!jtUruP5)u-!vn_nyd^|hz zM4A~DKEDIMTHBX)HT1OtE(Hst}_P$*<03+!OCSi zY>SNo#Zb(4bZ`g`3?vF^advhlJYOkE*P?$Q2cY`w*{C3pWpTL%eT4LlR$bp zywA?c3OGSd|B##84%EnAgd5HXgi*b_M&8iL@iFC;8Hr?us-?6vpzZF#fxrnAhvH2j zXjq0ug5n`7i;0>#0c6C6mYq|E*bew~-J{qJfJ2$m=TCvn)7GZIX6^yMB~eI{vV}Q2 z-czSuxFOdFv$4s~&Fx!t^7i)j(qoZe5lBc%Ote{{?W02~VOztf74XHe&KGBHv=K5l zL3_sAWPcu%U2AJ=M@O#BfrdqJ7_8p=T!j7yuxn5&NdQ$7lXSVv;Najju9#kcg#P|3 zPhx%gpCxNt0E659@4L*=hoXzgx_WxRXYo^orKF_v6?J@Q2NF&~LXum0s#Ro26U{Wl zke;5-AR&PU-HWNI^LG#t5VnGXff$k)gYWF5nL_vjX5kdd)sn~yzTt-t7{i+kk) zTIXP>-%`S;-bP1jfc)w+#f7^H5;-UsfwF+KLRj8g1n#+@0LjI}R@S+_ zV^CxO5zTT)^AL7i>I7{Icg=9sydm&W;355p?tC!e(*-t%hP8nC$`c-3TLd=HkBFDI ztbt?rDx7bLR6zzaGAinWW+|myJWY5HngW2M;D?;C)^coBH_V`#g5|)%0bLn#=-jUr z77^)==f}JgQQZgG2^1p$_MlA%95vmF+C4HduvY{Z7q@iGhLxMQQ008|$|myBGLeVm z<>loPT2rjAuan-q4y>?WWMm{!`YIkEQWj4i;H>$6wQBC?Uy*iT1KKWw4$ijSfAYdD zP*@Gl?i3dnH{1yMVQddN<*~6^Xn!VW!+O(^0Jw4Ba zbhUPl&%k6R2|Jq46t?-AT3gq;W35Q$2>^i9#d;gMs6k#;W_fs?p*S))sIH|YBPB(_ zI*U|CzJLE7jHtU?(Z}azidhagY?KZ^3N?E49YOx(!@#1E>PUWOACN{D|b` zyhV0SArn1 zAD94~ww|8YjzzynQ0f~p8#sw1DYF30c+pt6xZ?^&{)tIp4P{#IdFhltlk3&;^01MNDFW=M4(ce zUtP5Vh8EEB*p&{^Qr>qS7x^cm>H6J>EC9Q<4V zA%dia2HDWxZ?4oRK@jx%1yfT~LB^<8{ITLB^8eU-^KdNRwrluml8OvPB1AHlBtsb@ z^E@Y0rX)j|B2$J^NFgLsQpud55HgmK6iJ38b4Vc~W&GB8xu5rb-|zeT`|rKBXM48o z*Xp-MbwC z@JvkcDJj*Cor34ijUqxu4j+3KQa?1!MZbl^20sZI)$b7Rfdd9v2B;{cH-C4Rh^2dl zH4C<}5jMVXAy0p#PE(3CB&+Z>2 zPkO^*81OttMxE;xR!RE^LdN?0$27ko>QCQkAL@*aj-E4mrYA`WgiEe4cY@A&{aT@I zar3QPh#}xzub7l3M$}n@-$-!Vd|l4Uu2*)V(}(}SfeLUS2yTn@EPxr24fZOgq zFG}0C!!Q&Uwl&v~g^^K-^)$i;k|1DUFhR}u>gq;SR{DWkYB@g#luQT{_oa4EQv^nZ zkP&@3jut$A#U>NDJ6T(!K@R?z_yXDxAfc+Ns&c!Nh^Qzl&|_otem`|4zSy@c;!e2b z+e3CRG4aw;ViPhmGcz7Ec|G6~!6xkkz6fi9@?)Cb*~P`hsKD}Nrj$vVUK(=nxpSL0 zZOSz+3|{az5`Gb6W2814d$!T?OPZ)s~7s^K*}my&k&ThYZ`dF%F76O% z>FDU_P7@s)yFW^0)~E7e$UU{RZYV_{N^Sl|H4JUJ{_4Sl2j+FB51CgWanGOtqp2I+ z5V$#r*fu&J?Lb&GB|F#HIswQaYR9n7#kTO+A*=RY974M za$g!8bav;DV|%pn-??WQBmzs{xnomQrQ_$f4B`YO{qoY%+omS4;$>z|C}MBkM46n? z_8rik$ef4#o`WbUZZybg_ls%M*V8jIGg}b52-XL`27wGA(fP^~9A;RBzm{DLp&c9= zl26kt!V6XK=FKerM^H_FV)tS5bU@Yp?%nL%9BZ}#6Onseue6L3@fNiSA`y^k+8{M} z=f_no9&T>q9(RG57onvX71~mV)PDCZ!MD79t0ox7vU8^a*u{i|#&2#zLqpP1QXAK= zOV*0Kb&DttS|!9jG_5Qz%7C^C4h}|;*PW(F(720=`15D18R$IUWVUkuWgmV0wjJ71 zRAM)bX!yc`lu5nnJg^k3vo(Q4xU@CFKLlro&-Nv_dAg|oqbx3c^b0qk* znFrLDCb}Ww{2?fEJ35x@a#1NMz>gPfZJ#3`LAHSe5Yg??)!lu3?vp-<3pY>CsWN#G z9#eCa8!FBFa9fcx=l4?tSvfjNnn#FAW6dTF3=Cj<-?VX~&Z5Xeol<-kh%n*(`>&6; zS?-NeL6N3U5j6ctUwd~YOJqY%Ru-YG0vdo_0=@*ZqnbPom&{>0~JWk_grKTSaLNsHum%^;Rw??b*jX3 z$~?L^V-9&LI~ah*k47zYKhf!+=|Zs(g3l7ifqGhhYo?xRc+& z0@}V$1gD{I@%ds|&+5{s4D!d&{_DxK^eikW()Y$RHmAt2@7QsMDNcopP;^i?K#Gx0 z^=lp)9E3a@la%zOt1GkBj%s!1&9JblrI{v#3NV-IX?nH!oT8#AJ^lsLMj$X279N?~ zTw6bYBoIQwZd>>nH-%|e*$63;ja;PCCu`Ac-Rb}>at6tq>LJ!SyO$U%5X z_dP?5KmY?zoq92*(FV59YOiVQzBoG(6It0B;J42L+vao!M@JiM3o9!sR{oS!>+)0( zHWs)Fo|u*CanU0k5`6ceieFa^b1E-Qn5e034OdzOukTRgdtZaw(ZL~FEe$FZxR-%f z*UbbwZ?nF$6aol8`i#AqD4Y*f&VEEG4B{wVEBOVYfTX148Ubr)XjlaedO4X2suDPw z7q~-6TakN?J+pn!Tx^nz8Y>||m0?|1iL-^Hqd;T>SX@vMM+tAop~_E%pXFs`WzU~K z4^@)D#gDHG;YCM6vm?@7SoMNGbg5_K>0B;n@yTXUzoRG*D@{_8Vbg3n&g# z^|A>5RZq{{=lgyT7(g`$(*m(?p^?PBx1Fzy1=MqJc(k6$q1dPOk)m|m6L*Qqsc4V) ziJ~Z&q~)0@gcEMHjG}P%!~gkNq_ur-LWxo0l$?=~(O4aHm|s{J&@Tq4;2*^GOnF-i zzqxiC(%M?W%#T!{oh(rdyp3c5H3V?#*RNkV>MYCAP!KDhKGn@KxG&-Hwxz`x*|)d1 zH+cC$Lc(Y0O3Hs~6W&6%1Mf%(B)D?yltSF$?4uJ;&oqcIzfadpT4;KMJ+=V533jd5 z-(Oa!G2q(tba#iTVF9EWc$}LN5qViz#~?p~o@IopkE0nA^BZy{Q?HY~J&0389|N#f za2lY9!g@idK%M-=yt3Qwz69wODY12R-#SuYh@qL;5+sscyLN$)h9ClU?2t*(o4!5^ z?ii5s(~t;1arV~LorQ)49uXReh|f>CTtlMFz_~?QAY2NFav%fXR$2ge$i096?t?Dg z%g_Tm^P9f8rS4b+gMBwX-flKD9E5XZWD8(wxL{~C_7eDOq+`&Nez;XMe;1hqfU9k7 zN3a~g7RCpVPDTN!Mp{x@Yzy%d{gT zdVx@%ZQZ&xb1)ks8SDc3z8=3=Odwxssj4s|32%!-Hw;-li@VQ;tLjxn~dScO*v znsgh=7ua4R;UIyO>?2*0nQ7OVcbb8L0k{Yp$Bi2|up5V5j{5yz*iiFE7B*(fPK!k0y(VGy-jDx0#-JJD_mhoo$@3bl;tW{_fZ@n9oIF2lk(8Dmc6M8oUg1KS`YsnYz2x za!b)`h8#&!?|}6RzX%cp;hCInV26%KID%kZ+{eiYkE5-7W3~bRVn<&_4`{>$u#OPW z2w%tiNe7Rw7Sd_T`+8-4&hG|^4M+zrBrEbs+jj**#Q?5HTMnWjnCCzxCnBWc1EHKD zAFGQc9i+cu4oeuaGKlU!Ir&x09sgMX!<;mK8vfX@mzMa|u1EKzDjNIh=0HFxO-&8* z!C_1-EG&E|e8JH%hZun(f>ymRU&^Osjue}`AN?&UAu;PCUEK7;qhbq5iD{f~9f|5N z!EVJy@M>_!j8_REO-P7~cQ!W*a&y5 z<_pKq8vu&~x+2@Xs;$MY#S7BLUHDD_@kGVM^wc|QLuiy0761MHtE2qj2{cz*UHwRu zAsXDjJ1dgLoSS4b+K%msXubPY>1(O0`~gNVV@+VT0eIWn33?ea^b8a+l{yv(!qwoe zAYS`l_H%Bw6k>Basr^lG_DNZ{egOL2oRv8Y0}pSC#bm;IPGIH_ANKCt3Xo0Ba2q9` zd49>WXOHfd@yCuM2jGm3T@{Va9HGXM00SJHM`7^nL1m@1M}(?ioIb;~V5zPe>!(;P z9Xs+cX$o0UXVhoEW@dzE?H}BI0!Ar#{|}U*chvTG+})?jyYqQb5$r4oRPwW-3ps~( z>eJs)Ae20p;j2;~`0jG60!OSpBLK#ykf0?PpPs7Z8jcPRqx8m}mcOw3$dM!5G4_s* z>dCwL1Oxz62q#x&^X#b%VAp5QKBCe^!RONd2GTNiGvtgT`SK;Wvh`PF zAL@Xs5SNx-Ms8aDL`6yI;_12Th64EX zh9Tt2e50qkM< z$|dY0f4a^9fFkOm#g{18aJ-1vd*Om+YAehXmNYOclxqt=C5j#}fCH&%7>Ir_kKg!CN!!XpzqyED_U%Td!3r|`(gz5=US z6d}L^qJXbf4q|`ai}&e#uEA=;ZKa>nJ~1%?_yayxDRu5%dp>ncw`b?!Z;(vgd z0Kf>p4Dm$CmlJR8c!<#{HTl8bVeJV*}ozMA&xz`%0IS-v8hK zA_+095tsk@Crf_fJO9_K#(^>Qrmt0gi%=zC*91EhUs#}FV=~6Q%JG(JE z?cKyhSQgm%RQltmEEA4uh|<%jorDuKD1zWq1vFtToQU{}?xS@Jq{U@K1pf+p~QX zDV1=VDRSx}Ai>9=?At+J(xB@;YG+RQ`>$ZZ01VGEJ#4kxzI{7DEF>e&C_7Xj0HfD# zBV37!h=9!Y^qg-^Iz)c&><=IVn07!NiQYmU5=(k-Td1$EkI1kbSG@$E>UG-a`}YMI zZ^DxZI5zg4plwL~S2%iwl#mbzvo1jd<+~?BuC2Ja9SRlmnBI#>gvh&z}WuS9WTiy>s=I4wGt+NL6 z9vDbsyr~!tEC-69IQ6h5@smg~AC!I9Ti!zfh_*vOC*SQbj>Gs!FNd4%;_{1ElPr;t z*fhX)pq%e?)H%SY|1Ea?`t_(7l+KuwKSh4aKk74|V2@nb9#&_a%~}M;@joGIND)2g zeJ4Pco0zCkZlR?71upgbF>=hL5*-%5#lsmjhDsiC6hQjs2jtJI7d@U5@T21(L;@KZ z8RCxJC+Bq{mNAJVP=WzQ0S0j$L@yU0sGooN3NJ^6I(I)>! zucF-!X$ybcXMcKEs&Gm8%x0FA{c|~I)nxPR(Id{Q(Q4$c2}(E2p+P?l ziX~XA!U&ZW>j3>6c^XTB1(D8oc63}s4d+9>ee)Grke4BA?-epo%245@dIH4-tOca2 zyTHWYnom$hHGSJ9Xodt|QdkIE#5lt#w4RsZVvLNsTpC!g7*qi&Dk@AJ=g3PY#Vlx1 zMMz)Rr>KJQANOcEW7SX-?5Dp$R0pa1f?ke!FJn9HVr7+vb${T#k)a{uT*#|eudr@JE#;4fg4QiD z3LoS?IE#1h--mb@8ayu^P?rBmUKJ8W|HOo5MjOO}ii@LK$y#wxIT2~lHc|qZ{|qL4 z)OBQ=6*V+|j_haxN-U;0)1pU;x&#)(axT~(w+Tn6bksxFZnv2Y|=i+%EL_zn=S*+GPxi)de&BQSEjOH~GaxQf zX!jts5Uig^OPyOzDrlV3BkxL5{jLNJTahAg z>ud3Zqz~Xce@^5};#F#L1g`ljEc=z~z!Y&QH9JGaYnG`Ce(>`1(^GETcZ{4uNkVm` zX$k`k@}Vccz18A*@w#SN^3~tkwf@Qjr# zT!U&-BClEck595_!C!{ zw!xWbDadlAk@$z2)Xl`7_!Z{zZ4mb&{sje^IZvLP7y8_>^FM&J{@JTnatRt@Z*E2nlHWtKZkl4ObHl`8 z#0-jRUvE2mr>Ej=pTWDR@yS_l(>}Ic8-Yzz(@DHaMqy0U($?m=2EVM!(R=2d@SRizk(X)% z7_)`g+qXY>!qcmtYlw!!-%lIZSpI=8!K()1;$4^?^{0aoGT~2cjo(T9yOf^J|BTBZ z{`3C=`u{&m7-5!)HPA(@bWQ4$($e^bq4rOo&|T5rZ;6e7|Ic_+wEOq^K#pMIwAOU( zk846chnj}uj+#N)SAuvii9{3JFa#%fd0t+#ke;ET66Ju)Q4AFU$Gy8UYhBF;d7@0S zJOEQkPjx`G?B20sOgnZII(?Pcvz{EO0$n-8#XZq5^C@M+h7IuKa6Cp!(Tf)*dudU& zZbtcvSE__EiAjxI9^N_#+<`wwLi4kLfCB%d4?0R*Dc5S=`lI}XS7={-b3?hVyorT3 zJUkrIm-G4a;Ek!bZ?C7=+#hv?JdNT^Q{L(FOiOu7%YL*^J%jEE0c2%}eN{zG4gFH^ zn4mMff7&ZmdJS;~UeS3;fwqyi0{OF4Vzj`SlfbW;FHuqf%CshMlBh(<;iLXGI8#6y zITby+;tMHO z6<~8D)!OxMb%=UzBMf4ZqV$$eaaEQ7wRCdEAPu2GbrG^oX8y_+j`L!WJYPJ08bzxI z8<)9xl~rvpe2r1}=r!B3N(w}mGIe;BX1LGID!lK5@&L^DNb+l&1Psrf?dR;+(LSIdU6Pe`gH|q1)b#7WyRGK-+*w@L z?2OqY?kaosn}~WIXILWkZ1)yYjok_Io}ERd1f2?!eFUxE>C@7`>OO742ktve_^FYK zQqU=Qh?WwzZQ>@IXCy+kO-K93nTG98jVdrU4khV1mHU|n`~m1tg*Z@~uEa&}Vb(j) ze(7G`q=;GlZP6n(??*0N*Slo!Tbh-F3dS*x1UO_R$m^(NeB#7QG<&fhPjP0-%Fbqf zkj4C;;zUS@EfU5=WlB{I4Ut5-3AlGqLxM1>09jj5@Zoi~8g>H;N#LlH{IQ=xi;G2r zUj7YlI+&84g0?$*?TU0-9(Fm(sF@p?5x)c`>Q0qtmMoq6xbAoRccY`}`Fnr;Fb2+clawrPU8@FaysYiELj~;Y z6NN)A_|kitlIq)PX+*;uTFr)vGEgX-3 z-qUYWbvqQLVKghd0{~)5gMt0XuT8p*rO>nrF%{T~JWiIOl+>1F|#3Y6Lgj zDKoP@?W`tT^!RIhH?15BTJ*#m4P&<|#kGM(hLxr^6yz}FM*KIVGep>$?>xjd47{Q{ zk(i({QWN)e{%TdpdpL!fns(f*`xJWpdL2wQ@Kk~g(MWAw@ysf?{T4?L!|NOa~)StUrl=ha84q2V((>ed$B$YHH7(KiAUKjBWY` zhG)_v2Dv+&Mf~_Hi_)ntB~x&dU!xUEVr5`Zylx6_Cpc87o@k4N&JAYZ59R6_bE47k z%?*+umF_w@%GAnej;u#biK2p05_iiZzMY^%+Y8q<0E)$4Ar#QqQ%|0}6B?YFVrOBI z#3*%h`_I+1v2=2w2@Fp!F^yF@?NHsk8h3M@<r==wglAaE)V{yPQUo%C|3u<7aP z4WAgb_E|l;cI_I%3w$mps=%nw%Grr@!^8|rCzeRreS9A<;H|AuM76tpjS!I%icHBJ!6m7rl3A zv(eX;yLppK-@+uzw{S3r+!*{-EhZ{TCr8-b%1uE9q^ZZjVNd<90ZR>9EJ574*Dp-e zLyTT7wDN~vx}&WkCC96o6MkYOrr&Ep&>Z=qFJM*rWf{TMfB+2=kRTIPs=e3O#6wK5-uj}ggc7}oc1A&fU9(?WEt-l+|XMjx! zm2B+Go{K`Dyg_iw$Cot?O~Z=l2TNS`B>|3WXVcHx{IDa9AJFW>n9+cV`?4TSDG=T|T=yY?2L4}H9Xr=IJ!MWwXcQ?C)Ho z9o!>T8c9hy!%E(JwbQi>TH9nu2@woFx)7!UjrvN5^oX9$X zu@XS6kSNfXBvVs#Po9!PfrG1mb?!-|+)E22Zd*#X%U=*BcoV9(TqU0kTQslRI$>E_SWa84& zquCVDJo)+f8sEJ`_(Mn3XPhUBwi6Ez#j3@E@qyQ_dqJHdC@t+Q*n7ANb8-auG&!UW zb6nFf)~ZNfO7VQ5$)$Dt@h>L2cFj08?yrYbcfNq=*VAKmJVpETD;r@@8(7h-`wlek z_^ugs(VyhWdb=-X@%yHO+548>S_mRSkPUNi%%$mJj)H`=H2T|z|pE;uIU1pXV z>2e@|{lfYyfwaOd1pr~TgqLM?2Gi+md%)zcekaGjeab8+ zOYf>3WG8uCf!kK)9T`IRTVeOX(l7T0O)9<=EL6aS5VWf>$^_^PNDzDGWzX}fsuj3) zzzG*Br9M=;?B|D1$EvStn_h2LdNj^;?e>Fs|EaSRvK6lyD;+zw-q#ZU49K`9AJfF0 zw^I1aPC2#5UU2XJ49e=TjrB_(kDCZ`Eb;5bDt}V5wo)Hib+lvKOgckayPAGL%FWyN zz^MMfpD-O-Cd$#&=krvbNYkT}LwNq?_HVV>W=brZ6At2zV*%l7}KVOMK z0C)K6Kkn5i`fKX;XVXVBSrY+O$FozXE=V^n1uTF3zK+DUg$(24A7^FRqg5ZL{!=7$ zu$JSCKWW9TuYg(o^y$;jujQQubx=z+w6w&0&cfFJpQA3Q^EIi=Y?2gWPstHrLo$U`}s;NqO4L+yb(bRKF7_7$Y*tUFO?B>=@iiCz`lLm&b)sKN0E?( z0e2f5!k}F7s_Y&6`Ln`xsGj481)25`I*$%n8=idgtew?C2%jM!Ehwk?6eicOeWbBD_5mq!Le9-Ur%vbcCY>3OyGx5=q_$K2z6 z%XX$I@2fr^3S;015AyCWFwwB`-YRMoL^`!s`MRb1QJT>ycKJ}s_{~h)BNw4Om*xHN zIQ{$M7wUVC_d6Gt8R>XvTxV$MvJULFGyzo;@UH*iX)y>eq3(o_F0stmJ>7%Cg zFl&H$kTAqa{i?xJ-E3c&9p@`ketki2UVe|@z369`>7rD>YMSg~k7cVAE;zM=2;O&bd$RB)=ZFeP4n2xI4Ta0wHEr{BbNN&hmt# zlM}iNenGp0W6mOA44-bR8-6E&?sUj5BZ0HsTmMO%csnC6?auILWvb%07NGq12SGu# z=(mJN!0U%1v(LHwDCHHd?p=?w4YXc|*=A=dhXv(~sdumLh@$&LUpkT3yNM*h0U^Af z0%wdd3ZPriN3&{<>; zv}xkzFMs^he+j7r2rVu)_C}~)))L0T?cTZ5y~Qa7zb0_qUO;^qrrd)p6TLmYip1V~ zM=x-8F_HS~GsCc?k})@_pAPI^{a0}5uwR;Y{fh`s;AqnSQl)P9?^L4V#MztO0)xZ* znyUuOZrk4>^;{%|shOR7A)qSqMgv1S$w|(51mcc z;^FL^+W#vR;TGbu$l=3J)6)sEpp1PX9)pr-@5fWa1* zmOuO$7T}z46rO+dOhe&y!r1{56&>+aDp2*%%h(vx*{O}eB=9j$Jul76)5>WN3k^|j zIr4P7I{pIsBR~-&9Y%pb5q3kv6}q@aCJ8S{sW^;@#U>Z@^rBx{($e8Tp}v91^v&Dx zbmuM!&THE;Y?f-jTI4nFJ*BSTPsKyB{6);ir*edmAMsbxZCHgEYK-LQNx^|t5+8)`_{n=kKSrQ0fDBXW05l!9lTDRe#MnaQoB^9>Gf`z3 zqB%xm5UvN<6P`a8g9wbdIlewVy=EB6CakPJO*O^BBMEcRvuwp&_rpLV>%#Zwt6t-2e@Sq_r zM-V@~0;BaBUcUw!$^SBfN}r7l4zu1ec;B$wjJg)$N%=j<_Na(T?dgOf9V?xN0fSX&zMx5 zlusztxO@1>>&A>PH*URnR{?;?#K?GQbc45M>K=Z#B(*}*fTQPH&CX1SoxJC_yMtt@ z!bu!1KO|pRn$d2F{LMKCU;~G_GMl%;L!DXwN3g78m>!1KU=k2UKvau3!q={v9>oqn z_#>s%@0Z_THX*h>;ihqyApCg>7`8ynDZMY{{mk2k;C1~U1@pI7?X3%GXZ2M(&Oo<& zVDFXHgXY^LFO?J*!zOczu$m|;UJpejB!&Ht;(NZ|yykOBol}MG4jWYS7n}o1PHhOh zLOkY5=nfpH>FMcgQeFjBRptr?{Ot(NgfYnaHRZ(;v3>%ej6`nTzI~EjEFKCR8gMY$ z3pC*Iy?gsHRwx;DaCHe$oApG5nf+^^$m+NeYQ%T;aZaX^+Q|fiSk*JJOJ{;KOa$>O zIT6x8j|fW#oUyW+hDkmbu0+@=M=r3FD0UII{R6%aO_8m{d>7m>;%I^8St=+H@@3;5 zKhcoLn4F z$6unTlTl}*c#m))SZC z-5?hBF(!D}<1n*Ea-+Qq_(n5c=w-!eYEJ&x?D_Rj2KXlV`a}(9g_`!jaI#B|g zkC^#7-uAxTW2UI^a5c}u2ijG{A!`z8!&gLb%=t)8{@UXI=LqsrbIAXZsnpe*Fz8Y0 zzyaKpW{vmT4dK;Lj$}K@yAwf?Fh{hkE@>B=_+2zcCN|IC6&1qfliBA>WShyF++fM1 zkD>M1{&t&4!BWJIA)$a|VPW}l_VggQRLrj{D=iIugS-rf#i7$LY$OPa8%zh!cxNYs z&x#SJ19eL%nh7e+iDm&s1qF9=Nz4io6cxoVjW89IYiK7bV|Ut(g~HnU#_!)uN?!Kn2dL=u7h;Wxnox4ogDp^3y!zbH<~RXt&Ck@|t=NB0l; z8oheh$h+&J!sAA(M;-xln@I9Z#O|&6TT{9;fL!-~(2ieeJ~c4lia|^=vmfL&Qn3#LUvjyaE-$X*Km4|J{_ME5 zYm)o2PK@p|8a4Z>P_EcpUrx;=pOQ6{l@0uCLd>Zm|G)~kAvw{pClNx;`pLmVLE$yN z1&Gk$g7g6;Da1~XrPawpa~S?G`MGcuO;ViJ=gyTN2P3bU8X37~A?H(X-AW$?UpY=6 z<_TH94lTz{KxWpiJC(;h8X3^BXyI^J&G72c(i=fJnaV``yPKdSCQ>HlKJ&_p?zEGW zAZ}dGe)7JB&|``rlboPqq}y=|$@6?bFP>e{+9Oj3Dgvb*sC$LiXthR12T|%_{E{bO z5tX$7(rnCTT3!{EypY^ydD`D3TP-cSXvi+9`1JBHHFfWR{H!EcAT^#qZ;&_ag612%|a z%lJ$tLBIk9h5XJ=v>>@HTE3_jV%R{Mq_BXRP7#KF&8g3Y4YO#TE05!gEoC1|*2-A? zRZF88qzF4cjIW(fjL)F!V6qCI73h!V#luTN@k^~>X zB(#6tg9jPtFbsgGbEXID_9@*GTHEWZ_9zk5)fdrGF#h9*qRqSb!;s{#pm}KFfn^x} zXG}7}>+81zsJbw~w*w6zRID3nZWCK(%o&6~Og8W(h<~MsuVSa!vPG9aHvK9hEgE0% z+`)L5I54o^-0^0jZ^o#HM#R9_zueQuc(5o$-Rur^G%Y7l?tT!DaRo>CN%yklV9H0#r-n6+y~=~1D-e+<2Hh>5T~YvCK?(RmMCO( z)i{YrZwp^gq=Og#4Y2dyFjMzl{UyHa{k>!QI5{01nBMrlw)TvXRP9F6GC^B?&;~jJ zODhQc-A&j=&>e%__eCEAdYT}*fbfP-1OOHtaWV(2DPoosfLJ-L(*Q&izVYrmt!VLa z#lqj(V>)Y<$I<$Gu>{?23_Z_2nKROyoTJ10u7|*MA0ojMfu@9#je+upbO}=4Gbr*W zMn*cC_;5vNV>~mii?Rsibl`DMlndZIJm390f?V?EjS6fvDPAv3a?y0oreq~wtW~v8 z7#bRsv+)US@tH+`9vZr+Z5faEwp9%*rp@n8&Edf%!yx_S3_m}<-0~>qR!gHqM*XI# z86JuhX^UuulHozw;`+b=qL%s)f&qTV(Y*vGK+kLqETF&9c7j==?_>T}qOhswC$m%5 ze)_kCR;=ivdTKA84v2qY6O-EacEy>PsxOoZ&JYud%`m1)f#`=(7X^o!NDvALCl8!K z*|LG`#uR3yR9yw|XK1J;=Bm8;W@?ui-Nd7)Flo`H*<~rbV#U|A%kM_&z@4?n6$amg z8iE14P)eR1H%_g`Gcc z17cYv!aOvsaVm=DGVTQWia!kz73|x`wl?Tsio}#19K0cTx9V{T62s~r3AkxXx) z?}Bqe5lhfTV(>j65+7&>C}qTY_B+AUegT0LXcJ9`JLurZLq8be$JZV|YAvlQPEJjw ztRtb_PaB^31cincI?H$v71!*cN^?xH4p{o@N{0z6@iGA`xX(t}>qrzw@grp;Azb4_ z{ICNtbO#tN1;Y+tT>)Xjx(RhZC?OSfb;tAPchVu#V0tf3c+cCg0E@{xh55G%;_4mv zj`Gt8PFAHi?|rd{F6!`+g+fA^?4RUw5WK0!A+}wb0i#FvpmP~JA-$aHt^+CX#I>m) z66q@@k)cdH2itbTeMDG9d2}6Ooa#Z7qD(}aef#$D@xjcZrT~uvsyavzdf<$z@N#+KX&m3!zl9Hk6|`fYgFX0kpcj89vA+N$ib9_qIh-)aBZ zh1Y6n|7Iql{xsfMUotnNLr@_?IwA%){%qnqe!kWF+?iOj;~bl{-fYlTubFyXk2}5% z%nruw@1nz{nq*&zY9k4i{xW4DeQ1a248Rx^G-J!S}4a13l)+iM` zBOo!OmE-4)`C<0zyEtWW2Vb0jY8dubH(TvXWJE!n^2%!)!bi`vXZsUIzx$z~F(G#8 zp+QL^ENRVq6*C@ZYpnb`(KfG~Dj=`9?G?J@;Re81_K%>}di*w!oQTKo^-};JfUo78 z>ABc~8uS04$FoD9m=rr;y41*bw>O2ZxA*&UjRrk`BF+%r{?X=6I(u#K;kNxQNnMUU z(ga3hVnSI;!*Y4o+rJ_CQ=T)oUG>xU>Tea!71(xRwYVhr{W8cBi)#O67}(#nA0YJ$ z67`?c?K^k42=saSRq%GO1kh*DF)s3Px1ZhHw(yu&EQbQl*z@X?jGcW)^|bRg!H`&f z$m~$ABH`5%B@r~{cGuTDaiM8fx)gm+3-x-^WULxzjFEUyfAYuH-tvBJ*V(YxQjuf;Tt4e+?$QElU z*gXDmkX)P!ri`IzBl!`;ol7zh*Z1pM89&nC+tMNM)Iur|j4;WUax-0&#D5CCdzTk0 z*h#YN1Ya5&3V=X>D&i3Y8c94_vwzO(0`(E$4(KAeFh5kKou-60=RmnR6^ZE`Vyk5- zAyv5a*I+{FBJt=1a6w4*oR8Wa&<^$@S6fx}aJauwk)3X}7-77&beT5e<FtfL1eL{6sx)gXg{%I=nPD>>>uHNyqhJ>9Zh=wb#b(3gl2!O3tA z;URg8WF!U77F?!QywJncn*W`N1Pkv|Sv7RqBzHT!Oyyo5nHk+{>wi5p2h0)PiXx1cZY=i;&}?k11~2mpkx zIXDEI^H9~D#>s#W3z!D*9drK&z#M=SMPKgV;K!+OVplO;Mi~QCsdzr}#mcB3o5a}@ z_a0@X582)9uC)5tZJVJe`kBB==@}VE!k9@Ek~jiPjKD!?vO)glNNwdM5FtAKKx~!9 zo^)QN^+K5O@iD|uprRsVYB1j`;{+bBdC+;-&rwAsRQL5!@1RFdyFcDO#Cb3xrdz4& zW@yYCoF%RMQpRRx=j#noc5K9^r*g%$!h{JYDJCoIAjAT~!*TkBL9Ss^IoabPZ;YW* z1WynlePQ3vq^Tb-^n#R9iScHj&inG;uOlrGh=b}Zh#&Y9U~1Y)cU|raa77U$7M_ps6Wy{)%gbx!NZ^3tL!EeYSPh6-E&m_#$&Yx> zUGR1=SHJpSqL3n(D_3`SD(ns_sv>NBPe*(;DVV6zBk@QX(5>n3vAm#WE|mwH{cntt zh3Q7p>^kB;p<`+03@ZLOfD^1zkify^UgWV7Rrp0MN%ls$%T1<~%nxoVN7b zosbaaQD)f1h|w2#)Cn}atLTP1e;z#|e`aUz9XS^P`67XNGpWayhz0#SckN1g6%4N& z9suBeARFV6@sb9PCAwfU+E9;b5tN2up4l6-6MpFbQsKh{4yypxV@dL+rYqq7rDQq@pQh~ic` ziM*Hc0nrf#%ZrK(6i{*B#aJAAdWh~92%tWqfDEufi#WRnEUK193SPo8iuzX`_z9j$ zqDlh!1Z0nSHHX7X;0b}r7o%wBGIdkmp}MbGB7TV_tngx$ctl6#9nE`3(GW)%Zk4r( zH}3_N5fdN(_dlik8}w#EXaUeBa~>NAlAP*5dV;nh#!hF&2}85+(KR=3UQa$`3kHZZ zcvc(6z@So7umQ{?3VUha=O~fzK4P&8+}}Nfwa@p)9@OrdhbU2a08nTBZ)K0tEhaj8 zdf0=ZIkH@w-$Y_^A^+&_@k)5m*IcwXc9V>V$v8GUd<#do*9AZ z<)5N8p8x<<1c^-4qUE0X_DA^m>;W3S3hvHr`wne76pd)JjyH*)5FCPGxR{xP$>42z z)R5rNRgKnvf^rC4N8Yp7Fj6Hxo~do21w#}uwu(%__@Y2L&AA!%07_g=P^GBxN9@Tb zgti^i2-_WY(9(fCj2^dIdU_A1yzW*E*{B<$oqV;dg<@B9Cd#=B{0X(1Wnkt%sW`$2SA@_0DG z�-r#bfj|_Aw}7_6nZzvL;+cB%;F@W2aGfLA!)BmT(DV+v384l7fQJGvZrov}1o? zv8mi2ezLQg;^S!8@l!K9zFo-(r>P{kVFY-Lt|lZ$;+!L?|LfjFqB6u)e#l=_OR?M- zKhMvJasm(*T(V8czB`z+2^0g%u$i9Tqs||&4CA>T3zcVy8y}Q#sc@L*Mrfwe+tRGT ze*O+MRJit42C*{74e)2f0&ryubEofi*_j)R$S(63hor*BMOBuR4s(! z3Bm%G>)o^i=1RPn$b%gE|LkOSqG1uyA6~g`y*zYLON$Mn)K=lNy%+CgJ6!KfOSF*M z!N>@Y>-(+)Xp;xV3|w&m*2gX&RDcn9z|c)2e(9&t?@Qzz&+C{;Ke3IIQ;Th;KiX+) z#i&Y*ZkX0VmifvhVIAT`d4?d!E}--Ce^-Zgi#wUw*l=BZNC;PB7Z=RzpU~4KyeMs8 zo;s$NcxWy*I)!&#%bckrDse)vS_o^kBW7daD9g(Sh2l9uxn^Z<2yEE?J-NiaVxkaC zp#|t>C_WP@+M(v^60@L|)iGy^BlD2Z5-0K43`0PU_;}3w;p0Tt9Q+EPNXb;*T3QYd zGozzB*8db?2L@I|HHkKsE#yO>0MSx z3@_nzd~p&#Mur-j3?a?lI`%ItRAe_wsESc{3;o1CHkEj2YNgw- z?_5qHjuEy3_`Qg&Sw_e!=$<`8p-n-2tC0A)zLxxmfb+AP_}=U!Tw`M*i)B%mgEd#Ak!21n?E4-vYo8i_QQ1SJegIQXFFw=)I_LMDbGuL0`0fQ#p|?vO7F? zU+?>r{v*Q901+cjyHNm7r!kRc`G06O`lz=*HNK>#U~^5r(XXlZZ6>!*XEdJ#Fy4vHv*g(mGH_pmZkVJolzE!5vO+!Kn{jO=-18b ztaaEo)F_c;X^N5*Qv^5%=L)=9=p4^3u5hPbzNqtd#*bB?B){Y6#tRi+#Irk8;Xyfm zAm(o0L>h5H{mKa3oR2Wxia^+|GZamZ|Lz7~R@C>nIrMmBalOV_Olbb^cX)bvFjB#}yG__Z zFSRq8V(M2!!3hNoWli!A#}*vZ>PX_`%!{$<`82t$Vzj6w*CxAyd*Fi*IL4ki}ay*>h z?Mt7!KNTDKVg=EGN=*6-SZGVZ$2oWFll`bZ7t`=`uS(w%A}Qi|40DcgIL4uKETn#J zR(-BxrGE@Z`nfqj8treFc-q-B;Oo)MG!w(sUnW^WsFQ(KEp{T47(*&5TAY=os!$)n z%EHFBf{a4=)%WjDgXe;a%LeHO4*|+(V?e+oYX>*q1XHs(d0ar_)sqTmf^_oc1&#finKa_vS-s15?)01Z>4ox2A;FUPg z9_Q5cyM>0!|U;}D2&+mEd|HQx|`r}gXOz=%S!1hdf-#-=)wjN78cZKy+OFsA> zQgAFVcxh=V+1P@Se$O%K^Hir3cQ8^h@f14ZnO}>OlBhdixWwPhIv3)`L}IaC9I-D$ zs#MG%?4(ih_EmSjm7MBL2lQC9!IaxgJo^PsRE&mp){5^r_~y=44LZ7( zO`i9~ce3BD&vyDV$`ifDd8k6dCvYDM3E(~g>a=H{geM10)nusC1E?cQv%W-Cu0X`F zsU+l^bp#wqK94`0ge7B~nv?U-nJI_d>yMJS^@aJ4b5ftQ9&#ByMJ{m^Fw>tK010X_ zr!WLo)Ls~nDr5wSSr%(7OY>8dekILL949ghMv9Lt5yyYs*(l{Xng!A)%sEjbOMZGl zl3k35#g@Duzq^Bmwj%H|@6IqnuE7{h$TfsB(1o1T-_@UBtmKK)zH^TKz_A!7$M&U* z?A3H<*mkyDAN=Wi>eQsYOOR@F2qHgT8c@mrIEqXz5dJGXrw32ta)Wn{;Hv}kfLi+v z>)-K;AFZG><>CzRwOy?A4&;@2T9Qf}>Km0KY!!6)l)w`hGK}$B7vRUoJ?BK(g(0ko z5E$Z#D*J^pZpd;T=c!rmlFUZ!JO2+=e;pOo`u>l@qbME&6-7F9Kw3arKrlu?QV=QW zln{_c(f|fQ5NQyR7D15il5Xkl?(X_sdw74I?|SwhXPqUmXV1OwxZ)LV(|hr_s2Q&n zsw5)d8VW^bLQpCN#2xgbfhC6P32z{6_&xRI4-|bSU*S=Z0(;$@Cu{n_6L!3CcD1~# z*RNXvH4dp@+b^WoK*d!bGy?tZpGH|Q!0-PUzOh|k|KVx247263Z4i#_i6_<-p-6IB zP-Bt1%c1eo`JG6gd|{EV8fn9jW&l!EN|FbZ;}N}3a)Rf-PXky0+1fOpc*gIw$^JT+ zK6fqew;vRkpqI1FZ24sW{fyO}f`wA2N0+~Sahs+au@jA51r8GQvY|zX9s}tz2rZ$I z>}w0B?PDa$D|M+K!4HU`z19;F3AaJboa+?0_eYdG8H3?|t~a0nAm##zBtAIv0BF<| zabq{kb+5itivx=V*$F^ofaVaWsv1o-!wsd88~Ty|ikqpGya^(N3 z$%=?imq-cZeC^KfkhM$+fcw-j-lt%_^d#|Ha*NcTaO3bgwyJdshO zxj|#*nlj5!FG~l(40M=_-?#!Qq~bys*aFKIHq(2rr?{VbcVt>P0A@lu5EKUCR$ zB&|Dq)n*x%RW#qsB{)*i3nS#x5OkN(;|a6Ldt9{IF(HF z$t%K-&(1DucW27$g1hn2Wp&r>+h|K+oBjDZhe2Ls`CZc96Y_sKNr2{Tdx44TW2NbW zaWh0_6Lb_uy6&V^A%$b8$i7)4By0^Ch)F>}ts3n}X!S1y_j^tD2ln4v2XLE^!N>xO zWpYt;^G&E|5;6=Qy*dw_I;1IEA#XL5+)i|1e`O-PtwY4KWsN*OLoum(*HeflQpxJE z_N>2Bl!Hzmdv(4a_4qtZ!R_6m(J61TmMU`H;QY?37HDN(!ED@?4l@ZeN=h8ga~YO!QA-Za+(x5C z7pEK~bEZ|KRr8F;8>4zVo$R!9pJ~)qQm}6}ZG9V2OEjKd8DbGwFQm%V52U zY8vmCqx9h;caERa9QGwA-Efghd$QY`-(q>4@UBa~{?M3`AH|?SDzL)bele zpDdr>MojGI821m;kas*o5fDs~X~&XgAi4E0UC}o4OGU1ybS%x+4KBsdXb~vMA;1#S z?}0kEbsDiUL*iw+PKt|ewi&_tFV)^;t5#SCfuAY$rUou+bV(qM`8Tey^yi|8I7 z4gV~4Z``}`LHYCEsz7xIUyeR$;QG++LZ&O9J5h#ymHFWZJGxTB$lNh~8nM!Unss4z z8qz%WXOH)*pFI!M5-OP-*1T`F(Q7@@lXEs<+r^iK#=KEwgllDP?xpG=5;;*?{W%IGf znEcm(oZqW+J>#ULLM=x94@A_h@Zs><10LC9JEj=QPiSAQU&? z)hR^=GFJ0N6($*_u|aA~Y@AqeZ4J3hMw*rFB_U#&+2!pA)4RTbW~bKQhn(HN_X$f% zfRFgU(xGt-RXt0!Bl>?DT^lhFT>C%HZ z2!`(%Z#RoYs8RpA?36ZS4)iucfAGT|5>khK+>ZkpC|yM`2KSo`nIK*X zQ)DI#4}iKP0B|0(&Zp}>0eqwk0Ekbf$>>X2d?_kD$H;X9f~JThSnNwkyOxw$sMfBeN5v}soaj~OmP?|}Jl4dY(^KA89(E4+Q-fUo{J^ zZxU2o{Z!Jx#qHgFh9(|szq_OAb$40n;q)m2o*LiC;*yg0t2%OWnR!j$_%hcQo(}6# zvMm07o`!O@W6>R29ar~!&_SwPfE=TbMQv<0K|D%24fu?X%HlL zAUWl&iaT@ejO;9r=OjlXwr{8(kCpUVY#m>@;y9TnH=Dbb64DyoyX7j-aHp5gl`({-@RA%+e{%Z}wP5s7*W2{UKT!L6fDvErGl zeSSgAEdEn6c(l|6R}S4t+j7kAwau#DAd8@}p_yFo?;uB>7C-xhGGPr8%m8*uxDWN- zK~X493-j_SV!lO2PB(_Nry&zJ4Y$In>d*FnJ(4Fnke}OnHav6QPxAWdY z*he2KSNqO9wDq_SdzzQ;T2uPsd=yi7%7)6ZtwLGjo#S;&(V1ky;GHNHLh>=LUnN3( zx|(ZmBFBqLO)o7uL>nO!Wke7F%iwYhh{a)Vkb>9*&2)&9!89QS`hOQMLb+BLiaQ`j z4Oq>K7ePxNfi+D4=L$fGJa)^lt=vEslSH6PscfAiw@Z!S8>Sl2^|2gyH8~@!-POkv zJzDB@;k(89SYzx|F)_(eYw%*>kS_}xkHG%fW0&=u?k-!_Un6-7i!Eb=-}jgE*yV?W z^(Uv+U)fvtDW+XHu&d>XHTrscvhnx+*u<5W<83+SLx~&VLM$6W9d~4RnPg36gbVNJ z4)+UwGZekEb^fqDC)@qyS3l8Z#*O|gc}(S9i~01}qyFOzS{aIBo^nRpCE@nJxy9>i z)i)KbVGzo+pa^*bFcVM{M!Gx>Gtr)1X`0JpV}N=z(bk48Q7SYPz%+`@FsXCy|6#UJ z7P1gxe0Vw69{Wf~>@{eYFFqiwbF@h~4mO`E)(pHhY1{DpuHHTT6zAO!+3d%a#_>uk z-fzm;x18*&x(2y%&_YF)}dU6 zG9W5J3qjFiJO?}rc5VjG!jDyUDtn4a*4FE*uH5`{BD`q?77HQ5fxb%`8u((JvPX4n z_cLeK)0W&V>MK=W(v}2Ss9O8l71So8< zEBmd;1x*N!O4#hSeS^9i^|^}sTz~mglUD>4agn8`8PHWG7OkrcJU`@+^y#ji82Fqk zXI{HA9Ff~)>iua&mmdj!Py=iq%Kv~=3JAxC@dClE1cZTrnm5z}mVvg`3sIhJ5M?M$ z5R?_iZuA$iux)twpRO*t68p%7issm}>6Ujumq0{vCN+1|y{&9Hr^Z1fXhdD&h5j}i zXOLJSFeNbK1C{w%SOLRGo~0#2JY|L=?F$r^eeLS-PM(=l-k1CdhR%FnDo97c-neRY zF}fsHf%#Y@@^#v8eu_iSKPtjYu?iPDf36;tx0s5^cT8I9_btxTM2wlG$$utaMxsHd z5T2TrbsMWYyf3WA0?MEB#`46fW1tik9CiolZ`fUjFB`T5CRd znxXm{0QXv@kwxP2*o#v$kpMSo!8UK@N zT5pP_hV!VW#CpAk(w71KfAp8{}LshHcW| zr;~Rc3Q}<82$znhbQZl9d(JDZ2$fRv0Yahq-18ARn2#kiL`AKsjJw%8F>f+sj+|-d zaTS9H>;MA=zZGlnVnsT(NYgjXWs?Q!yGX~U4E5JZ;z1NA@om#ymrBO)KOI`?uTVc85OrEUu9aR=~ky07j3r7x9 zrk@#UHrGqFe;ch{T(Qd(aGWwt#YPZK1#x?~+0C&F9Ct7u9#TJ(NU~0ziBNl-*#_v^ z^%p^zd}a~OHLj14w@9i192CH;HGjX)f(F7b)RmxN0}j_X^y?)IvKZUd0tx$#+znac zW2;RRF$x{)5#7S}1v|0;MMXZG|64A|eA zWSpk%zZ)1r{zUZN7DxXzGchA0$6r=ZM+5%z^=UQtNu#fLH_4jm%BRSZwwRqO6p)%&-_&EFE3%V4w2E-^!#11oZYSc z%0&=g?*mvGQ2LClpk0fracEcI!zX6uAbZA-G$$x^0hbRn=5aWCFlz-(bta+Az$>R<+enFpPYjg;!*)<7VZ$BnBm)t8o*c{D8vMj^y|b127x7EPVas*(jZ+1AHf=KN}tw-0A%{ z{vycF!$bD!xc_2*mIyHqNmcQxZ3eGhV4|P6}?I%+E5icM=BUkl*s3psjt9vCwM{S2pqp0=*58J z2`?X?AV0rp&!16n!b3LIksOYaQ>6a|mZvRZ1*oYHryWWd{ywJJB=5AIlv0(qR7~pr zl=qV?fjr9ayC&hj!h%?7`14?Lf#}lspKvFIUfQ20#|+AX&;Z~wBU~< zw?EZ;ixOsgJ$fk~@rdyzVeLh_vRz&6PuN$lrR{fJj>4)km$LJ8#pvcErX8>c?vGrV z3%9hV(!$4gqT6yaz7{RNNv>mn<_#8JI)pbMbcHzbq zHS#dai2udD(1yNSqp4oVsoz72cpb)RTwef`>{9H$nK*Sk|}WZU9fwifp#k8b;ND}@y@ zRfg2+6xWw~n>$x7=hDUd927M*l}rwDRCUmt zC-hf%+d}FF{sIXJ*IK~|AhMennGPr+?oCH))=l3(@2~|M&nb>p$2xS;E{68@J2Xct zp2wS|Mvc>Se(4Tr)?1I3}i51 z45Y^iG1k3kB!L4HAMv?u@k3!kLOb&NVUN^=r6Zm$3K(~{@=fFMcP(JqjSl-K*ez^g z;aA5=r{LhaWXKy4_Mvqhzor*58L=S{q<~8(i?>Ou=O*^YN6qIWPT{-(*jo0`ztwkX)reNE}?}ph@jla2t0Yd;4Eh7>qEN(P-vG zIhjjvO=7K~7mSznrg`%c)SI`1+hz95@t*pwAUR1k>$nN

3>RLdLTE|`d3y~27El=5pk0fZ~@gB;2me*69!uV z{3tm!l^zUUCOX)VO%XN1U_^7U`Tg{?pJFv@Qb&UG1XT4b zoeY$-Gyp;b@M-Xu0SV$=5S)(QgzXmw8$(1%$r@0n_U~lOg?_Ld;svelU@*nV^PomX zktFr$Z}{b(KWCuTP3-NCg@_U4nVE^bp|t~6T9DxO_xFSDma{?dV-PEZ{=K?7Rc7-w zzncCM=fY%7+~cBrjOP}2>v`w@i{RrA{fxmpPY{TOk##$N0qUeu@{k!PDQFbgztPfi z!$RvGP%41sM?f8?!B_|YXdosJ#Jj#eRfAmobKndJ$SpTF6iF8H@<3?QOtEp~VWC;p z?I3}dSnNT%8Z)Fd6-e=NyQ8P4)@e>Nu^l8TKo1YlVBfz}8-N-XKnzX6b*S_85w~q& zaYhDU#sHYWNefMIopk^bkfE zoYs3xdC}qE%mqLc@K%3tGjBN?xhsleY1f-^FE`F5Y9qTNHFo6;tdAn2j^0O$0>4;j zSS1JM+mM-8eIL1X2SDn4!mA3BZi zgSi@D?j$8ILTh|T$O{Af5(Mk{e>bfI4is zdwO5tYp@3FgK22;@+>UxZb-{jnX;FUuY!I7 zkol@~RTa!RFy5&Kx8#M781AG`Af-$%ysw0f1i~&VLqZWT005A%kEHCO1h6!nH)6 zuuC9f8|Uxb1HdUjTBabamb-aXDoXeeEMlNB9xp#@T>xmk``~~jBvb@c70}X-j(*2< z8GwbrO@rniIPgUFa^Rl9=OJ{58XxNEO)%<1`vpv^9P;ig!H?X4)u^?W(Z2|25yN!l z?cd;Q4bmRVi;Fgolr9-Kzd(bQHYg;4jN9WD2)ZUFCkFxa4=YYTvln7QooW(R<(tIb zpuG{SdI& zU|g`iivY`E9?cCP>l2O(CyNOJu-pjrW1QW5i@tWjUB>t#{4@H|5Q;+uy6Ds*E(ZX4 z=8gD_1<^Dh*MkW-i1P!659{zD`7eGzU1dr*IWaM>gbD`pQ6ip`{PTaX^}{uy0X`0S zYN=H^(BTDrLF)8sQ(myTd^=KyV=pymg%m=MJZQTs9d z_uqe4F96olcIHLu1&UX-d%wWTA~x`zaCltnEAalJHHRmKtC|9^Z!iw+?T;~VLO=}( zm>hN?fE@$d5^6t&fVyu(w6OLokvESn1Zf3miGuf)BfHZ{dNb{p+qd$+1Q zTl>SHnW0NJLk!T*_EXd9$5&T^ai5GLg<=U{Wuf{4J|c~^@J0f@eg#cT=Ek zTp;jz_Vh#078(axbb5brwGPzOvK=`n(aK*QhOm%gIqU$w^6pK6D2HdKk#E zG87l%H7}Tj#IPSMEy-Zu>m|r13E3`$!bDMK_5E{;pWpsu>qs@GhMDyj_z4^jL4*wv zLC(wD0U8hn4glEc0Kc|9QpydUQ-47+8u+Y)whmWd;YUA1(=fN#9>+$7#1;O$81!E*dvevg!`ucCJV-$^y@qchg@(=yH?dyag4btM`SG}tM%1b%P49??#cS5W=OI@Hd zA`D*g+}s_I!>gzxWeSkILL^RLoB-!%TNp_OdU&wMfJ{=O#y|Km2QeJ^q;(Dgj6@*A#lmZM{d%=nx13Il5GSD+WotP*$#$A~Q%=h9>|JJH>wTc~G;6 z1hE!Cyo1XjnFGk+&|Ry8768c1sP&)hr+K2X4EvtsTUU(NHsX5ICm85j2)ClZ%8rqZ z4MHkF?lfW_+!O~!;xg`AjXXl85chAzLf2y#gJe835DsC|55gg%-rwmA+dWvRZ!M@q zG>KwNc?Id|MVW(q4}EYYUleuFcbQ*1_xG#sn%C4;Z3E*@o^h2*Y;FaV4gd(QR%Gw5 zg6$j}ybs~T?b~M^AHq2MI3pjJg@~`3^0I{#LUjg|QH7)6XmvhraFL@Am<78~2xSfd zFa->CLNYSM(w5Nf87WQ&2?F0D+eLCNFig*czXfLB!VoUH;Yi9h`e}dBX7*g^1|&-m z3t~EyAML&|iH0JcKSnTzN>U`G`fL8up|%xZfHLH&bHCBz{hRY?Zhyst7VH3@|ZZU&XbcD6r_ z5)mtotekpgf4b@A-guIE^Kj??8isiuu5Pt{c(VIR<`pVw%!zP zA0Ilj0dqQ6m{bC2zA44Fa%h5hJX?rKx-z&Y*6Hm5M;%zYAaJjftqM7pOr$`S-ZfTY z6F`n!^U?!7Ng14!6P$F6oxbINZrRdGM>y0ZIY=^be5)53^WWtA>mhM`jM&2C<{D`t z#2#g}5Ex(Q1-63eK%Rfi_}y`X%zNzY%Md1!f1Uzwy90O&p{yS(M!}LDTQvsQYo#qn zAmP%Li0~kn^uiLSQc?4A*gL7_1$T%=h4!shlHWoqGAPnqp#-W*z5Z*_s25{vivfU>nH1Bh+w|7F%EtRc z%)%fu?B0lFK13tU0&}=UkMc-=+eC{t?)LAsZ$U={ou`}Y8;tBEfe$`dLxzhAB#9ya z4bv^w5Rr%#I-MooB$di}yFOU$R zK0sA6NMaHcJ|L$L^#{5D#Eg!eN-tgz${`vtdnY^Ho1gI&F+Uwm3uo}N=f#}^(cNFq zP1m&ZvUEm92UB3I|16~|CL6+YfX+z+;Nl^iJOwA89vFrwsjGw6Ef|5C7*v8DC18L- z^9^=Ppl88lr}+Yme?f{C0|juI*U0yR2^j<#=;PPz4KEGo8V}xG;`^yC_Ff#RXuu-% zpwPQ}&3}kRbg&v6v;ISNv1)cCYg4kb+lJ!+He1|@AOvLiYhDwGNu`z5K5!<}I*mbF zz-*`}EHspV<8MX=r~9Lam`Bmi(EfQpY;Ye;$^h9Bc4p*rO~QR*idL(y`tu1MbJ1t< zsE2~jzC04^l(s&*o(Q8`&4YZR91vC>MT1zYsku2jVSZsDX#8-46Fih~eZxVy^9Zbf zxgwf?0s=rvXs?3RjX`F9Ny+!#{C73upg7X0pLX(=tBZVnFN3)a$e(q0Z@>FB-xPAp z*=`?v_#ymt(L;>wk<-4<%+SAV9?fixe9KS{S8~{jz9D;mKJfMPA$EWT*cdW2Gz4r5 zo%9~?98%VY+#VWVu0T!$p1|DZp0=YHsFc~m*#P!(GIJ;UfAx)G4PcY60+7$Zm7myK zKVA9g+x9Nlo1MLwbLls*J(?OCXwfI-fbJ|LHZDDbeECOEuZL|Aa?Iz?uXAylbg`x@ zfBW)iKC z8q09lBq8|(b8;{T1kX570RdbAEy&&@!6y`5)SaF0Yaby&)kolLYP~msF$c6B3k&Rk zjpC3cV9;c5NM_&=MvQ{}#oszQf>av^^0wew>H;%z&=mw69u!P`5X}pihR|#SPgX1- z9&K=`DNK8w1=YqVSRbLJu)2J%&<7-eiv=(bU}&${KZPfO^BQ9Au-yibxm3w94O3u_ z1ZjcT1>k1DMNg94sR|5u1qBcftMYQG229;&gpb$|x4zZ^x}9bp-{4V|SMp5WBK6G8);& zogWNu;653(tz~XSB*s{f_*QjphH#yOQz082;8}#ZUh#GVL0>@q}tvf zE-B!0umeZ)f~_DSsH3JTr=ww5Z{95HL|7Vb4aj$jg;NO1XkOTcNqYEm0A6@{0@WQN z1)#HWhJhvdbrA7w6f`q7mS+xvV%XyB>@74OUoL=c#p%96phoh)PYhLtiX4*Hy?iOi z!SMhC5Ml_pphZ<~Z46%sIhl#!I0TmnLjMOhd%$KQDvE{+fSkw$kkg%&QP|~+}TdS8j5V5)oy=%mVXQpw|i%Lo)}i&_6)5 z1;IVAd|zPR2Guzv9tCT-H{cui8bNJxBp_qv4HZ&Cunu>Weh&AALP85H!Whtwg(DUC zwD+=~oZM{&3T&`_Ln9|teNvgV3-a_Rhbgk?XESqM@EcmJNWwh@r4Il;pvj%L-GL1` zHKKVmsR^ruOWFDt<{??tlWQ@U&2!U#Ij?G18( zgkGnlY^3by?EK7G^$@99pE`A_`PKgt^fX=q=OfBZ+iQey=9leaFuW|;^FK4)$t7n( zMJaNgYsfdTE=gcusf38rfpYPf1%K*1?!35;%zU7dkwmrdk$-+$d{p9q=U0Q&Q;};s zy6+(pk^TFd{XzRf1>ba1>bHUoJpD9dZZtX^as$NTj)Y_ysw3fMFwM1`kWu#7*xZD0 z9;Ox9XHm2~BN3c#v}Rc+2+X;i2NrZ$=s!>*0p1|s^x=ds0HLZTopef&9?k_G#h>5gjRxzZ z6`ps9FZ$Iuj=GbmwX);Bf)9<-ktl}fJIAA*vj4uxa!o&P_&o9F)FXIDP)@$+fam57 z>lBy}-vQW|n;U`!Ljhi{P^FTj($;kE%f2 zr)Y6Q$-n;zW`aaWwfEb9#`zDWJDZIlo0W`UDJnzV6l(K;3IDRr-Dck z;VskQl0zsh;$lbho=G8US!C0`mdJZDNaHg5BS$UUbreo!vd*vCzmx)U2ZjW7oe024 zhMB6rp<)4wCcLDV8f#%I2WhNK%Sj1Hc(XVm!3V4pEEn)rhH#2(V%7dp^ol!)Mp@%Y zytZ@RRB>%&U_E8BYouJ^omC&QQF)z%Az6o}E6I%;;Ib%YfAg9b7+yiDq{7;T4Y7A{ zfYUk%3-kpL9Egh2gqC>3=hA%KD6D81R9&LB&hg=`DmSHz`F;uxMw-Md2!c@8uYOlO z&0hiCC|IOWz1-i2ZLrAz2#m0{VcQfQp@M3b(Ea-~`hK{3aonAi(kR!U|HYEn^Ld-q zm|qq%ye$yz|beCnRIeD}PQ- zy^+yZ+~oN(4=_;jHgEP*+t5F6lXJCIljog`DFMobtndCCHK^_p2Cjy^nYiFMdHI$% z)K@_56rY-gdRV7B$^)w zEu5^Z4XE^pj*p0J!Q;XEggm>#_@u}+A~lyYJGV94>caQ*`6E6XqWrCz&y=Q$@-*=f z2G`kGSr2MJX*IUA_mo?D{f`|5ZMBf*()o{@K1CxeB;4HPDlC?oE%_TJMh57ws%|u+ z`3z;wwUd_lYQokNpzvjxFC-v<6q6yeshHb*>kO$G2#+=y(4vXGvq4GO3zMN$etMec zWP$;m32K4Z%Y*g@bqXxG;}^)xzKr7Up84v@5N7VLzk( zv5g@VZF~f-d#``-p(Cs0(fs4j=lSM{LZg z!EYo;0uV?>?;bqB7-#Q6o@-`ms`u#}K0fIF$;dRDq!oigwoydW)a-27*RL7o!zIv( zxq;I=gxumx08Qw^Qle8%cx(o~P>~l_fS@B)_pisPE6Yne&bx~&Sm?kNWGJC_$cS$z zc&Ik`Qobg2i78yDH6%EwjLR!zOV?oOIsD7qN~y^fGEYILy7_nM{d@)WkCzm_%Pvg% ztwkudh7a?CVp+`h_iM8SO*VkIcAtlh72BZyCULL%<=4G7!A~Cjx4UHZ)rciGR41uI z)S5LW%EuC@$Sw)_8SZ4{y>ZMU5X-G{-?Mbq&y`iC2;A5B$`(#i25;x#U;bVbF=G!l zvUn%2{D1a$>|TCie8n6xFUZd3Y^OruKlm(%ftIZU>RkBem0s^FI~ulc=UYvhpo43Q z0FZ>=SrYOUQ}R52An9RD;Ol(jgj&@v&H7IkQ`4U}Et5bgaJcD{|>3fgdift5~QPg1|K+fa~! zIRgx1IKcrG*|Y32ecYJ2R86r!!Cot-sU*s$^o^ilT8l5KJC z1Yc`({2vw|KVR%Z*0Dbi_dV|5sfPZYHk+s4>hT^o{5H%C=vqq6!ml>#3B0qh_>-N5 zKm5+~;7P`d!&quH%ip8pK6y=N@sE2prZd`h^@>uz&ELJ9XO)Q4Kl3wg9!Fk!G8_M>bBNBMm66x8B8R-Rp+(Iu?iTNzalS5(wuASwnOux3 z4{F~vw!D|;)2q&YK}>l^@Q+IM`NAwavh{)`SHsJmk2_jZ>iu0TDwWVpKBJ@^pAOpa z*wq(Tio>I(TD;z_Ruq53>!s;l=`QiVbAC)HeP;By;*=CC@0H-Sflv;3ffzJ6{v<_E&|krAW^N6kO;aE#0g4HB*47-fuy3u5 zR^VDHF^gO=R6+1opc_RW1IE-)bkm_~NN;NNkfOKcwRZq@t;6JlzA)BXguN_Rie6}GiA^%H zm<@9{wm0YH4YO<==5t!PvJ#R7<>z<*mNRE&Tl`euJijoI_475zLsf4yemS@B{V|3> z?BYk74h7R9DtR@LFZr2`SHH3;O(velU;dWP#WcIUpHqChy@+Z)FYnf}c*ig^Gw+#e zgxOX4|8e)*&lkM~#VGki7cy|j;|Q;Mnh$HwoFqZhZAWo7tyBc7dud@^`zv zN_hnZcWV~ock6n?yeN|eN=L}KZVp)IJ#(S6YxkQy%P^;6#268tW`f^+gOl8g|69_x zTicfhHv9}EO-AuN336Yq$@Z@f_;I0)h3kGVOwk=0HZO|1VfoYhbK`ddwtf~h3Qzp4 zX}3!$bdGkFS0nOVAj)+RTUZRCED&M}ly2H9fAXFBpxLR;cY(AfN>)pL4SiXKf_zyu z{Q}CP>;T`*|1Jv?2;uq2UneAtmQTXYTyfp0fcj=+$B7kgnK+2)h=BPpkn*>Yvaxp+ z6rjYVrS-Q0podxqX4&9x7;1O-F|-0;L%$FC&{>dHWM>qhrG2Zp)q0Q-nf{a#jjmXI zpJAqL@b;Q#y$3O`T8UnkRZK8ubvaL%gH0e%B0D5i)##LGkCS$cwS^IVVJDJJD`s5t zl-A4TY+1s)9xpefA5^H9;hWO9(UEud9p&5Fn$O=7iO;(h{j-?0#7lo18~kxduF_9^ ze?sQjv$yd+ar(M;n;TIG(?9#qctiak&G(54qHI0GkD=CggO`zcmzvf;H6Yg2TfF zpd26;2FYutp)4fKplDNyw6j!)%-%ZJ>QQ*VxbTz<^ruU^O=oV~mxZ)=tLZe|OQ!k6zj zb-8MFlUjJ=s@;_1aRK4T1zhzKJD0Y?z%fVv}y z(G00CgI!EO9pu!yx&5F~J7zx)QJLtB$3|SYCi8)Uc3|9UDRXUFT#veuoGE&rN?(na z(BI;_lnR0H|Usjv`k56wYi1ote^!h!@JTwx8vwu zCVwSiY^V?Xl;LN`B0QA4%(tuWD&zR?Fow)dIBw#PSI@hrr9(vXu1fKq<^!^Y*#S$J zP#>W*f`J$a02QXZAXrsH=TQj7w!7y*TdmpnB=~Uy5p788B_t)G=N;w`;w6&tZP392 zY4AK~omj*_Q1Q_7d=!?(k?@47DNVa(aquQ(G&AFu$4v*5VfWHJhMa?2S7u8F=DYrp ztg{>iZ;dy8Xb9@H3(461J0WdOXZ}`Kgsd|^jNMFdt()o|MH~(Nkgm&v+)n$b5W>nU zH_^jCNh~czU(W2^5-JeHLlJIy6nzFI7X7!q4py_a5;&$dj5@g|U7zc!(q^WgH zS{zOrtz!K-ub~+#)$>QI{C&5E<6@-U5O`r?dQcp*tL?n?r$6hv*Vn&4edl&U!y{3~ z3!gQJDszlkSUg3xmw5$KlG4&G^v*gABi ztQkrvHlst2Szv$0_H%ATaI5`%Rbo|AHJGN;dhJ#(1v9g!d9x|cQRCuu>cPlUZoq{s zdj@^MHvJ_#dbMVHt*c=_=TN%B@VX7DAQpS+T-&23=|=k_u8TVLIuyZ^9?x)PMzZ4K{R?atyl81-`W}fTrS$6^*FZ| zU|(rxaGj7WOyoQ&k6@nZ)Kx+dD?`vy5ORZOF9Q9`v0v4JVhyOUxIbD&L{?#AeB8}@ zhm}=D)(C) z_Z=7SyGZ=e%@nbZWqrN<&X7dC?@KWAMs}8Qy)etqj`e_{=D@et3D0-yV~Srq-?bGr z7W1&a%%gcn(6WejF#s<*LjPRqq`~rpVchG!jl#wO!)<+rPxW0-bsxX49nyZrG7+!p zBGr8PyeIb6J67G%64T9+tV)C4wP!N9ISZMeejGRY^k=8(Y$&Z_rrxPvm^BgO41P69 z5$F9rk7`r@tXKm%fUpntWe3Q{S_i_eGhfmV;5GO3`TG9!*Novno%wSps0RdmYcfDI zwB+RcHAF~_t?~z;bpVCJGiT0(N+sY}6es<43UCjZp6(tRO6{J9Jf09aGoUgYpN1PX zRCPpxaZ5r2>q`=oUm|B&f2ha~C;v%I6pNQ<3aST<69YO94ya(KfO!GnsG5yQP}NaA zB%CorO}wf7m2~H5#~7v*zNus_FXHX~8u%8gxOVv(TV2ooG#}^fTsv!fbn*yISBiT6 zr&7I;biBv9`YKWShHMu*mZaDniyy3p;FZYg$Gz@(nQ(1tK_uqcD z14DCJ5>7|HKe0pn%(+Fu&X^Y#Bb*E?UU@#b4VGP9dJE_b)umoapxe#`{r$vndEw}} zOK;*n(O~6yBDTISnRbqfeeWGjFRuP@i53(y@836`%qb1LaghBmPlo?*4lyd=n)fa@ zUl|^_bOluDfD59JpP${49n@?P0L|ulHysc8XK26z7zSVh21ubUA4+Zj9kS%NJD3M& z3&=rwO{s0qL76U~&c%S@N@{6oluATre}6=i?L+xjyb&OS1$APz43#H<2v<@fA(W03 zfEMK7E&-qk`WLrAo9j~K)EI#1B6mgRplPkl8oW+10}fX6^XnTM(3NUFUIO{CM$HEx z+m@D@nF*gzF?wl#bc7OcI)Evx(gD5YrrqI4EF7IY92{j(EL(e40b&%t6`}P6a<0>^ zc2Mtu9UBqk!fb#(*9CXl1^T@isUb}>3JLK|=1tq7yZlw2F`5Zj5>H>KFvZKOC@LCo zhJ_MBNj*pc^i((2U2j#g=k81fH%vm2QQ)|+@F3*nRMLAB*L*O>1GV*E>!pGyH!Cd{ zJShQ4wl$qrpFq&8sY%0y{=agE*nz$h+8=|6Iu)dq?16zj=yV`{HsDAPVN5X_4UkIO-p zG)#+L3%e&|Y7v?nsA~4C(CqQ6=T6nG_YXJj+kHW5QKStkwKwP!0QCtKGUy2yh*_W1 zDv}hC=50X%0Bzt3)eHZH#Xbu0RlNTFL6C!0p1KvWfX%WQ{K!r7>KZ<&?0}$IURbz_ z@F{LSm&*6hsQ~#%$a6sx$eiZ2K;@o;7GuxU%!>gUMoQ)@T{ z*isLJDxtMhjaF$Gr`DE9mK$YcjJw&A2zYXCx0_ z72`2?_V6KzXaca?bSDrlY3o@$n01sz(TP4IHwvU`p|se>W*Ssr^~J z+O%ga+v1r`dp2_5NSr;7tzBx?6;`zHq?AaXC=s6OL@)aCa_u zm1WOY|FIIc1R6Jrj$>N6%Sp3)qjRcP)LduC4}|d=fq+Y+QK;1(xbR3C3u2=}4E>kN9nIIW=6{E;BXt!ne)aJ!8op+CfNl7h&~wYP`$ zm@+p@DMb3_c6_1DERFg}$r>dRRHXy$y#4**<7TH_^@cm`8HaS{)1TL5Ge0mOEwm3%iPa0jkeZR9H2C-dEts!;zZej>)LF9S^aoZ^KUByG#zK(#$&LWRFU@ zlozryF%#VQ#TUa*6vXE3%uu){?$VTePww$|_AaN?e|`7b2r|mVcE6s|YJ`wPH?$NR z{wqmc%nH4%(w<5o6nbO)TLSJKqD1vLNC6>Y13Nu*u>|lDYZ?)eQaI%R)(xnD&``pm zd{94x(kl9EonEsE35p);fmbT>Bil29CaG4lX2Es0Izc49`Y_SIrzF?J=TkQyRh}qB zclAR)I$i$uy8HeK`n8L8^i2OT%$E4=L|eLO}&)ud$xr1l^%8LLYH`mmKTK zK6}iVDUe#g%AO~4pcmG09OC#6#gPiv09geE z1etXdM=PnIz(VEf)bK7gYFtpy<6URZfGNZLYKW5x`=B$PZ@Jd(u>l@4h3Tmxn;#G2 zUvsD~mwdw3YKGq$C7}$O4p|CH9Sk&y z0skS`%*jRZ=($=4CGLr(&;SMn>?AaQLF6@C_aC5IKot*w7Z4}pEmP@ns({5KYzV+J zh4n+ss(h84oE-e$u3lYXq&Nq$gM=PD*5SvNqw!mw(v)b`(C^v28%u%~6{0=teX2o` zfklNLkK);t;D0F1?e_kGZ3+{OsA| z=&+XCgZE#YM$un^7()hADup>-r8yoQTwlyMHn9Rh` zW&GE6{f*qveil#Ajlqbx#|$*epGA42ME8D2CH#Narw5>GQE@UuZZ*$7QXX3m%_8W zbcf?|(x@a?*IDXaev#=#>8FJ{=kQJyMvn}Sa|(|eGOGvC zZ{^L@ki=y|vd>hHC3T_B>e~0)-h`sm|6^Lc&T0ywmSsf?Zk9sac!vBWbAV{(Y(R_D z+Q`4(#BOM$cG_-1M1HHc+WlW?gy9GU%sSzHDq(Tk*ZYY0_E)YckENlJ|(@Lllg`9wVI?M-~3&72$ISk zurqUt{H{IZ60u%fEPD5G_Lw{(HZ{&Y!^geZp$f%e`~RL-CR>-oRNUUn-fk&)t~{FI zITlOa-0;41zra=Fm9;VK3(&4sZ({`D-|+Yw#GB4fJ+Di5xL4fb|u_GkI59uhP6ncV-n`X zhOPh^Kzd4H?{yIpvqsJaZO6w3)_} zu6=e7dMN|H-DYo+u9(0_-9!Ut6nD9uZ`Q-N~X|yjUTj*0U3VSo`=BkJRk$yAsyu0!x57stMcVJWG7X#C1kI za8eX~;qql$qf+GijNkZwF9He)|AvN|4Ki&8H4+Vr3o06`qEJ+AC z`6?3npA=C|9B~Gg3wggr-$gfKOWOb5Q)?7SIojYgO&W3G8$uBa)K* zM23ZR-_W?0)GehxTcDFd5>Dtd11t`Al~uO(^}Pj<2p|W+7LRmeYb!_f_eoa{LdYri zW}3HNy`}(F`E$}9$~Cij+kpJ(^)rCtz+I%inNG<{)1IXRY z4Gqa@X~O`N07k*t(*Q+*sw$v$paa!NoB%+FDjf;rK35O{UfkuQq?o)3ASgiL0JIR; z%)0o!rnY)|dLU&V^TazrD(vqi3A$_OuMLy`!=5;Yh7kZ@zS)!-Xnc(ZTz)lHHY6yH z^8Z`YC_}5|yiv0htIX`ytbFbl4>G?WJq>}nP(uj2l7a#lYbF7HhDZ($yzdXfD0H(qKA``wadlnb1yO8O9;6o4-9qkKZknbjB0OOuFw1N^=z3+*JxJLee z)5U9VLJ%07k*dUUSJNARC*edSJ7n;w=g&(TpQp&{J9*=QcT-=Q#36XlNqhw0IAG>M z(el0D-`gmNw+9?-O>cS^&EX)AL;wG8I=n>!2r}CLcFr`O;S&2}2cvrn*Wd*IUIwJO zJ21=-AKtkG;{Fj80B%mv`E1DJy1h|73q-z}Dk?-u3q*}x78T=>;B(Yrd2`QADeZk@q-abAX0DZ8z*8HD#T{}R7S!>e*zEpeSYyJ@^Ap`YsnnYMsdVF|d z;w>;+U%!5Q^UcH2|Jq=ZLGORGVi5HWd~@1DHadLON5QQFI5lQkBz0}=?P;iGpukp+ zDhz;VMB3}uDvD5m14<1vn^Eu@hw#?O}l!vu#z2?(dMu|c%wAz;t?q;{$|RYW2&JQD(8V1h?RK4<-RSF`UY zm*e%jM>ke|1J6puPTxw!%OcTkBh3?7i|mNW)LjZ#_p7e&oZ45KG*wm}GF2X$4;VIk z)w<7*_&AbOPH|<;I$xix3%Y(aq@2166PJY>kA)?E;oUo{AMYF&54&i~NfLwpyo+ym zA9$o{E$zDK|I6j(al_JXz*ey~X3%Qlh!Q@XV7kh&2ZFVvRrduPLNcg5vdkPK2>2&L z3-O7G=vq0%x~1k#!6&>z`h9mGc(P9CJZnZW69xlY?+_ZaLmTmJxy{}+41EF zAd=%Oswj~TzzBkBqCtd)qT94Dc(V?p4+9eRlVR~{CluYGwSOa5xpBu!e z&~;AwGG#eifIGt~j!4$Uq715klQYJUQ*_f@wxB}{SP?KtpTS`UnItN8 zoJs*|*M2lqBy2js2^cP8U9t}i4Jd1O5Xy1{OOARlTx0>iX8vFATOxgVrON8+sDnBz zV5}pTR{c8Mrz9zJ)sN?J|{5u&(>M9oMVr%S6#uq z#~UoK0bB|-5VSE+(gklp!xO>JtWm#U%!y=+B>`Cvmp~53HxSt!77T5lw;6w*n0V8D z73>glfj|Qy1MZzKKvR$EHT}%k7_cXm5p=5o#3Tf?Kmm|W2Mf=SAHKQu{Tv;A{pwX^ zQYsM4FTi7Stm6p&QgE4QKA5lvD9I#LYMT6gt*xyA0B`8{E6UQ^8hj%F-CFJT9GQg{ z4KI8R5^0ol69BovT@KDvLSMjs?shZBxv7eQK_LoUy0rU%J6U}c8=PZdp1XCIKfHIZ z3d#$=ep%!Vjh927;}7j5$ZqMxp0XfHM}5IM5OkpS51JIdW!BaCpvGvrN@7@Sx(jp)!V>`sAO9l*&;b$cGc|e1_tZX~k z$jSUyuuTihDjz$Tc;K1!f#o*B1PFs*x+Hq*mMdUO@1Juil6ABLXi3_y2EdbGjOge& z?ob6EIu?9qn3;bAY?WAP2S9`G1s*AbXVcTC<$X(_xIYV8>3vHWWzc#pIbvplE9&Nh z1yv^)ELgN~Sqj3~Z+QwnbhZ5)`rV8IP@-*fW5{(WJWN+Hyc4!nAD z|MwC0@A0(Kz6l~k#09}jEu}H0FS}K&IBrBcP;_Cf0Fl_~!CP+JHn1xNU2|dB1bOMP zVYfLs47~KL^iWX`$y5UVF09S5l$c2DSoo*Qv%bqaT*wbOIp5z)o!%(N8vQ1sK?ENp zxlY55R4MJI#g#WU8L-sqbWKe!;d_3(dIA{F_i$(?C1GY{Wm%w@HKm@g+JJ8ZScdgq zO7N|-7b!u8Xz}pWsOoA6KTH?Yp9;e(A~I^m|Io()b{lQ6YGPm3lJhh9kv%uCc1`i({4l-c80)C?p_!UOq{BcA0 z!O#}&q?s-)1@eLH?Dy?G8!j(S;iJGv^Hd)KUJF1=OB+)Et;C*z-_(sd#MxJmj(&W>Cq0WI%BQTg0aGt$;2Snq=BBSb(oE%G7 zGPSj}bT_xP@+xw26pK@atD?AqfW7zRcV~e*6@*|uq{JVq@z2tQ+DNhw$1oa!VyBf8H?Bma7}~d zfvQx)BKD|1zma87<1!DS7-5Tb#fsZmMN%X-ZRuzs8x1#k4}cUNRpw@j7!=>z|1(B0f>4!5zoz?B4Lujg=H^sH z18KWvRYn?G`i+QaMay6=W8e_x^GqSY1_2Koeo}=UVR1F^urr;ofq=sR-%A1>pou}+ zg7TT&n5@pr%_YBny+a(Brbsb!4 ztV-_{HqM9B3_ra+K0eOFLxp<1NREj!UWaoqtf7x7ICP&X6fs}*AFCvcxqG3_U{n|Q zv7M&&6C}cbuY3n~HE`N#vgvnWJda$y;s{5IV|Rn)*TjG~4mwiM_sZgM0{A{`iaZ<~ zW*w4QXd$pQN1dGVfum@&08atf`d-qecUdFF>(Hv} z&um0w zmp<~RS&cG$1^yBRYv%AI#Af|g6Rf;j;{YXBR2-&AnPIBc0!z5 zPnAnp=2`LO4TK(To7445x|ljTI>c)RS&yOci2y8fL6axb>THU0MoIoFOyFNnD1Dm; z^bL;LCj$ssvni7jY&RtG# z1yrMA1c*g2HeR!$UUR_Rx*H$=4Iv^zI%Ij>GHCfrW*h=(Prpk5uRMi{JNU58q*fuj zMF4B%6Jc1SPa5wCnvN-S6|13+4M?KstQr7UsN;N3mub$==Qs)e_va71Iv$}eYNkRH zY4XDm!=e-@b{{Qh%pZ%*zzn5xHF;qisi=590vj?K1XV;WKEtag;n4Jia3Hmpd=2nl z6aurd(>;BCsQd!hVvP`@R84{^2&!xj^r6C*e{*d43gvH?zRQk?S(TO;=JfgQ$C2t7 zyax^lGlnSV;$Q*ZZ~;=1eP=jwKM^uw8!pBIe)MN0q2jP9++GUk*{E(CLgs9q=se&O zj5B?g(mVs(Hap4|UgagRP;t#TRLo zzd>~#0n^P2{t2$-I?EUBXF}WcId9L?8!iNc&V1>6-#zTsz<}9Iszf3SuGK{t&sp~) zWEIaTQC}K$VZ;e&X{AVPxOLeYUdhgpd59OTa?nuSq z`V?p6zsZ4`AI6|zP{DE=EJ{X#zjR6+PF=&rbQ9N7BHed=Yk-4VBf|`mAQJ*-NJ&xA z3;2E1wWkRbl1FfC{@#!pcx9oNfO>IiVx=e0$AWkeG%sL_feWy;G44A5e#K1)VnEoU z0Em+dwvDg^wcp%)R(+@_)#`^zZ3Zgun3^_2yM_bkx;1>6=vo0|B=m=7L}qzkh(n%#mQ3t@9|`J|Mw5W&Sk9_x<(;c9G_x?Eee2&2qvqM?qpK?AQ6k! z0-W_Oh}oCZ&%trE@pr6*);rNpaAq&3Pg_?=0sanQ;;vn+D`wEt%HmL#2{JwV zMFGB9WAMpU82ri3E1(3ilb}M67ttjZ5IBpQGd1@H#ng;)2p0uO8~LUE|)1V0f5 z!JM$k&?oCaRW@e~aOD5Z@>yKxb=#odC*i?bi8)+81{aVCY@eRP*02Q$mJi>@9;%y` zxIvwr%FVM3=M_LG8wc>%?CjVW<#~m@;9F4fL;ym+)r|iH4TKn=O_JWXQ;TXfbAf_*wZzF|2o69u zAu0=K&8X4DCZNt4S^;eIqo+MKpA4XB*fzfnyy$G044@TC9n(4Qa^%2f`wd3I?RFN7FSediSzHcn3W$beEui60K{kjQd75!5XpklE`C_^{c0 zc|jiwUsd-i2c$at)-dwZknTZk6nh&)lol2jm3N05Y8QHWyj*F9QjIFc9R#UiGN#N< zeXO|hsj)WZXAx`>c2NTNUfx*6DTU~J+yU0_-I~G4)3!EwX(dI>gJ?F`_M!-*I}!tR zi!6W>y$hoRaAS}CPZs}eh~ldo{vZknpm7a!+-LGo?}aG8dd8=)&gn%yAB0&jLt%^C zi;muCTZID#oZGv%4#BXlkVtY{7N40Bb(^|?g6cy^L}DE&0m27DE}y2IP)GeCn0-l9 zwGvnU?>_hUDi84C5hbOi)srZ!0xA@OYgv3~bmEpDAgdrNg^9*Jq~?F+zf);cFWs?k z8@2$9e!I$-Y?@K--2c|dXoU3Sd%4EOY6EUam}B6l#s8g1b;83x@dX_E`YR!WLBPS} zsv!={8n}#AEN0$k8o`8wwF}BR;&kj@1w``;s3M0OLBqw#n!lyFd!EPo*!_Z)@&keTE;)yUPDxjOTymp|J>_b2cjug z*NQBT)oMu339v&E4#GyjEk+dIOHEGh>=;!X&U>bGWDoZWGrQJ*^Xnw#an&>FXRsua z4NIg7u**w(KX`queB5gV!hr^dd3x z7#qegD_{lm=={N2T#}v$aXS&pw{7z-kR?NURYC~%pax)XYHDw%sfZEPT5USH&1%VD zxh3LX9KFk@C}sXM&^lixqznhwZ)lWs?E3SPAYPXVj?EBBtg4-ULkl`WV{H@fg;$5O zfu@Np2q+BY=7I(wCOX>w0W2^u7%MWa7ls)zk}xRS<%eOc?I27OWbnZb{7LX>9P9+C z_c!b-CsHuYprwKxio_KV^X-|8`+4bKFRy5Oeukh|{KoL6B2n8hTwes}gKVakg zvNSQoo6w0nVw{ zK+@u-1sxj+feqTOWyK{jC)|G9uxiSFn@P~@sJNQ4(YI8t9BrhcZj_-G+wx;D1H~|cW14t z(E612x4k9cGz7W5(ZwG$_TD&q;ERVG$7}$8AN_81pfQ*R!=>MRv78+@45(TPK68)S;X^j)um}(5r-BTf^#B@&4OME&AyEJF-%VDJf%#S}@c+2+#>@-12vZ zYMVezbUyQc0nABlY4gRz(k|2#1R(kGkA1?ScV(cg;H5D&vmkjGZLv`jq75yKkBW0y z^tQ_V8xB1Y&N5%FrL7McFyi9+8di5pw?vc`{#I46;|o_kf7SV-^{Q@tll#?cL~hTT zKtB(m5RPwN9(;oQ-}5Sf;S84P&*U>fmAeD-i>x0kGf|6DxWZ`EvQE>yr;Mj)E#l;z zjQnvym)tI&tlTDTEq3#5I@QlrPB27|HP|PAhBHy$a`5KQX%)r1unY62xHK9PziF%G z#`NKWEdcxNp{yiY3>D`yVy-z(tO*u+?(s6sAb-idq7H33lm)XR@$_IyOuja%&I+5M z49d~BX94{Z$(SXrZZ8K<+4YqT&xjz!#LUpVe7r^C6^EcmKcn;E`b-{qU3B-f8}T6Q zkp#CGe{Kgdpe|tLC0~65cF=mLJp;n#dzm&&9Bc|S*>iTAGr^n6l6bAS_JnRvbf2f3 zB*-b{pYd2SglKkqVVaY?C#_LudXDo6-2#i(AxHpYXXuSrMirFg$nmk!wx2MqrvA4D zuJ*y~&R(QJ=})W~L`L$qClXA0d8whHAud3qvBgMlGm+Kfo(yWPI zWtO|+uB%aX4QzkHIIrnlCk`=-++)1I@+(t-S!cBF*Sub^IOgiy6d@vazRa@yCUtT` zKV|j~`Lg&=Jm%A_~%iV?gghZNhl}n|H-f zDKo8cVI;c(Itd`3V-TUB=;m!_m3oz-C6N4fb@qxY2dNt;u8<;jSmSn@d|PinYu0@B zrYZke&?2_r7Ut2qn0tYhx8@w|3iHyqto_!t7{qqrY(amHaee2`KAuwCp_mdp$LMc) zNAbs@1&=$b|nRT#FnB@r&KGY%ZPr4gzRh(mP>`tqUvP+I!h>KG{I zPDPIxS7`$$|D8`pDzUUr#M2N?jr;fD{qsxJ--a$qZI8AzGOR@F)YE5Tr>H282t zm9x3Dwf+(AM*WSo<8{!8G;wj?`>Xtf&xBO6d&Bt2=5UzNYQ{tj59AU^WaxT*iJ!K; zBQRC63|d$Coky3a^F4b`V!UKjm8zXjW;_waKc&JBr09I1Zc<{! zWDsN)>9BJ@+cvr&!13%^ph(&!#;QzsHSN>w#7DNs0mFDbT*Q0QFWM1SWQe01#4;7< zHC47eXu0#|vcPWw^a9$q2S| zArZ9hmL4wI@(ZeG8T=_3;L{~UEVvE+qU}q&P`^hBGi)57OyogzD(>zbMaTbTm(B&p zD9!!OuC8haGNm0jcGiM1a4aY(NpzRE$5k7yBdCQLKkz3$-A-zIi(zcB6j5_9|9xvt zA|_KteuOVUwBElXCz>GN=-ZBcQNIBKH@-6Xmd%;OkEW0)(_i1YY>p)S@-oAGS9*2R zlLc`)GZ8wc!h`gYe$x$CpJQzd8W)p^R?V&V=*Uwx;Zw;3`|F)X-CnJvX!6>?>z~LJ zKqDr*y(JTVmBz(~RZH^uTbb5cjNp?QKi}bqf}ej7UTR>dGezT|xG{+^qm7cgnoUQu zFJ;$c4zzmENwRvRpwJF^l)=4wGJsm|iomi-4N+SyjfM9bDUKWtD?Uej<0|$8eg*r1ZYE2HB;=Q; zkqb5mLFE*c*0%)egfA2x99ko82O?fIE0y7uNKsx;{y3w*pcbuSe!@#@Bu;oQRlO%b zFaWztnB|A^#9{DO>s|aMr=!BjhrT`>aOCkZK1vjK?V{}QKYp^5 z55sOXtCZmp&=^U`n;s!9><~I3E_AYgHw5tGPeLHcI5`hM!18h$H@JWQa1<&TP|Tsb zWv#I;&urHLk>mX~rZXXjSjA6_cNOfzrNu^`^tUkI+jfmB`2msvKX0m0Yp%7U!k81N z64XKuU<~@L!)ZrUHZvGIn0B+_3sgBWK`)zwxvOZhD;f7C5=;|TqT~H=sAUv(O*j}u zo8@<%zVyj{^UEP)@|ON`1wQF1G6~s6kGO(gE-a_xM?Fr^L3H_GU&;Ji$dA}EqCqMS zv~DKJh&eG#M4hO?@bN6|%(Vj}y5v#IGfMXKjhc_j{AOQXBFyN6=i}sxWZT&yugCk_ z9AU;fs@4%auSRb8Qtr`tsqykwCXjfb=?IcPcr+T8ilrn!mTeN>Pig)myfdnd1|B1a zxi()E;i{tk($zq@{V9fE8o6iITDqZT3G4I+ZRMd6)xWpxRmNgYn&rf!_mui6E$Fy9 zzC+0euunnBoep5(5F;`p3JD4HKORw2>vCuu;A(aJj&fHX|zdntZ2hNvOP&0+HO@^a4D^u38KADog z{E!*{=icX4<(BO`SV_c5#Fh+Gr$(Msw}?ID@MM$CXei$J3>liI2i5q6N#YKp-ORb= z;`h7^cZfJ8ye)v4^lC<&O82uebyP9lOxVz0O2DYGNrsB_rC{1K9tz)jSQ`9%P;#IME<(fs=Y=$KyM2|*n8xRBui86 z44Hq8-4nZyP8`=>dkyjZ4L^axnIIf9BOzwYmgyOoLgf^=S3Ax5tq?b1OX3gF#2scF z#^1#q>ui-o4Qu0?~v;^>6kn`J&(#--iK;8wsuB%`#ca9 zaOEclcL!K*lOh^TW^WqPXafC@?24`6+aFtBzCUo;3?dC_#y(+rcj}BNi&0r@M)n8E z@}O64(+2Yp8SehX>i^qH^Rk)&9~+7p%Gm;xDK~4?ppOQ33R-;y z(BGH2*oiwU(3@rCh#EZS$ddl`y@yyEd0Jg$s4Adyf%$pSqeJj{7IG}|Wgo1`w5*wI_wVB@jZ%&9Eo@@{hYYZSuMWY>tmTa^yDs|cxpTG z*C=g@x9?WL)EnJj|Lhu;eC=229fwjUQ^LveCW5%E^tiI0y$9-RFKSy???HE<^qXVS9$NDuZch zQw+O()sy=^9!k1UlS4Bo9!dE_t)z>Oi7uXof{4nz<=p}|B`AEDl#bd}0^xWTnuw?x zHXXDMPBOLX&{R#sj;N;b+3KncoleUG@bs07vNMAf)9eOP5_bKH6rjvgXYG^ZjBxoo z3aM96=L?$mX#IvJKPwq3ofYup`yXw4Ch!;j{zO+!NX<<8nE6TUTX$k5fjJ7z*57O^ zvh`Jib(mx93h9VhPOl#1sgbG9qhLqwqHHuCzdXid2;VP~c-)>(_;M!)fK<_ebLsh zAPkmmS+eavRpSm;*dWF4#2<4G%LqLb{c`0q3kzcTmpKhi4<#=8mutj5^QDfj5A7VE zN>g_-8jFZMZbI`Hn+=Ly;YCp23YQt#?9+A@`*DtE&WA)E8>v1B;yR}I0$m0roHfpY z{cLZd1}g+oJu;mhDmy{86ZnAy2wb1BzZP@^1T64P4&?CU(!V^UfbtQ|^r*hxo107v zJ+~Ml7^$fJ?SthWi97tBlZq;%c;AjIZrn=J=QXo_!x~`9(9ll$4R(k9|(&>e^WMtMOY!d5Vg6_hl(tmEoK6gg(L5YYsiK?Vlh%K(1q1!tpAGzeE^D%m0{hUyEfH`w=xJ zMw=5yuqqes?CqL^EZeJJo?@mEe@1QL{ImU|y95aCahsV?bD7}G3VOqExw2{89m+N* zueg>#`l?TKT+~!J%=2t16OZX0o|46gAz2jCTt+)ug$bWmm}{sQ$d}>8ljMi`%A7qm zrweU8Y!%+L7*r1-mCqpG40Q>3R)*U{pn5KxxY!~{Mt!Z#q?Xm^`pQe4jdTrQA4y@h%{e_ z4_Dv5G%Z_nlhzZD4%eRNynA(^n_9hFdXoRBD)w1in{>@VTW$TL;?yvz$Q~7guv22m z58G)@_xqL8(I>sey4nRvTX(mU6}Th3nErO(xf(;Vs9Wxxbf1cJct(M$RyVoa$)2HB}UPH|>ZA9|jYG~PN_p>a)@s=F+hLX`{{T>LSN*{MaU zg{RSpMf?0Pl=_|#IBp)H#k@bpj!K-U&I~hb{@LNKhfG10x`&7M31kmH$cv9ub3)a~ z%95SgeJ7!ku$2vy29q^^KRw8m9g%X=kU?v7+5Ct6uU@D|Whj)PsS%q~G^orUp);}< zd8;-;PRE~vCfkqJ9j~PN3S!qTk1#3z$4ti_EP+?6cKCB-iHV=0nOAPcAn8R;q6mID z#azBXt-tlpo0?nmC*hl;A{jWN@0E#8$z+4KSlW1Nn!;_p*w+{_(K_8&rtp6gAK8-} z*pQ{SnqnU^+Bov(R3^_kKd^g5kH#8ihJj=r!#!jaZ3-g=11miWWB@rnr;a5iT@Wef zmp@ZzOHSR=DJn=?-bAMeeJsu^Uw#`#hFf_iOS~&bik7=3xrTt}5r0e*@!cx_L1+us@Fl_E zgB-q)+zL*fA%6VR=YK?V-TiWj?jYCY&S&SwqTuxBub5`c#ZPI9mOE^7rTk&MO&>}c za*CM3$5Ls}pzBtfQ17v02YE9+5;D{nr!S(xS~FyM-ekgr8&K zp3ZST%M%=&l>8I)NP>1UQ=t7VMeRYN(=#RoaSSLfiha=!A?*+U(e6%P!iPqn(auEi z-rI8N(lWpAW}NKEwfq1KJyu$y`O?;SoXqInwgj}Lxs&UCO=2RKJ6O;I56jMf$FwiLTP2(bZ=U16Yj*Ib zkrgIvd?)A_bjn-l!op2!_GT*nJNatUiA6@`CIR<&zyI$nE;6jDC*3~iKkesAQG+Y-d=JOyg!MDCjiql>K2`Q>wW41h zZ~&Al@7pI7g*ra0Z#CpXMLNPccA}mwl|nieDN||=R;>8xf-tC^_&}mj^P=hoL5I^ z;eVqa_(X@buUY41c|l7d9r6gymOIjMnMAI)-N=Uh8`s?OPt6rE^zp^@NsI-wA75*t zyC+G!PufM1=HM_xv%znZffv1<M4)sNn5NftH!7-4d<4^)E!(O*1jJXIJv>|2o62Q738ogT}q8zjwR);gwTM1cV$vqqozW*UjXv32J}oHf7wv z>1Rccw50oZuhqBc6cr86EI@y8(qb>z3xWZRYB zc~f0){xS}M1Wt|}$5XzuhUEzoH_9_Q{9{H;DS6&^$No7QQ!Nz>pAtd>{%BW=_skf1 zEamJeR+wqgih0lfCDKxLjJVA%ZE&Gop`81+_uxxHHMftGYnt1Nz0kUktL;G1lv~9E z{>f`9T8+DTr49x9*YGoWWat=kWU7>|{A~1zK;kZDx&Me(q4U~(p7o%XLc4Kp{i6ljC5wV*LaD)S-&U)5l|lMyoyxd2(b54`*flO$^p0E0L#jyyjH?tHyfn z^*;!BzFd*E)@m#qk}RzAchPnG7r>Xex& zAeEm(e=9vI>`$Nf2|Fg6Q6pT6;(*4ynFJxv3p<`KzJ-{)mTd4P?b#BOc1ub)^dX?t zkZo|7%Qr~LzZYRc8+$@TQWNx%BH3lRH#= zYDQ-w!^`mGcw<7%v~IZb9iA(j-j;kB=iuZ+Nxbgu`|YMN;W5IF^8KQQEiwFmlz6QX z)Q|Ap(XVr7kQ6LkPFoGTJ?p)f zdHZ?O#Q7S-J6|`GQ#SnfJUxrk$AfZz$a#JCngn0wIgP5Unfg2QBoC#pn+lEQ^cd}} z2bypEySLQQSVws{YWy4#1=PLu^EZ^oXvUeA z&C?^p-tfoS^}2Qkc=gQj1~1`Se%g1DBU+;z>ueWpG9F!S!Sd>1Ojan89UIzwv9UU1 zY21;N)%6?inLKuAtHpCU?Q$Is&}&9~>FVmrG5tKbK^V~vEn{ zMU2wTd2)@N7&kHt7s;5}dzM8S@(Aaxv_kjwaf`3YtJB8UJ9Wvt;xfG{BtPizl6wpo zlDv*PqS}Zeics<*tgiC585mrI`1-BzMs&MLsPH3N~eTYwu0LBcEK z_67~DU;>`fXQKS*Eh-6TDZXc4eW+FNxr{<6FvI|wOx*bA=96!qMr8?#h+qKlL}2B5 zX~6cXn|NyP$hi$76QfTvt>J7e=ep_E<d{wYTlr6BYR5!+|h>To} zO1g)+{*HUP^>FRo@%j%QZOte_h0=h>1K*XlRIko*OmFK@>m08-*2+wa?Ka0cd4FDD z@E8xA5kCH!ef9EA)dh}*sLrK8nO>Tk@oJV6>EwZ)^V+Y!u6_W#+fO$8ZS|4>A^C6u zm@C5=cK)do`z~8?!_`!OnNz|&T$5O7+AA3E&9z0u-ykVc*$@{Dh)t3ob6%HR>%VQZ zVwPj&mQ%c^v3xB0+Le&;u}txYUWE+Xbgdgh-J2uAL?ML9v@m(4 z(dtBPiWBUwQ;bgKzcwu^@Xt>8Gcpy*TS5^K>$dRu9==oJFU9<<#w zW0`7PA5bkvlbvYm+U)Z`tQ|_NPLh(~6uDFN#Fa|p7K4wabq}uoMR_`TQ{9@><2A1D z4=%n&5Hb47*<&LeE}F2uMe6UTm-`G&fsMk>@A9_*adT2-#{A`)F@f2n$*NSE@C|1YRP>v> zFw9lAsr{R`6`4?Q4|)rm?nTbKq=O90ADc9Ft?53b(prd1WkR<}M!Rs^bX@L^$q&%DW}1 z6tj$%riaFULgA_-t)J*LFJ;FtwsgJX+TKPC*PBs~9P6Uq!>Im)a0p?QE2u)h4MCbEO#Dzu#|f+`IDPYmZQ7QTe(XZf$0H zHao(|WHY~tnUqcQn^0qQ;XZ4*^^e{tKOXOQutzYqSfcw4E?DEL9WrdUxb@_G&GkrS zU(nVXq8kgG#!6Hw#Q%2SK?F6l!+)NA2=$IYHQ{LTXnuK^j( z^O`GTHp`m`xHMdKKSa8v|0O0RvVR@<38IIq#j44h)bQ)7Rd5WuTEuf7jkKl&4@;P@ z6@89SbL2{sWU#<`>)Gy4tj2%yP2ou0?Har~xrElv%rblxHO3GvsBG{)Ge8StJcY*e zp&SBw<-+s_G*Ds7cz$O|`#m(+Os#U}n(kn+Vvc)0DZtFARC+6Apwb?HLJ%0{CWJ{h zxD_FGb!k?i4DWG3TPPV}EB<`@vgyfNyicf0cM(;i+WaIvl-$fKhdY4}&@L$8bh1OyU zdC8Y6-Aw52xWlcrbp0)Y+~v!yl8G_O7Hm#8UnuBSU^OqSeCdR#kNfRJBlxAkZ7H=el<`pBB@Rm*(hudrjPU0)a@Zs1n9p z$&R@8EP`*^{$t@w#7o=7sKc40fTN?-wPZfSYT7E2my6$d>b3?V0{A&&Dk_GXx1(~K zHlBXiH7axD+fVEfy5U^tO(bzRSm{~IyWm*+28E5TBYizwO+vbb;Um1CYfU%x!Dftd zrN-!-`a5%cIbuZMwbVyPBiq9OQBQ@B4h8Pn0#?-c*Ftljv~*B!o?x<&BR?U`8PF+E z$r|Q`Ap(lWuz}+6TenD~RRI9k1e1`CMcG?S#3$@2+RR2#y($(y1Fe}Z; zmmWopMrL#J7c2SR7>xIGqMh~n292p7v8?rf#?mxmJcXu|HXe+Y&tuCSxg{KrfqN(V z23^beBG~wjSJo-@68t0*omILq`pmu5n1otG2wWVVJ>n81AM0$BMjM%eeX>)Kawy&a zp%mVXZ6VfheLF2^J?Q9 zME8AHeF#;`37dvQPj6^EpmZbR9yg}T7lMKv%M@lH&pV0Xs=<&uRtX=;4wXARq3m7h zi&ZRE9>TcKi&rwmw5)I5J760g;r<4ZE){oW7uQlMcvS>>H_Q9AmN@$tf9-*TBIB~o$Rv4| zAK{OT>WdVnEOVyDd%s=x*Rw3poU9t0$tK^@eQB1k@iM_pzkXptoQBjIX^#B|@C@^u z5R;`$4CLOf{PS?qD!*W5Mf@GTu;+LM zk^5^={tpX$UL1j~3fgiXXZBYgMJJyxe6T9z)-$?$ZJ!7@B@81QLkl;mHa^VsxA(-Q z`L4WOtBQTt!ym8*7!uajw1KiMIN%;Tjy!c3!U zPSwb^Q8Z{3Z@h~02;i0H&O zqKC7r*OBLKsSp%w4t5Yw$0~{(Zp0hGkS(MC;d9M{l9A)2wJau>6(?D@sCKsAZKwN8 zjMopdi#(?J+su)Qz(u_*k>T^Hm))KJhXu(0oE-ZA=YJ@M#I0qvwf+Z2wlPe04^3P5 z??SVLM=-pbHK%*~uJXM}x9LU3r@TDe%;r>h-y>+lw)Q%v6z-~LlVD^}XfP^}w>>iN z4GxY`_IZOu?rWvoda@aa`Jh~U^t8CT?djv9_SMYK532uI>;`MkOfEP0nn!s1trUuk zG9<+ddv1R5NR10E6>Q@sHzdmJ^OiEPs;cHi)9S)h)5GKMc&-a}{;9g7 zebef@-`RM?NZ{v&qR$%goBNdqVfk18jb}TaDGaB5$)xfE&)Y+@etD105B9lhu!9P1 zp`fdg%XTc^Lj;Tq0*rC%V`7PrqmZPPWDKgSkF@$D2vUjjLk)s&T`#j_-rwA$LBA?K z#{MmNhyHO)YjqzB9htl)?nw59!f+t1Etg~Z*bYbW!cC(0g}Xma5j=qLi;M8LSPNZ3 zxOsfhjQ!kAD9%eh#i!EEDN7RK?lRoE)6wzvbi6Fqy7zpBX?d8pNo`}2dfd_djL1#% z{zykP>stRFk!Y3NLAJNZ+e0Q47$sACb#ohLnD*}{jn!kwSGeV4-bO1UDMATn!4r$E zl??CoR3F#b?q&=wGqZLex&w~13ig}GR*EuIeJ%waief)>5QO&88YS<{h7#1G9_GF? z;ySX|m??hhD0GuPWQ2OHtWIR5t7r4FJJR+|3C|aNUi% z-|X;Gy^NJDC8%yFPbyOIJ>gIP?JrS0iFk}(=MxO=^`5ar?Eb38yGriQzL8eBc3<+c zf9mmLW#zC{>7%bjN`be%{Dv;B-_ogidT*v8kK!!glKrxNU*uWEx(!eK`-C5s82jx1 z5nA$ZZITW*%nY?YuP%QfZLF?o^khEtJ)xHA7qt_&-aDnw_q^7h7n$DtsRr~f&IifH zycCGk-rS*%IRVl1dab~D9^-9pL`pf752m$8P1F+Rr76FP=R-;S&8*`HBP}6N77!lw z#%nTIOC>NEuSQ~zY*lLt3YSJCB)w+Tmd{#u4;p@`$rbU3-EhCq$Mv1qu)psbsOSu9 z`k6d^9F8pbWD`d}o}B()L)h9C|DHSM^s9+F5g~JS#27oX|G-ZcFL`>=D&=xQ1SZ|D z$4m=G{T-gZ`8^AXR^twXG#FM1Rf9F6e8ZW=ZcBL{t@>9yIluhYnMi8i`rO;jdM5oi zzgB}n)Di!FYhcN=wEy5`-%Mkdko)W7O`4cQp{Sf*8Gfo9l0kKg~bL&(LX&V zdUA`;OAJqqpLnGGm=#{3Kfk+i;Amg}V7$qF@Z4u$Ki9ajqpD;q>w4imLmgdR<{5;N zDw2i$>+K&~ahR$#rsxTO1EdeSB*ny*F#IyMz0>+m3GOyjf30Wm-0V_%ru|4kw~`R@n7)YWB~QYAb7=2W4~5-5P}Lr@l$P=r!<( zlY9NP_F@Syf2`JF@z*sZAo1vc4 z$p6S9>AlkNc*xYWx3XsE;(5AtEa6^WYW!S+^x>3iD?J8daly>h(^o&lSOp-qCy+4D5K7&*kSK=ExxhDe{v^lDAjx;SAul zVnz~wFMA(sEAw4tt|&YVtI+vgIpoq>wu17BRtc`eH%b1g@^goYN21S#>k!y;exJ>< zW++;kzZse!M@^bvC*o8+xjXMlOOe#jI`0yh)m>hs!M1iA+9_Gi_x82q$F*XF9>#cPWfh0nw^W`DY!8wg8A2vMdIiha93AsxY;c?|NWSCe> z1T~H>lV&_hy`yEuL5kSkHM7ZBTgBJs!WAT_%x|?4V6?Z{hAf9Ihn?S8y`r0jlS<+w zVOf{l8rsu4mg)Lr=izW#zb1|dt)9?B$*Fraj%B9d3pjU{GOLIW)FQRY7=x!>ey{Lz zzxmQSWUn6ZrZ@(_z{$YOhbMTk*-={=m_rJb;?c}poTfNYA7O797U#0GjSj(Gf)5ZNAt7jj2Mrb=K!A_{!3pl}G9*|6!67&V zcXu5mxVz6laCc{h?_uq|-o4NH-gVCWc&>T4fbOpDs=BMXyYBazZZBLny7g!{{FYnr zZEbXgnGE9dmqNZ~qIZ{sYu6dQk@(znJkjPSgBwOu`u?3}lK}gJME@(XBq6-DY?*quJC2Kbg1ei81c1$f%RJ&dmH< zyepM-1pcbY$JqI~HW3h!Aog+FpxzkL-$gH~)eZn8GprNsr}&^vQ;E4h(-((7L@6n* zjvQfT*w)>FD0n<_-{R-DHB;fpK$DPEQS0nxnI|~@Pb8BtKFTZ>qvNuPRUIu|q4__N z5E-g;0@#ev!~uO_iB-~39>qsS)h@N12}=dRJDFJW{`?9HVxbFWK5YfT;Y)S`MQW^4 zwL?d|7RR91?F{QL&7L})PVr%xEL@W0pu*U>e&981QSvkv<8?Gb#q&?Kj>)B=HDh$| zc_p4nx>{n&k7a;s9P?NMvnhvI(kQ51=KXVcY^KWR_xO@R4JeDJ#3CH0ej#IAud%Cr zC{*x{-U&}`y12Y^8uNw0>4QxwseA+L`*c0~ZzSJ{J@ngfP0!ILbh3p=Zn&TGv(1^$ zpO3@pgc-6bnQiG2effGQts~DG?+Pgy7CZFX11M1RCmPQAC?1m7@nR}p(P_}WDaAck z#$xb~@U8!Tj8RQ}OQt>hz?2u{pGCiIx@eoaz~zjk*!HV2iG8{zj^C~H@vjofb;&$2 z^txtD5$o(~)i#%^_ggiYEojctWy!wtb56;T;v(dUPjC&1q@+)p(q}n<|pp)!`F0G?r`0c-Odvn1biDmM^8{>rGfI>dQ7wNKT zTBAU#ISi)0s*1G{>Cg;>t?tEf**tfxnMz2K1>c{0Z|$_InJg)O;8zSS81 zh2$y9_IXH2!fe>=sATS&B{Z+fYzz9OR%o2pvBnN7AX&h|)0s;6tSur1M60N1ld6n} zU{^@Ts@gd}(O4n%1;2lGZ3Xm81gwL9-&U6J-x9+15n;+5UvrSleqXOmz(+dwe2KH& z9W~5B!^hXcDsE@q?FEUQwo%6R6xL)+>~`ICfck*|sIty!wf z^?B{4TCD@-adyl<9H2t5e>9zG^22H?m8BR~$^8ev3eu5~X_MC#`+~zP%Sij#Zj8?> zf0#x0ITv62Fn$sdAWnw4_`yG0l9#%OJOfvPmcHFO2*JYEnRkV=-chC(Fi)U1-fKFH z=^?@t*AHA*ToND%HZ!yNaz?6sR+bWgAeq2kWP9{v`BwsHkM!GvU3CUQ10l?Dl)Am8 zz$=bH{t4BnYPvJIRpl^WB%fJSYnh#zyS($Ku*`K<0Tzaj)f8Oi49cN_Hq=hF5~7qD zSm_vc9Ulqj-Qx-6EODQ-JA)i1m-rg}%BYzQi4(t;eHu~l6{f*MO(!R!kJlFpn(N3L z@;l>6=JiFhGE0Kvvg2)fynVewsGF~Vx<`uT4A@tFi9Ho&8Ht>ON#Ghx>iZ4%?dMFQ z$<;5?`8kxZw%Gc>vQPe@lu^^Nr9!H1? zQexLFk0=Exz+(g_c7rOZgUw_oX*cjgvuHkK61fP)WTNoXOrucHOe2FkM=DSB8tLO!>y&2U`JK?!zX|Be!?qs?qG@MOQhdq4bo2Jae(lH?eY;t zKO{lkn=kkQ^VsUNzBUsJxlQTMZ9%OTM1tsH4gw`@_V~`-zk-3n1V;H|NrH9mGo=!w z`hd{+iF9DPxU}o|p)<;6T@1Sf%o$66mWwd7fqA^riVv4?dd-*D4E^CXFU z)E8pfB4v(^5S3;^FRBHCvTHt5+>X~deio!vsxQpQCkz?DXe$1N7s< z^1ueXt<3SjnXit)=;j;gByDz zydA6zA+gaK?(a{ ziV_9( zk*pKf&A)qo@zm9gs^Qu923k0K^nnvA)&FdZHS2hNJo@&DB%Y(?++pFe>7}!syu?Do zC#%a-oAcn;jn>(c&#K3JJEHk{&O%%g^`A@Vye!K0E!-0BR0eQBG?tA9#T%xHHqGrl z$Njxo*lY6jUb+E^7-szRru5iBkqqD93j+=iupK!Xjs_IjJjRf~!1}+{g&%7geC$1%en`$;Fo-eaV+bR55|A3-h{RJ88i` z8M}Ze2VZ(dX9PYc&Qx-K6lWmnKbL7Y=^0+tIGN)P8|g7V`Kew(+NKM0N}iOA{uUvX z_r}#ad5C%<&4TyBp`2K`Q(m%5;#EP4MhXAIgu7qR7CnoY|0WtGUITcUYO(bB^n<^Y zB!)l22apvB8}LOxz3B@Opp+IYd`T>&Mz+0viB>SG+$qUhp^7a8om9!r8P9@-Yd2j|r;5eeppxoJ(BqHT}p19}?Oa>i)%kMKCUoc)s4`zB2 zc^-;}O>)%qe)Oz7^?OW__Knv!(R8u96zCJ)gyRev!#p2(j;*S(70(c;1%pj(ah257 z-TKc12WOmkZ4*kR0Q6Tgpgyj{Y5+7j&hEg85o~5V$TVpt>*+0e>Ic+LhM=q0xZ!4+ zKc)AO`z6X9!%xKZS{Z6KRth{w*d{m=0rL^^6hO9xPq<`BiD>Z=K9+5IuNPhOkc8X8 z%X$9HzWCOq-z{qwejqZmm>%H`vX`a!6%yQ{PoxE!2tN@)SOYf*f+X#F4cGj}nTn{- z@1e)v&fNL#A;-8lH_G)qLwH~k;QTUZ`5r6W7(7Rj>UrE&2JC(Bxd6m$=TkJ?Bd{oeYYN(4~ByNN{4Q0rbHrzS{JWFBL`+d0*tnI~Q}?Qq#|i??w76ekfzs zF$gZ_Ng?Fo&pS@>FZ=Cg=|4KVf2w!1Y48~>ejn=ZKnhq+>!3A(uep4IC?C+j;f1g`B>#pe-8YHtq2(u-%5-O z)G!>4VC59d9jZDj{pu7QOjBOvE=C@7gUam}V}k@yZ;gL65@akPrb=!ICiU7K9)#`q zVyVr`<44;YF!Q?3d2rB2ZV(yR4E)%0@YmO5z~gJc`Ta6Q z-~)m5b)Yil{42oAum?1^mu|2;Sqk*P<#;ZGu_`|8QweQ*JaT4zzfN^%eE|ZK{0}&_ zw7ge&Lnk?+BuwpN#C(-0jF%~EMS*}1C*(b|`^iicWfcqm6G5=250RA5z&*<~c>Z-w z0IhNu_kG?Uq9`oI_ohA{&vz);amuKgrERT@6?K?}jr^#u0is|1#Ux}ow5{V)Xunp| z9?gS^&f1!qsXZ6g*tY=^C`rU0)6$Vy7rdX)+7HAxvr>Q7S~M0{NhW-D4sa=hrZd%| z-nSOG=B66%641dMj;PN}NQTQMvUb5S?OY(JqsQI6_B}4q*uK zyRhOf@&1u042rP(cI`fF**A*(2eWtJ?pgA)T@yzp`_58y*3ZJJmg4u#C)m=m7Tn}e zV$*i#d@%`7J{zHe6XoV%EgZQ5AgK7&Sban54gSu!Ew3-S+IYDWMc`omevO#Bp)!m! zc!{&-y~U$cK4>Z*q2#MXQ;at>CscA;wJLf&kXUuio!2GruxCb~|K$j~E zwgkZ2_;eG7bK#hY#~5&#-Nhk3N6t3{ld^e#(t}a?n}XyNAbntAi}3VYT3gD@wC`;f z7pvT_{|X+~@U!#)!-j^thW|tZfKdKKB-#?}MW*vZbb*p&n9ejYj~lC;W;jnUKxd|Q zXZW^y3lXGJocp?zBOb6N@4?`0PL&hh1(#pxnWY@;pnO!2y2yZx!MV<@b!o9vu0Wy6 z1u9!-S?Y;aw(%K^maw4C1UJTd9e*&;f?eACd6B7CqCWqR1Te-&nhC>SG_#?@3S#|W zVFgT;D-Q=-7>l!eC{shZI8a z_4G5q!p#%xywXsrjq;R>!KbzPlm2bL%QWY14IgyLT6c{>GYxu87S0gv+So|=4+g$x zP%`gqimp60;H2TsvSqd-k08$X#uDb+I#CN)>_Z~9x^jvf1gtw)B;OA?^?K5|TrDk9 zGpy%|F{j+s#?m^wvCBAM4UJ7YkMk&y2?&LF9s=s&{PkJP_6OLKe4aGI{Gf6pG$37= zl6(OxZzVl=$7?akCxIVSMrCiz>aPjHk`td8Zm1p31Wb13A^=sq_VbQ1Z5BPZ@IhnUC)l$UsFh=y^+>>(D;(R3h z1Ox3?i()t6FZH`Zh0`X)!w+ALAhR}7tk}sz=&>9Uq}Bv6PZ$6%JD1oR>TAOy@yr$K z>CgNNslaMYM@e4r5=)M>&YnC~d; zM0Se~iXiNYSW}jAIisds#iyHkuRXukObp6KS*B7B-#hlzD!WfRDE{FKYEWu*!je!N zw@lq5*nYWKI?7> z==y(w90TGjdZ+OQK~NtUi;Dg}4}tS<)wqu?fK)@0-U?T8byaouFt`#E^$Cou1epRj z|3ce`e1#{S9|e>6-R`ph1dd-W+N^D5;4!IL1pk7E;x^Q=uF(5d&(PGcwKi=0RI5DbOvz;lHIJ1D-p;dg6zf^ zb&RM{_?_~P*sZ8lZCB_8ia<$+2L@nT+0Sa+ZJ&f30s^V~Da3be4_h*L6;^25K8Whe zhp$5DY(7r*585JITA|~+xj&ldzzt024V|V5As4fZTLosVmqu}Cpic^aE3_pPh$G^h zDq0k$0o!KETX5d$HPcAkmL#aK4U1kHJPCX=>K$_+X7TZ5;R86Qm!+O-P9to#W~;y+SLy3LSD4QhC?@k)QgB2}Dj(-EXUF>= z4UF*ANyf*96Nb%6bTf2C-XV-MYl;Eu)R=@-bE{2oU=ns?>nb{v=p7!vSfxlQeJ=A4 z_H(R|1A%|Wq+dPqgz*V>!DZ_7w)r1+Z&e)2=V;Lftc;Hxdjkd6FcMs73aQBQYS2jM>Rs{CPl7+wy=mojEj}O z;hbu7iPO=Z0}S+<)Zo>AoM2uzgV#I$_d!#@MA%@mNxz`|diH}qE{d605PL3Pxy$8D zckq>B8R;v_u<|fmJZ*d#DqxD|g-?xS&_O`L@jcjacz$((fm@?fHeX>9uo55+Fbhn2 z@#QZ|-ZemjjC_AJ0m0_KG4#Ew0RW1}M@o3~n(9`mpwHvLqJYa#aS75$y zV8+MijSIX`JSQq^LSf&YmqO5_Ki`99-T<~|MX*3rdhg}I*P`6aQV*{U)gS`E?ST_o zzFfV~c7{C`v1MJH;nZ}pn04rSkJtY_X9rc^NI5*l>`9eUG%o+QhAJ*DcmPIn?g1&jS;qTn? z3ig1hUljsT{7J2%7{}`9h@!Na1tC-e*dwyheN6ocX>i~w{&6}T|~VE0A1ndr zh+t|wPweqr>5G=Lc6=4Jzs~~vZu+WIEEr3V@++!KnegL*>;oHDNj^hzZz>q8^FiieXG56 zg5i|jqNsn2aiGYVzI~E2A#VQK4P(M^9-=yZ9QZ~erMB2!S2-0aQg2#&wsvqijoe$;SYig10+ig*hBV?$^Yg_k*dw zGhT+kM*4x+cA;_pDRJVFzGS0QrrOcjWJ!Z6SFXx_)5xj!Dg!Vg>TLl40aA{Q~$kO z-)|tYW8JuY48K^46Tv&UdaGT!if^U@f4UCUWVd_N17x(I{yS;E092m_WUEsNKWb~` zx^ml^88w0cd_ZTp9kyf6N}D*Bpcgye4^Dhn5Rgsj48X+mLciY@=?Nf3l8K{5j^?## zPR%^O>Ip5!-bN>wuR&X=uOMB40J98Q!I=7elcSxkn_OkZoST?W0cfU^hZy1nGXCP1 z3ocx~Hb7F+io$@ythm_8;aTlmRVx3bgPNyj(hUM+)QW#`&Zqv{$#fNzcosr#0j5?= z`*IQpcPAnHV6WUQNk%CBq1JX<0chl}M8rvrBM?Qn7ZsC%{|Ok-J4|*s&^SxyiLFiF zRCOb=wSdh3cSagAYg59vd2ie;Ih-$^FTwi2BSkIvK>V&XRSV3@k^%RhYa0#u=DQD_ z44-uizsTILhFVl-=@&Ou=K*LyayDB$dS>YN<_Fk_6NS*Wys|o4KXzTQVmA{`-osyV zUrmIwbZ(e|xIu4-+V)UiWc+O$@uaNnBG^VliKG;04^(Hx48i@m0%{HX+*6?jz5X(A zukpYZ<~BDLz@Ul^Bwja5)Kr5~*MS%Za~sEi#mvGSwpGk`pJ>)rvpv>?;IuRk8ZVD1 zyp|;ays_ZJznTLp&iXAu$3yVX-U&Mc!Cr$?qlpJAu&`hGS_;wQfc(T=9}8z1vnl?A zb~0%+Q2jAUK zP;)itWO+Sb@=_!s;3}0Yz9~I&MQ{M_l3(mZ0hj|oU`ic;pRtF+)=6S(2PJcXi{=UZ zmlb-}@t&qhHTG^j?bH=PFBkI;CK`b@l8Du7JWfak(WJ!2igIZF0a*1YN;}=hitBBS z1z5lO5!sCq{5*|~%}sl|;^>o`fx8Sjh+w7WRDRG>>C!g1c&c`55r`I$JO!fns4&-q zhH>9|cN4tS)Fw#^BmwF{&SE?wcrZ<^EkG|?F8j+!GfS|}`+d5}B%7lnz;i>5Lb3cj zB+@heKn;sp?Yq6}%8h0K%W8zJY$w572-q7g&(&Z{3^;jL7?XN#6e(2Xb3Fd=MS&~S zWPUf>?KeOU1xNoCOc^B~IL%sTqGjC>&3_5|#(84nakytaRHoeN>FQk#Ms;GbJ#1Xe z4y<>D*+x@=+)06~U$;2fv|3^O`t;5o;DhzM){0?Gs^ozT{cZT>UXlNltemD1uv-Eu zy#|eM?OskyQD)4_8Lmcm_XQE!Xbw4sFgHJ;5!n;)=u`Q$f-@qk)%Jptxbx}nzOGRH zZi2Xc0jTlLoJV=qfcx>+6C;4?EtXXSa>hcYu&%`W{Kx^s>%0#|%saHt3=X?oJn8O# zRHtM9%>?BeV_2$76Li>P&4bfN2b3r9)Vk@<`S;*a$tF3H10uo{JFl~5#6UI(a%sR2 z1*Em2yLujeHZB@2aEP5nEK+s5=F%`xpvST5>-l^~3uJal7U%Qvw;HfhV>n52p0-$c z#v!0YodP@+$z8Q5w!ou)S*(w+zK6yW@$84Zf;nIb$FJ5#(N` z9qgvjRGppYGJRmLXIHWBmg*b{eDu~N#1m4E=s(zvokU4Jk2Dy|Us(nEBhy(HnxDY@ z$E*Hu(H!UyZCnZZaad6dm54vBZA2)ztqcDwY0rk3f;Hgbo8{l=8~I$%4zP|{9Vl( ztSk!eJj1l6g|h!bjptHpIdq9NMW15-GlG31b7Sp&m`_Ql8l>x)BvkABLDv`dhye@? zpRT2hoa;Y4c6I0og?9MeV`|w9*hby`Z$Ti#H zBR<}<PMD{U)q3JD4R+o9teV74zI|pAHD1-WNrti{zYtW?wo7eh zn@JJZI!a0yKrl+~UA6Rx{IaX?nfQJq%IL_MQrvSeXON6P1Ceay}QXcAbSA~D5S#;g-j7Q;bX z3}4F|POBx1iitk5;<;qH2G3NnYuY=+XG9oCsr&{OhfqsRiT0I~9>MDerdfX!s&2Cs zK4UJC%;I#<^xyt&sdtXweeZv3#k^DOy-G3*9-7$+8zom?dSnv!dZe%9ufCA|H228R zBO-fhsu22OfK96LH%JNed<82~cf5iu-74U{#WCV&o1BSU-R-^`QkvStD0jL$5pOhk zHLKw#)^6>a1IQk(o&7Wd+Bx0gO3}>s`NET{Ky_y!5KyrWLy~oHl7d~6l$iJ>P-__| z_&b7uB_SAoj4@Vv3U6AT=rZpu#Lczk^NE~Y3;eulGD3I~xX^v(2%j?bvG+L{&?gKy z{Tr+5`XGQ;FxwA|06@w$3j81&A% zpJ|P`f+C%NzC=zAFGdkL{v2hR>7funm6C=LciFa(*s*!0&9=auVlsf25JM`NUO`k`-KW`2J+0k9d|g&XRThoe90cpsachGbl2V01#=u00V?cn zcb16x-)fvXH_7!3KD9OG>0sVKW@b#PE8Zm+8pUtMx_b+=ga@lKMy%X|KZu=?7VZ!qQE z6?0@Hik&=gP_$<-a5_N5{tpSJzL|hTpbWaG3MAuVeu z?2QjUssoHB2>N(riptF%Rj@v5%<==hu&W%B@4GIQv_L-J2=QFmFD6-iyn}&o{h0FL z_1h-lDvywf*=snoSvF&d*L5OL%usc>%6xx!C8=>%ye6V?aJi6uE-2;Lt*k&Hzslcp?&7U6(8A0CPo`@p?7S46j7DdVcP8%dZcXI*Mj&}p9 zj)&2SQ131iIjHVr3ZxK?Ip;J%OLcAC-M2D(tC+r?;;-zVed3e?r+$ifeP>V4kDvGx z*!hBE2akUJ%=6nbyPfQn9%E&ktj@fO(>znsn z0~LsJc1SWEo>qXoVvCjfY)VU!68zFz1OwzN$@_}=;*4mu{Ht&c=K=Fu$-M%eMwU?f zd82b~uAAqtcl}InrN7VhD%v?b1ij#>9I#JyrZf&aA#p9He>6Jpda?F%+l7XfxRgCH zAtR!p;7JLX;}a3GkCf@H?!zXXk{`c&Lk}9$UV%VyY;)0`fcDlmOPPo<^;~ECiqI-> zWj-S?#sPh|(^-E}5q474fz{f1z89AosohaL??U6|(4xuV*uT3$(B?g;Hh7+@` zJ+m!#dvUgA5Z7$F0tUVP$HweyQ99ox6XenNwOz91(V(##x51QFum>V5j^%mv@Zg)7 zS*%72U_i?FIkicfRT)eE2#eUA3;C5r;*)FSesg+Dizq;00DKr3KLZ?H0Lj=d3_^dN z43D?|PAGS6pP4chu2jEo-6WH_hK3NRaJ@zJY=!Xep25Q`o)26NF2opkWWT3Md0{zg ziJtRwnuO(8SL-FebC#&TK}_FfojEQfT6M-ww-avq+_?v$+Hf=GuAZakc6NugZzu@?~);^!!Qr8NA>el1p{^HsSp%HsgI;hqr7# z&(wAo%iON(Hi@#|i*Xr?PYqQTE8rq8&x@EUyYR-D!XTZa zeftIbX9{jCUS@L5k=070i_Kw^eEx(?cv7`d$B^oWHB0@>d$*Bgx?qJ?nyO1tv(U?g z;mOu!zg}TBD)!(F_3oF5B|G_!ug*K(0Zr^qHf8(oz77pySntPv#9=zC^vpDWYo`PC z@dk)nlmKF$dm;dUl?EWV3WH1bgwyWX(r4ic5YV`_Jn`IuyHG}NaNHVWa6DQ#YCA8w z3gE5B)JxrZE@m;{!)(}@8l0CO!W9=jKL5iVq7`BPWD&wNP~~`4)p^I`@Q{KHxyDG_ z55BOSzuK-?_!{hYGxgMQL{abT_(WxP*p`#3*$mNVE~xYN0j@8nm$OY*ViS(e@mCpj z_R!bvZ9~?a>_dy5yW`%RxfkJdU0ER-c5ImGj0c2N^XHq~CY&ibFJpISBX71V40A92 z>JujMg?tp~GZKDOwt^VdzymJbC$ z8jVkFrRR#Q=oI_)b1U?aagmRbuC|baTht)mh=i1vHk~bTday=|dEv06h{*hx`(6f( z_A^!4(19NoZtClgPFUWs&6V5EKd|lXF6x9RDCyPOcjDqIwZu=EreTZ)36z1-;wm{$ z#vdm&=Z`(2C{7i%T!Ec|FE|#3lTd%m?o`O5b!6;e)*>bxyXLY>2UBXs&}!_H_|k6r z`rV&$AZ!693;AJ-7Zr5ckx`M&C$Y&$f-Wex zJ}a7YK3toHv6>>hI;(!{o(&su&On3vyzxK$Wt-NW0n!RuAr~}H(kxWIBzAxqbtaP@ zm2^;qgbnU9uhm>(%MyxD2QZtp0Gv1l-^@`B0HnGf;+`0{N1EL)J$3 zO!pcxUmOXXP66Uqcgl&E| zO~v)&!26z;*=?~-bDC{)c4i|?I=@0GtnTz>V7TU6r}&7>PDM|aLUY^@4v~|is$Dqg z>i+ZJyFA)MgX~K$Keq+DD<)}^q-s=Ob}m?@N$5Rit@XZE74^tTKl)~4^2Wo>Whg(I zNti^_lQ|h4SGh;(BsSQWxaefOxLY)k@QU@^cHZ4n_BrNA3oPA>C`&_q%jq2mMs|H|XRR=ZC@7|vd;QTO#W%Wis8z;x)(jPs3!l2W|q$Gc&gTC@U>Y>0c zKQ$+4nXF57O&=c{+h;8lueW#9O4oe_>Wsa0!Q+q9)N6#oc_T|_q3rZrhMT%Gk}Rq_R(CImK>y;dhC6s7a`@-tj(FP$GC4EjyYvBy+P5=$lX*! z93-Fg@gNlbh#Onm!J-0EUXo`XjX$I1P!!*d zR-nV}JNlP;jseVhl@%3$dIE&3-J{`yqSZk8^{A+*h=>S)YizoW4wp&;sO@=Ab`Sbh zFLQmb&nLrTg!;?v0Y^tiZFKKg0n!2m1%>{V5OVhIG3U>Qh9a>sd9FNEOF;0J)$gRD zg51$g*2VnQ^#Su&P6mO#^XOp1^UYI1@-Qi}q!qyL}kA25C6P5Z+Y?njpOHHi3SPzzFadZz~ zm56Kg^(zWre&t<>=VjMhRUlgfiNx{$HBuq~k^1AgEiW&prs4xEH(2KySoP0=W2@gt zUR)JBUM;!99N%n|pn}X+-nVpLNq*X@gK&US~yp-q+1dh&!mFpYm|HUR&_r5 zu=$iz^X#oh--y|}4toiM^W#Y&MQhzpy$@cuH+{r?TH|%BVlF#bDU9VdT+7eB$FuUT==yWT%0J#Gun&`Ki*hxn9Dsg&3Yu6&igm zYQ@+6n|Xa^MGtt8T1NiV(Y=tnx1sqMzVAv=1yXdo+l{z@%c}edeT7~_Vh!#H8M62? z7FT$`d8kqt?#%4IY-UELK+H~#X~`YC$P1*Q%)Q3l4?#kZfq|hdnkR2^TR%J?B8iw6 z^D%15a*a6#Ia8zS>L<-6wQBB-$B#8SsB2*kds~0EccjWIHhnrGd3cK~E4GwxRb8kGzSTELG zv=VEZwN4T<(QjT6{u=sllfz#JdVW@vc3jAH5i507%#5t#iz<^>CYs*Y&KeMBK0d;pD9V+gP*8~>7=(95?iwo`V?3HuQuOyg&ik7O^_}Ual214ujtH?C9|dzT!cxG6qkdzH&^80mYH| zlC*&vGt)L>o$HVUDr?tMCIs_aVQtZE0r>%n-IqjT<{v#l^iEu>eyHxV zBmO_`Jlx(qvCMDwO0O#`>v7ZhCR>MSxf|+pM|5_6Zz)tabwv!oyR3 z2YU<7rwyV2!2elWVPngz!tp)z<=r_}bor_VKtv>NZ~c3Z)d6;^C=1hb{rSdJ_-ck! z zUuA+^W_~nw9Z`f3?k`q54vS~<{wd*oReEQk+4n+yc{(VZMnsL;WqPdfAqffN4|L3M znnlQJMTFg5^j1e3)!3s(emQd%kqS=N>C~pLs!tK@7sbf_B#1jt*zvY#yPgyRTUNk7 z`{FpoOp`>S$Jel2L*u89%XvOPI;{TjBS8OtdJ02w3NiQuhlBtm^l19~3-y0_c7WO! zD35Lly5~veF;gxJ8pjbQl8}(lq)QWacL2OPJUl1@8AdGqa>kH8Yy2Go2NWoZJ?OuL zr$5Z){U!{Vz&Q++fY9N+xMk9IBL=-G_EVT1okcNP5b$2u&fL-pP2+=`Nn(6UM9uRe zEF#F9M)zb6{i~PZQhy;1LsoB#ll4I+CMJ(&AH?<9{{wLJ3=I*SYxK0f|McnV_GB2< z4Ir5WIGOxJlGSFc`1;7Ou<5tqz|E7ttjoV15vdvXN1XrrXCn6->;L|hG00)#BQV|1 zGC{GK6?#;%!PmgAT4(;}Pp%?aV0J;v<%?d!oWBoz7VNsyf<1f~#snE4gTGgKZ@!BB z@Xe%}(Yw_!rDw<*E^ng)F(CRxv@CxYx6z?dDdQEM&#R$(68T^L%kG_mV*{j3wZClQ zaHRS89Q}P3fCdH`2&)5Wf3GSz?OC?GjnNNhTr$Hr2a5qzEm&KgRnY$##8&NP#Udv= z6k_p};VD~JL`2Qu)-ECz1UeB4`Ap)|99O&R!}gSIeLpl;WJ7Oo7&(bB{~j3M_A;>7 zRjg*eWBg~1Ws1+iZ1?^DduLf6V;)XQlnF=$^lECd@&V;Jw&-BDOeSHJ8IFzgz(M^$=l-(tz6 zrqGaAu1a!)KG^6`J_NGBkJCgvT|X-fEY8wGB+g6a=#mdlO>@Nt8pPN+?nj<{bSlKu zbhSB^%YEOEm)PcnrSn=_+*KLYFeUu~J9w$|%3@^*4*Zj&UZR1U#t(+&FedQ1F1l~U z^nO^qvm~)zy|aOa#z4ox!sY-4GDn;{!i1i|{}PCN{$4U$xdWaM*E>T_T9t)bn|{wU z=*?Wg^BkRF4tK5_JkVZ~7^KGB;7Q%=PRpeQ93B^nqFjHobtN`$CuM(dP~(++v!AnO z$O_Z+xm(fdM+3cpoI`xh3tjt2xcHl|_Mx@bnnE&>ce!aIx9^Fc7F|LPir=oiSU=*2 zUawa=*H%-a_lpMy4sf%Zuq>&um<>Mahx zJ$)KGKoFyjVSwgpBOaN=ez5OxF$jm}3zsdI%ka}2O{~^m5A~&$&RVCnY)`u0HLnaR zDk;`NTGrFowE6{++V;t$UX#zjx+2_bwMn{nizzC!VNyAufuOt7Zq7F)h>Ovvs1(-E z@^IY~xR|Gvj{Ww@9kL~BX^|=YMo;Ui-841wNV-(i3C?}+;R)M()!s@tT-&vj5z^6d zA=Ws&+uZoTYZepgy)Qdfd51)1l`n*bN;S^XoG|5Uskn=T4y_K+^l+}2K(988PlV5G zO@`hD55tDr2c*NO9_FL%`hAWj>8cVWV#0LKE!aG3oNy zcbyb9-nnyw6{gg0e@~e0zc>&Z5PRXNY;|kL4q7bB%JLubIkLs!K{dx9k@zMCoVfp6 z#HUJDV--;71n#A674kl3w_009H3b-^>H3du z9Chcs=d=_9BC$K*PbNS&#nxdWx&pgrca^db;9hei#vLN3^ zCf@30{Dq|#>@$~HF@Z_=V-}y{2cCj%({FD*thZBCNkgY4{_Jj*do3^LaEbcm48+d} zDBBz^$xb8iDXP?2QGRn=r71p3yWO)4&u;FLe)l~5skZtDZd7>eQLc@2`Vp25s?Xr7G^YJ!sqdxMGB9JgiCj_kh z3H#u1GF=cJrvXZFXF=w?`S-~F%k6EYvAC8t9h56&RdPe_{^+a(2C?||5vq$emDikA zlHrhRTdXI6*LM<|iO2~-3-Or9TZVg8UxbvNZ`_%#^wsj2aJnPl zkOT^<%}6KgXXrCM?hqeK>8Ly0v61DDM&Sw{zkjRv{Q=a!T{GuLALP)p*vN~Pv-P=G z_~8ok1{8AwNufV}EW2^%CdDVtoqq;VMDuvskL`9A>Wfw^Z(La4I=Ub`IES#7ehE=x zq}?Ggb7yChYKlCw46bU93(3*-c*^rHIOLmMXEoCuY^M-}&~p2oF?Y)#Kh&k0W!xN1 z$CFwYk0&~rp;Sdg1d_CAg23+Cd^VLVcLb3{Vmk8vnCHKi3-tGii*LvT@097wgTbpZ zSe8OC6yFAq<5jr zXKr24VY*5TZ)VShxoWP9Nwq(+c%IhzINieYg6Ed>WD0~OkGr)fDzrEHA-CnORHtM{~JBT zeO6U9jJ#Wx2j|>gmoR&NLV6}azj-Zv=?P7vnXSIrT%w9LboQ%SB7_`X5Rze+tL`f* zY9fPV#C*7JzNanMCRF0%+;k!ini8Aiyp6gJP^4G}g5d7F(A~G|k83+E4WKT!(SrxE zov@o*JOZpxnxfX_yVa&>uZ=?$Zj&dcn<(2ZL2cRZQrf*MTu-hEt1r6$^exktLVRBl zhCO$0ysRV)|B*~Ptmad`Rx9@5Cwn8Oa~=75h>WP$-b2rYv8#tD9M5?bZ_XhOeEag6 zkr~{vUWa{Y1gxJMM4~vToem0O^RFNt=gWGD>TC)$Y`heZrmM9*Q=3oFD(*Bk4uxE4 zW90en;@MGoer0rnZsId$GmJ4jAUS=XRQY>)uX9&FmO{PuYLjY2>tATS6t+MAQ*Dc| zxb75}Ifo`zI-tXZ%WS$j3h5A5gP5Gf!Zfv~gRk-!92IB0pwx6k@q67E;P134V3^b4#hY{#^Z}3dB>Hrt#{gr_i?4Ydge! zM{H-=f^!ax@%ho+&JIPI&vJ9@1vLGeV*F8SAHVwG8vJ=L{1DlCPHhYTXxqX?~99sd>Y>#8Dvwo)mfk`o%}pjXZ!>vcbeyOpS@&!uX$Sgd0IIN zd%5AJyQ8Hz{+8;q+Hm!`^iYNPirs3(LOPpFR|jr$`Ds|=-E4T8_wnoPf{UAB3(mpU ziC_GQ{)GQuQ2?-C|NjF1{%G$8Q9iU_ss)Yid=()DG)IhYZEcO_;%>GPI>T2YtaK_i z7;}@Fm}6StlAZEd4{V1$RPxr2L)#xe-v3M=r%y-Ku8c(jg$-u3oMT0w^Cv+n_=}Vi z-NJ_lPol|pf$WH4iBXz{08b6iBLp6Gr z6H(wB6$B1A0=8xT=QG3nga3bCK%mw)2Ea-8|9tpxR`CDx z1}an0ZvJ;$zJixQkjtRbmh0_YF~k-exd$g11?XMX55A>(-4iptk#aqNA=Wq{pAIzi zEw2EsI=x#=2SU0^fFJLB~Y^zJ4Nv1@upfV0&5 z<=-9kE#53eZkO)EngL?(MJGX>1C5%WUZM~ndh?J$(IRyq+%~qcDSbn$Z3Bw| z1QNyxf&8+*D~E}87V4`S^{du$*ekTjD zEOn(RJM+3BLv-qmp5Nud>_M$7zE?5-o^QI4MrgL}T>|-?@_~T9{PlU7`EuLFEuh+J+J)`5w6v5$8z^oq zP~6>VA;sOD;_e=-v;~5@TXAZnR-p9ZB>q1|D7%pGv|4~h2&hiTecI{0UKtiVa6{uW&VE}Wcw1WE z{qR8;%DKy=}5X1Jv#tz(=0f#$=19X+*70!gv{ z=Js*%u>MN((xGHq_H&Ox*CdUf#>1Ki|J)swUUL=adfwU!ifibhyN;4!bx3BiZ##? zUhCRJNbIjHTGMzrwlWZ;l zfL^PEcfG8RxJ(8~pwvhD^z#Q_EYx_U)~F}{-2O@HZTuFlP#lgiL=|G+i7m`|1gE#E zRGj-Ot57ql|L_~Lc#!((pH@Ce=zY2W0dY-@-1S(C>*d_Cp9YIOuz^3cx}Ikwu7jx9 zB*Ouh{=4K3i}i!eEeE)EcH`<5caaX#LDoO;A0ZF)qKrL*&nt{|cxaANHEe&O09x7qjEg zlzv-caQ(J_>l~sCk;J|O-(LW+e=dOQ=t-Rh@7%M#v-ZrI5y4v-~ z^#=!J-w>xJDL<)l*&O+y17rFm2@w$_J{rv0Awss~2kGw?NBr6Y`6GgHS&q|brrwl} zYn8cr-hCk(jnTup)0#CGHdxMUkQc>A5nHrv6Cpj|OWut)c4T-#$ylFtA3Z{ew`2Co zS0X0WtLM{Ov5#XKPQ#&>Zst{)^AY!fyl5hCs_8U*`#Qq81 zXTL*-8d^8OA^@CfZ8bU0caWXhxL8vtlDct`LUFZ|ZkTE+u+2X-Kizpe)3sis15=$U z;NMtj9&rxRe|>?hW63cE63vOCrI{!VtJ5{LnWH|M!9UMgA2$K{=R_*cC4*Q_RBRfi z>8v*hT<6cDvyY=WwG!9XYHCw#7H32Xwg>#LoH^KV-G#ek3Q_zgTQ%n;$a}8nDt-o? zm9H_K?zE*Z54q{E)zq{wy>67ZJ18oRvRO|u1zkY#uG^+cQYt1x~O6g6eJV#2$$$NF+r~H*3iTuJ#ZW$h3V{+41 z0y0WZn?we(d3pF*hb^qIYLBm-4R%;Pn`yg*KxO_ma{kM1fp_hrzka<*eKt0$BOC7D za%1tc$%E(GOLybe*v?(}u-w?Y3#Zh}!?@)Ljn5?Cm4jz?Wz7#gjg5m1+@z@7K)zsu zsGPnA$*_)1+5xng#HY$sgg2xsmZl|+- z{#UEWEBR%qvhHbSrlyN~X(|&hf43>8t})&Rt{6<+V3zz}pKnIMvun21+3hO^ZMC~o zIiIcCx3Xmr`&{b2yvX(NoFmuewZQ~~sff0B%G^t%W|wSFe|i`@+s_JqN_ye_DwVH< zPTA8b>-g7uwYcIr87rKTk;7jZfqhFQ!%(o;-LMru%j>as4z(l2;Dn^5#UC>QSZ7kw z==%mhAR&}1LrVX|H@&=3nYYBa)bCocxj9pcudqQkAYW3I3>Vb1^vWP&B5)(SXJM}@ z1wHqPvU~Hw6focP*Ig(X8&Og+o=#wbLGVar{-=edC9vg0sOCwXm?|ssEUs;<5Vj$hzXeq`@*-$slAG<%(lZa_%~su9~il_`5X-^ zA0-AKe_63^V0b6sf_-ef*ZoeyYqu=-Bn&z=IU!&9TB;k zi<>r1aLOD*pU0v3?=8@?*FnBQfhL^7?7wwa31|3D+Pp5#2JVb@3}=bg#;d zZ*1w#<@?<(`LLgSMhi-j4*-kT3?)fw+T&=mh#G!^9QO7P*Nk2;_=wqhrP97e>;q|h z6c6m|H!-MF__%QH?)-|~d_z%kOiF+ez`XOcR^lVe{eSL$HmNyxu^)wiiSX&;s9qaG z)$yW0-7IU5p8C_GzQ$&(bABa0*xMz9*q2kwQJj$Z!?=KWOy4T$jXOAg*qd2#I<{_8 zflL3Xe_UuPswpyQ_h=jgJx)FQbQ>5qs;FZkc90H-NC|O3EL`G65*o0<{n3IF;cjpO zfVxy9mgBWBi`ckBW%iE4PI3%Dyob^uW@DaN18{;JO`~JG6rLL`-i7rfK0V_DOoqn= zfM>Y@LzHbA--UU&B?+9L>Y6Xc;4ESUJnEAih{hYijQ~-o;6X1K0@$ZTqI`wY!wE(T z604~M^6We7uO)kQ*l)%o$nBvvu`Z1(Ff;Pyc-v1*_AX{K#SZI`c#C|utx#*Wmm-oA zlxr{yaQs>CaO^D2MspY6?4GXV{yRQnk{dV*j+YBw)Z8GUMk)gq{B>Z(# zLmiLoB9D)yx9mX(<=-x)&I(-k{ zr1fyGo40Gl&dhxt&@7ZudT;~VL3GXe(BoxMi17?mTO8oSEeTWR#z42Ri$JT3J;mN> zWBn{j8$GheM@8s^!%DrjBDB1C3*+IGg~4o)w29j zr*w8~nNRyNTBxRq8dz`pW1-q)tAA1;C_Cb$&X7hH`1-CBNBh&bBC(ZdKC-b_wyZ@~ zr|TOn=4x|_e;iU$7=m`-Pnt7R;vIvNVTU5zn zg=X+2C6a-_#{7}|sEHMeX#V~CeQs0<47Os-Wr|q6mZotr8LqbQq%0%7uk!|XGJ7BW!LNqt$pc`vp__jHnGwKJU>dtKe;4UfnWSiG@UM& zXTdgxgkQ?8c{iMz2=}Gx;AK^_$t}oSWdHYQ_gW0mDJI6s$tzwfDb*K@PgkDOW_bHN z7;Fy;MQr&<*Zh9hY^<}uTppf4E)&*e5>zdARaC=}MDq%ZcXD{kF)`kUs%4h5ddA#J z?{f6>DI(M-0G*L6aLaNFbI2uhLX3{3rb<=9G{j;(S+)Wus{;qii3;-dw+Y)?ahWg7 zvX}dTZSS*ocmVP|&g|mJMf;2|GhP8uj1^Hc9r@(TyB{dhD{K2d!mJy{`u1FkLz!dL z`2)GWgwfaMUwmSwzvpzXJzfi!-cfi*3fY;uu;fXR+3DoU@F>TRM4wXnO3ZIj+p>?U zE6cdnDJ*TNoZ_`3hLLVAN`VjNQkSP0?0@r|Fd|jc)9M(L${8MJrz4v`CiXl@r{29OH7|&Gto3?T< z3j>yO6`QLOks;IV>$(}vC@-+}(DsR@YUHf@wiH{@?8z&3ROD4nv~icKiA47)+UAD? zqjX1TjcWZ(&iUgRjv<8|nvR15bMx5?xrMh4aAd`L?GArw`^+~? zInWTaTPI}z&i zfi*WL&lDF6=I7Et@&ZOzzNf@yU2>Hg_?#D0V3;2R$+4)wFoYV!zTI3)MM*_8*oMBb z$PLjstP4F2xdF9~SP}3$roGVoHKE~Sa2)w~OVxyZRfofMkU;m9C5Z?{Se*O%h;HfG zz_&M=VP}XhOe4${>kSl}gDT$1HO5@a(>R?=q4iXn0=!@mBtW%!sk>#^8Nt_qLcHI7 z4KF69G>lR4ppWd~#9<=X1+_aQIeQIL$t%aSxVihsY_s$sIFOyKodC#G)FisY zoq8^0E5HIJCDxdCs4}78>x%@xKQ2HvQAzhQZK(T8x3u1$TLGqyMiU1@&IVCn)EvaR zEm0AhkZRdeG?f?Zh1qt91&(E;_?1p0r0gk@^Q5wT9hX64yW;Hv8$ZQS`*JZjD}caY zfV^?Kc~{8lnwWXWMKcGZc(|97itv7RqD{|F}y}AaZwg*4tDJRmgM$MT`xh-#U|_c9Hqv;ufTa50tAc(d~$FU zXWM``64ArG*GAf+C=8-{Z?FIWOdy%))J*TudArA?Cy4IdtF=?9STNOLY*(H}a!biJ z-vEWNBCwlCLfr2 z3M677di)&1!00n``$BbsI)$;9d`V(kgi+)^;CQ+|!t9o3F_j+H{Wp3Z0}n{lBQ13X z2m$gO4dYiwW$n{-loHaw3&$g4YO|Boo{}Z1%;6_cnREbv zctyWhm{eSlVeVW9t3@b{_*o{$+q8q!QwoUD>1rvFL{$0BO=m~id1f(psR@(NZ}fZ6 z@%1A5yH5O`bSdlh!A<-0WsI;zR9BahCC#hG$k>LP!DT5%WB>7Gf&{x6kOF#To;POF zHJudYO{$1H%yrToBnBJT>X{pq-ECIP8AoZbDkZm%zU0AAe3naKl}R}O1SWsnQE7yU z%=yn4Xd5R;_T)YaxIr4ku65b>d1!A8cmJwq_4BHTdc4?)Mt^_M@?40Chf;09d1}9b z*al5QYrgXB%ocOcE%5t{G0V~Yc*>QlH{q#liOKMt$VaoRgH!nls3P`ubMA8+Uc$DfG8+~Q3zcO1!o^DrNp5iw zM+qk}a-VqK5+1xDGzJ3QcSD=V_G!tc)1#ZDjZp&*e8Gp&efG}eM~lx$lp`%Q2BcIB zLow3OCwt8;E9#+>WhcVYXmkC$VWsc^{+>m!oyD;`X)-GIU#G1By7qQj3I`J?5?Aleo+pQ{_C^iqa5Dy<5Kf= zZ1GQ>FCsnO@7yga6zIpz4!rk{qd^Ide*>#L^?u#=`gvVmPmSg$WO26(1q5KvVhCxj zQbJ*-*j2IW;g8~^{n9&dsauoJ`?#A~FHW5o^G8eryGMA$FH9=poearkF)jf&SpFJf z{XeK?4ACQlV0Os1-iGa_O5L{Bd)8Nbc)`k@9y`eifJ(3Mf*<%1w{yUd!Cw3F+2UVi z$7M8}EZy;ClGVh=k4uz08_mUfZnuFoITei=1=N@h$X ztzy~0muK4R4 zdJ#jI{vop>Or72}ASxXrJA%zjcYY83$G^ju+ zxzJQuteR8=P?_j&l3Gn3nI>fljn7g`gG+fSQoUC2St&65)NXBcVw^7bbKusvELS*& z0MD-Tu{d|$sW)!EWu=tskB#qixVU)a*&W>Y1FJ$ZKJga=Q~Ey21oa3Eh^-hm?_l=S zu(uVAGE8g%wb(FlfwTx-v$k|6A~uk8A?whVIP}K0+%Q%}%x-ybfaG!&=L^(ba>3aq zdTJ?t$0H|pg4Nulg&_VxLyCyMyd6?Kzl9@+`~zZtKg6ID_VzcB`Aolfcl{FLDSelo zay#N(=t5O?dJR+Eg7Vz#wv6b)?w^S9NXuD8?Bab)a1xaR5=AWEfWGs;$~OH&Q}3Jf z|9hgVHB4LoXFumbO7jT?$woKW7s34wtOP_j9VP?DgOJL6N z81Kf&lFJp(n6Vu%l#^XE)gerKKm{v4>`G>aK2Uy@z_onJaEB;CM&(*dr{zQ1mc@L{ zGzRL__ssnCw#{esukXhH19TRKiKE&r(5B?1kV20|vYX&Hn}G{UPsy0|*AYMAm%Lho7KGhk4qhU(08->ZTJdos#P@bWyNy4_E_DZ%i($+>cz8u%V#BKWVyU@v}# zgzQW1X^oH>Hw0le+h3e;J^EcQtvsIu-nl-G_W>9wwB61_Ss;MiJ?aF?3=jLF+&S)4 zLwC#2xMUFqtfT{XSqFSv6$Di!sh4@H2{ z=%-GTO%vk#wm(3I0<65;`y^%3euB?riB(nnhH}gr8p(!!8BVW7LuM*Re17qX_YkQd z0k#fZc&&0f%sz~z!dy7yY4A^4R-Q@sP?-1?3)zKb!MQaTlr(sLt?&%dtVb@rWScRf zz4Y)7$6X0HnmSO=h2>cC8pmMy%hR$J+lBJX|ymjY)eXd;UL_r*nSIv$A z*wU>p7WK=hH{5rw$6|J1B_wp2$!$-~?``v>jkA=i-`!3+1X9Iwv8qKRf>wp75^$=l z8-UewueZKeb_j4#=4mtJ(yS{m-=U6Aq3cC4k`eGu8}+KnI|!&ag7Tt zyGS=$)caHlA81fi@C8^ zoVfg?w(CR(K_W~T>NLP$wH{NWu>+)V{Jl?|D8uP(Kj((KHCQMyU3Exhh6U=YwMcPz zGg(O2s?`wS?q9U71iq}`HHdxJ>@eRA-aGEce%_aFO5Cgtm|K1~VVxl|;GHX%x0eHM z%6S!WWS^zAdh~tjJuoXZWo~oqizpS&uNS~C-Mgu*U34y zAVX5E)W?Qz3F8Nc8Is1k!Bn>ajP13Ml^|t7J;jKq=o5H{%<(kE>s*@3NfM zQ1=cxA||9ouL4t!fYnAa9II(!BMd#Q$4B-kIjJYEI(sgB*(L!ecxiXYD5A6bfi|e$ z&}(;Ijg+2$oq(YU4Y9>+9kv3y2-$VN3Dt^k+D_u<=OmG)J(H#cC!|pJuaRCMU!t#E z`H|3Qm#0<4B<1?ej+k^`>qgmju1!~JeN#-falO=aF3^fKcb8I*;Hef4Zbp~Zp|_Eg zdW_*_yj9az{qdtix|~w3w#Gul(G*qB710{*?{@xR9FbFYRf-oc-s~M-Dc|8iq3E06 z7P_LR$=t10BbCkSF|bQ{K~bGu0WL}*I!oS?#~rFx^YED*DafzS)txhmYpz$pqq6jd-bw-6(O{&XQu5rr2R4 z)db?SXEDfx8JKP4;x*Pu?-7yXqH}iw=%-@jVg&f0jP=6h<~>TWxskzGxO;D5l2d9L3p1K5}CAUh}&=X3du+JNt93sD0735&_SC*RFZ*bT6P-8QkUrR0?hh4@&?DPaXf2^`D_5AVV3}|wjayB z_8(p|%^!U2Lec-|J{HaGf>?lr`NNL|f24dR6-s_kz0*gcoLUTEv~;e@lu51eLeEKG z+b==@U@g-pfSlc#hX+^QinB`y@g`AdZJw7OdbyyCYC0K=MY>P%nx%*}!lFuJdq(-? z3GLLL1j>F}?kXj*evCBXv=nX}XC4w*ksy^Cuh&J?*4Z7ROZL0;lQh44o`=0C?9W+l zAs86MDIRY6=oS^B$>0E+eS?L?LOMM&;tgzutKR0v?0m$@Pt0j#eVzDhXAWQU*^`{g z(PjJH!e^0DMLj9&?z}@a0oYqUZ|4M+&OhW+I|Lf-FXZrv0<#FWCeG%syf_(Qy496x z<7`1!ePX6Gdprz7sy>TWk)d$4AWZ%-d&OB!c$vnjmAQAjmkj*4m36z{i1 z;2TE+xjEqg)F>3~GNNi!cF}CiEn4E0kFI~<>-zzO5|PyLi47l|r|dpw(6C@hh@AQ9 zO`>e}5xlpPA~Pa$Rc5DEeS^oibircc>;;;%e>-ZT6VIzu%F`@u?Scg=Hb6vP^Wq`l zkA>TeHyCS`36`hpy!m4~rv4;Z8Z4r0frQ!Xie?$gS2pi5JE`7P)$x^<41aVNw2w1( z<0njwmm+bY_}WI^TVmZeOe8lV{gx$^DhZL>mC0towLQ1XdkcSz_`ev5T(AngLZ5+o zjE0rAiXI;ucMR^Va2s?5l(|ktexeDW*L79G$Y*u3chGs}y=`h%?Vew6KIGSx2meJv<|!x>ZiE*VhGXbLTL!(#~LNQf)9n3B%xE8g=QDKEE~ybyfNzM9%NL2e5o#m`U16~D9pc`Ma$bK`0imaqKGpQuKJ zUjR#H{+YDSSa!$R5zBb>ETCc-5|IjiM?>O>8X-m~to{2M$k7IKwo*jwidqQ?Eb;G1 zN4poE{6Q4@8~K)k=2%B4cQf;=_Agb>Bw+_V=|8nIhsDSz3AHf>F8FOk`VNf>7#bFv1?u>TsytFW~bJ6W>q~LN#uNztHEnHoZ0-cBRkVLmw%oy+*1&PeU;c^ zgs?$8jTkRg-Fnqy*xQ+iKm2dSat^YVhP*DD)(i_)z z^e$H^FXPP&!;BYp?7VrBH9o~EYK&QO(KEoN!uL+%4ZKNzS+U|>^bgqD@+GhKf2FKm zZsci?@bN)<3y-rd>|(;<@fJ4)v&g2w((j5`lV{j~e~y4> zqc4)>N0r>gku3Y{>v6@eHBgW+Y?_{Px26d}M_x)BTJ~7=!iAF@%NHXG-ooR@Zfa;x zk`WVn6<5Inqj{7jkJ5M4>t+O9zX8Th;x$4(?bM*Gv@OBK;|MiG*Rr$`4K#4a$sfkO zFbSpKLK$fMI;<+>leN7o1M1=2Ge-;xEI)in@Ve9m>-GevJP7OezV^-!&%N8ZD?#{j zUDw$@_`Ct&+oRmS2E{>-TK&2P^MF!Ut?7sAEKCSu&@+8JeKDD`%~Gf7 zQ^`M$9bngqZ{*<8BB-McO_{tD$?O^W4H##kI;BqWXrga&d!7cYp zo!Sl`B)R8dPYr0%Rr9uTes)3OB=SZ+0L)b+{!}>{9D4~u>e8-pcc)L7YmX9r@{E}5 zZD=RL-4izRcEIi(GYVog#xW*+TC3~*x@YrltOpXu`uUFA`y#^132uPEYmQs(vVzyJR$yZ*QM zVYFi+J)-tYfJaluXL@S>J)%ptk_p}ylc0*BF#kr@ErhpKrv8uS_rNJU`QXRGi9zGT z?Y9KCW1lxh#A*-;|(W7xMg(3aR_t1YD{RG0qPfh)qpD;FA|1^6Jxz_?Ws8BH_N!Gj_9b;dp){ z&`>w^BW0sDXyA(X-nl7t)$|tFcJH#559V7aQ(C{Vb;9F6OqkKLva((#s5#6iA3K`; z41*kLPF(!B+VVqgb|~6rxAffQZr0N*yplM4)hyHO<2@eNyzj8fdDK{LQ}1~416DPc zf%~!92Pa9oW@y@DtIi3Dg$ zq@Ag=c7^nJtLDgq5U4;_eb?q&WS2vWfZ=pEZ+B(YtEyu(v__-V9jB_vC~{DJwVo!T zy9PS?GE;)@mb&4RxLfKU>6USk2M4-a{EZMmO}ff0K`kOHh{5kf&uo|R^mr>Ld#%6- zFI!9zM2{a2R9LHRgw1XNtS?3}t_ZRwd~a}iPU)cqXUi7GYsoKXr54Q)9< zu6W?d!AcuKv-LD9?TE*KFWf?Yb7&-DYTOZR4CT_7=A$Sx)fn}ld?4_e)sMfo+vW_wO za$iTsb{IbvIwhsSMo};ri~)1e&_UU0C=T6VSI?4SA+Bc{=EahM0+He6iOVK@D_|Bo zXwdDZbJ9wD9tQxCB_Ey8gX>V%bu4X1T=eg*{_t+)z`K3J=ce_Rl=T1OJq6`%y?Rm7 zN$pZFuXia7{?)XjQ>Q48y+-Lb85;O;o7-X=={{u) znhhz_3^}2_&XQwO_hoeSEHvs>jjbfJeu9&!%Nqcrvjqo-wes-8<*oraF1G^4JM z3UhUf#UsUoo0-@UyT0^{?T&?eLnd7A_r-y0sSbnk{*GBQP0K;0;5>nbeOz@O_g`<6GN$k-o!^2Px7Dr?OR<>>Tv_4 zI1}AN&*0CZn*h&)UvlTHBy46`Z~_2E!k$FVu!%3zMlkO-u{tGtibcUWZajET56IjT zmnqc_#Id#G&iLNS*(8(H0hsmQ+ij3-fA{qXx#QtIzLoMOP730hI`p!Wm~iju8FzXz zonwm-DSi%~{>J^VmG+1aa6K{$X8ww^$LC8_zniP25so&7X#X4dHAQvRT4+md1lXY6 z2LWQTt!f7o@FK45v(8O^t3HG4u{*s3p~TqWsN^)0*uF{J2uC)A8A7`@K~DO0&*M-o zsJx9I7?OA=!=0?u`naW$CoT5O;n@^oWED8qTMGmB2Tq0_8XlBA>gc)s5*!P3|AVfrpUkk#-g{W zOYF{?GzYYtjZrs=SABGm@Ly|RxDiL@Sv0HX-ywh<4KG4$0*yRy4PvWdzX9ZoIes4- zh-g?cv+CHH9Q0blT&F&TVBqVJf>+M9_9MWEfckW#=GyGTR4Rm0^*cJ9%<&^>_mz%u zXdr+HpSsM8cr?kGRgS`bdGivkCDGwKd8)qrK~61+EwaZsT)NIbqtS!?gA{F_`OikB zJ-xP>gxCa1ax^4Fq>9l=lSKD2yt2!XJA8-4yBIJxFb9Ha%uJwVW6JI3(x9`E9BCuK zQSOFvwH7oq)d!Pi!2b(o%t$8Fj-6_LIOrFtT^8&Yawvl?+SjfEmSM$SZc+P+l1b204kNq3-Wz;fDo25LVDlDS7k zGIuSJHZB%$`2NT8Qstn@Esr@i`pX|LqmL9ToL}3_$Bd*rW2M5r*BaKey^ZBmXYyTOi;KhvO#pd{6A=pQFbto8*&G=~oi<{~l! zh=99=xZ2B7HNqI#o`W4tWGh4Vs++?7`=nI`4Yaq7*g=f1+%?#h!!+`)q%aU4ij`O& z`Y5WG*=kWq0g5!Ges6GbBT8^YHA=cG+;VnR3wg8N^$8@L0CzRIEH^?Z9E`-spFfgM zb)<`_$50#{w-;vaW+fFaRIob@6jqRQQ&e1GF-sd8H=?bHN*ypB`Qw5;Xeb`X&XGk^ z)5XP45;x>zL07uBt|ITPud{!*zT_ayPNV%wK^kr(C{n8s7h*c~jXhn(eY-FAKXaV& zF#v0)yB-|c9!GY-i)`~OVUDryqR{ER(yR7~5y^owgrQPiAnNkl8jCA@{>K?(9U9z4)TUP^_b#G9%WQvr-v)l*F8C+dpR12>;ByviO) z$hHS9v({!7tFIEA?`2FHvf+n>LTPl%uq|P}B5A6pr5;F7^~9vkbq@Ch-nLHR#;^3x zVr=qvrj%%8FM*|MM4!G6#0@HPq?Bx4V!-&1m)Ta0ux>v81I)U912f1+v_~xx-!~mK zpRg*y(;R@v&Mhys%&oK#{j$EH65I+Tf0i4PF*JJNP-{bR^Gf!q%I=_Ur1-*H2&G6r?Xm^&xk9c7jWY9m*EyiFMo1@1Pa$-TOyUmA9rXZla46JM1j$+wIlXCMUpB#1UKVz6>peCKqo{E?l~D{ zADlcf98yF4C@6$S(t8uW!~4F&`DYG*-@Re=JjDgiSwnFFdwW}gqzjtS-V${#1|hBp z!<>7#v>1b!5rzYsdKRW;6{4wy%0s`qvn6Q4zQ@FZWN`5V-ub>vpDn2RBv^zU9&@m& zMCHi*I`ycI(xZdq1#%8wbqP+BmZI{Dq*!vXmdgTa_`0yC|L#12)Rr?E2}f_pm)3Xz zP7d34Rqo7iN5k`BJr{k7SIN))bA^_|{Dnxuf*UtqdVeprIXvGkk?scAMV|f`nRS)z zwOSS#&t7Oue3;7g&yY!t^6QZ4n+%mbr?94FCsT2;n;yji-Y=6Wo}0_~icrcT3O0 zgy}=vjYb{bO1obQvvy=(Y*HgOcMU|`i35oB$M}RVwMN|`%(i-li=Lvp{hr9#M^pXn z_`0Z;I+1T~wu}5`CA~P78`ArFt|P*#>=O_>tu=k*{;*|>?#%TRDt{ITbtMv-QPW*ZUuB&rh*Ol41geI&KV&(kX5mp zs0Lku&xtErg}$K>)Y>%Bi}W8et7kz7oAn((1v^{Gtu#vlWv?Z>>flQUcEWruYQECk zQc4;VS$*FA8--4rGw@_n+#d?Kiqzl-x-3CiVT3!>UsEP(mJ78?b@lm;D5plA0^-gZYY(>2iQOe`^Qw|ZyR8iz|mPdwRZZGj1veqgG-u~n5y4*Tqi zT%9!OEXPps$oD|0SfkKkU8P{?U`U-{a4FvRf7xS!1*I>XAo>nawaZ&xf#yVR(hN(E zN)_(UB((jxkN<8*W!C=#>nnH#z$*%6aNAvBp3oCGOQvBUCvAIgnA_tGDmsp_-JEUx z*_cBFBjF?5yctcWuuQQEq*I`Xd8YfU%c*VyD_00eJ{f90>|6ee+QMWsheP2~g2`5t zfGg42TjKI-y+p!)?}LT(KW$H#gQ59VzlBxisMU_=gX?%Jmr&a_lRtUR7&XAm3*qBr zeX=Ny>?}t@Huf(Sb#R^bXWlDmN}`2WIGfTpN8r^KQ?4-uU2>N9LfajOVP;iu#ON{C z|HOL0X?E|rbD!79Jf&>rOoCK2zce#Fz_xyf12ilJ>{PF^?z*xb_58sJG9Q`re%H~Xy6Jrd!!g-%s8~t>^^~6flq+4%B zJl|reJRtZiKve)SaD>+_ydq2-xk&7T?}D%7EPnJE&l_cVPhrBtBohVjakXN{!7YC}gZj$_0h=`m!5;TRM`9WK^|q)T zEj)b(bK?q9hv;+1Rv8t8s4>rOzig64amC-UViLkoPac|u!>DWtId8zVE7;KJs_86C z0PxxiC{9-#8u_w838A7rc1tV1%T&ve`}vW-X6_NI7^E-G z{yueWc9NYf0cO^#HRs(=XjBJCS&!dUNYA}x3Pow?pH65ko-JPb8vHHw{h=CMwk0vr z5c;V|zejVUKREvMYv8qR@Cl5<+);*MTM+HsdYF-S0mrJYuORd)m3+z)T zvssu0i{d1R`1VYf6|V4B7W%O6yzqY^jDi14VXW`v(%*WPeXUT(U`N61PuzPH3+l)G zp<*ZV@}^(6a6NnGBC5ax5@L3*7bw*8MU|=>`G8R%L&q^t&}T~F`w8Ok@ZSRcU+w7n zhu+Qq%T)ei-mcSz^7w(Y#HmL6d-{Q6Mp_=^^+@%yJQw@U#? zi2VMCw#QEytPiw#^lAt!2hRM{#@kegJjVBtG#lDPcqhfaiIYhs-Y$tDhXUpB_4L1? zps4+9d(O`k4kL-nx|mvzoZde3C=)ccZ)$|ycrEPcz}y%9Qq4ABum8!0+`rN9it#r0 zKM{{f_Cv`gil`}<8}7UQuZ1#|z1P!HXWVz_jYlD~AErKK9fx!qf@_2MF@|$x_0=xZp!p8q zBSF~Drw7ol!uJ#I5s%iA2th543)@=Mhj$A4ZyGTs_k>zo0I*c)I+q5-ym+leH;KQG z{OkKK>i*x_TWiY@}v(CmN`)~fp~V0pN;LP#g(Jw@TU8UV6@C8 zt+xt_Q*slq+izh!lIl~wAR*``$am3w=%ZR>TsdVZC`W>~|1e>nUGt8mJ) zM!bj71Fuy3T_e+S97x(7)Z^7BBFHn}0JZe8qA2z*SB6qE9C!T;pS75?;DGHorJ^v* z7F%zRtV1gIcw5@%8-Dg9YeFm=?%7C!SW4S{@tW> zh)%iOZd7TU4&$&;ewF{yBAy9Mpwg|h8lGo!q@qIhVAAYQd-&|lX>6RFld~bh;I|px z<2_Do56pVkf@|L_z~SP*>X6wcE5ct|Fa-4+G%y$nsm#^577V_|7;Wbg-r2cXxn;StFbQJH|P z(%BMPlw=ooW@c0}4d^#fMvu5Cznfcwj0BAx?u*g>ouflZ2b7==xJs+HLjQd736aAS zZ$@?}4i@`JK3_s66 zUyT{+UpG3~!3hCJ<|h^2%d$gG^RP(QjPc9)l_zP!bq7XLGlH*OITs_UChr)idPGRG zsr|9rN0GOpMUA5azZG6(V>b|sZ@5jEh5gdcuh6?gfv%pu_NIGvZQ4(3aco1C*;i*( z%JpDU=y%p;abb7jb1PuwBVtvUke7;z=&15(oF}RmnWvLI=py7zB(z?(HbTao=)v8$ z4D?46jhb(^?V%?3a?){e5+#OTuIhN-j#`31FDB)=ckdQS=R9UWJf{{SjkTj!+8SZ& zRo>`|(6cI6=KcaaxzQ;!9>mHCzyb8 z%n>ZjXN=!EdsqM~4cdzNA;vb@8-~r!hrs2FF8ic)(yr8lJVd6H3f4Ni~@6 z@w{~g1Kje^Muh^MRiEJ|4W#PmsW~NTpI*slr@uIHDwLj`@@NjW7Lg#(243+sSRnuu zWjDv6reK0GXBPx$7$eTrjDf@c#eVtiBkDK^Ygs>Aj_OpnXEY5f+r8%XCK;mOf>z~9 zzMcLU0C89s2X-Cne%UKPZ=5Pm3Bv@o z7~Bw~An2drMw+qO?xA1+;WfCVrYFs?wmE=oZfeSSg@A{T7etg~&b%?g)!c|8@A%Wi zrhY+(E>S(FP!{BHjBI>qoBJ5%!Dh+3++>&$HGG_RpU;;*9X!_6`638-L1-{da=df} z1ePZaS*B9ks9aN(1~+FieZh$p>ACi~wa2U;b{IYu6j7$QVyuHS#R_us94>8cT5w2{ zX@vA^Llwfjmp$Dww;GxZZ2GG3Q5H;XzlN*?Yc5w!h6K7}jc255(wzR76~(KrQT%?@ zWO$T#v-?xzu|+m4KjMNwefuyZ1+!1`CrnDJQE=N`Sy2;Jag4lH(^!MWF>_f@x0WoT zr!(!Ku3m#ySpcgphIIX)Wp7e#b#d~ic5qCY*hFZxCrr(D5fVs{-tu0y|Wgk~C;pfLhL( z*}magEV=8zDun3d$I}4tunVSns<{8^wxa2m7T}PfL{Xm;xS8Y?>&pY!G=!>J`K~ zLdaO@-N+PDZNUrAa>Z>^oDb<^Y0@;@#0>GmFKKX=jMUq;a9YtjJpLq5nNv%-cw_qn z-a&Fpc%;SIq z$z8V_V(S>vYh8-iz$_uSAOidD)At;;Gg(DomN6@^Zg&AlXj4dyWwU124u8_^y3;MF zvBiDKq8;O{@==jBfzOPSLCxYa(1Ia}l6_{AzdpIcMS_&Q-c>Tq_7~{{8IAZpD>|vU zQ|^1Xd)+9oOyzQZM2bQelc})kRnGQF9skn=XG%ghAt3O=byFm<-p_+ltuR}oFCQPE z+aRjekhn+s;Gpr%{O`h!hKAvZcA`Kuy+l>#BHfE*^j2gOo1dxb>cw^3c?Zhf6;I6{ z1llugIP=RaGy&H=Yi$7wDNx2Hc7wOuLyM> z6jiWR4Lh6|CDu}}fB{1fVVh-Ycf}XV`AfRJ*0m=WhN~hpWK6Z)8A3wrNH|U8Oa4nF1Lhol| zv70wDqIj)Ph7!zjJ=EHHg(gFa35e*{M0_U56yKhkgD9F zu7nz|P~8NwI8WIuK0JHMx8K&=s~NGGs9A>aVt*uibh-Eu}P2 z+*;Bi#oeJT!QEYoyE_5eQXqJ74+RPoclRPG8Z5Y52<{T>o_^)M_s9DOylZ8_I*>DG z&dlt+XZC*fv*Xi$hwh#^1H!6prxD3fn9QUcP^Xd0pqu{0g*(7m$UcL@F#ApfW9|h)GllM`)V8{sRQjN#? zd4m?bnI2lL(16mml7-C`>msIUMF-OI^l5TvqD@cD`5L<8M&XCj!UsR*x~=j(o7P=f zisQrHN(l?CjrORaXz~|K-m$RxYXg&%v^tBlWG21LcK&kwTTl$4Z?dGG<(Fssnwd1J z7*%3Y32*D6s+B7YTbi*xmf-5^fvY-W8a4j4d(mU`br>q~D2A9#sDMpMRuBtt+1i)6 zWSE1xD2^TXHz^Up_PP0p9YLKGT}!K|7dcc})$wB;y$>tO7gQhI5yUzAFOOFB>ZnMt zc-Sp(-M;CH*iKZ>>*47w{Xd(1X$L(3aS}I(g*6t}u({?%v)I>8*aM_Cafaf69$eZk z&3trZ;ryp>&59w9Fitmxy(Vu?qL>S>Ns71=o~E7{bPT;qcd`!I*XYV`LTyYcr>c{M z6oEifitmK-#9QIg3I4}DzdI+S^;RzrEpyN?c;!=|X@8zrmh@gt|I}nG3;yK{tsCfo zWr5)fyk8MYw4fy^LhgsKpRvHZnLn;wQ>99-C{N{FT4NI2IC`!DMg3OzvU?U|leq`n zQ}%x9B80Vfpy2JThugY2R|g(!OeM+sYBVp+mbvC!o*w)Crz+KB%>z_I&a&y+Hz^(H z?v~|+CQ6rpvv&C8jyoCrzg`ffJW)0m{$;FDy9Yg?z)rZBj0^C zK7ph8tgX?93z=~?lUCVs+Y)^By^IsNSNA~Cj`r4@=7+zL;6X9aLfNRff#SjwU~;N% z+BT-T@rHmPLg-~2-_ctCm~Xu3(vg}-#W$A+w}Mn|ii1t|ifQh6(&Hz2jKfH%6 zQanK(V&6I1&wgX|9w?1e!pM13=ddf<+qNfiraX*gimfAkdK*osh`dY{c@bhcw8PH^ zy8864vOA4eF8ZF;zWu=6SYOxI5FbPZxS!Ba5kBr-J;h9pNHL!nS?*_t172 ztOeji+qk@wUg@fht2KD1!V=l&*Yx7z_X>2;iE^=;uIEog+7`1Ww(rkT0n;7JU;jCl z>^q#=ykCR?amL-S6Uk_XTWRfW<8byCNsU3pZ@a~stg*6C(M=JiLn33M4+6{S|A-do zENh!%TJN5HQZ8dNZesi8DVioPGjC9h}g*TB+bl9i z=>E(8@pm*A&4SPV->jzhd29>+8RdWdO8@;o7WeP9>(l>H1%EI9@7eJ0)t&#n`OcmH z9kBmhB>yWI|9{G0Uon#wJ*3J|C@0*t6_e5wIoi=S$(}iuUL5Ab zToh19C%zCf$0CiD7+Tq=-sMj2AD`#_{Vp0i_kBt$y*%f?SO8OwofD>_9rq>oXISR8 z)~Rdh#wpWjlSW4yIzQ%1dHrx-M^t^l!&lxR0q|3!Pup&d1J*pr0~%ILDZC9|$5vlg z_Lx@ahl@ll-)(cZ=I7yo6$Uj`y)J)Zw-i1F^ujQ;XV+c%&P_g`CnIu1+*0IeV=vD8 zW9L|8WXJZ!CjxK9Rkh_!!qHW3cD1q(_M@`r^pmcTs6QQZERWk18bmStoTN9x#U0}na|dDA%65A3@#^5{ ziBls8@$3R^%BRES+3Rs4!BJ=(ejumH>!1wrndE1MQk*~Tk!VdzyJ9KXb?3iXG6-jh zV0+HW)X&={`jrT0t{*?z(fV|FRF5_`iLYr!{N6c2nnmsbt74$XwYAG<%D9I5q!Cz> z5Rje=H|G%bx=3gK>~6twF73FkVgA^kld^^AnZc8{jEbsGF?%}n$EudSjJrnCcNXhM z$H%riOpm)~QFzcnP4UZA&I43Kp!clmLhwf%&M((?*WcRtx-&@9Zy8=<-Q_;*TE!z_r>e)EEbgx} zE+%AXH<2QHo_g14pVtjszxkTl9R2TKWwQlMJ^G9Wx8frL3HDjzCSdLd8(Flm`RVfq zRBvK#;b$s$u5g?*7?DT%SpTm>bUk!UU!wAe_i~Ig>cu6dJNEzNmv7VvhnVm#C%wM? z^~@q22J2_0ta`EY3Ei~sv`GENS2VeO)D7PF@A1KTc7$7IR}~zcEDK+`^eOfk$Q3r< zV!S^%!76u?G)q$aa)En7@KkpoqX5UEh&Hyz)LlX3*TuU+QS0$jg(@d5e<7DyTaKN^ z7sD_q9G?N;8&wuY+h>Qe5&dEd`Ed~n@bZ}=^CL!ZbZB;|H{hp@L@-Ph0bi^{(eek+ zCqEOlyi%Rg)nu*PZocdX9$sik?R{x|TrN@QB4!Re?_`di`ApK$NU>w!O>eNT2Jk15 z8?!mERmDM|BFi(%P3D&Qo%p-xELlx|%7Qlu4#``4w^<|+(<&^I~Eq3xxi%J`~B&qw_XKpmAHm9kIRsPI8f*vg(2%D?Bh~ zA{1fPJdxZFG#~1)ooZP#Tx05=fz!gTX1%LIeEm9KgT=P&;wIEV#W@x91P=%a`TZL%Eg(GagT4floEP~Nkb zI2Q%J8^&uZFI8fLf#F7=Dn<;0eM)KpWc$Ko%G)ltWSC9Amc%Xyu5 zhg~qq^0VE)O8al84xNxWh0(#3Iq6et^^4?)ozm$db5-`x2Fa57qOki5aVwt_u%A}z zOu18w5v`LO3DX^aR%Z|=ET%QM6laf!cWoe;LP=nOSuF-k`%WpnDXKci%|PI`DjKQ- z(T<*?e%qHUrL_J@O+U^;g>#pY&BCPiOVeq`#0tW*L0gye4kpb$a=F5%i*qTgIy01H zAuT4H$#M$K#(Rp>XGy@kU!2r;=Pgc$UZp;=2sPN`PA+Q6;HHuBwO-(BsMaL3es_g| zp*Pwj@`PPyHB||x>H#C*YRM5#r-O5Os$uJVboRj9pYc=|SaBS>cBRw7^Unsa4I1-m zJ+AJ3PVaaUc_s$bvcD%e9grN&co5NC(Q}zq+h4>JVv=gAq}w#%$}Qs2vl3_9b;o&( z`0BMbVKS~M&H!iH`Ui)t*HJgJGbG2yVtIZ1MwKalhqM?N(uK#I!=Yz(mZILk5MWLo z#>1*MV0BhCHPThA>;xdI{EUE>?EBvMX1>*4rzK|D3*i?Am1omM>%v&j0FYwd^y#BP zX+=rZB~Cl%;JhyoKC$&dVJ_(Pit?++e$%zA#0=Q-q@JBj&zZRRa|yg6e<#f-*?kzQ zE6spwUZ5KV)|pM~EfUFy@N-%^_e(|D0xy0#Az|*vNW|VK#Ch1z?2!RPU#3r~&wR%_mk4jv&@$f;aH{_|5EORsiK4Qqw)|B(o#`FERkxzVM##q^|@0t+xT<*x&1wz;Gj~)08 zHdvXN>T>;)9oc9U{<+f8IUcO*1UW5l>@yn`TQGsv#_FXosQ|GO-1-vi}sf<7A}1qJm|FCbw<#ri|{8O%6JspU|X z1a82<3MkKnd3+cw9Ug^ge5QU~{AJ+6M&}do(3`E1jk_AU%GY0V^z1SEA)sjS7vCa? z&TiE78MhdZ&^gN!L7g=S2_&Kbo~1rP%iGW#(&_mrdkRKLqL0-z zJRaWm>T*(AJxQT*<%{H_prbQJ@@(M;wi1kX(`qs$FhJ+R7yWB1Er!PBtHupq@ zUMMW$6d*aGrhVrx>Rw+}n9yj+u+AqEsa{e=^0?uCSZibgnNPOD_zHoHrk5BbU(tvH z#2R(ez~%QDCUsMH=n*0QTgP945RcH%jLff)t>EeQ79-F{9rLCky3mjLflMlki3RaY zaC8WaGWFe_LsSVriF(k%(^^UKNLVZ)HlBRqaCb;*nKN+(CbkPCMG+~BEIU#-(eJUA z5I?PV&<}?(?OwFX%92N3={`nxa@VfFiq6Ew!44F2)4xKGn`&DdMiboK#?k55l~t3Y zLmTYD*%=dpa92;0*wmAmoHNRR_SZwd~%%LHHqu-wga3yHJS(Sr61Gcr&6|4 z%TodjvikE%UeqnTuQ_QH_7g|v#yJY*mnUgS)z-HfNK#Wqj_hu0UtfPv?Ej6Uzea6( z*ce8B7xBJkNT|b#;#i0LaD%W){{t&=Dxb1~(gQ0c7V17&qNHr_;E5q39{e2fsbY1-kIG7hKjpy=cIKj-cgPWDCdJTlO3(UDHMYl zPt__Z97<=%34@t@RqB<1eXGpuUnma&L(8A{iDR7QZ?&6g#NJvR{Q1TEF^nOnUC!;u z>D!lqsXv=0nMX8*7+WGlXZlJ1S4~szn$~D%sXZ2TIn;$iVbtSClNXI8=7Tg5ZUTNSLNL|X*1{J`*n@dEptOP$EGIy2K+pm?fe2I6i!mu zM~B|K1?R2Emw@UsHcFK6fAa9yH?zS<4T0)@Jv_A796fu*AOYE4we`gzQj~UkoY1TO z=~q7xh^*!EE*taIUrUGe>;>g2a?%*n+Tc50x|6n&c!tHqy90-%* z<7qj!VE8T6*I9yLkCfiSXp>LjYQ=WO>D0_U0{mB zKp+=ZHMoL)G9Mt7BItPLtgY**F2lqGKlu&GIK4?$XGmwC!vJkBBeF9WDIE@+K&VQ! z)V+0c)Qc3PP0H2fqr9NtZ z8IzyW3NS->F0=zm^4vea$l|`b@*n2SQMGNOAI3}lBZR)@Fn*Cjt#hPRS61Gu%y?(C zF0!-bq>qTkxK}fWh+Saehr{`k(%N9@Ji2wTtZXX_Vd3=9y6N%7qjo2`>B%Vgnz80_ zwunobdzgOYa7JhsaxV4c^aZHALzU1*+t6EauPx@RwOlUW+NI~B?E@V43)vd|RaiHf zPYUveQnizXf8WmP;zTmcduy!!7WK1I_Yd<;#;-ic7YBkaZVUWMhn{d4AG?wWgTpUM z+=yivlV>d)EQI6K;&~@aIZFH->_b{xve?{{y4395N(Ps74q+qS@y9-_8d<>=mtdhpC=-vSFeev2>XV}mI zG$48|vwqTt1~k0rxrV79M3d`09SmHjYYJBv&*j6+=Y&gA#Uoxv`H`YL-26OiDlW)u z^z*XX&6h#@Q&d!gcy<5%7$MAls4D#A?M6y-!lWRANZM!7mkDbVws_m6uJt>ua5!V+MbzI{|mO4_Y5mv}? zpDm6kLDE0;75!eYOkZg!(@WjpQogHrjBJO;+_9xyDH&%=c25QZ zkvsNFr%!ZP%ln)y`{D#-+4Z7($g#*OaX#p~rBT_`n{e`(L}KIt1R@;MiBr-S*5!A} zlz3jl*E$#}pLnUlE@q@2{PXuHL`w8Mn^)H1SGsecFZa33OW?@k9|PB!YclKQUwD;aYd z)1Pr^SoJd)mXNcqef(k)y0vXd-)yzUC8HQdSA7vWJ|>**;em=23w8QzQq)@0w$*z6 zFcP*hw=glwSo4zJ{b%UKBcSG9X20fBFpcbW`||J@NCI+&IpiUn(54=l@WQGoh*aCiz<7B`z6rtV&Yv; zL6LwsUhAYg&@VL7CPvk`9pOF#b_r;5GBc$CWEf`3v%nm){Ka`CD+kTJU}W@1mEKl$ zXw(L-6;PDz${%-bARbiadxRTt)Zs@%qY+I_v=?jd`sL$p-m?4%u0v*tN&(}|sx9iS zS@s+yYR5o8(#sSq&8C4bCfPl%+FP?uPPY5-5o67)^@wGacc)v6=Rv(^i+}}FMp#sw z2zwGyf`q@Ce=KAp?LA~n)hT6i2pW+2U}gSWKM1sUozDXxB3KE-lpFNQ(w#iAp^f=F z8$E);3uRt<%y|d6IzvXjJmcd~u`sj20UzKz&{<1lgGe^SELB>!v`;z~P2p0f2SdOC z1GLhO<-Xc`Y~JFiXL9(|y%2T%5>HKy0NDYm0k{i&$9xF$-bt`OZd2=Bff^#*Ih7D8 zp&ek>polo$S$xSVq6nr!NGG*=8c`NXYunF@l)E8qjBj|!k>5;0(YQQ#t+b+ih9M%! z^&=?XH>HcvQ?>xR5p}WeOQUeCfB2MJ)+OdvJ`j}O7d;YoI5NEU62u-nGojhcR(h@| zJNAUR!BJSgbCp+8A3ES6=QT>lnYC?PxBR4`t91U!pQ26hhXi2j$&oCF$rk+>9SliZ zEvSTh)aUnQD3p1)JhC@G1#K29na2Og@>HxHzt@iu)Kq_c<=3nx zcZ#Kqe`p@V#7@&|D%-`aMQH0OQriNTMbJj7Yd#1$4WI#8DUPgJ#8_i*S1Xen(B-{* zfyS*t>kBSr(+)b>3qnb?^{f|#Sd~;}+2#DrYgp_y){Rx49pzVO84_4jgZM!Es|S&n}Oe2DD?$ z?crEwH3oC!etjR1wC_OTFwzV@CXy9PnW`1e5(J!OypO6;TGq6xGoDR80u5DlY-_vh zdK!po$-q{ZWFME^lzXoHY1iSfk*F>B*A%*oi0OND4w98#H1lhM>T|h7Z#|XscUHS; zKAHSxC^deq6DDqNUfAOK;`wzZh^}rhp;nqKs&Js|hHWy5b1((`-aByp)G3Qizsj{zStr0H4mMSwZ6GoPM}a z(M3u13h|xoEPLfun3QVjUhK?wZSKAwJY5;bmzRa2__HkpLco$3o^W||@tlqb-o&H+TMC~?>vEoP9q%a8M%^69DQ)1#IFR9CBjeO*mu-R4njL2U=O$?bDPy_F)>m zMP1p-@h}2?3;pVq{z|``68Ra@NYwP;_sJWh%4Xl>*yg>l=W?c{lID;LwJUe0A9=*m zJ}LP=boCpzA~nZ-SLf0uJ~&qa0B%d*^i{N42&^YK4Y!4|3fSz8#PqxbMgO3GOtLn5 z;E8z?MHIF${HqTm^hy9P^yk~`1C>?XF!4Rh&XC^n$UzLJwv$eQNYA`h$bK4nDT8@F;)megw?+TIJeNO5lyhOC{<~d_ds0ACuXcv~~;K@mXwHpfGQS?Qu_~k0uj0S~Mdw-p)T_#b6f2DnTUc7rXB;$HO&TH}k0c4{6n}~% zf`ns5yDM=GMJEB+r&k#^_EaY!>CH@`=#m!>m}Z>!mAZ!s$B{WrZ=#J-*n+e*q{wgq zW6h>r!%4GaP_h0nP|m%#+U?IVb&gwc@iS#v+E_BsRwdBa-#u;TK6h`m5fX}4^^_49 zjW|DvpFyk)#4Z2O@sb{pSTiZ8M20}(Zn{NXooK!NX9lBU1Bn|h8hlax{SZi8-Zbu_ z?O+G@Lyb{9PDm$qySh10if^faf8i4oJ`dP)7U4<5?Co3b{5#V#6hd;C{tK(#ttq5b z*KdpxZ1eW>9i_I>|0`5%FVbppR~~-&Rr(aC5&-5#A1K>n?cc@H8M~u1AJGwZ-H(yq z6Fn;^toxTF(MDqOK1`(U#mppVqb!tCKe-2IvwUTrXAr!3f+SpHERR~}Lg zv)OXuBk%9ouVCV!@lMm3YBBw3ymMN7)B&YQ9)n2Gm`&p^lQV`#^BGPUa1L$$d(~?@ww{95cqzq19zbYwN`!p!!3cA~EZn zwyKK_;ND3sZtp#tD%#OUX7!nldeNw$^&(^{(C2yyfDSiA5kGg)XbDtRPHyEO135KS zpVAb0$DHBPfkzUE*QpalRKZ8JYRjGzQwgk?#p094e$8!NO)izoWTl}^DOXO;tNl)w zHwH5zE?!e#6gOE&H=gwSttB%3oWpzEtS}?8^?8}}!j$$3!4pC9AhkG`ylSEX0`(OK zxJmnTw?s+}syySe@`;A$pR! zENnptmujReNph45?2wL-qBwnr0(%x_C^IN_;)4 z>AB${hR(QL4ZSZNu%1^f_{S`F?lPFZ@Qk`-_XWU)_W-a(+tzM`weEmte6A{Yvz9f9 zc|Et!R?}QPKIyJ!N~TH>P=JZkHpa^vwm8hqPMz<5ikJ6Ii4Fk z^I2Qx58gy5Z{1H3Hy(jW9p4FVnk>17YR*XW@t-A|k|fn;Hid7Bss0{^W>j1Mnh6a! zHkDxQO+cs4O*&XF%GX(g8l(seXtR7*wyCv&I zJa8C&Wx=L;TSkk(SxLW(4t9O@Va`ND=>(?b#g+5x8xmsN55)=!ara(;th#WBNo<7P zeCjHqGko^`kX`(WE53z5cD4DbWd2OK9K1)85Dt6JzirEcA4Pk_@>nu|!5AZSfOu(P zf%v46;enZOa+KSs;ii^i=d^-^SGiSBd8hbISB#iZH@(tHErp?{>z6Y<>z{Jgs(d`C z(!6*>29N-X=1Pdh!K9i=Lrd`8e4xw=1c+Y&Ka8v1jmK!tm6Yph)6j&yI_bGzq3-Z( z2dQ=ZVP{xNNHCRe6@F=Lf8)({qb1KAtlGDfd>g+1xY;DJG%~~XTH{7SOFw$Xe(IFK zwfNleJ`Ss^cB;E=B+B4V(>3DD$XkKpW8r`u%YVq9eT$JfPff1R_&6+DG1WL62z*!r zz;n+R9&6^!GwTzZRF!)o&Py34ker+g1FZ83X4G`xsMu)gl1OdHTJb@?;?<5`@{Q3T zrx3p1FA!)8Kj*`gbu|aD!1~iIE1a_IOTt8QE(7Z%oTRC(3)I85aB5#ZNnL?HLoNOn z3!sSA(_aciS)QAZmx|J!`|-INf)!kS3hm30H_-Nzbv>1g_8m}H!2O!$aG=}>trKH? zF>g$5qu};GV(ngnzlNjq;K&tgIDnA%Q%;a^X;V}kUZ`#2Z7M%G)Zhw#y(Ur@rn!Ch zy$@CCPc9nctU7J?D&b^x-$&J$krPRgES253iSY~zDPDoqsYhP&eGcAD^f#udn$ZrK z@mFQXeMPcmb{vA$iOMbUgzjtw9D4XBlHD4ry{BB%k|ZUQ^6$L*unwHewk@`e&*(^m zsm_MWH;QeKy&-~Y=8(9kAp4&oNh{$FD?I5uk`@u!gSi5NqGh8=^}}voiYPQw0~66+ zR3?nf@m{`_(A4BDA5FoIa_bpFd_fA^nrc?gZn7PxlVF~9H|A((q`ZIgixyJ(;@p)9 z^zsCnmi1u7(P&v_Xl}n7bgl`Yz+6MwIl&_-^AEHdBrBmrC*Nh4EY{(j%Xm_x{oVF- z+zPH#sDlRE0k4b;@pYO(fjOKD69>^Uga(Btg|dQEnGA ze>w~f)qL#xjMw>lV>WdE`hiXetG{7_KiTQqyzL?ux`{Q3rbewQ9`&5jnJPr+MHN7n z^QZe_Gl)&pGsQ&@BIbJW=^9v&gUxwr2G$AKsOF`dgCZnh-TG6#(Xq?&Kh9jGnozEj#`8)@YV!d8OI(#Cky(Tyc3KmLVAu+)^@F@K1B_`dT zJa%K2JqRyzWluS;tMr)Ov6Y_Y=ctKMvG0~zn289TtEnn8=_YvA?xI85NZ2zU3YnN? z!Lh3CSVBPLPSskhoronYSc8L{s`;jR*j*}B?+Pks$e*QX^fnDglQ9*J`!z6kl-td^ z2m)cbdRAUPSh>dh!n=t#6bFjHXB9QJHw=tER+j!ylE=+=gg|j{-r)F*TMKlB0|2mx z*i(&04RuoOT;EnC^q7XgI_-7YKWeA-Dob3bF~ONzGBf+~UuGn|;iu#oi7Bs>u_>RV zj7S=Fv%Sn{GV0vm0Y)vW%GcsY+mTgf*`?KQ2=s>!T3}x?Z`(?NUjev|#xHKB>(Q*?KhL z!pn6VEYYc_xlX5m5;~^Ovv1Hx6?OScqvQfay<-$KGlqDHp73_)8tXkV&ey1!# z`kXFAN@OJ;dhCLg;A@cSTwU}SRgcAmR821rn$cPd?c}X-)E6KP)8;ZiY_O4}ky|&v z8~cM?vW5Qw!jWz#41_fD18dX8)Sr%SRH0E6l}|jO_-(S{VMr+X1mJ^SvpN}gx?`@< zjgwcx1LI3Jeq=;gK%FuyQBy{mEe5w!f(jW|nrLIDviDqEcq07-^ z)V4LXtTt16+4toY)I)ls_6pk%MnE2mE102lIqZa!B(X9NhZpnoO{d6Jr4g`$9WQOg z*O2Wdz@_P%(^3J`v@CNAH#z_AkqVoO%=gH0sy;t_lnxzhPi)lz^ZcS0o-s6C`YyH# ztAZT6<48)#v>}wtF-*%r&#WP6fc* ziN^!sU0XayOTUvQ&_|K|bEWj>?5(B2^chcsS1?;gpm@t6H0M5k>mW(NQ|`Y-{BXxw zO9iQ;X01=G^~cfhx>aMyFF=E0U4T}u9(ivQ_>Uj zA@s?`d>z@uw58;A?^F50j8Fi?Ld8{p!O~Vr-7ww_1X+bF3sTNl7GY7&O)Je${6#_e z`96KTnou;~~^R>4A`!vh(VRwTM z$jit~HD+|0I@7UWH_VR-X55#tPgbTrGCsre5cq_6g(}>_8@BSf#SvX@<38TRGM~X%xPF z#`?6M_dS9s)IsZ2)-lp$XVg?0#c4)%`;nr*47kYQ z^#;US58Jyz(J6JhzNUS7=$2^w~(sEHKi51Iq8L zYW-EgTT#40%)rluZ?cfM6hV_(?P9S7E!d1xLXbw5>!G#-D zZy+BP3#z9pB7ND^i`vJjzB+jDdC}-Z1SJ+~Rug4l9rR1t0Hvy4B*yK{nbK6A)Jx#v z*@QZJD(5c_Pv{v})90aRQnAjJr&dDXd~}+0EcGt8^(-hc5nY(egl7(YqUTHWXnrbD zkTr(f>Mq`NW;@TGZ;F5u*YyzixCIOEE^G8pbZan+ocZd3jV0$w;PRUH?yyEed9Xd- zFOPmobW-Cev{v_Y#D$w`jPXTQ)A?lE*JUom$iAUa4b?7;w#_W?OeG#V|DNYElCSdd zM1PKembxFwYy)|N=OZ99Q5$}mx}=|{F9Z@!N^LOkkB~MsZM9qEUg)P5babCk`s;zi z{TU~5Ie%(9$TQVlRhBuv@?P-CqdkGG<&!=edr2Bam}g>3hy7&4ur~R#oW@jbhZ9nR zDe|MGlwuYH3fPSfSxyD&^2_RsF*>JG^yCyP1hzz#8gqM|nmt$Iq) z#@s8>JV7S74aYp&^*hgaY<_$CTviaJ-qxJHkGh|0#80?}HM&?w4@-MmDSjn~EQMb3%mQ=F#nUTH{FB z4-RV)p4XuxV#jO(E?{v$P&OLUWJHHMHfC8FA_(FL)Dsc*DcrBRI&EfZMRw*wzU8!P2y-WQo*&f;D$B&KK8S|I1pxN?T1c2W*8 z`Plvo*p7e0%ZJ544qkb1djZXO%WXVz!R~RAVpfW5hfy&xG1-_pVHNgPW3?jG0>#~_ zj3IGXpNvbO#otr(&W-+@OnEN~6N9s=)v`Qa#cf~zEU;d^j|_BJCPWKVA0MLH;$aeR z(vDwdked}<)L6OH$Y%IoF^7P1ZqVe|H%(6ZpLj&hY8dxj1TJ3`fk)lO zbXklQ4v3A&D@@jenNOhsKDV7Q3bFIZ`JpE@av21mtQB(5P#Ld+P6*4jJ?JPv7g@l zOTVX#puhx>H%+cP=A$fI8E#x1xBtn8x-U_l{lV)wJi3o+#4+h;Nq#(~7HTUj=#-rr z9YZ3>K?cACPn&n9((EeItv+4%Ms$9u!GCu14S^Cr=Hoardy`Ig^AoAw$hq6S(a&ds zu?J(1)TNA6CinUYp?UkgwCs{@I+^xX=FZd+))FniRV0tlP&|-c}cKd`eKNrwE*Y3g~wo>hI=utGvC>-yfEX|4v;>Gx6EiLlo*!O#c7qNg zLuSfD?gPle2`cpxVE}m+7uhNIBIiTC-piZC4dYzn;j%;!NHzDiVCIKt9z{6JbB|Sh z%K$s1%*2n-B1VSlws!)otKM@mPm?hOIXWcpfieGu&Jh4e@i%*n+wf;DMNy64@z;Up z09MFCEI!Aw`JMBy@{~%E@xc!3puqv(Y;i?cB`P{d3qeKz?3H9}OjD zBnlvi>nop?ASAUy0Htu?Zi%WSfd2_c2)z7YLNlbxL!8DqZ(WwLbmOY?++KN`xT|D@ z)|J0IyT13ZW?n1V@jZ(h)%aW3b%=(ty4R0^XnA|wCZXNcXi=_&jJ&wG+M=JE?Y2Hx#ljDz3 zu0!DGLgMW&&wj&*!}-{{zAzX}Ml_a*KQ6H^o3UrTLf|%`+M7{0m2*bf&1KO~Bh42r zq2;pP?a|NTB$7xz1w5eTV#|E|EbTVzja^Kx-N;5m{T@1<4uQTJJQCs;Mqi{0MOj`- z#DvLKmTs;!EMRcbWCi+!{cp8UYt9T8HR?w@+bT3!?&9X7D}Ha6c_a%O&2S8Zx!=kz z9HfI$3kO|__hcXfUscupf9f*~k^X`usJuDixWA-<471r@9CyBJ_M=ns~7NZbeagkVgK}5FHLT z_w4dQ>7g&IptBli~SU~IYI)?3h;0aQ!XqC7Ryo37rmH7VesR3D|O zZ_;;{q+?Vy)8MUr&YAW&ix}X1gQ8=&iPMO7iPE|~_##-ni-iuWprb88hAJj~{=$vV zY--I;HExtV9(UWLZWtP=Mr0lj@F+WX6#Dj^1xFs4FjW+C#K-5R3d(0Ua+H-^W-pZN zDi+3VS)&HTatN&*^eGTdyN3G=AWTTV`h?d}bk%8MdAx2fkerD{f{N8_>rvsHC&e1| zCQrIHpC5Sg%mSs1{c{>dbnBS)=+3*4U)LU8dzr0}opIV&tv$-dhpw5cbQTAf^0xH( za3JSwyf}pG<9(VAE8S6DQ%(uXOKZe5@%V10#^pczu@Y-USy3WtP;)T!~+~i7Rhb`1SIWagK~2SM~&# z_i=noRPEtD%!2ab5!X0?S8z(p*`7U5{_dZcX(KZ$vsHeD2u3)}I-KYEVZxLyVth@r zc0(KaDD}3ox$S5d7WpD8li;B(MEfW4_7CF6O|Vh8Q3&$xrYbf9Txu@O!QJZesiKvi zRjzH?G3JE}Ud|Vf5LONEC@c&R!!T&cXP$v~3Mf?le5IyYO;m;3S+f?0sz6 zT`~kQk5Dx@1sd#;+E|n!zlg+*qT57fSG&8WGA3ipWQpia? zA1`9JPsQ5u)lCcu#?j}TU3|6ZM$3Eb0hoM(cXAR;rw2^T6fz5Cvm2^sAl5BGfWCTDwDMFel$+yTE`WiAarObPNjjg zF3y<@4NQ}^oFB!LxEU!-bIalkLB2RbJMEvipsbc+QBxN{gK%d!IO?<>^13QTh zU+h9WbK`QR1J_ct$5NFl1K%S;i~OTACo`MnI(oJ{I|4uu$s_;v_z4#4x<-V`OuZBX z8;;SsjkmnvxxG`JYeRRsx4DQC?=In$d$1hUx5hUpk==V|{Pf!L7Jg*KPQ$w!wYRWo1poFs zQOw*@pfuQmli*8a#M$HhOQmo;VSmqtAJ9aiUXzW#IpH^-cMT}Y1_y~x9EEtD918=i zM)ug(7n;ru1@ZiKlr9lO_#Hwt%TJ5}Iyh8C>@B>9xJwB1dg{)Vf$+PR8pttk*4S!s z2| z5jfIq>~~}BxshGPY)nB;wK+fi;$LJuZJd402P}8scB1mnTewpGpk)clEFWj9qCIa( z&(k@6YqHQi56s&eGjtJo1M#nmzd!sI&VBz&i*v`4_`iHBKo&B~;eUxc?)=bS{U0W}_l%s2lP`Kh*V_K>&bi3plWGf$5q1h3zCx={Mp3G7Uo{Sn_5Y9NCxH!rf zB=$>RtoiLw557(?x&K+CzE^vrxAR( z{bx{*jPhEmt8WoVcWp^nII0ye>o$Uz~%FeFVT~iit3zm-M zd98V_4S^gzz)Zokak2j`{H@SPs0Umqo=mV*5Md9+4ph)$ZQO@kf_a;eaZVV!_F zU1&e6c68;?)%)@mx_Ri|r&@=0Fc3L$zCA??Qz_=1b=?=E?yf|EW4byS9OPdI7w`O^ z_P#T!sjcl6^*wry3K~&Rio6D;9zdii)e;0jK)RF=8=-^rnxLW>nuriWXb~_VHDG`M z5dwz}(n2pGw15Fa3oVr7i~8Ps|J*U|xcBe<{_U}|ch(-ye%4y^nRD&AGREyo$lV;Z z#C*|PX)MFMPTJzWp?&lynj|(ky%|)w84tIv(7U9>j5m)^V5|m&*!Ki$_IOd($W!_8 zGnTYDNyrxWeWFyxf*7>7{Sg`5{21iGH;)$vY%Rq&L2i^be%}bP=k`HHC?6&)T>YT* z)*&wY_Kv-|`hw1wnD-9W%m^P-TwQNxV)9N1pKOM9udG#NYFtGNO3zDje)v?|mn@jH z6mn2@N&3^oc6`H2hC}?qjrdj~Yzm1_q^hJ|rFKh}WQy+kass^axW6p07zg1O)kFQY zsr!i4ocsGZ<`HZ*qbJm$^A9fq-^n_EML14E+>EQCw9(n(O>G;)eglJyuVUF)bxHWzCW?KFnD=<12&W}vX6+PLIeN?h+*eWDzjvGSk`!w^`ArRz_hqG7 zfus^N)y#cunk5S|t-B^6G?8d}pCFjqqxv|bzz>}5L)<_22|mg$YYFKaj?|PN-csYQ zM8KFowjwo%y6a37_4PVyP=rD{A)7IjR~?(S^Pp|DEDIRl(g$m z1fmL=yJYJ)7WO#50U*0<@^x{Wp;~UXqXDafX;ZVD*UM(F zcTZfn0~(n8K5@TkQEK=@ou*;vTZPmTx!u;$=~~)7bP_a$TU?Np$LbQQF~c59AMF4B ziZ=^Q_1qAWjVrWiTx&-9X7b4Z`WnmZp0ecu1hRiEc_LdZo(8{nciY8m@scg}eM$Y! zDV1aHUsy7Xq}YoCvTNVxjoqqELHJ1ALI?3cM0j$Ax#^p3f_$|ZKq?(w(ABCY5u zv9uSIR8GWP$U)%@TX4E#pKY+DQk((Bic8P71r^vg{nPXp$qQpif0yfp=^^xpvHu>f z>TN=VV|xBpK|mi4YV^ELLVT`o+6R5MzDIfUPw^kxbr8EDvqen9`n?+Dq+2QsxjgVV zQrpIP=B%CUGeyNOUngFZd2<4>HkJ@)nWgL9HKKHBu&`*WjqQ0IGx{8IzU1tayQ%cK z_{7FqAaI_TKeYE^)&fR!@gOk_N-dJ>ydsetGHe0SMLlKFPQrhU5^Qn%Z=eKzpfj+5e5;eEjja8&O z+%j6dvh=IBG;05{yFUW44jFZJmsgrEEL+$Q8HBuZ%Y- ze#UcA0kn-Q0G^JcLh_^0K9=A0@`lctElnV5W^!}n|&o+ekyYI?hsiQIMh>d+LXQSDPdpVs3o;-nbxk5s&9c)D$o zJEWtjHK z?WGzH}i7Je@U^l&a8Oimg41%J!Mfx(dKA(T_=BLg}hxzz2|%A zX3TE@Rj=f+nUab>O(_O}Cgz`K&x>+Ktvgrdgm6};5I4H_5p)6Ws2AjD=y?79L`W%n zkiPeH&#=)|wlM*#2r=!ru5L=&K1VtOAY8aN5D%Aw1IQGhr%j@%bv!+!jw;|dD+-LRoDvax=O}AuaHIn` zmKBxya-Lj`(0}Xox4C)KfT?BLfJ;70rq}gqDD-?ab{h3Wa$~)Um7DsJ z*y?_0aNAxhEzU%q`tR%jJ@X1=f^3E1rb1i?>7;YgnNWMayBcO33U1i!(x^A-jJI$C z2&QNll~B*Vxw;ueD+J+Lk&-?hMHY2qIu4v8?}Zc0RIh}=u&cRDUb(H8{;4ao224r- z&s5aY-#*hjIb$kk;rSsqY#i&V?nEKR|IGZ;c`$T&;;~G^lS?Rw$|!96(OilHvHiUI zvNiC7iNvy1B~s#|bV!8P8@KK5R@@a2K!uys7ZTjVj?vcp82l;4Bn(-q3o5TKd$BA~ z&7W3nXV+n^6!l8~t&U%jW>tEvDl+Uc`CRN*=uqo~(pl~7s1Z7j9~-sEAa5)+hj|Xx z@C~6KuHSWEjKyhJB}+kej7V0*_VNHJfb^UUb6fBUCrS`Bz;4U0Ei9OE4*IP3DJ2Sm z!}Qc<-Ill3(IEd!2^zN-W#!L!%RfOxrBU8r$Hdji@W!%N(EJzeMDA;!;#$XW#6I8C^~E`&s#^=#o^ zIyPc^sS=^@t+;It%W@6(Q&kiuo>8TIx#s~E?n+=`vCZ~dG0(e(4L}U(!L$rmZ-}AC zms3(4Vcyi9=P~;7ghjiI!k|8j5Z@D}2Zs3HX zhK>4{1f-#Ooq=WQwD1U+=%$FQ^N2xIwi0CI{++!GQ;-2jKOV~|e$&Kl<~cGw7NH;S^|9fCYqFyhAo#tF zv+Gr>%@rHUrltYE%Ydow3L#{XP%-+iuE4aH5pas!`ayF8N>9=Ys%HB#3`xxQy9G+B zaQfJgr(u{eA#c5si2Vk4vy}goV_sdjXmmMTHbXADs+gU@+aY!8`8axjaug%)R{Y+R zL^6pw3!PlY>^nCmWIfREDGIIir=9hw zeuY2`FL_veogBr2n!2qWPOhxJefJ$0Fu(h)qskT@FrN$F-Mn)pWxbHN72e|+s8V`R z{8|ne-=T-fY->W6j$YczK=<{&*k*N$vK!1-AepS?zv7;#7P$s8D)nf?b4p@-%EzmH zzo*IpKXjJtnSEKuq(v_eV^d7_mj+%6YG~c%Oq0@UcY>cVly!q+>uwEXY>EwFbltiL z4_(jFR2GRZ5r`n-S0J$2UYlg~xuU_DcgBI~B$YZ;9r85IsMn9s_YRz{>EYt3vA4-e zWHT~)yu|*@6ge2)*pHaswU)=oMpxB3)b_EeYbQ(A9ZVkcRO3xmhC7qtCQo}#`l}XH zYb_}0COio^5L~pAZSvp^*B1C;x_(uQHS~ysQLi0(nWffa0?+WgkH$L@t+uWArh+q< za_{sL)rH?kalz&lWY)de9gwTZ^YxCofr_U6h}-k?_vh!o(Ks4d2499&p!eK^h;52p z8T3zC8HJcadCGXHm0_i{bjkS5RIj6`G6qZ0a%0E=WzUr*2sFZFeg*mn$_zaG4z&Jgq! zQM(cuR15XFz}{m#H$nelR>sOgCWQb1JA>fJik23uD%m6CxD#i_+X*LcN4PeI|^HA;<6BBm^k@a$<589K-A#`!+>eyYjCB69d+$c zr3{W|$Oet|hCXL;aP6Fl?b|$M#TXV8xaklv8f7~*R5UBj->Nrf8o-7E*NnopmUi}Q z-Dh$V*>U% zD`(XBqn65c0$JZGm=R2Rl$X=eaQ0{I*Xv0#-JY7fCfHqyouxOj&-2{Zbo6mg)#$FX z+2{sBYlK()xDJ+|d$-rj8jc^0nU|z)NaFGBhHSZ@YEA=fRXCBZ$DQ&ebmAfdtlm6G zzpywlXCeaMgYobf{AY)}(%_g=!ba0(QpJ)*<#!Y1276E5;hNr**5eTR+9*MQ=^(#i zH7r8U2%rJe$~>2Vd7{Lutcq)x9V|Q)$_tJ{WZ2c-UWrVq>=#oP%|PURAv{e08$^%N zPqp-Wn2^8pJ>Fc8m5M8TVy=FYny}iY^R)fGeDI}@MC>ZH?0bbIq2Re&mvyGUOYzya%UT_e6}K3m5V(x@)Hxb;4B=gQT*H z`b=8gKJWt9pL;WXwGQU@czBZD|29!~ces?%Q6zM$liEEO4eS_s?5?~;n|y3z09q%^ zTcgC|WjX$Yzoy)K>4~I-@Yfre7`P*GSUqf! zNe+4jT}Q&boED}Fd5_MZBw3@6kP+m*m`Zo}?nXz*aG+#sNwHA8LX%1DcgosARwuPM zkY_Kg@1>x+mO`eHa@)HkV_lc=%&8N-#VVNKjZ!Svlw&TBzWZU>7^(ij|5*Bf_A(a6xSRY9%D^6xRawKjV|C$&y3r?s#uA$LeT(G^=S( zQqOA)*s)D0#YO2J*__S6wmZplQ!8Mr5Z@3u^CsK*m|o&iQFu6%ro!CcpQ9d5P{6Z@HiO{Z!PlcyNv<;qyL+m=kZGCo zI$&$Qx$T&@9Y{y{J0v{Gp&h| z^d23r7b#Eea=JFduuQq0vXN!C$6x2|Eq z3tEp6BlHt@?qG6Jv$7Lt?cgv!c7nc%^F|jk*CI6+^eH7eJmZ{=Tg7|He58bP&G`4^ zYB}p5Wic&PzqPa<2Cbz`rgdWuL;zI&Qk?BCnLs|glD_E%WYMQdu`OaFomVbviyRNn zJZD-*xO)ejrnzKXY!3QCT-yQLStTEKelxBfD*vpinGNx~>Ze$C=CSHp-_#V9pLL8r zq53o;>Wi&((}d&5DaL*{kjr}KF=Y=4F1P4WMKA>2ki#!2v^Ww}@7gxsdC!E~Vf(kU z$>BeKbj92`*7z4yzlyu6;(iF0sU|w!&p5J9#cOcMKi|wo>+zH`CwM?jzaW=pqo)B^}h$5ku0VqB)U?%%*)jFvDPr3i66 zZO0I`a}HWIJi*`EweDb`w0j?KtswX3-yMIll`76mDddxFe)4#ePg80m9c*B>iA~z|cmO{ho))3sb!cG!m12kV?l82q&yP^^R!o7BS z$kn&4WmhPo=ZO^-cwbMMhZl4#4enV7ZI#W=NpP1sSbUEe%Mfi1P8Xr`b0c*bMbK)N zaIPEQzY5@P4-?PV^<5?IVy(|uho-haX?i=`%2VPA^02qtu5ss>qt!dC4X)MI@F8N^ z5|~YL;D~xTOJ5w4&A){OiJ~9+B@^F<@3&fVrr(kYCMUo+X$gPn2bs6JiZ>kke<)dX zuYt@LMhq^+_^#|K2V%2ocyoFl*0J?bUYAV=&3H9_^04aLlF6Y#1Q$ldH&4r5`OAVR zC`1nSX(OYqzIraTOb+shYGf%^{6@Ril?l^uuhIqmp*^|t+ zcogsmIAF^`Vo#q=+@C&yZ%6Apej@z^o6fh(A9n+_BAxdy?9tKNK1%_jLxXEI{c$F66a)w z(QVWVgA!!8U+H6fDxtf4Z@5wxcE0t9Fz%82-4f%wTd0=1NJ7swH8tG5z~^DwDuIsI z%c<)%C(uN+{VlElJ-wa#fv|9Q%ftRN+)opoDXPQ2zH+Vn$)!MrL|H^&p3Y8)-=YSRl$?sQ80_y`1z@rSl&E?5Q^+#4)7omt8ZC{lL{)VyKUQKwy)n32HwkK+yB&3m zWXm+_4I|LOCBV+_?)@2PpLCDfJ_b(a z?5ys@S*#nBqR$Lv^TiouocJl=0#jWW6VEBgmga{}P;;hv-|*o&hc32sVl|4NvLPmX zF<#-5w%ekJoivCU{=RJ@<@^o6>ZXfXo8t=2Cma1+;3p*Z9aze376x1v-`Bmi<( diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml deleted file mode 100644 index a229d8f34a366..0000000000000 --- a/localization/ekf_localizer/package.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - ekf_localizer - 0.1.0 - The ekf_localizer package - horibe - Apache 2.0 - - catkin - - geometry_msgs - roscpp - sensor_msgs - std_msgs - tf2 - tf2_ros - diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp deleted file mode 100644 index 95acfc2efeca8..0000000000000 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ /dev/null @@ -1,736 +0,0 @@ -/* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#include "ekf_localizer/ekf_localizer.h" - -// clang-format off -#define PRINT_MAT(X) std::cout << #X << ":\n" << X << std::endl << std::endl -#define DEBUG_INFO(...) { if (show_debug_info_) { ROS_INFO(__VA_ARGS__); } } -#define DEBUG_PRINT_MAT(X) { if (show_debug_info_) { std::cout << #X << ": " << X << std::endl; } } - -// clang-format on -EKFLocalizer::EKFLocalizer() : nh_(""), pnh_("~"), dim_x_(6 /* x, y, yaw, yaw_bias, vx, wz */) -{ - pnh_.param("show_debug_info", show_debug_info_, bool(false)); - pnh_.param("predict_frequency", ekf_rate_, double(50.0)); - ekf_dt_ = 1.0 / std::max(ekf_rate_, 0.1); - pnh_.param("tf_rate", tf_rate_, double(10.0)); - pnh_.param("enable_yaw_bias_estimation", enable_yaw_bias_estimation_, bool(true)); - pnh_.param("extend_state_step", extend_state_step_, int(50)); - pnh_.param("pose_frame_id", pose_frame_id_, std::string("map")); - - /* pose measurement */ - pnh_.param("pose_additional_delay", pose_additional_delay_, double(0.0)); - pnh_.param("pose_measure_uncertainty_time", pose_measure_uncertainty_time_, double(0.01)); - pnh_.param("pose_rate", pose_rate_, double(10.0)); // used for covariance calculation - pnh_.param("pose_gate_dist", pose_gate_dist_, double(10000.0)); // Mahalanobis limit - pnh_.param("pose_stddev_x", pose_stddev_x_, double(0.05)); - pnh_.param("pose_stddev_y", pose_stddev_y_, double(0.05)); - pnh_.param("pose_stddev_yaw", pose_stddev_yaw_, double(0.035)); - pnh_.param("use_pose_with_covariance", use_pose_with_covariance_, bool(false)); - - /* twist measurement */ - pnh_.param("twist_additional_delay", twist_additional_delay_, double(0.0)); - pnh_.param("twist_rate", twist_rate_, double(10.0)); // used for covariance calculation - pnh_.param("twist_gate_dist", twist_gate_dist_, double(10000.0)); // Mahalanobis limit - pnh_.param("twist_stddev_vx", twist_stddev_vx_, double(0.2)); - pnh_.param("twist_stddev_wz", twist_stddev_wz_, double(0.03)); - pnh_.param("use_twist_with_covariance", use_twist_with_covariance_, bool(false)); - - /* process noise */ - double proc_stddev_yaw_c, proc_stddev_yaw_bias_c, proc_stddev_vx_c, proc_stddev_wz_c; - pnh_.param("proc_stddev_yaw_c", proc_stddev_yaw_c, double(0.005)); - pnh_.param("proc_stddev_yaw_bias_c", proc_stddev_yaw_bias_c, double(0.001)); - pnh_.param("proc_stddev_vx_c", proc_stddev_vx_c, double(5.0)); - pnh_.param("proc_stddev_wz_c", proc_stddev_wz_c, double(1.0)); - if (!enable_yaw_bias_estimation_) { - proc_stddev_yaw_bias_c = 0.0; - } - - /* convert to continuous to discrete */ - proc_cov_vx_d_ = std::pow(proc_stddev_vx_c * ekf_dt_, 2.0); - proc_cov_wz_d_ = std::pow(proc_stddev_wz_c * ekf_dt_, 2.0); - proc_cov_yaw_d_ = std::pow(proc_stddev_yaw_c * ekf_dt_, 2.0); - proc_cov_yaw_bias_d_ = std::pow(proc_stddev_yaw_bias_c * ekf_dt_, 2.0); - - /* initialize ros system */ - - timer_control_ = nh_.createTimer(ros::Duration(ekf_dt_), &EKFLocalizer::timerCallback, this); - timer_tf_ = nh_.createTimer(ros::Duration(1.0 / tf_rate_), &EKFLocalizer::timerTFCallback, this); - pub_pose_ = nh_.advertise("ekf_pose", 1); - pub_pose_cov_ = - nh_.advertise("ekf_pose_with_covariance", 1); - pub_twist_ = nh_.advertise("ekf_twist", 1); - pub_twist_cov_ = - nh_.advertise("ekf_twist_with_covariance", 1); - pub_yaw_bias_ = pnh_.advertise("estimated_yaw_bias", 1); - pub_pose_no_yawbias_ = nh_.advertise("ekf_pose_without_yawbias", 1); - pub_pose_cov_no_yawbias_ = nh_.advertise( - "ekf_pose_with_covariance_without_yawbias", 1); - sub_initialpose_ = nh_.subscribe("initialpose", 1, &EKFLocalizer::callbackInitialPose, this); - sub_pose_with_cov_ = - nh_.subscribe("in_pose_with_covariance", 1, &EKFLocalizer::callbackPoseWithCovariance, this); - sub_pose_ = nh_.subscribe("in_pose", 1, &EKFLocalizer::callbackPose, this); - sub_twist_with_cov_ = - nh_.subscribe("in_twist_with_covariance", 1, &EKFLocalizer::callbackTwistWithCovariance, this); - sub_twist_ = nh_.subscribe("in_twist", 1, &EKFLocalizer::callbackTwist, this); - - dim_x_ex_ = dim_x_ * extend_state_step_; - - initEKF(); - - /* debug */ - pub_debug_ = pnh_.advertise("debug", 1); - pub_measured_pose_ = pnh_.advertise("debug/measured_pose", 1); -}; - -EKFLocalizer::~EKFLocalizer(){}; - -/* - * timerCallback - */ -void EKFLocalizer::timerCallback(const ros::TimerEvent & e) -{ - DEBUG_INFO("========================= timer called ========================="); - - /* predict model in EKF */ - auto start = std::chrono::system_clock::now(); - DEBUG_INFO("------------------------- start prediction -------------------------"); - predictKinematicsModel(); - double elapsed = - std::chrono::duration_cast(std::chrono::system_clock::now() - start) - .count(); - DEBUG_INFO("[EKF] predictKinematicsModel calculation time = %f [ms]", elapsed * 1.0e-6); - DEBUG_INFO("------------------------- end prediction -------------------------\n"); - - /* pose measurement update */ - if (current_pose_ptr_ != nullptr) { - DEBUG_INFO("------------------------- start Pose -------------------------"); - start = std::chrono::system_clock::now(); - measurementUpdatePose(*current_pose_ptr_); - elapsed = - std::chrono::duration_cast(std::chrono::system_clock::now() - start) - .count(); - DEBUG_INFO("[EKF] measurementUpdatePose calculation time = %f [ms]", elapsed * 1.0e-6); - DEBUG_INFO("------------------------- end Pose -------------------------\n"); - } - - /* twist measurement update */ - if (current_twist_ptr_ != nullptr) { - DEBUG_INFO("------------------------- start twist -------------------------"); - start = std::chrono::system_clock::now(); - measurementUpdateTwist(*current_twist_ptr_); - elapsed = - std::chrono::duration_cast(std::chrono::system_clock::now() - start) - .count(); - DEBUG_INFO("[EKF] measurementUpdateTwist calculation time = %f [ms]", elapsed * 1.0e-6); - DEBUG_INFO("------------------------- end twist -------------------------\n"); - } - - /* set current pose, twist */ - setCurrentResult(); - - /* publish ekf result */ - publishEstimateResult(); -} - -void EKFLocalizer::showCurrentX() -{ - if (show_debug_info_) { - Eigen::MatrixXd X(dim_x_, 1); - ekf_.getLatestX(X); - DEBUG_PRINT_MAT(X.transpose()); - } -} - -/* - * setCurrentResult - */ -void EKFLocalizer::setCurrentResult() -{ - current_ekf_pose_.header.frame_id = pose_frame_id_; - current_ekf_pose_.header.stamp = ros::Time::now(); - current_ekf_pose_.pose.position.x = ekf_.getXelement(IDX::X); - current_ekf_pose_.pose.position.y = ekf_.getXelement(IDX::Y); - - tf2::Quaternion q_tf; - double roll, pitch, yaw; - if (current_pose_ptr_ != nullptr) { - current_ekf_pose_.pose.position.z = current_pose_ptr_->pose.position.z; - tf2::fromMsg(current_pose_ptr_->pose.orientation, q_tf); /* use Pose pitch and roll */ - tf2::Matrix3x3(q_tf).getRPY(roll, pitch, yaw); - } else { - // current_ekf_pose_.pose.position.z = 0.0; - // roll = 0; - // pitch = 0; - } - yaw = ekf_.getXelement(IDX::YAW) + ekf_.getXelement(IDX::YAWB); - current_ekf_pose_.pose.orientation = createQuaternionFromRPY(roll, pitch, yaw); - - current_ekf_pose_no_yawbias_ = current_ekf_pose_; - current_ekf_pose_no_yawbias_.pose.orientation = - createQuaternionFromRPY(roll, pitch, ekf_.getXelement(IDX::YAW)); - - current_ekf_twist_.header.frame_id = "base_link"; - current_ekf_twist_.header.stamp = ros::Time::now(); - current_ekf_twist_.twist.linear.x = ekf_.getXelement(IDX::VX); - current_ekf_twist_.twist.angular.z = ekf_.getXelement(IDX::WZ); -} - -/* - * timerTFCallback - */ -void EKFLocalizer::timerTFCallback(const ros::TimerEvent & e) -{ - if (current_ekf_pose_.header.frame_id == "") return; - - geometry_msgs::TransformStamped transformStamped; - transformStamped.header.stamp = ros::Time::now(); - transformStamped.header.frame_id = current_ekf_pose_.header.frame_id; - transformStamped.child_frame_id = "base_link"; - transformStamped.transform.translation.x = current_ekf_pose_.pose.position.x; - transformStamped.transform.translation.y = current_ekf_pose_.pose.position.y; - transformStamped.transform.translation.z = current_ekf_pose_.pose.position.z; - - transformStamped.transform.rotation.x = current_ekf_pose_.pose.orientation.x; - transformStamped.transform.rotation.y = current_ekf_pose_.pose.orientation.y; - transformStamped.transform.rotation.z = current_ekf_pose_.pose.orientation.z; - transformStamped.transform.rotation.w = current_ekf_pose_.pose.orientation.w; - - tf_br_.sendTransform(transformStamped); -} - -/* - * getTransformFromTF - */ -bool EKFLocalizer::getTransformFromTF( - std::string parent_frame, std::string child_frame, geometry_msgs::TransformStamped & transform) -{ - tf2_ros::Buffer tf_buffer; - tf2_ros::TransformListener tf_listener(tf_buffer); - ros::Duration(0.1).sleep(); - if (parent_frame.front() == '/') parent_frame.erase(0, 1); - if (child_frame.front() == '/') child_frame.erase(0, 1); - - for (int i = 0; i < 50; ++i) { - try { - transform = tf_buffer.lookupTransform(parent_frame, child_frame, ros::Time(0)); - return true; - } catch (tf2::TransformException & ex) { - ROS_WARN("%s", ex.what()); - ros::Duration(0.1).sleep(); - } - } - return false; -} - -/* - * callbackInitialPose - */ -void EKFLocalizer::callbackInitialPose(const geometry_msgs::PoseWithCovarianceStamped & initialpose) -{ - geometry_msgs::TransformStamped transform; - if (!getTransformFromTF(pose_frame_id_, initialpose.header.frame_id, transform)) { - ROS_ERROR( - "[EKF] TF transform failed. parent = %s, child = %s", pose_frame_id_.c_str(), - initialpose.header.frame_id.c_str()); - }; - - Eigen::MatrixXd X(dim_x_, 1); - Eigen::MatrixXd P = Eigen::MatrixXd::Zero(dim_x_, dim_x_); - - // TODO need mutex - - X(IDX::X) = initialpose.pose.pose.position.x + transform.transform.translation.x; - X(IDX::Y) = initialpose.pose.pose.position.y + transform.transform.translation.y; - current_ekf_pose_.pose.position.z = - initialpose.pose.pose.position.z + transform.transform.translation.z; - X(IDX::YAW) = - tf2::getYaw(initialpose.pose.pose.orientation) + tf2::getYaw(transform.transform.rotation); - X(IDX::YAWB) = 0.0; - X(IDX::VX) = 0.0; - X(IDX::WZ) = 0.0; - - P(IDX::X, IDX::X) = initialpose.pose.covariance[0]; - P(IDX::Y, IDX::Y) = initialpose.pose.covariance[6 + 1]; - P(IDX::YAW, IDX::YAW) = initialpose.pose.covariance[6 * 5 + 5]; - P(IDX::YAWB, IDX::YAWB) = 0.0001; - P(IDX::VX, IDX::VX) = 0.01; - P(IDX::WZ, IDX::WZ) = 0.01; - - ekf_.init(X, P, extend_state_step_); - - current_pose_ptr_ = nullptr; -}; - -/* - * callbackPose - */ -void EKFLocalizer::callbackPose(const geometry_msgs::PoseStamped::ConstPtr & msg) -{ - if (!use_pose_with_covariance_) { - current_pose_ptr_ = std::make_shared(*msg); - } -}; - -/* - * callbackPoseWithCovariance - */ -void EKFLocalizer::callbackPoseWithCovariance( - const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & msg) -{ - if (use_pose_with_covariance_) { - geometry_msgs::PoseStamped pose; - pose.header = msg->header; - pose.pose = msg->pose.pose; - current_pose_ptr_ = std::make_shared(pose); - current_pose_covariance_ = msg->pose.covariance; - } -}; - -/* - * callbackTwist - */ -void EKFLocalizer::callbackTwist(const geometry_msgs::TwistStamped::ConstPtr & msg) -{ - if (!use_twist_with_covariance_) { - current_twist_ptr_ = std::make_shared(*msg); - } -}; - -/* - * callbackTwistWithCovariance - */ -void EKFLocalizer::callbackTwistWithCovariance( - const geometry_msgs::TwistWithCovarianceStamped::ConstPtr & msg) -{ - if (use_twist_with_covariance_) { - geometry_msgs::TwistStamped twist; - twist.header = msg->header; - twist.twist = msg->twist.twist; - current_twist_ptr_ = std::make_shared(twist); - current_twist_covariance_ = msg->twist.covariance; - } -}; - -/* - * initEKF - */ -void EKFLocalizer::initEKF() -{ - Eigen::MatrixXd X = Eigen::MatrixXd::Zero(dim_x_, 1); - Eigen::MatrixXd P = Eigen::MatrixXd::Identity(dim_x_, dim_x_) * 1.0E15; // for x & y - P(IDX::YAW, IDX::YAW) = 50.0; // for yaw - P(IDX::YAWB, IDX::YAWB) = proc_cov_yaw_bias_d_; // for yaw bias - P(IDX::VX, IDX::VX) = 1000.0; // for vx - P(IDX::WZ, IDX::WZ) = 50.0; // for wz - - ekf_.init(X, P, extend_state_step_); -} - -/* - * predictKinematicsModel - */ -void EKFLocalizer::predictKinematicsModel() -{ - /* == Nonlinear model == - * - * x_{k+1} = x_k + vx_k * cos(yaw_k + b_k) * dt - * y_{k+1} = y_k + vx_k * sin(yaw_k + b_k) * dt - * yaw_{k+1} = yaw_k + (wz_k) * dt - * b_{k+1} = b_k - * vx_{k+1} = vz_k - * wz_{k+1} = wz_k - * - * (b_k : yaw_bias_k) - */ - - /* == Linearized model == - * - * A = [ 1, 0, -vx*sin(yaw+b)*dt, -vx*sin(yaw+b)*dt, cos(yaw+b)*dt, 0] - * [ 0, 1, vx*cos(yaw+b)*dt, vx*cos(yaw+b)*dt, sin(yaw+b)*dt, 0] - * [ 0, 0, 1, 0, 0, dt] - * [ 0, 0, 0, 1, 0, 0] - * [ 0, 0, 0, 0, 1, 0] - * [ 0, 0, 0, 0, 0, 1] - */ - - Eigen::MatrixXd X_curr(dim_x_, 1); // curent state - Eigen::MatrixXd X_next(dim_x_, 1); // predicted state - ekf_.getLatestX(X_curr); - DEBUG_PRINT_MAT(X_curr.transpose()); - - Eigen::MatrixXd P_curr; - ekf_.getLatestP(P_curr); - - const int d_dim_x = dim_x_ex_ - dim_x_; - const double yaw = X_curr(IDX::YAW); - const double yaw_bias = X_curr(IDX::YAWB); - const double vx = X_curr(IDX::VX); - const double wz = X_curr(IDX::WZ); - const double dt = ekf_dt_; - - /* Update for latest state */ - X_next(IDX::X) = X_curr(IDX::X) + vx * cos(yaw + yaw_bias) * dt; // dx = v * cos(yaw) - X_next(IDX::Y) = X_curr(IDX::Y) + vx * sin(yaw + yaw_bias) * dt; // dy = v * sin(yaw) - X_next(IDX::YAW) = X_curr(IDX::YAW) + (wz)*dt; // dyaw = omega + omega_bias - X_next(IDX::YAWB) = yaw_bias; - X_next(IDX::VX) = vx; - X_next(IDX::WZ) = wz; - - X_next(IDX::YAW) = std::atan2(std::sin(X_next(IDX::YAW)), std::cos(X_next(IDX::YAW))); - - /* Set A matrix for latest state */ - Eigen::MatrixXd A = Eigen::MatrixXd::Identity(dim_x_, dim_x_); - A(IDX::X, IDX::YAW) = -vx * sin(yaw + yaw_bias) * dt; - A(IDX::X, IDX::YAWB) = -vx * sin(yaw + yaw_bias) * dt; - A(IDX::X, IDX::VX) = cos(yaw + yaw_bias) * dt; - A(IDX::Y, IDX::YAW) = vx * cos(yaw + yaw_bias) * dt; - A(IDX::Y, IDX::YAWB) = vx * cos(yaw + yaw_bias) * dt; - A(IDX::Y, IDX::VX) = sin(yaw + yaw_bias) * dt; - A(IDX::YAW, IDX::WZ) = dt; - - Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(dim_x_, dim_x_); - - Q(IDX::X, IDX::X) = 0.0; - Q(IDX::Y, IDX::Y) = 0.0; - Q(IDX::YAW, IDX::YAW) = proc_cov_yaw_d_; // for yaw - Q(IDX::YAWB, IDX::YAWB) = proc_cov_yaw_bias_d_; // for yaw bias - Q(IDX::VX, IDX::VX) = proc_cov_vx_d_; // for vx - Q(IDX::WZ, IDX::WZ) = proc_cov_wz_d_; // for wz - - ekf_.predictWithDelay(X_next, A, Q); - - // debug - Eigen::MatrixXd X_result(dim_x_, 1); - ekf_.getLatestX(X_result); - DEBUG_PRINT_MAT(X_result.transpose()); - DEBUG_PRINT_MAT((X_result - X_curr).transpose()); -} - -/* - * measurementUpdatePose - */ -void EKFLocalizer::measurementUpdatePose(const geometry_msgs::PoseStamped & pose) -{ - if (pose.header.frame_id != pose_frame_id_) { - ROS_WARN_DELAYED_THROTTLE( - 2, "pose frame_id is %s, but pose_frame is set as %s. They must be same.", - pose.header.frame_id.c_str(), pose_frame_id_.c_str()); - } - Eigen::MatrixXd X_curr(dim_x_, 1); // curent state - ekf_.getLatestX(X_curr); - DEBUG_PRINT_MAT(X_curr.transpose()); - - constexpr int dim_y = 3; // pos_x, pos_y, yaw, depending on Pose output - const ros::Time t_curr = ros::Time::now(); - - /* Calculate delay step */ - double delay_time = (t_curr - pose.header.stamp).toSec() + pose_additional_delay_; - if (delay_time < 0.0) { - delay_time = 0.0; - ROS_WARN_DELAYED_THROTTLE( - 1.0, "Pose time stamp is inappropriate, set delay to 0[s]. delay = %f", delay_time); - } - int delay_step = std::roundf(delay_time / ekf_dt_); - if (delay_step > extend_state_step_ - 1) { - ROS_WARN_DELAYED_THROTTLE( - 1.0, - "Pose delay exceeds the compensation limit, ignored. delay: %f[s], limit = " - "extend_state_step * ekf_dt : %f [s]", - delay_time, extend_state_step_ * ekf_dt_); - return; - } - DEBUG_INFO("delay_time: %f [s]", delay_time); - - /* Set yaw */ - const double yaw_curr = ekf_.getXelement((unsigned int)(delay_step * dim_x_ + IDX::YAW)); - double yaw = tf2::getYaw(pose.pose.orientation); - const double ekf_yaw = ekf_.getXelement(delay_step * dim_x_ + IDX::YAW); - const double yaw_error = normalizeYaw(yaw - ekf_yaw); // normalize the error not to exceed 2 pi - yaw = yaw_error + ekf_yaw; - - /* Set measurement matrix */ - Eigen::MatrixXd y(dim_y, 1); - y << pose.pose.position.x, pose.pose.position.y, yaw; - - if (isnan(y.array()).any() || isinf(y.array()).any()) { - ROS_WARN( - "[EKF] pose measurement matrix includes NaN of Inf. ignore update. check pose message."); - return; - } - - /* Gate */ - Eigen::MatrixXd y_ekf(dim_y, 1); - y_ekf << ekf_.getXelement(delay_step * dim_x_ + IDX::X), - ekf_.getXelement(delay_step * dim_x_ + IDX::Y), ekf_yaw; - Eigen::MatrixXd P_curr, P_y; - ekf_.getLatestP(P_curr); - P_y = P_curr.block(0, 0, dim_y, dim_y); - if (!mahalanobisGate(pose_gate_dist_, y_ekf, y, P_y)) { - ROS_WARN_DELAYED_THROTTLE( - 2.0, - "[EKF] Pose measurement update, mahalanobis distance is over limit. ignore " - "measurement data."); - return; - } - - DEBUG_PRINT_MAT(y.transpose()); - DEBUG_PRINT_MAT(y_ekf.transpose()); - DEBUG_PRINT_MAT((y - y_ekf).transpose()); - - /* Set measurement matrix */ - Eigen::MatrixXd C = Eigen::MatrixXd::Zero(dim_y, dim_x_); - C(0, IDX::X) = 1.0; // for pos x - C(1, IDX::Y) = 1.0; // for pos y - C(2, IDX::YAW) = 1.0; // for yaw - - /* Set measurement noise covariancs */ - Eigen::MatrixXd R = Eigen::MatrixXd::Zero(dim_y, dim_y); - if (use_pose_with_covariance_) { - R(0, 0) = current_pose_covariance_.at(0); // x - x - R(0, 1) = current_pose_covariance_.at(1); // x - y - R(0, 2) = current_pose_covariance_.at(5); // x - yaw - R(1, 0) = current_pose_covariance_.at(6); // y - x - R(1, 1) = current_pose_covariance_.at(7); // y - y - R(1, 2) = current_pose_covariance_.at(11); // y - yaw - R(2, 0) = current_pose_covariance_.at(30); // yaw - x - R(2, 1) = current_pose_covariance_.at(31); // yaw - y - R(2, 2) = current_pose_covariance_.at(35); // yaw - yaw - } else { - const double ekf_yaw = ekf_.getXelement(delay_step * dim_x_ + IDX::YAW); - const double vx = ekf_.getXelement(delay_step * dim_x_ + IDX::VX); - const double wz = ekf_.getXelement(delay_step * dim_x_ + IDX::WZ); - const double cov_tu_pos_x = std::pow(pose_measure_uncertainty_time_ * vx * cos(ekf_yaw), 2.0); - const double cov_tu_pos_y = std::pow(pose_measure_uncertainty_time_ * vx * sin(ekf_yaw), 2.0); - const double cov_tu_yaw = std::pow(pose_measure_uncertainty_time_ * wz, 2.0); - R(0, 0) = (pose_stddev_x_ * pose_stddev_x_) + cov_tu_pos_x; // pos_x - R(1, 1) = (pose_stddev_y_ * pose_stddev_y_) + cov_tu_pos_y; // pos_y - R(2, 2) = (pose_stddev_yaw_ * pose_stddev_yaw_) + cov_tu_yaw; // yaw - } - - /* In order to avoid a large change at the time of updating, measuremeent update is performed by dividing at every - * step. */ - R *= (ekf_rate_ / pose_rate_); - - ekf_.updateWithDelay(y, C, R, delay_step); - - // debug - Eigen::MatrixXd X_result(dim_x_, 1); - ekf_.getLatestX(X_result); - DEBUG_PRINT_MAT(X_result.transpose()); - DEBUG_PRINT_MAT((X_result - X_curr).transpose()); -} - -/* - * measurementUpdateTwist - */ -void EKFLocalizer::measurementUpdateTwist(const geometry_msgs::TwistStamped & twist) -{ - if (twist.header.frame_id != "base_link") { - ROS_WARN_DELAYED_THROTTLE(2.0, "twist frame_id must be base_link"); - } - - Eigen::MatrixXd X_curr(dim_x_, 1); // curent state - ekf_.getLatestX(X_curr); - DEBUG_PRINT_MAT(X_curr.transpose()); - - constexpr int dim_y = 2; // vx, wz - const ros::Time t_curr = ros::Time::now(); - - /* Calculate delay step */ - double delay_time = (t_curr - twist.header.stamp).toSec() + twist_additional_delay_; - if (delay_time < 0.0) { - ROS_WARN_DELAYED_THROTTLE( - 1.0, "Twist time stamp is inappropriate (delay = %f [s]), set delay to 0[s].", delay_time); - delay_time = 0.0; - } - int delay_step = std::roundf(delay_time / ekf_dt_); - if (delay_step > extend_state_step_ - 1) { - ROS_WARN_DELAYED_THROTTLE( - 1.0, - "Twist delay exceeds the compensation limit, ignored. delay: %f[s], limit = " - "extend_state_step * ekf_dt : %f [s]", - delay_time, extend_state_step_ * ekf_dt_); - return; - } - DEBUG_INFO("delay_time: %f [s]", delay_time); - - /* Set measurement matrix */ - Eigen::MatrixXd y(dim_y, 1); - y << twist.twist.linear.x, twist.twist.angular.z; - - if (isnan(y.array()).any() || isinf(y.array()).any()) { - ROS_WARN( - "[EKF] twist measurement matrix includes NaN of Inf. ignore update. check twist message."); - return; - } - - /* Gate */ - Eigen::MatrixXd y_ekf(dim_y, 1); - y_ekf << ekf_.getXelement(delay_step * dim_x_ + IDX::VX), - ekf_.getXelement(delay_step * dim_x_ + IDX::WZ); - Eigen::MatrixXd P_curr, P_y; - ekf_.getLatestP(P_curr); - P_y = P_curr.block(4, 4, dim_y, dim_y); - if (!mahalanobisGate(twist_gate_dist_, y_ekf, y, P_y)) { - ROS_WARN_DELAYED_THROTTLE( - 2.0, - "[EKF] Twist measurement update, mahalanobis distance is over limit. ignore " - "measurement data."); - return; - } - - DEBUG_PRINT_MAT(y.transpose()); - DEBUG_PRINT_MAT(y_ekf.transpose()); - DEBUG_PRINT_MAT((y - y_ekf).transpose()); - - /* Set measurement matrix */ - Eigen::MatrixXd C = Eigen::MatrixXd::Zero(dim_y, dim_x_); - C(0, IDX::VX) = 1.0; // for vx - C(1, IDX::WZ) = 1.0; // for wz - - /* Set measurement noise covariancs */ - Eigen::MatrixXd R = Eigen::MatrixXd::Zero(dim_y, dim_y); - if (use_twist_with_covariance_) { - R(0, 0) = current_twist_covariance_.at(0); // vx - vx - R(0, 1) = current_twist_covariance_.at(5); // vx - wz - R(1, 0) = current_twist_covariance_.at(30); // wz - vx - R(1, 1) = current_twist_covariance_.at(35); // wz - wz - } else { - R(0, 0) = twist_stddev_vx_ * twist_stddev_vx_; // for vx - R(1, 1) = twist_stddev_wz_ * twist_stddev_wz_; // for wz - } - - /* In order to avoid a large change by update, measurement update is performed by dividing at every step. */ - R *= (ekf_rate_ / twist_rate_); - - ekf_.updateWithDelay(y, C, R, delay_step); - - // debug - Eigen::MatrixXd X_result(dim_x_, 1); - ekf_.getLatestX(X_result); - DEBUG_PRINT_MAT(X_result.transpose()); - DEBUG_PRINT_MAT((X_result - X_curr).transpose()); -}; - -/* - * mahalanobisGate - */ -bool EKFLocalizer::mahalanobisGate( - const double & dist_max, const Eigen::MatrixXd & x, const Eigen::MatrixXd & obj_x, - const Eigen::MatrixXd & cov) const -{ - Eigen::MatrixXd mahalanobis_squared = (x - obj_x).transpose() * cov.inverse() * (x - obj_x); - DEBUG_INFO( - "measurement update: mahalanobis = %f, gate limit = %f", std::sqrt(mahalanobis_squared(0)), - dist_max); - if (mahalanobis_squared(0) > dist_max * dist_max) { - return false; - } - - return true; -} - -/* - * createQuaternionFromRPY - */ -geometry_msgs::Quaternion EKFLocalizer::createQuaternionFromRPY(double r, double p, double y) const -{ - tf2::Quaternion q; - q.setRPY(r, p, y); - return tf2::toMsg(q); -} - -/* - * publishEstimateResult - */ -void EKFLocalizer::publishEstimateResult() -{ - ros::Time current_time = ros::Time::now(); - Eigen::MatrixXd X(dim_x_, 1); - Eigen::MatrixXd P(dim_x_, dim_x_); - ekf_.getLatestX(X); - ekf_.getLatestP(P); - - /* publish latest pose */ - pub_pose_.publish(current_ekf_pose_); - pub_pose_no_yawbias_.publish(current_ekf_pose_no_yawbias_); - - /* publish latest pose with covariance */ - geometry_msgs::PoseWithCovarianceStamped pose_cov; - pose_cov.header.stamp = current_time; - pose_cov.header.frame_id = current_ekf_pose_.header.frame_id; - pose_cov.pose.pose = current_ekf_pose_.pose; - pose_cov.pose.covariance[0] = P(IDX::X, IDX::X); - pose_cov.pose.covariance[1] = P(IDX::X, IDX::Y); - pose_cov.pose.covariance[5] = P(IDX::X, IDX::YAW); - pose_cov.pose.covariance[6] = P(IDX::Y, IDX::X); - pose_cov.pose.covariance[7] = P(IDX::Y, IDX::Y); - pose_cov.pose.covariance[11] = P(IDX::Y, IDX::YAW); - pose_cov.pose.covariance[30] = P(IDX::YAW, IDX::X); - pose_cov.pose.covariance[31] = P(IDX::YAW, IDX::Y); - pose_cov.pose.covariance[35] = P(IDX::YAW, IDX::YAW); - pub_pose_cov_.publish(pose_cov); - - geometry_msgs::PoseWithCovarianceStamped pose_cov_no_yawbias = pose_cov; - pose_cov_no_yawbias.pose.pose = current_ekf_pose_no_yawbias_.pose; - pub_pose_cov_no_yawbias_.publish(pose_cov_no_yawbias); - - /* publish latest twist */ - pub_twist_.publish(current_ekf_twist_); - - /* publish latest twist with covariance */ - geometry_msgs::TwistWithCovarianceStamped twist_cov; - twist_cov.header.stamp = current_time; - twist_cov.header.frame_id = current_ekf_twist_.header.frame_id; - twist_cov.twist.twist = current_ekf_twist_.twist; - twist_cov.twist.covariance[0] = P(IDX::VX, IDX::VX); - twist_cov.twist.covariance[5] = P(IDX::VX, IDX::WZ); - twist_cov.twist.covariance[30] = P(IDX::WZ, IDX::VX); - twist_cov.twist.covariance[35] = P(IDX::WZ, IDX::WZ); - pub_twist_cov_.publish(twist_cov); - - /* publish yaw bias */ - std_msgs::Float64 yawb; - yawb.data = X(IDX::YAWB); - pub_yaw_bias_.publish(yawb); - - /* debug measured pose */ - if (current_pose_ptr_ != nullptr) { - geometry_msgs::PoseStamped p; - p = *current_pose_ptr_; - p.header.stamp = current_time; - pub_measured_pose_.publish(p); - } - - /* debug publish */ - double RAD2DEG = 180.0 / 3.141592; - double pose_yaw = 0.0; - if (current_pose_ptr_ != nullptr) - pose_yaw = tf2::getYaw(current_pose_ptr_->pose.orientation) * RAD2DEG; - - std_msgs::Float64MultiArray msg; - msg.data.push_back(X(IDX::YAW) * RAD2DEG); // [0] ekf yaw angle - msg.data.push_back(pose_yaw); // [1] measurement yaw angle - msg.data.push_back(X(IDX::YAWB) * RAD2DEG); // [2] yaw bias - pub_debug_.publish(msg); -} - -double EKFLocalizer::normalizeYaw(const double & yaw) const -{ - return std::atan2(std::sin(yaw), std::cos(yaw)); -} diff --git a/localization/ekf_localizer/src/ekf_localizer_node.cpp b/localization/ekf_localizer/src/ekf_localizer_node.cpp deleted file mode 100644 index 45d2f56bab576..0000000000000 --- a/localization/ekf_localizer/src/ekf_localizer_node.cpp +++ /dev/null @@ -1,27 +0,0 @@ -/* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#include "ekf_localizer/ekf_localizer.h" - -int main(int argc, char ** argv) -{ - ros::init(argc, argv, "ekf_localizer"); - EKFLocalizer obj; - - ros::spin(); - - return 0; -}; diff --git a/localization/ekf_localizer/src/kalman_filter/kalman_filter.cpp b/localization/ekf_localizer/src/kalman_filter/kalman_filter.cpp deleted file mode 100644 index 8610c3986f834..0000000000000 --- a/localization/ekf_localizer/src/kalman_filter/kalman_filter.cpp +++ /dev/null @@ -1,126 +0,0 @@ -/* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#include "kalman_filter/kalman_filter.hpp" - -KalmanFilter::KalmanFilter() {} -KalmanFilter::KalmanFilter( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P) -{ - init(x, A, B, C, Q, R, P); -} -KalmanFilter::~KalmanFilter() {} -bool KalmanFilter::init( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P) -{ - if ( - x.cols() == 0 || x.rows() == 0 || A.cols() == 0 || A.rows() == 0 || B.cols() == 0 || - B.rows() == 0 || C.cols() == 0 || C.rows() == 0 || Q.cols() == 0 || Q.rows() == 0 || - R.cols() == 0 || R.rows() == 0 || P.cols() == 0 || P.rows() == 0) { - return false; - } - x_ = x; - A_ = A; - B_ = B; - C_ = C; - Q_ = Q; - R_ = R; - P_ = P; - return true; -} -bool KalmanFilter::init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0) -{ - if (x.cols() == 0 || x.rows() == 0 || P0.cols() == 0 || P0.rows() == 0) { - return false; - } - x_ = x; - P_ = P0; - return true; -} - -void KalmanFilter::setA(const Eigen::MatrixXd & A) { A_ = A; } -void KalmanFilter::setB(const Eigen::MatrixXd & B) { B_ = B; } -void KalmanFilter::setC(const Eigen::MatrixXd & C) { C_ = C; } -void KalmanFilter::setQ(const Eigen::MatrixXd & Q) { Q_ = Q; } -void KalmanFilter::setR(const Eigen::MatrixXd & R) { R_ = R; } -void KalmanFilter::getX(Eigen::MatrixXd & x) { x = x_; }; -void KalmanFilter::getP(Eigen::MatrixXd & P) { P = P_; }; -double KalmanFilter::getXelement(unsigned int i) { return x_(i); }; - -bool KalmanFilter::predict( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q) -{ - if ( - x_.rows() != x_next.rows() || A.cols() != P_.rows() || Q.cols() != Q.rows() || - A.rows() != Q.cols()) { - return false; - } - x_ = x_next; - P_ = A * P_ * A.transpose() + Q; - return true; -} -bool KalmanFilter::predict(const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A) -{ - return predict(x_next, A, Q_); -} - -bool KalmanFilter::predict( - const Eigen::MatrixXd & u, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & Q) -{ - if (A.cols() != x_.rows() || B.cols() != u.rows()) { - return false; - } - const Eigen::MatrixXd x_next = A * x_ + B * u; - return predict(x_next, A, Q); -} -bool KalmanFilter::predict(const Eigen::MatrixXd & u) { return predict(u, A_, B_, Q_); } - -bool KalmanFilter::update( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & y_pred, const Eigen::MatrixXd & C, - const Eigen::MatrixXd & R) -{ - if ( - P_.cols() != C.cols() || R.rows() != R.cols() || R.rows() != C.rows() || - y.rows() != y_pred.rows() || y.rows() != C.rows()) { - return false; - } - const Eigen::MatrixXd PCT = P_ * C.transpose(); - const Eigen::MatrixXd K = PCT * ((R + C * PCT).inverse()); - - if (isnan(K.array()).any() || isinf(K.array()).any()) { - return false; - }; - - x_ = x_ + K * (y - y_pred); - P_ = P_ - K * (C * P_); - return true; -} - -bool KalmanFilter::update( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R) -{ - if (C.cols() != x_.rows()) { - return false; - } - const Eigen::MatrixXd y_pred = C * x_; - return update(y, y_pred, C, R); -} -bool KalmanFilter::update(const Eigen::MatrixXd & y) { return update(y, C_, R_); } diff --git a/localization/ekf_localizer/src/kalman_filter/time_delay_kalman_filter.cpp b/localization/ekf_localizer/src/kalman_filter/time_delay_kalman_filter.cpp deleted file mode 100644 index 5b309f9c43f65..0000000000000 --- a/localization/ekf_localizer/src/kalman_filter/time_delay_kalman_filter.cpp +++ /dev/null @@ -1,95 +0,0 @@ -/* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#include "kalman_filter/time_delay_kalman_filter.hpp" - -TimeDelayKalmanFilter::TimeDelayKalmanFilter() {} - -void TimeDelayKalmanFilter::init( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0, const int max_delay_step) -{ - max_delay_step_ = max_delay_step; - dim_x_ = x.rows(); - dim_x_ex_ = dim_x_ * max_delay_step; - - x_ = Eigen::MatrixXd::Zero(dim_x_ex_, 1); - P_ = Eigen::MatrixXd::Zero(dim_x_ex_, dim_x_ex_); - - for (int i = 0; i < max_delay_step_; ++i) { - x_.block(i * dim_x_, 0, dim_x_, 1) = x; - P_.block(i * dim_x_, i * dim_x_, dim_x_, dim_x_) = P0; - } -}; - -void TimeDelayKalmanFilter::getLatestX(Eigen::MatrixXd & x) { x = x_.block(0, 0, dim_x_, 1); }; -void TimeDelayKalmanFilter::getLatestP(Eigen::MatrixXd & P) { P = P_.block(0, 0, dim_x_, dim_x_); }; - -bool TimeDelayKalmanFilter::predictWithDelay( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q) -{ - /* - * time delay model: - * - * [A 0 0] [P11 P12 P13] [Q 0 0] - * A = [I 0 0], P = [P21 P22 P23], Q = [0 0 0] - * [0 I 0] [P31 P32 P33] [0 0 0] - * - * covariance calculation in prediction : P = A * P * A' + Q - * - * [A*P11*A'*+Q A*P11 A*P12] - * P = [ P11*A' P11 P12] - * [ P21*A' P21 P22] - */ - - const int d_dim_x = dim_x_ex_ - dim_x_; - - /* slide states in the time direction */ - Eigen::MatrixXd x_tmp = Eigen::MatrixXd::Zero(dim_x_ex_, 1); - x_tmp.block(0, 0, dim_x_, 1) = x_next; - x_tmp.block(dim_x_, 0, d_dim_x, 1) = x_.block(0, 0, d_dim_x, 1); - x_ = x_tmp; - - /* update P with delayed measurement A matrix structure */ - Eigen::MatrixXd P_tmp = Eigen::MatrixXd::Zero(dim_x_ex_, dim_x_ex_); - P_tmp.block(0, 0, dim_x_, dim_x_) = A * P_.block(0, 0, dim_x_, dim_x_) * A.transpose() + Q; - P_tmp.block(0, dim_x_, dim_x_, d_dim_x) = A * P_.block(0, 0, dim_x_, d_dim_x); - P_tmp.block(dim_x_, 0, d_dim_x, dim_x_) = P_.block(0, 0, d_dim_x, dim_x_) * A.transpose(); - P_tmp.block(dim_x_, dim_x_, d_dim_x, d_dim_x) = P_.block(0, 0, d_dim_x, d_dim_x); - P_ = P_tmp; - - return true; -}; - -bool TimeDelayKalmanFilter::updateWithDelay( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R, - const int delay_step) -{ - if (delay_step >= max_delay_step_) { - std::cerr << "delay step is larger than max_delay_step. ignore update." << std::endl; - return false; - } - - const int dim_y = y.rows(); - - /* set measurement matrix */ - Eigen::MatrixXd C_ex = Eigen::MatrixXd::Zero(dim_y, dim_x_ex_); - C_ex.block(0, dim_x_ * delay_step, dim_y, dim_x_) = C; - - /* update */ - if (!update(y, C_ex, R)) return false; - - return true; -}; \ No newline at end of file diff --git a/localization/ekf_localizer/test/src/test_ekf_localizer.cpp b/localization/ekf_localizer/test/src/test_ekf_localizer.cpp deleted file mode 100644 index 3288a5c85e612..0000000000000 --- a/localization/ekf_localizer/test/src/test_ekf_localizer.cpp +++ /dev/null @@ -1,289 +0,0 @@ -/* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#include - -#include -#include -#include -#include -#include - -#include "ekf_localizer/ekf_localizer.h" - -class EKFLocalizerTestSuite : public ::testing::Test -{ -public: - EKFLocalizerTestSuite() : nh_(""), pnh_("~") - { - sub_twist = nh_.subscribe("/ekf_twist", 1, &EKFLocalizerTestSuite::callbackTwist, this); - sub_pose = nh_.subscribe("/ekf_pose", 1, &EKFLocalizerTestSuite::callbackPose, this); - tiemr_ = nh_.createTimer(ros::Duration(0.1), &EKFLocalizerTestSuite::timerCallback, this); - } - ~EKFLocalizerTestSuite() {} - - ros::NodeHandle nh_, pnh_; - - std::string frame_id_a_ = "world"; - std::string frame_id_b_ = "base_link"; - - ros::Subscriber sub_twist; - ros::Subscriber sub_pose; - - ros::Timer tiemr_; - - std::shared_ptr current_pose_ptr_; - std::shared_ptr current_twist_ptr_; - - void timerCallback(const ros::TimerEvent & e) - { - /* !!! this should be defined before sendTransform() !!! */ - static tf2_ros::TransformBroadcaster br; - geometry_msgs::TransformStamped sended; - - ros::Time current_time = ros::Time::now(); - - sended.header.stamp = current_time; - sended.header.frame_id = frame_id_a_; - sended.child_frame_id = frame_id_b_; - sended.transform.translation.x = -7.11; - sended.transform.translation.y = 0.0; - sended.transform.translation.z = 0.0; - tf2::Quaternion q; - q.setRPY(0, 0, 0.5); - sended.transform.rotation.x = q.x(); - sended.transform.rotation.y = q.y(); - sended.transform.rotation.z = q.z(); - sended.transform.rotation.w = q.w(); - - br.sendTransform(sended); - }; - - void callbackPose(const geometry_msgs::PoseStamped::ConstPtr & pose) - { - current_pose_ptr_ = std::make_shared(*pose); - } - - void callbackTwist(const geometry_msgs::TwistStamped::ConstPtr & twist) - { - current_twist_ptr_ = std::make_shared(*twist); - } - - void resetCurrentPoseAndTwist() - { - current_pose_ptr_ = nullptr; - current_twist_ptr_ = nullptr; - } -}; - -TEST_F(EKFLocalizerTestSuite, measurementUpdatePose) -{ - EKFLocalizer ekf_; - - ros::Publisher pub_pose = nh_.advertise("/in_pose", 1); - geometry_msgs::PoseStamped in_pose; - in_pose.header.frame_id = "world"; - in_pose.pose.position.x = 1.0; - in_pose.pose.position.y = 2.0; - in_pose.pose.position.z = 3.0; - in_pose.pose.orientation.x = 0.0; - in_pose.pose.orientation.y = 0.0; - in_pose.pose.orientation.z = 0.0; - in_pose.pose.orientation.w = 1.0; - - /* test for valid value */ - const double pos_x = 12.3; - in_pose.pose.position.x = pos_x; // for vaild value - - for (int i = 0; i < 20; ++i) { - in_pose.header.stamp = ros::Time::now(); - pub_pose.publish(in_pose); - ros::spinOnce(); - ros::Duration(0.1).sleep(); - } - - ASSERT_FALSE(current_pose_ptr_ == nullptr); - ASSERT_FALSE(current_twist_ptr_ == nullptr); - - double ekf_x = current_pose_ptr_->pose.position.x; - bool is_succeeded = !(std::isnan(ekf_x) || std::isinf(ekf_x)); - ASSERT_EQ(true, is_succeeded) << "ekf result includes invalid value."; - ASSERT_TRUE(std::fabs(ekf_x - pos_x) < 0.1) - << "ekf pos x: " << ekf_x << " should be close to " << pos_x; - - /* test for invalid value */ - in_pose.pose.position.x = NAN; // check for invalid values - for (int i = 0; i < 10; ++i) { - in_pose.header.stamp = ros::Time::now(); - pub_pose.publish(in_pose); - ros::spinOnce(); - ros::Duration(0.1).sleep(); - } - is_succeeded = !(std::isnan(ekf_x) || std::isinf(ekf_x)); - ASSERT_EQ(true, is_succeeded) << "ekf result includes invalid value."; - - resetCurrentPoseAndTwist(); -} - -TEST_F(EKFLocalizerTestSuite, measurementUpdateTwist) -{ - EKFLocalizer ekf_; - - ros::Publisher pub_twist = nh_.advertise("/in_twist", 1); - geometry_msgs::TwistStamped in_twist; - in_twist.header.frame_id = "base_link"; - - /* test for valid value */ - const double vx = 12.3; - in_twist.twist.linear.x = vx; // for vaild value - for (int i = 0; i < 20; ++i) { - in_twist.header.stamp = ros::Time::now(); - pub_twist.publish(in_twist); - ros::spinOnce(); - ros::Duration(0.1).sleep(); - } - - ASSERT_FALSE(current_pose_ptr_ == nullptr); - ASSERT_FALSE(current_twist_ptr_ == nullptr); - - double ekf_vx = current_twist_ptr_->twist.linear.x; - bool is_succeeded = !(std::isnan(ekf_vx) || std::isinf(ekf_vx)); - ASSERT_EQ(true, is_succeeded) << "ekf result includes invalid value."; - ASSERT_TRUE(std::fabs(ekf_vx - vx) < 0.1) - << "ekf vel x: " << ekf_vx << ", should be close to " << vx; - - /* test for invalid value */ - in_twist.twist.linear.x = NAN; // check for invalid values - for (int i = 0; i < 10; ++i) { - in_twist.header.stamp = ros::Time::now(); - pub_twist.publish(in_twist); - ros::spinOnce(); - ros::Duration(0.1).sleep(); - } - - ekf_vx = current_twist_ptr_->twist.linear.x; - is_succeeded = !(std::isnan(ekf_vx) || std::isinf(ekf_vx)); - ASSERT_EQ(true, is_succeeded) << "ekf result includes invalid value."; - - resetCurrentPoseAndTwist(); -} - -TEST_F(EKFLocalizerTestSuite, measurementUpdatePoseWithCovariance) -{ - pnh_.setParam("use_pose_with_covariance", true); - ros::Duration(0.2).sleep(); - EKFLocalizer ekf_; - - ros::Publisher pub_pose = - nh_.advertise("/in_pose_with_covariance", 1); - geometry_msgs::PoseWithCovarianceStamped in_pose; - in_pose.header.frame_id = "world"; - in_pose.pose.pose.position.x = 1.0; - in_pose.pose.pose.position.y = 2.0; - in_pose.pose.pose.position.z = 3.0; - in_pose.pose.pose.orientation.x = 0.0; - in_pose.pose.pose.orientation.y = 0.0; - in_pose.pose.pose.orientation.z = 0.0; - in_pose.pose.pose.orientation.w = 1.0; - for (int i = 0; i < 36; ++i) { - in_pose.pose.covariance[i] = 0.1; - } - - /* test for valid value */ - const double pos_x = 99.3; - in_pose.pose.pose.position.x = pos_x; // for vaild value - - for (int i = 0; i < 20; ++i) { - in_pose.header.stamp = ros::Time::now(); - pub_pose.publish(in_pose); - ros::spinOnce(); - ros::Duration(0.1).sleep(); - } - - ASSERT_FALSE(current_pose_ptr_ == nullptr); - ASSERT_FALSE(current_twist_ptr_ == nullptr); - - double ekf_x = current_pose_ptr_->pose.position.x; - bool is_succeeded = !(std::isnan(ekf_x) || std::isinf(ekf_x)); - ASSERT_EQ(true, is_succeeded) << "ekf result includes invalid value."; - ASSERT_TRUE(std::fabs(ekf_x - pos_x) < 0.1) - << "ekf pos x: " << ekf_x << " should be close to " << pos_x; - - /* test for invalid value */ - in_pose.pose.pose.position.x = NAN; // check for invalid values - for (int i = 0; i < 10; ++i) { - in_pose.header.stamp = ros::Time::now(); - pub_pose.publish(in_pose); - ros::spinOnce(); - ros::Duration(0.1).sleep(); - } - is_succeeded = !(std::isnan(ekf_x) || std::isinf(ekf_x)); - ASSERT_EQ(true, is_succeeded) << "ekf result includes invalid value."; - - resetCurrentPoseAndTwist(); -} - -TEST_F(EKFLocalizerTestSuite, measurementUpdateTwistWithCovariance) -{ - EKFLocalizer ekf_; - - ros::Publisher pub_twist = - nh_.advertise("/in_twist_with_covariance", 1); - geometry_msgs::TwistWithCovarianceStamped in_twist; - in_twist.header.frame_id = "base_link"; - - /* test for valid value */ - const double vx = 12.3; - in_twist.twist.twist.linear.x = vx; // for vaild value - for (int i = 0; i < 36; ++i) { - in_twist.twist.covariance[i] = 0.1; - } - for (int i = 0; i < 10; ++i) { - in_twist.header.stamp = ros::Time::now(); - pub_twist.publish(in_twist); - ros::spinOnce(); - ros::Duration(0.1).sleep(); - } - - ASSERT_FALSE(current_pose_ptr_ == nullptr); - ASSERT_FALSE(current_twist_ptr_ == nullptr); - - double ekf_vx = current_twist_ptr_->twist.linear.x; - bool is_succeeded = !(std::isnan(ekf_vx) || std::isinf(ekf_vx)); - ASSERT_EQ(true, is_succeeded) << "ekf result includes invalid value."; - ASSERT_TRUE((ekf_vx - vx) < 0.1) << "vel x should be close to " << vx; - - /* test for invalid value */ - in_twist.twist.twist.linear.x = NAN; // check for invalid values - for (int i = 0; i < 10; ++i) { - in_twist.header.stamp = ros::Time::now(); - pub_twist.publish(in_twist); - ros::spinOnce(); - ros::Duration(0.1).sleep(); - } - - ekf_vx = current_twist_ptr_->twist.linear.x; - is_succeeded = !(std::isnan(ekf_vx) || std::isinf(ekf_vx)); - ASSERT_EQ(true, is_succeeded) << "ekf result includes invalid value."; -} - -int main(int argc, char ** argv) -{ - testing::InitGoogleTest(&argc, argv); - ros::init(argc, argv, "EKFLocalizerTestSuite"); - - return RUN_ALL_TESTS(); -} \ No newline at end of file diff --git a/localization/ekf_localizer/test/test_ekf_localizer.test b/localization/ekf_localizer/test/test_ekf_localizer.test deleted file mode 100644 index 1878685aff756..0000000000000 --- a/localization/ekf_localizer/test/test_ekf_localizer.test +++ /dev/null @@ -1,5 +0,0 @@ - - - - - \ No newline at end of file