From b78d68510ada1ae33edd0cbb53eca164e90e0d77 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Thu, 26 Oct 2023 12:30:27 +0200 Subject: [PATCH 01/62] tested multivargauss --- CMakeLists.txt | 1 + include/probability/binomial.hpp | 67 ++++++++++++++++ include/probability/chi_squared.hpp | 39 ++++++++++ include/probability/gaussian_mixture.hpp | 97 ++++++++++++++++++++++++ include/probability/multi_var_gauss.hpp | 78 +++++++++++++++++++ include/probability/poisson.hpp | 62 +++++++++++++++ test/probability_test.cpp | 39 ++++++++++ 7 files changed, 383 insertions(+) create mode 100644 include/probability/binomial.hpp create mode 100644 include/probability/chi_squared.hpp create mode 100644 include/probability/gaussian_mixture.hpp create mode 100644 include/probability/multi_var_gauss.hpp create mode 100644 include/probability/poisson.hpp create mode 100644 test/probability_test.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 25922272..ffaa3e61 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -68,6 +68,7 @@ if(BUILD_TESTING) test/ekf_test.cpp test/ukf_test.cpp test/erk_test.cpp + test/probability_test.cpp ) target_include_directories(${PROJECT_NAME}_test PUBLIC $ diff --git a/include/probability/binomial.hpp b/include/probability/binomial.hpp new file mode 100644 index 00000000..a7cbbe84 --- /dev/null +++ b/include/probability/binomial.hpp @@ -0,0 +1,67 @@ +/** + * @file binomial.hpp + * @author Eirik Kolås + * @brief + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include + +namespace vortex { +namespace probability { + +class Binomial { +public: + Binomial(int n, double p) : n_(n), p_(p) {} + + /** Calculate the probability of x given the Binomial distribution + * @param x + * @return double + */ + double pr(int x) const { + return std::pow(p_, x) * std::pow(1 - p_, n_ - x) * factorial(n_) / (factorial(x) * factorial(n_ - x)); + } + + /** Calculate the mean of the Binomial distribution + * @return double mean + */ + double mean() const { return n_ * p_; } + + /** Calculate the variance of the Binomial distribution + * @return double variance + */ + double cov() const { return n_ * p_ * (1 - p_); } + + /** Parameter n of the Binomial distribution + * @return int n + */ + int n() const { return n_; } + + /** Parameter p of the Binomial distribution + * @return double p + */ + double p() const { return p_; } + +private: + int n_; + double p_; + + /** Calculate the factorial of x + * @param x + * @return double factorial + */ + double factorial(int x) const { + double factorial = 1; + for (int i = 1; i <= x; i++) { + factorial *= i; + } + return factorial; + } +}; + +} // namespace vortex +} // namespace probability diff --git a/include/probability/chi_squared.hpp b/include/probability/chi_squared.hpp new file mode 100644 index 00000000..468ddec6 --- /dev/null +++ b/include/probability/chi_squared.hpp @@ -0,0 +1,39 @@ +#pragma once +#include + +namespace vortex { +namespace probability { + + class ChiSquared { + public: + ChiSquared(int n) : n_(n) {} + + /** Calculate the probability density of x given the Chi-Squared distribution + * @param x + * @return double + */ + double pdf(double x) const { + return std::pow(x, n_ / 2 - 1) * std::exp(-x / 2) / (std::pow(2, n_ / 2) * std::tgamma(n_ / 2)); + } + + /** Calculate the mean of the Chi-Squared distribution + * @return double mean + */ + double mean() const { return n_; } + + /** Calculate the variance of the Chi-Squared distribution + * @return double variance + */ + double cov() const { return 2 * n_; } + + /** Parameter n of the Chi-Squared distribution + * @return int n + */ + int n() const { return n_; } + + private: + int n_; + }; + +} // namespace vortex +} // namespace probability diff --git a/include/probability/gaussian_mixture.hpp b/include/probability/gaussian_mixture.hpp new file mode 100644 index 00000000..d6d7652d --- /dev/null +++ b/include/probability/gaussian_mixture.hpp @@ -0,0 +1,97 @@ +/** + * @file multi_var_gauss.hpp + * @author Eirik Kolås + * @brief A class for representing a multivariate Gaussian mixture distribution. + * Based on "Fundamentals of SensorFusion" by Edmund Brekke + * @version 0.1 + * @date 2023-10-25 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include +#include +#include "multi_var_gauss.hpp" + +namespace vortex { +namespace probability { + +/** + * A class for representing a multivariate Gaussian mixture distribution + * @tparam n_dim dimentions of the Gaussian + */ +template +class GaussianMixture { +public: + using Vector = Eigen::Vector; + using Matrix = Eigen::Matrix; + + GaussianMixture(std::vector weights, std::vector> gaussians) + : weights_(weights), gaussians_(gaussians) + { + assert(weights_.size() == gaussians_.size()); + } + + /** Calculate the probability density function of x given the Gaussian mixture + * @param x + * @return double + */ + double pdf(const Vector& x) const { + double pdf = 0; + for (int i = 0; i < gaussians_.size(); i++) { + pdf += weights_[i] * gaussians_[i].pdf(x); + } + return pdf; + } + + /** Find the mean of the Gaussian mixture + * @return Vector + */ + Vector mean() const { + Vector mean = Vector::Zero(); + for (int i = 0; i < gaussians_.size(); i++) { + mean += weights_[i] * gaussians_[i].mean(); + } + return mean; + } + + /** Find the covariance of the Gaussian mixture + * @return Matrix + */ + Matrix cov() const { + // Spread of innovations + Matrix P_bar = Matrix::Zero(); + for (int i = 0; i < gaussians_.size(); i++) { + P_bar += weights_[i] * gaussians_[i].mean() * gaussians_[i].mean().transpose(); + } + P_bar -= mean() * mean().transpose(); + + // Spread of Gaussians + Matrix P = Matrix::Zero(); + for (int i = 0; i < gaussians_.size(); i++) { + P += weights_[i] * gaussians_[i].cov(); + } + return P + P_bar; + } + + /** Reduce the Gaussian mixture to a single Gaussian + * @return MultiVarGauss + */ + MultiVarGauss reduce() const { + return MultivarGauss(mean(), cov()); + } + + /** dimentions of the Gaussian mixture + * @return int + */ + int n_dims() const { return (n_dim); } + +private: + std::vector weights_; + std::vector> gaussians_; + + +}; // class GaussianMixture +} // namespace probability +} // namespace vortex \ No newline at end of file diff --git a/include/probability/multi_var_gauss.hpp b/include/probability/multi_var_gauss.hpp new file mode 100644 index 00000000..2b8182b8 --- /dev/null +++ b/include/probability/multi_var_gauss.hpp @@ -0,0 +1,78 @@ +#pragma once +#include + +namespace vortex { +namespace probability { + +/** + * A class for representing a multivariate Gaussian distribution + * @tparam n_dim dimentions of the Gaussian + */ +template +class MultiVarGauss { +public: + using Vector = Eigen::Vector; + using Matrix = Eigen::Matrix; + + MultiVarGauss(const Vector& mean, const Matrix& cov) + : mean_(mean), cov_(cov) + { + // Check that the covariance matrix is positive definite and symmetric + if (cov_ != cov_.transpose()) { + throw std::invalid_argument("Covariance matrix is not symmetric"); + } + if (cov_.llt().info() != Eigen::Success) { + throw std::invalid_argument("Covariance matrix is not positive definite"); + } + } + + /** Calculate the probability density function of x given the Gaussian + * @param x + * @return double + */ + double pdf(const Vector& x) const { + const auto diff = x - mean_; + const auto cov_inv = cov_.llt().solve(Matrix::Identity()); + const auto exponent = -0.5 * diff.transpose() * cov_inv * diff; + return std::exp(exponent) / std::sqrt(std::pow(2 * M_PI, n_dim) * cov_.determinant()); + } + + /** Calculate the log likelihood of x given the Gaussian. + * Assumes that the covariance matrix is positive definite and symmetric + * @param x + * @return double + */ + double logpdf(const Vector& x) const { + const auto diff = x - mean_; + const auto cov_inv = cov_.llt().solve(Matrix::Identity()); + const auto exponent = -0.5 * diff.transpose() * cov_inv * diff; + return exponent - 0.5 * std::log(std::pow(2 * M_PI, n_dim) * cov_.determinant()); + } + + + Vector mean() const { return mean_; } + Matrix cov() const { return cov_; } + + /** Calculate the Mahalanobis distance of x given the Gaussian + * @param x + * @return double + */ + double mahalanobis_distance(const Vector& x) const { + const auto diff = x - mean_; + const auto cov_inv = cov_.llt().solve(Matrix::Identity()); + return std::sqrt(diff.transpose() * cov_inv * diff); + } + + + /** dimentions of the Gaussian + * @return int + */ + int n_dims() const { return n_dim; } + + private: + Vector mean_; + Matrix cov_; +}; + +} // namespace probability +} // namespace vortex diff --git a/include/probability/poisson.hpp b/include/probability/poisson.hpp new file mode 100644 index 00000000..ea1ec24f --- /dev/null +++ b/include/probability/poisson.hpp @@ -0,0 +1,62 @@ +/** + * @file poisson.hpp + * @author Eirik Kolås + * @brief A class for representing a Poisson distribution. Used for modeling clutter + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include + +namespace vortex { +namespace probability { + +class Poisson { +public: + Poisson(double lambda) : lambda_(lambda) {} + + /** Calculate the probability of x given the Poisson distribution + * @param x + * @return double + */ + double pr(int x) const { + return std::pow(lambda_, x) * std::exp(-lambda_) / factorial(x); + } + + /** Calculate the mean of the Poisson distribution + * @return double mean + */ + double mean() const { return lambda_; } + + /** Calculate the variance of the Poisson distribution + * @return double variance + */ + double cov() const { return lambda_; } + + /** Parameter lambda of the Poisson distribution + * @return double lambda + */ + double lambda() const { return lambda_; } + + +private: + double lambda_; + + /** Calculate the factorial of x + * @param x + * @return double factorial + */ + double factorial(int x) const { + double factorial = 1; + for (int i = 1; i <= x; i++) { + factorial *= i; + } + return factorial; + } +}; + +} // namespace probability +} // namespace vortex diff --git a/test/probability_test.cpp b/test/probability_test.cpp new file mode 100644 index 00000000..89c95381 --- /dev/null +++ b/test/probability_test.cpp @@ -0,0 +1,39 @@ +#include + +#include +#include +#include +#include + + +TEST(multiVarGauss, initGaussian) +{ + vortex::probability::MultiVarGauss<2> gaussian(Eigen::Vector2d::Zero(), Eigen::Matrix2d::Identity()); + + EXPECT_EQ(gaussian.mean(), (Eigen::Vector2d{0, 0})); + EXPECT_EQ(gaussian.cov(), (Eigen::Matrix2d{{1, 0}, {0, 1}})); +} + +TEST(multiVarGauss, pdf) +{ + vortex::probability::MultiVarGauss<2> gaussian(Eigen::Vector2d::Zero(), Eigen::Matrix2d::Identity()); + + EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{0, 0}), 1/(2*M_PI), 1e-15); + EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{1, 0}), 1/(2*std::sqrt(M_E)*M_PI), 1e-15); + EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{0, 1}), 1/(2*std::sqrt(M_E)*M_PI), 1e-15); + EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{1, 1}), 1/(2*M_E*M_PI), 1e-15); + + gaussian = vortex::probability::MultiVarGauss<2>(Eigen::Vector2d{0, 0}, Eigen::Matrix2d{{2, 1}, {1, 2}}); + + EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{0, 0}), 1/(2*std::sqrt(3)*M_PI), 1e-15); + EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{1, 0}), 1/(2*std::sqrt(3)*std::exp(1.0/3)*M_PI), 1e-15); + EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{0, 1}), 1/(2*std::sqrt(3)*std::exp(1.0/3)*M_PI), 1e-15); + EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{1, 1}), 1/(2*std::sqrt(3)*std::exp(1.0/3)*M_PI), 1e-15); +} + +TEST(multiVarGauss, invalidCovariance) +{ + EXPECT_THROW(vortex::probability::MultiVarGauss<2>(Eigen::Vector2d::Zero(), Eigen::Matrix2d::Zero()), std::invalid_argument); + EXPECT_THROW(vortex::probability::MultiVarGauss<2>(Eigen::Vector2d::Zero(), Eigen::Matrix2d{{1, 0}, {0, 0}}), std::invalid_argument); + EXPECT_THROW(vortex::probability::MultiVarGauss<2>(Eigen::Vector2d::Zero(), Eigen::Matrix2d{{-1, 0}, {0, -1}}), std::invalid_argument); +} From b6604f128b5b2b988009b5a19c00ea86382b4c77 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Thu, 26 Oct 2023 14:53:16 +0200 Subject: [PATCH 02/62] Made EKF and models --- include/filters/EKF.hpp | 121 ++++---- include/integration_methods/ERK_methods.hpp | 6 +- include/models/EKF_models.hpp | 328 -------------------- include/models/Model_base.hpp | 102 ------ include/models/dynamic_model.hpp | 104 +++++++ include/models/sensor_model.hpp | 61 ++++ include/models/temp_gyro_model.hpp | 41 --- include/probability/binomial.hpp | 2 +- include/probability/chi_squared.hpp | 2 +- include/probability/gaussian_mixture.hpp | 2 +- include/probability/multi_var_gauss.hpp | 15 +- include/probability/poisson.hpp | 2 +- test/probability_test.cpp | 12 +- 13 files changed, 251 insertions(+), 547 deletions(-) delete mode 100644 include/models/EKF_models.hpp delete mode 100644 include/models/Model_base.hpp create mode 100644 include/models/dynamic_model.hpp create mode 100644 include/models/sensor_model.hpp delete mode 100644 include/models/temp_gyro_model.hpp diff --git a/include/filters/EKF.hpp b/include/filters/EKF.hpp index 98639517..0f73b46b 100644 --- a/include/filters/EKF.hpp +++ b/include/filters/EKF.hpp @@ -1,63 +1,72 @@ +/** + * @file EKF.hpp + * @author Eirik Kolås + * @brief + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ + #pragma once -#include -#include +#include +#include -namespace Filters { -using namespace Models; +namespace vortex { +namespace filters { -template class EKF : public Kalman_filter_base { +/** @brief Extended Kalman Filter + * + * @tparam DynamicModel Dynamic model type. Has to have function for Jacobian of state transition. + * @tparam SensorModel Sensor model type. Has to have function for Jacobian of measurement. (get_H) + */ +template +class EKF { public: - // These type definitions are needed because of the stupid two-phase lookup for dependent names in templates in C++ - using Base = Kalman_filter_base; - using Base::_n_x; using Base::_n_y; using Base::_n_u; using Base::_n_v; using Base::_n_w; // can be comma separated in C++17 - DEFINE_MODEL_TYPES(_n_x, _n_y, _n_u, _n_v, _n_w) - - EKF(std::shared_ptr ekf_model, State &x0, Mat_xx &P0) : Base(x0, P0), model{ekf_model} - { - } - ~EKF() {} - - State iterate(Time Ts, const Measurement &y, const Input &u = Input::Zero()) override final - { - // Calculate Jacobians F_x, F_v - Mat_xx F_x = model->F_x(Ts, this->_x, u); - Mat_xv F_v = model->F_v(Ts, this->_x, u); - Mat_vv Q = model->Q(Ts, this->_x); - // Predicted State Estimate x_k- - State x_pred = model->f(Ts, this->_x, u); - // Predicted State Covariance P_xx- - Mat_xx P_xx_pred = F_x * this->_P_xx * F_x.transpose() + F_v * Q * F_v.transpose(); - // Predicted Output y_pred - Measurement y_pred = model->h(Ts, x_pred); - - // Calculate Jacobians H_x, H_w - Mat_yx H_x = model->H_x(Ts, x_pred, u); - Mat_yw H_w = model->H_w(Ts, x_pred, u); - Mat_ww R = model->R(Ts, x_pred); - // Output Covariance P_yy - Mat_yy P_yy = H_x * P_xx_pred * H_x.transpose() + H_w * R * H_w.transpose(); - // Cross Covariance P_xy - Mat_xy P_xy = P_xx_pred * H_x.transpose(); - - // Kalman gain K - Mat_yy P_yy_inv = P_yy.llt().solve(Mat_yy::Identity()); // Use Cholesky decomposition for inverting P_yy - Mat_xy K = P_xy * P_yy_inv; - - // Corrected State Estimate x_next - State x_next = x_pred + K * (y - y_pred); - // Normalize quaternions if applicable - x_next = model->post_state_update(x_next); - // Corrected State Covariance P_xx_next - Mat_xx P_xx_next = (Mat_xx::Identity() - K * H_x) * P_xx_pred; - - // Update local state - this->_x = x_next; - this->_P_xx = P_xx_next; - - return x_next; - } + EKF(DynamicModel dynamic_model, SensorModel sensor_model) + : dynamic_model_(dynamic_model), sensor_model_(sensor_model) {} + + /** Perform one EKF prediction step + * @param x_est_prev Previous state estimate + * @param dt Time step + */ + std::tuple predict(std::chrono::duration dt, prob::MultiVarGauss x_est_prev) { + prob::MultiVarGauss x_est_pred = dynamic_model_.pred_from_est(x_est_prev, dt); + prob::MultiVarGauss z_est_pred = sensor_model_.pred_from_est(x_est_pred); + return {x_est_pred, z_est_pred}; + } + + /** Perform one EKF update step + * @param x_est_pred Predicted state + * @param z_est_pred Predicted measurement + * @param z_meas Measurement + * @return MultivarGauss Updated state + */ + prob::MultiVarGauss update(prob::MultiVarGauss x_est_pred, prob::MultiVarGauss z_est_pred, Eigen::Vector z_meas) { + auto H_mat = sensor_model_.H(x_est_pred); + auto R_mat = sensor_model_.R(x_est_pred); + auto P_mat = x_est_pred.cov(); + auto S_mat = z_est_pred.cov(); + auto S_mat_inv = z_est_pred.cov_inv(); + auto I = Eigen::Matrix::Identity(); + + Eigen::Matrix kalman_gain = P_mat * H_mat.transpose() * S_mat_inv; + Eigen::Vector innovation = z_meas - z_est_pred.mean(); + + Eigen::Matrix state_upd_mean = x_est_pred.mean() + kalman_gain * innovation; + // Use the Joseph form of the covariance update to ensure positive definiteness + Eigen::Matrix state_upd_cov = (I - kalman_gain * H_mat) * P_mat * (I - kalman_gain * H_mat).transpose() + kalman_gain * R_mat * kalman_gain.transpose(); + + return prob::MultiVarGauss(state_upd_mean, state_upd_cov); + } private: - std::shared_ptr model; + const Dynamic_model dynamic_model_; + const Sensor_model sensor_model_; + static constexpr n_dim_x_ = DynamicModel::n_dim; + static constexpr n_dim_z_ = SensorModel::n_dim; }; -} // namespace Filters \ No newline at end of file + +} // namespace filters +} // namespace vortex \ No newline at end of file diff --git a/include/integration_methods/ERK_methods.hpp b/include/integration_methods/ERK_methods.hpp index ecbc00ae..55918fb7 100644 --- a/include/integration_methods/ERK_methods.hpp +++ b/include/integration_methods/ERK_methods.hpp @@ -12,7 +12,8 @@ using namespace Models; // Base class RK_method for RK4 and forward_euler to derive from -template class None { +template +class None { public: /** * @brief Does not integrate, just returns f(t_k, x_k). Use if f is a discrete model @@ -23,7 +24,8 @@ template class None { }; template using None_M = None; -template class RK4 { +template +class RK4 { public: DEFINE_MODEL_TYPES(n_x, 0, 0, 0, 0) static State integrate(State_dot f, Timestep dt, Time t_k, const State &x_k) diff --git a/include/models/EKF_models.hpp b/include/models/EKF_models.hpp deleted file mode 100644 index 0560c353..00000000 --- a/include/models/EKF_models.hpp +++ /dev/null @@ -1,328 +0,0 @@ -#pragma once -#include -#include - -namespace Models { - -template -class EKF_model_base : public Model_base { -public: - // These type definitions are needed because of the stupid two-phase lookup for dependent names in templates in C++ - using Base = Model_base; - using Base::_n_x; using Base::_n_y; using Base::_n_u; using Base::_n_v; using Base::_n_w; - DEFINE_MODEL_TYPES(n_x, n_y, n_u, n_v, n_w) - - /** - * @brief Parent class for functions that need to be provided for the EKF filter. - * All children of this class will work in the EKF as well as in the UKK. - * For the latter case it is recommended to explicitly specify disturbance and noise as additive. (i.e. f(x)+v and h(x)+w) - */ - EKF_model_base() : Base() {} - virtual ~EKF_model_base() {} - - /** - * @brief Jacobian of f: - * Calculate the transition function jacobian for time \p t at \p x - * @param x State - * @param t Time-step - * @return Jacobian A - */ - virtual Mat_xx F_x(Time t, const State &x, const Input &u = Input::Zero(), const Disturbance &v = Disturbance::Zero()) const = 0; - /** - * @brief Jacobian of f with respect to v: - * Calculate the transition function jacobian for time \p t at \p x - * This has to be defined if the disturbance on the model is not additive. - * @param t Time - * @param x State - * @param u Input - * @param v Disturbance - * @return Jacobian G - */ - virtual Mat_xv F_v(Time t, const State &x, const Input &u = Input::Zero(), const Disturbance &v = Disturbance::Zero()) const - { - (void)t; - (void)x; - (void)u; - (void)v; - return Mat_xv::Identity(); - } - /** - * @brief Jacobian of h: - * Calculate the measurement function jacobian for time \p t at \p x - * @param t Time-step - * @param x State - * @return Jacobian C - */ - virtual Mat_yx H_x(Time t, const State &x, const Input &u = Input::Zero(), const Noise &w = Noise::Zero()) const = 0; - - /** - * @brief Jacobian of h with respect to w: - * Calculate the measurement function jacobian for time \p t at \p x - * This has to be defined if the noise on the measurement is not additive. - * @param t Time - * @param x State - * @param u Input - * @param w Noise - * @return Jacobian H - */ - virtual Mat_yw H_w(Time t, const State &x, const Input &u = Input::Zero(), const Noise &w = Noise::Zero()) const - { - (void)t; - (void)x; - (void)u; - (void)w; - return Mat_yw::Identity(); - } -}; - - - -template -class LTI_model : public EKF_model_base { -public: - // These type definitions are needed because of the stupid two-phase lookup for dependent names in templates in C++ - using Base = EKF_model_base; - using Base::_n_x; using Base::_n_y; using Base::_n_u; using Base::_n_v; using Base::_n_w; - DEFINE_MODEL_TYPES(n_x, n_y, n_u, n_v, n_w) - - /** - * @brief Construct a lti model object - * - * @param A System matrix - * @param B Input matrix - * @param C Measurement matrix - * @param D Feedthrough matrix - * @param Q Disturbance covariance matrix - * @param R Measurement covariance matrix - * @param G Disturbance input matrix - * @param H Noise input matrix - */ - LTI_model(Mat_xx A, Mat_xu B, Mat_yx C, Mat_yu D, Mat_vv Q, Mat_ww R, Mat_xv G, Mat_yw H) - : Base(), _A{A}, _B{B}, _C{C}, _D{D}, _Q{Q}, _R{R}, _G{G}, _H{H} - { - } - /** - * @brief Construct a lti model object with no feedthrough and no noise input - * - * @param A System matrix - * @param B Input matrix - * @param C Measurement matrix - * @param Q Disturbance covariance matrix - * @param R Measurement covariance matrix - */ - LTI_model(Mat_xx A, Mat_xu B, Mat_yx C, Mat_vv Q, Mat_ww R) : LTI_model(A, B, C, Mat_yu::Zero(), Q, R, Mat_xv::Identity(), Mat_yw::Identity()) {} - - ~LTI_model() {} - - /** - * @brief Prediction equation f(t,x,u,v) = x_dot. (Use intergator::None for discrete time) - * @param t Simulation time - * @param x State - * @param u Input - * @param v Disturbance - * @return The derivative x_dot = f(t,x,u,v) - */ - State f(Time t, const State &x, const Input &u = Input::Zero(), const Disturbance &v = Disturbance::Zero()) const override final - { - (void)t; // unused - return _A * x + _B * u + _G * v; - } - /** - * @brief Measurement equation h: - * Calculate the zero noise prediction at time \p t from \p x. - * @param t Simulation time - * @param x State - * @return The prediction y = h(t,x,u,w) - */ - Measurement h(Time t, const State &x, const Input &u = Input::Zero(), const Noise &w = Noise::Zero()) const override final - { - (void)t; // unused - return _C * x + _D * u + _H * w; - } - /** - * @brief Returns A: the jacobian of f with respect to x - * - * @param t Time - * @param x State - * @param u Input - * @param v Disturbance - * @return A - */ - Mat_xx F_x(Time t, const State &x, const Input &u, const Disturbance &v = Disturbance::Zero()) const override final - { - (void)t; // unused - (void)x; // unused - (void)u; // unused - (void)v; // unused - return _A; - } - - /** - * @brief Returns G: the jacobian of f with respect to v - * @param t Time - * @param x State - * @param u Input - * @param v Disturbance - * @return G - */ - Mat_xv F_v(Time t, const State &x, const Input &u, const Disturbance &v = Disturbance::Zero()) const override final - { - (void)t; // unused - (void)x; // unused - (void)u; // unused - (void)v; // unused - return _G; - } - /** - * @brief Returns C: the jacobian of h with respect to x - * - * @param t Time - * @param x State - * @param u Input - * @param w Noise - * @return Mat_yx - */ - Mat_yx H_x(Time t, const State &x, const Input &u = Input::Zero(), const Noise &w = Noise::Zero()) const override final - { - (void)t; - (void)x; - (void)u; - (void)w; - return _C; - } - /** - * @brief Returns H: the jacobian of h with respect to w - * - * @param t Time - * @param x State - * @param u Input - * @param w Noise - * @return Mat_yw - */ - Mat_yw H_w(Time t, const State &x, const Input &u = Input::Zero(), const Noise &w = Noise::Zero()) const override final - { - (void)x; - (void)u; - (void)t; - (void)w; - return _H; - } - /** - * @brief Covariance matrix of model disturbance: - * Calculate the transition covariance \p Q for time \p t - * @param t Simulation time - * @param x State - * @return System noise covariance matrix Q - */ - const Mat_vv &Q(Time t, const State &x) const override final - { - (void)t; - (void)x; - return _Q; - } - /** - * @brief Covariance matrix of measurement noise: - * Calculate the transition covariance \p Q for time \p t - * @param t Simulation time - * @param x State - * @return Measuerement noise covariance matrix R - */ - const Mat_ww &R(Time t, const State &x) const override final - { - (void)t; - (void)x; - return _R; - } - - Mat_xx _A; - Mat_xu _B; - Mat_yx _C; - Mat_yu _D; - Mat_vv _Q; - Mat_yy _R; - Mat_xv _G; - Mat_yw _H; -}; - -using Landmark_base = EKF_model_base, 7, 7, 0, 6, 6>; -class Landmark_model : public Landmark_base { -public: - // These type definitions are needed because of the stupid two-phase lookup for dependent names in templates in C++ - using Base = Landmark_base; - using Base::_n_x; using Base::_n_y; using Base::_n_u; using Base::_n_v; using Base::_n_w; - DEFINE_MODEL_TYPES(7, 7, 0, 6, 6) - - Landmark_model() : Base() {} - ~Landmark_model() {} - - /** - * @brief Prediction equation f(t,x,u,v) = x_dot - * - * @param t Simulation time - * @param x State [x, y, z, q_w, q_x, q_y, q_z] - * @param u Input (no input) - * @param v Disturbance [x, y, z, r_1, r_2, r_3] - * @return State - */ - State f(Time t, const State &x, const Input &u = Input::Zero(), const Disturbance &v = Disturbance::Zero()) const override final - { - (void)t; // unused - (void)u; // unused - - // Derivative of position - Eigen::Vector3d p_dot{v.head(3)}; - // Derivative of orientation - Eigen::Quaterniond q{x(3), x(4), x(5), x(6)}; - Eigen::Quaterniond q_dot = q * Eigen::Quaterniond(0, v(3), v(4), v(5)); - q_dot = q_dot.coeffs() * 0.5; - // Combine - State x_dot; - x_dot << p_dot, q_dot.coeffs(); - return x_dot; - } - - /** - * @brief Measurement equation h(t,x,u,w) = y - * - * @param t Simulation time - * @param x State [x, y, z, q_w, q_x, q_y, q_z] - * @param u Input (no input) - * @param w Noise [x, y, z, r_1, r_2, r_3] - * @return Measurement [x, y, z, q_w, q_x, q_y, q_z] - */ - Measurement h(Time t, const State &x, const Input &u = Input::Zero(), const Noise &w = Noise::Zero()) const override final - { - (void)t; - (void)u; - - Eigen::Vector3d p_meas{x.head(3)+w.head(3)}; - Eigen::Quaterniond q{x(3), x(4), x(5), x(6)}; - // Convert noise rotation vector to quaternion - double alpha = w.tail(3).norm(); - Eigen::Quaterniond q_noise{cos(alpha/2), sin(alpha/2)*w(3), sin(alpha/2)*w(4), sin(alpha/2)*w(5)}; - Eigen::Quaterniond q_meas = q * q_noise; - - Measurement y; - y << p_meas, q_meas.coeffs(); - return y; - } - Mat_xx F_x(Time t, const State &x, const Input &u, const Disturbance &v = Disturbance::Zero()) const override final - { - (void)t; - (void)x; - (void)u; - (void)v; - return Mat_xx::Identity(); - } - Mat_xv F_v(Time t, const State &x, const Input &u, const Disturbance &v = Disturbance::Zero()) const override final - { - (void)t; - (void)x; - (void)u; - (void)v; - return Mat_xv::Identity(); - } - -}; - -} // namespace Models \ No newline at end of file diff --git a/include/models/Model_base.hpp b/include/models/Model_base.hpp deleted file mode 100644 index 78430d55..00000000 --- a/include/models/Model_base.hpp +++ /dev/null @@ -1,102 +0,0 @@ -#pragma once -#include -#include -#include -#include - -#include -using std::placeholders::_1; -using std::placeholders::_2; -namespace Models { - -template -class Model_base { -public: - // Make static constexpr constants so that the model itself may be used to infer the sizes instead of individual parameters - static constexpr int _n_x = n_x, _n_y = n_y, _n_u = n_u, _n_v = n_v, _n_w = n_w; - - DEFINE_MODEL_TYPES(n_x, n_y, n_u, n_v, n_w) - /** - * @brief Parent class for modelling dynamics - */ - Model_base(Mat_vv Q = Mat_vv::Identity(), Mat_ww R = Mat_ww::Identity()) : _Q{Q}, _R{R} {} - - /** - * @brief Prediction equation f(t,x,u,v) = x_dot. (Use Intergator::None for discrete time) - * @param t Simulation time - * @param x State - * @param u Input - * @param v Disturbance - * @return The derivative x_dot = f(t,x,u,v) - */ - virtual State f(Time t, const State &x, const Input &u = Input::Zero(), const Disturbance &v = Disturbance::Zero()) const = 0; - - /** - * @brief Integrate the model from time \p t0 to \p t0 + \p dt - * @param dt Timestep - * @param t0 Start time - * @param x0 Initial state - * @param u Input - * @param v Disturbance - * @return The next state x_(k+1) = F(x_k,...) - */ - virtual State next_state(Timestep dt, Time t0, const State &x0, const Input &u = Input::Zero(), const Disturbance &v = Disturbance::Zero()) const - { - // Cast f to a lambda function to keep u and v constant - State_dot F = [this, &u, &v](Time t, const State &x) { return this->f(t, x, u, v); }; - return integrator::integrate(F, dt, t0, x0); - } - /** - * @brief Measurement equation h: - * Calculate the zero noise prediction at time \p t from \p x. - * @param t Simulation time - * @param x State - * @return The prediction y = h(t,x,u,w) - */ - virtual Measurement h(Time t, const State &x, const Input &u = Input::Zero(), const Noise &w = Noise::Zero()) const = 0; - - /** - * @brief Covariance matrix of model disturbance: - * Calculate the transition covariance \p Q for time \p t - * @param t Simulation time - * @param x State - * @return System noise covariance matrix Q - */ - virtual const Mat_vv &Q(Time t, const State &x) const - { - (void)t; - (void)x; - return _Q; - } - - /** - * @brief Covariance matrix of measurement noise: - * Calculate the transition covariance \p Q for time \p t - * @param t Simulation time - * @param x State - * @return Measuerement noise covariance matrix R - */ - virtual const Mat_ww &R(Time t, const State &x) const - { - (void)t; - (void)x; - return _R; - } - - /** - * @brief State update function: - * Use this for post-processing of the state after the correction step. - * This is needed for example in the case of quaternions, in order to normalize the state. - * @param x State - * @return The next state x_(k+1) = F(x_k,...) - */ - virtual const State post_state_update(const State &x) const - { - return x; - } - - Mat_vv _Q; - Mat_ww _R; -}; - -} // namespace Models \ No newline at end of file diff --git a/include/models/dynamic_model.hpp b/include/models/dynamic_model.hpp new file mode 100644 index 00000000..d8e6223a --- /dev/null +++ b/include/models/dynamic_model.hpp @@ -0,0 +1,104 @@ +/** + * @file dynamic_model.hpp + * @author Eirik Kolås + * @brief Dynamic model interface. Based on "Fundamentals of Sensor Fusion" by Edmund Brekke + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ + +#include +#include + +namespace vortex { +namespace filters { + +template +class DynamicModel { + using State = Eigen::Matrix; + using Mat_xx = Eigen::Matrix; +public: + + virtual ~DynamicModel() = default; + + /** Continuos time dynamics + * @param x State + * @return State_dot + */ + virtual State f_c(const State& x) const = 0; + + /** Jacobian of continuous time dynamics + * @param x State + * @return State_jac + */ + virtual Mat_xx A_c(const State& x) const = 0; + + /** Continuous time process noise + * @param x State + * @return Matrix Process noise covariance + */ + virtual Mat_xx Q_c(const State& x) const = 0; + + /** Discrete time dynamics + * @param x State + * @param dt Time step + * @return State + */ + virtual State f_d(const State& x, double dt) + { + return F_d(x, dt) * x; + } + + /** Jacobian of discrete time dynamics + * @param x State + * @param dt Time step + * @return State_jac + */ + virtual Mat_xx F_d(const State& x, double dt) + { + // Use (4.58) from the book + return Eigen::expm(A_c(x) * dt); + } + + /** Discrete time process noise + * @param x State + * @param dt Time step + * @return Matrix Process noise covariance + */ + virtual Mat_xx Q_d(const State& x, double dt) + { + // See https://en.wikipedia.org/wiki/Discretization#Discretization_of_process_noise for more info + Mat_xx A_c = A_c(x); + Mat_xx Q_c = Q_c(x); + + Mat_xx F; + // clang-format off + F << -A_c , Q_c, + Mat_xx::Zeros(), A_c.transpose(); + // clang-format on + Eigen::Matrix G = Eigen::expm(F * dt); + return G.template block(0, n_dim) * G.template block(n_dim, n_dim).transpose(); + } + + + /** Propagate state estimate through dynamics + * @param x_est State estimate + * @param dt Time step + * @return State + */ + virtual prob::MultiVarGauss pred_from_est(const prob::MultiVarGauss& x_est, double dt) + { + Mat_xx P = x_est.cov(); + Mat_xx F_d = F_d(x_est.mean(), dt); + Mat_xx Q_d = Q_d(x_est.mean(), dt); + prob::MultiVarGauss x_est_pred(f_d(x_est.mean(), dt), F_d * P * F_d.transpose() + Q_d); + + return x_est_pred; + } + +}; + +} // namespace filters +} // namespace vortex diff --git a/include/models/sensor_model.hpp b/include/models/sensor_model.hpp new file mode 100644 index 00000000..cc4553a2 --- /dev/null +++ b/include/models/sensor_model.hpp @@ -0,0 +1,61 @@ +/** + * @file sensor_model.hpp + * @author Eirik Kolås + * @brief Sensor model interface. Based on "Fundamentals of Sensor Fusion" by Edmund Brekke + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ + +#include +#include + +namespace vortex { +namespace filters { + + +template +class SensorModel { + using Measurement = Eigen::Matrix; + using State = Eigen::Matrix; + using Mat_zz = Eigen::Matrix; + using Mat_zx = Eigen::Matrix; + using Mat_xx = Eigen::Matrix; +public: + + virtual ~SensorModel() = default; + + virtual Measurement h(const State& x) const = 0; + vitrual Mat_zx H(const State& x) const = 0; + virtual Mat_zz R(const State& x) const = 0; + + /** + * @brief Get the predicted measurement distribution given a state estimate + * + * @param x_est State estimate + * @return prob::MultiVarGauss + */ + virtual prob::MultiVarGauss pred_from_est(const prob::MultiVarGauss& x_est) const + { + Mat_xx P = x_est.cov(); + Mat_zx H = this->H(x_est.mean()); + Mat_zz R = this->R(x_est.mean()); + + return {this->h(x_est.mean()), H * P * H.transpose() + R}; + } + + /** + * @brief Get the predicted measurement distribution given a state + * @param x State + * @return prob::MultiVarGauss + */ + virtual prob::MultiVarGauss pred_from_state(const State& x) const + { + return {this->h(x), this->R(x)}; + } +}; + +} // namespace filters +} // namespace vortex \ No newline at end of file diff --git a/include/models/temp_gyro_model.hpp b/include/models/temp_gyro_model.hpp deleted file mode 100644 index 607dc330..00000000 --- a/include/models/temp_gyro_model.hpp +++ /dev/null @@ -1,41 +0,0 @@ -#pragma once - -#include -#include -#include - -namespace Models { -constexpr int n_x = 7, n_y = 7, n_u = 1, n_v = 6, n_w = 6; -using Base = Model_base, n_x, n_y, n_u, n_v, n_w>; -class Temp_gyro_model : public Base { -public: - DEFINE_MODEL_TYPES(n_x, n_y, n_u, n_v, n_w) - using Quaternion = Eigen::Quaterniond; - - Temp_gyro_model() : Base(){}; - - State f(Time t, const State &x, const Input &u = Input::Zero(), const Disturbance &v = Disturbance::Zero()) const override final - { - (void)t; - (void)u; - Quaternion q(x(0), x(1), x(2), x(3)); - Quaternion q_dot = q * Quaternion(0, v(0), v(1), v(2)); - q_dot.coeffs() *= 0.5; - State x_dot; - x_dot << q_dot.w(), q_dot.x(), q_dot.y(), q_dot.z(), v(3), v(4), v(5); - - return x_dot; - } - - Measurement h(Time t, const State &x, const Input &u = Input::Zero(), const Noise &w = Noise::Zero()) const override final - { - (void)t; - (void)x; - (void)u; - - Measurement z; - z << 0, w; - return z; - } -}; -} // namespace Models \ No newline at end of file diff --git a/include/probability/binomial.hpp b/include/probability/binomial.hpp index a7cbbe84..bcec3887 100644 --- a/include/probability/binomial.hpp +++ b/include/probability/binomial.hpp @@ -12,7 +12,7 @@ #include namespace vortex { -namespace probability { +namespace prob { class Binomial { public: diff --git a/include/probability/chi_squared.hpp b/include/probability/chi_squared.hpp index 468ddec6..50fbd27d 100644 --- a/include/probability/chi_squared.hpp +++ b/include/probability/chi_squared.hpp @@ -2,7 +2,7 @@ #include namespace vortex { -namespace probability { +namespace prob { class ChiSquared { public: diff --git a/include/probability/gaussian_mixture.hpp b/include/probability/gaussian_mixture.hpp index d6d7652d..8b015acd 100644 --- a/include/probability/gaussian_mixture.hpp +++ b/include/probability/gaussian_mixture.hpp @@ -15,7 +15,7 @@ #include "multi_var_gauss.hpp" namespace vortex { -namespace probability { +namespace prob { /** * A class for representing a multivariate Gaussian mixture distribution diff --git a/include/probability/multi_var_gauss.hpp b/include/probability/multi_var_gauss.hpp index 2b8182b8..5486f123 100644 --- a/include/probability/multi_var_gauss.hpp +++ b/include/probability/multi_var_gauss.hpp @@ -2,7 +2,7 @@ #include namespace vortex { -namespace probability { +namespace prob { /** * A class for representing a multivariate Gaussian distribution @@ -15,7 +15,7 @@ class MultiVarGauss { using Matrix = Eigen::Matrix; MultiVarGauss(const Vector& mean, const Matrix& cov) - : mean_(mean), cov_(cov) + : mean_(mean), cov_(cov), cov_inv_(cov_.llt().solve(Matrix::Identity())) { // Check that the covariance matrix is positive definite and symmetric if (cov_ != cov_.transpose()) { @@ -32,8 +32,7 @@ class MultiVarGauss { */ double pdf(const Vector& x) const { const auto diff = x - mean_; - const auto cov_inv = cov_.llt().solve(Matrix::Identity()); - const auto exponent = -0.5 * diff.transpose() * cov_inv * diff; + const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; return std::exp(exponent) / std::sqrt(std::pow(2 * M_PI, n_dim) * cov_.determinant()); } @@ -44,14 +43,14 @@ class MultiVarGauss { */ double logpdf(const Vector& x) const { const auto diff = x - mean_; - const auto cov_inv = cov_.llt().solve(Matrix::Identity()); - const auto exponent = -0.5 * diff.transpose() * cov_inv * diff; + const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; return exponent - 0.5 * std::log(std::pow(2 * M_PI, n_dim) * cov_.determinant()); } Vector mean() const { return mean_; } Matrix cov() const { return cov_; } + Matrix cov_inv() const { return cov_inv_; } /** Calculate the Mahalanobis distance of x given the Gaussian * @param x @@ -59,8 +58,7 @@ class MultiVarGauss { */ double mahalanobis_distance(const Vector& x) const { const auto diff = x - mean_; - const auto cov_inv = cov_.llt().solve(Matrix::Identity()); - return std::sqrt(diff.transpose() * cov_inv * diff); + return std::sqrt(diff.transpose() * cov_inv_ * diff); } @@ -72,6 +70,7 @@ class MultiVarGauss { private: Vector mean_; Matrix cov_; + Matrix cov_inv_; }; } // namespace probability diff --git a/include/probability/poisson.hpp b/include/probability/poisson.hpp index ea1ec24f..f17802a5 100644 --- a/include/probability/poisson.hpp +++ b/include/probability/poisson.hpp @@ -12,7 +12,7 @@ #include namespace vortex { -namespace probability { +namespace prob { class Poisson { public: diff --git a/test/probability_test.cpp b/test/probability_test.cpp index 89c95381..797f3fec 100644 --- a/test/probability_test.cpp +++ b/test/probability_test.cpp @@ -8,7 +8,7 @@ TEST(multiVarGauss, initGaussian) { - vortex::probability::MultiVarGauss<2> gaussian(Eigen::Vector2d::Zero(), Eigen::Matrix2d::Identity()); + vortex::prob::MultiVarGauss<2> gaussian(Eigen::Vector2d::Zero(), Eigen::Matrix2d::Identity()); EXPECT_EQ(gaussian.mean(), (Eigen::Vector2d{0, 0})); EXPECT_EQ(gaussian.cov(), (Eigen::Matrix2d{{1, 0}, {0, 1}})); @@ -16,14 +16,14 @@ TEST(multiVarGauss, initGaussian) TEST(multiVarGauss, pdf) { - vortex::probability::MultiVarGauss<2> gaussian(Eigen::Vector2d::Zero(), Eigen::Matrix2d::Identity()); + vortex::prob::MultiVarGauss<2> gaussian(Eigen::Vector2d::Zero(), Eigen::Matrix2d::Identity()); EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{0, 0}), 1/(2*M_PI), 1e-15); EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{1, 0}), 1/(2*std::sqrt(M_E)*M_PI), 1e-15); EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{0, 1}), 1/(2*std::sqrt(M_E)*M_PI), 1e-15); EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{1, 1}), 1/(2*M_E*M_PI), 1e-15); - gaussian = vortex::probability::MultiVarGauss<2>(Eigen::Vector2d{0, 0}, Eigen::Matrix2d{{2, 1}, {1, 2}}); + gaussian = vortex::prob::MultiVarGauss<2>(Eigen::Vector2d{0, 0}, Eigen::Matrix2d{{2, 1}, {1, 2}}); EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{0, 0}), 1/(2*std::sqrt(3)*M_PI), 1e-15); EXPECT_NEAR(gaussian.pdf(Eigen::Vector2d{1, 0}), 1/(2*std::sqrt(3)*std::exp(1.0/3)*M_PI), 1e-15); @@ -33,7 +33,7 @@ TEST(multiVarGauss, pdf) TEST(multiVarGauss, invalidCovariance) { - EXPECT_THROW(vortex::probability::MultiVarGauss<2>(Eigen::Vector2d::Zero(), Eigen::Matrix2d::Zero()), std::invalid_argument); - EXPECT_THROW(vortex::probability::MultiVarGauss<2>(Eigen::Vector2d::Zero(), Eigen::Matrix2d{{1, 0}, {0, 0}}), std::invalid_argument); - EXPECT_THROW(vortex::probability::MultiVarGauss<2>(Eigen::Vector2d::Zero(), Eigen::Matrix2d{{-1, 0}, {0, -1}}), std::invalid_argument); + EXPECT_THROW(vortex::prob::MultiVarGauss<2>(Eigen::Vector2d::Zero(), Eigen::Matrix2d::Zero()), std::invalid_argument); + EXPECT_THROW(vortex::prob::MultiVarGauss<2>(Eigen::Vector2d::Zero(), Eigen::Matrix2d{{1, 0}, {0, 0}}), std::invalid_argument); + EXPECT_THROW(vortex::prob::MultiVarGauss<2>(Eigen::Vector2d::Zero(), Eigen::Matrix2d{{-1, 0}, {0, -1}}), std::invalid_argument); } From f7a375739a2e44802b81d22b169ff0141fb856db Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Fri, 27 Oct 2023 09:09:57 +0200 Subject: [PATCH 03/62] made tests work --- CMakeLists.txt | 11 ++-- include/filters/EKF.hpp | 32 +++++----- include/filters/UKF.hpp | 2 +- include/models/dynamic_model.hpp | 56 ++++++++++------- include/models/sensor_model.hpp | 30 +++++----- include/nodes/kf_node.hpp | 2 +- include/probability/gaussian_mixture.hpp | 16 ++--- include/probability/multi_var_gauss.hpp | 14 ++--- src/nodes/kf_node.cpp | 30 ---------- test/dynamic_model_test.cpp | 29 +++++++++ test/ekf_test.cpp | 76 ------------------------ test/sensor_model_test.cpp | 35 +++++++++++ test/test_models.hpp | 53 +++++++++++++++++ 13 files changed, 207 insertions(+), 179 deletions(-) create mode 100644 test/dynamic_model_test.cpp delete mode 100644 test/ekf_test.cpp create mode 100644 test/sensor_model_test.cpp create mode 100644 test/test_models.hpp diff --git a/CMakeLists.txt b/CMakeLists.txt index ffaa3e61..81542049 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -62,13 +62,14 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(${PROJECT_NAME}_test test/main.cpp - test/matrix_size_test.cpp - test/lti_model_test.cpp + # test/matrix_size_test.cpp + # test/lti_model_test.cpp # test/six_dof_model_test.cpp - test/ekf_test.cpp - test/ukf_test.cpp - test/erk_test.cpp + # test/ukf_test.cpp + # test/erk_test.cpp test/probability_test.cpp + test/dynamic_model_test.cpp + test/sensor_model_test.cpp ) target_include_directories(${PROJECT_NAME}_test PUBLIC $ diff --git a/include/filters/EKF.hpp b/include/filters/EKF.hpp index 0f73b46b..c5b79521 100644 --- a/include/filters/EKF.hpp +++ b/include/filters/EKF.hpp @@ -1,7 +1,7 @@ /** * @file EKF.hpp * @author Eirik Kolås - * @brief + * @brief Multivariate Gaussian Distribution. Based on "Fundamentals of Sensor Fusion" by Edmund Brekke * @version 0.1 * @date 2023-10-26 * @@ -23,17 +23,19 @@ namespace filters { */ template class EKF { + using DynamicModel::N_DIM_x; + using SensorModel::N_DIM_z; public: - EKF(DynamicModel dynamic_model, SensorModel sensor_model) + EKF(const DynamicModel& dynamic_model, const SensorModel& sensor_model) : dynamic_model_(dynamic_model), sensor_model_(sensor_model) {} /** Perform one EKF prediction step * @param x_est_prev Previous state estimate * @param dt Time step */ - std::tuple predict(std::chrono::duration dt, prob::MultiVarGauss x_est_prev) { - prob::MultiVarGauss x_est_pred = dynamic_model_.pred_from_est(x_est_prev, dt); - prob::MultiVarGauss z_est_pred = sensor_model_.pred_from_est(x_est_pred); + std::tuple predict(double dt, const prob::MultiVarGauss& x_est_prev) { + auto x_est_pred = dynamic_model_.pred_from_est(x_est_prev, dt); + auto z_est_pred = sensor_model_.pred_from_est(x_est_pred); return {x_est_pred, z_est_pred}; } @@ -43,29 +45,27 @@ class EKF { * @param z_meas Measurement * @return MultivarGauss Updated state */ - prob::MultiVarGauss update(prob::MultiVarGauss x_est_pred, prob::MultiVarGauss z_est_pred, Eigen::Vector z_meas) { + prob::MultiVarGauss update(const prob::MultiVarGauss& x_est_pred, const prob::MultiVarGauss& z_est_pred, const Eigen::Vector& z_meas) { auto H_mat = sensor_model_.H(x_est_pred); auto R_mat = sensor_model_.R(x_est_pred); auto P_mat = x_est_pred.cov(); auto S_mat = z_est_pred.cov(); auto S_mat_inv = z_est_pred.cov_inv(); - auto I = Eigen::Matrix::Identity(); + auto I = Eigen::Matrix::Identity(); - Eigen::Matrix kalman_gain = P_mat * H_mat.transpose() * S_mat_inv; - Eigen::Vector innovation = z_meas - z_est_pred.mean(); + Eigen::Matrix kalman_gain = P_mat * H_mat.transpose() * S_mat_inv; + Eigen::Vector innovation = z_meas - z_est_pred.mean(); - Eigen::Matrix state_upd_mean = x_est_pred.mean() + kalman_gain * innovation; + Eigen::Matrix state_upd_mean = x_est_pred.mean() + kalman_gain * innovation; // Use the Joseph form of the covariance update to ensure positive definiteness - Eigen::Matrix state_upd_cov = (I - kalman_gain * H_mat) * P_mat * (I - kalman_gain * H_mat).transpose() + kalman_gain * R_mat * kalman_gain.transpose(); + Eigen::Matrix state_upd_cov = (I - kalman_gain * H_mat) * P_mat * (I - kalman_gain * H_mat).transpose() + kalman_gain * R_mat * kalman_gain.transpose(); - return prob::MultiVarGauss(state_upd_mean, state_upd_cov); + return prob::MultiVarGauss(state_upd_mean, state_upd_cov); } private: - const Dynamic_model dynamic_model_; - const Sensor_model sensor_model_; - static constexpr n_dim_x_ = DynamicModel::n_dim; - static constexpr n_dim_z_ = SensorModel::n_dim; + const DynamicModel &dynamic_model_; + const SensorModel &sensor_model_; }; } // namespace filters diff --git a/include/filters/UKF.hpp b/include/filters/UKF.hpp index 7ea8a719..350a5cb8 100644 --- a/include/filters/UKF.hpp +++ b/include/filters/UKF.hpp @@ -2,7 +2,7 @@ #include #include #include -#include +// #include namespace Filters { using namespace Models; diff --git a/include/models/dynamic_model.hpp b/include/models/dynamic_model.hpp index d8e6223a..bbffb89a 100644 --- a/include/models/dynamic_model.hpp +++ b/include/models/dynamic_model.hpp @@ -8,18 +8,20 @@ * @copyright Copyright (c) 2023 * */ - -#include +#pragma once +#include +#include // For exp #include +#include namespace vortex { -namespace filters { +namespace models { -template +template class DynamicModel { - using State = Eigen::Matrix; - using Mat_xx = Eigen::Matrix; public: + using State = Eigen::Vector; + using Mat_xx = Eigen::Matrix; virtual ~DynamicModel() = default; @@ -59,7 +61,7 @@ class DynamicModel { virtual Mat_xx F_d(const State& x, double dt) { // Use (4.58) from the book - return Eigen::expm(A_c(x) * dt); + return (A_c(x) * dt).exp(); } /** Discrete time process noise @@ -70,35 +72,49 @@ class DynamicModel { virtual Mat_xx Q_d(const State& x, double dt) { // See https://en.wikipedia.org/wiki/Discretization#Discretization_of_process_noise for more info - Mat_xx A_c = A_c(x); - Mat_xx Q_c = Q_c(x); - Mat_xx F; + Mat_xx A_c = this->A_c(x); + Mat_xx Q_c = this->Q_c(x); + + Eigen::Matrix F; // clang-format off - F << -A_c , Q_c, - Mat_xx::Zeros(), A_c.transpose(); + F << -A_c , Q_c, + Mat_xx::Zero(), A_c.transpose(); // clang-format on - Eigen::Matrix G = Eigen::expm(F * dt); - return G.template block(0, n_dim) * G.template block(n_dim, n_dim).transpose(); + Eigen::Matrix G = (F * dt).exp(); + return G.template block(0, N_DIM_x) * G.template block(N_DIM_x, N_DIM_x).transpose(); } - /** Propagate state estimate through dynamics + /** Get the predicted state distribution given a state estimate * @param x_est State estimate * @param dt Time step * @return State */ - virtual prob::MultiVarGauss pred_from_est(const prob::MultiVarGauss& x_est, double dt) + virtual prob::MultiVarGauss pred_from_est(const prob::MultiVarGauss& x_est, double dt) { Mat_xx P = x_est.cov(); - Mat_xx F_d = F_d(x_est.mean(), dt); - Mat_xx Q_d = Q_d(x_est.mean(), dt); - prob::MultiVarGauss x_est_pred(f_d(x_est.mean(), dt), F_d * P * F_d.transpose() + Q_d); + Mat_xx F_d = this->F_d(x_est.mean(), dt); + Mat_xx Q_d = this->Q_d(x_est.mean(), dt); + prob::MultiVarGauss x_est_pred(this->f_d(x_est.mean(), dt), F_d * P * F_d.transpose() + Q_d); + + return x_est_pred; + } + + /** Get the predicted state distribution given a state + * @param x State + * @param dt Time step + * @return State + */ + virtual prob::MultiVarGauss pred_from_state(const State& x, double dt) + { + Mat_xx Q_d = this->Q_d(x, dt); + prob::MultiVarGauss x_est_pred(this->f_d(x, dt), Q_d); return x_est_pred; } }; -} // namespace filters +} // namespace models } // namespace vortex diff --git a/include/models/sensor_model.hpp b/include/models/sensor_model.hpp index cc4553a2..d2dd2f51 100644 --- a/include/models/sensor_model.hpp +++ b/include/models/sensor_model.hpp @@ -8,36 +8,36 @@ * @copyright Copyright (c) 2023 * */ - -#include +#pragma once +#include #include namespace vortex { -namespace filters { +namespace models { -template +template class SensorModel { - using Measurement = Eigen::Matrix; - using State = Eigen::Matrix; - using Mat_zz = Eigen::Matrix; - using Mat_zx = Eigen::Matrix; - using Mat_xx = Eigen::Matrix; public: + using Measurement = Eigen::Vector; + using State = Eigen::Vector; + using Mat_xx = Eigen::Matrix; + using Mat_zx = Eigen::Matrix; + using Mat_zz = Eigen::Matrix; virtual ~SensorModel() = default; virtual Measurement h(const State& x) const = 0; - vitrual Mat_zx H(const State& x) const = 0; + virtual Mat_zx H(const State& x) const = 0; virtual Mat_zz R(const State& x) const = 0; /** - * @brief Get the predicted measurement distribution given a state estimate + * @brief Get the predicted measurement distribution given a state estimate. Updates the covariance * * @param x_est State estimate * @return prob::MultiVarGauss */ - virtual prob::MultiVarGauss pred_from_est(const prob::MultiVarGauss& x_est) const + virtual prob::MultiVarGauss pred_from_est(const prob::MultiVarGauss& x_est) const { Mat_xx P = x_est.cov(); Mat_zx H = this->H(x_est.mean()); @@ -47,15 +47,15 @@ class SensorModel { } /** - * @brief Get the predicted measurement distribution given a state + * @brief Get the predicted measurement distribution given a state. Does not update the covariance * @param x State * @return prob::MultiVarGauss */ - virtual prob::MultiVarGauss pred_from_state(const State& x) const + virtual prob::MultiVarGauss pred_from_state(const State& x) const { return {this->h(x), this->R(x)}; } }; -} // namespace filters +} // namespace models } // namespace vortex \ No newline at end of file diff --git a/include/nodes/kf_node.hpp b/include/nodes/kf_node.hpp index 7f01ff2d..5f57349a 100644 --- a/include/nodes/kf_node.hpp +++ b/include/nodes/kf_node.hpp @@ -10,7 +10,7 @@ using std::placeholders::_1; #include #include #include -#include +// #include namespace Nodes { using namespace Models; using Period = Timestep; diff --git a/include/probability/gaussian_mixture.hpp b/include/probability/gaussian_mixture.hpp index 8b015acd..6ec3e14c 100644 --- a/include/probability/gaussian_mixture.hpp +++ b/include/probability/gaussian_mixture.hpp @@ -19,15 +19,15 @@ namespace prob { /** * A class for representing a multivariate Gaussian mixture distribution - * @tparam n_dim dimentions of the Gaussian + * @tparam N_DIM_x dimentions of the Gaussian */ -template +template class GaussianMixture { public: - using Vector = Eigen::Vector; - using Matrix = Eigen::Matrix; + using Vector = Eigen::Vector; + using Matrix = Eigen::Matrix; - GaussianMixture(std::vector weights, std::vector> gaussians) + GaussianMixture(std::vector weights, std::vector> gaussians) : weights_(weights), gaussians_(gaussians) { assert(weights_.size() == gaussians_.size()); @@ -78,18 +78,18 @@ class GaussianMixture { /** Reduce the Gaussian mixture to a single Gaussian * @return MultiVarGauss */ - MultiVarGauss reduce() const { + MultiVarGauss reduce() const { return MultivarGauss(mean(), cov()); } /** dimentions of the Gaussian mixture * @return int */ - int n_dims() const { return (n_dim); } + int n_dims() const { return (N_DIM_x); } private: std::vector weights_; - std::vector> gaussians_; + std::vector> gaussians_; }; // class GaussianMixture diff --git a/include/probability/multi_var_gauss.hpp b/include/probability/multi_var_gauss.hpp index 5486f123..b9bd056e 100644 --- a/include/probability/multi_var_gauss.hpp +++ b/include/probability/multi_var_gauss.hpp @@ -6,13 +6,13 @@ namespace prob { /** * A class for representing a multivariate Gaussian distribution - * @tparam n_dim dimentions of the Gaussian + * @tparam N_DIM_x dimentions of the Gaussian */ -template +template class MultiVarGauss { public: - using Vector = Eigen::Vector; - using Matrix = Eigen::Matrix; + using Vector = Eigen::Vector; + using Matrix = Eigen::Matrix; MultiVarGauss(const Vector& mean, const Matrix& cov) : mean_(mean), cov_(cov), cov_inv_(cov_.llt().solve(Matrix::Identity())) @@ -33,7 +33,7 @@ class MultiVarGauss { double pdf(const Vector& x) const { const auto diff = x - mean_; const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; - return std::exp(exponent) / std::sqrt(std::pow(2 * M_PI, n_dim) * cov_.determinant()); + return std::exp(exponent) / std::sqrt(std::pow(2 * M_PI, N_DIM_x) * cov_.determinant()); } /** Calculate the log likelihood of x given the Gaussian. @@ -44,7 +44,7 @@ class MultiVarGauss { double logpdf(const Vector& x) const { const auto diff = x - mean_; const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; - return exponent - 0.5 * std::log(std::pow(2 * M_PI, n_dim) * cov_.determinant()); + return exponent - 0.5 * std::log(std::pow(2 * M_PI, N_DIM_x) * cov_.determinant()); } @@ -65,7 +65,7 @@ class MultiVarGauss { /** dimentions of the Gaussian * @return int */ - int n_dims() const { return n_dim; } + int n_dims() const { return N_DIM_x; } private: Vector mean_; diff --git a/src/nodes/kf_node.cpp b/src/nodes/kf_node.cpp index 30c5ed31..1535d273 100644 --- a/src/nodes/kf_node.cpp +++ b/src/nodes/kf_node.cpp @@ -1,34 +1,4 @@ -#include -#include -#include -#include - -#include -#include - int main(int argc, char **argv) { - using namespace Models; - constexpr int n_x = Temp_gyro_model::_n_x; - constexpr int n_y = Temp_gyro_model::_n_y; - constexpr int n_u = Temp_gyro_model::_n_u; - constexpr int n_v = Temp_gyro_model::_n_v; - constexpr int n_w = Temp_gyro_model::_n_w; - DEFINE_MODEL_TYPES(n_x, n_y, n_u, n_v, n_w) - - rclcpp::init(argc, argv); - - // Create model - auto model = std::make_shared(); - // Create integrator - auto integrator = std::make_shared>(); - // Create filter - State x0 = State::Zero(); - Mat_xx P0 = Mat_xx::Identity(); - auto ukf = std::make_shared>(model, x0, P0); - auto node = std::make_shared>(ukf, 0.1s); - RCLCPP_INFO(node->get_logger(), "KF node created"); - rclcpp::spin(node); - rclcpp::shutdown(); } \ No newline at end of file diff --git a/test/dynamic_model_test.cpp b/test/dynamic_model_test.cpp new file mode 100644 index 00000000..d498ad85 --- /dev/null +++ b/test/dynamic_model_test.cpp @@ -0,0 +1,29 @@ +#include +#include +#include "test_models.hpp" + +namespace simple_dynamic_model_test { + +using State = typename SimpleDynamicModel::State; +using Mat_xx = typename SimpleDynamicModel::Mat_xx; + +TEST(DynamicModel, initSimpleModel) +{ + SimpleDynamicModel model; +} + +TEST(DynamicModel, iterateSimpleModel) +{ + SimpleDynamicModel model; + double dt = 1.0; + State x = State::Zero(); + + for (size_t i = 0; i < 10; i++) + { + EXPECT_EQ(model.f_d(x, dt), std::exp(-dt) * x); + x = model.f_d(x, dt); + } + +} + +} // namespace simple_model_test \ No newline at end of file diff --git a/test/ekf_test.cpp b/test/ekf_test.cpp deleted file mode 100644 index da8b26dc..00000000 --- a/test/ekf_test.cpp +++ /dev/null @@ -1,76 +0,0 @@ -#include -#include -#include - -#include -#include -#include - -using namespace Models; -using namespace Filters; -class EKFTest : public ::testing::Test { -protected: - static constexpr int n_x{3}, n_y{1}, n_u{2}, n_v{n_x}, n_w{n_y}; - using LTI_model = Models::LTI_model, n_x, n_y, n_u, n_v, n_w>; - static constexpr size_t num_iterations{1000}; - static constexpr double COV{1}; - - DEFINE_MODEL_TYPES(n_x, n_y, n_u, n_v, n_w) - std::shared_ptr model; - std::shared_ptr> filter; - - EKFTest() - { - Mat_xx A; - Mat_xu B; - Mat_yx C; - Mat_vv Q; - Mat_ww R; - State x0; - Mat_xx P0; - - A << .5, 0, 0, 0, .1, 0, 0, 0, 0; - B << 1, 0, 0, 0, 0, 0; - C << 1, 0, 0; - Q << 1e-4, 0, 0, 0, 1e-4, 0, 0, 0, 1e-4; - R << 1; - x0 << 1, 0, 0; - P0 = Mat_xx::Identity(); - - model = std::make_shared(A, B, C, Q, R); - filter = std::make_shared>(model, x0, P0); - - // Generate random measurements - std::random_device rd; - std::mt19937 gen(rd()); - std::normal_distribution<> d{0, COV}; - for (size_t i = 0; i < num_iterations; i++) { - Measurement y_i; - y_i << d(gen); - y.push_back(y_i); - } - // Generete vector of zero inputs - for (size_t i = 0; i < num_iterations; i++) { - Input u_i; - u_i << 0, 0; - u.push_back(u_i); - } - } - ~EKFTest() - { - } - // Vector for storing measurements - std::vector y; - // Vector for storing inputs - std::vector u; -}; - -TEST_F(EKFTest, filterConverges) -{ - // Vector for storing state estimates - std::vector x; - for (size_t i = 0; i < num_iterations; i++) { - x.push_back(filter->iterate(1ms, y[i], u[i])); - } - EXPECT_NEAR(0.0, (filter->get_state()).norm(), 1e-3) << "State estimate did not converge to zero."; -} diff --git a/test/sensor_model_test.cpp b/test/sensor_model_test.cpp new file mode 100644 index 00000000..a0c8252a --- /dev/null +++ b/test/sensor_model_test.cpp @@ -0,0 +1,35 @@ +#include +#include +#include +#include "test_models.hpp" + +namespace simple_sensor_model_test { + +using Measurement = typename SimpleSensorModel::Measurement; +using State = typename SimpleSensorModel::State; +using Mat_xx = typename SimpleSensorModel::Mat_xx; + + +TEST(SensorModel, initSimpleModel) +{ + SimpleSensorModel model; + EXPECT_EQ(model.h(State::Zero()), State::Zero()); + + State x{1,2}; + EXPECT_EQ(model.h(x), x); +} + +TEST(SensorModel, predictSimpleModel) +{ + SimpleSensorModel model; + vortex::prob::MultiVarGauss<2> x_est{State::Zero(), Mat_xx::Identity()}; + vortex::prob::MultiVarGauss<2> pred = model.pred_from_est(x_est); + EXPECT_EQ(pred.mean(), State::Zero()); + EXPECT_TRUE(pred.cov().isApprox(Mat_xx::Identity()*1.1)); + + pred = model.pred_from_state(x_est.mean()); + EXPECT_TRUE(pred.cov().isApprox(Mat_xx::Identity()*0.1)); +} + + +} // simple_sensor_model_test \ No newline at end of file diff --git a/test/test_models.hpp b/test/test_models.hpp new file mode 100644 index 00000000..3c085553 --- /dev/null +++ b/test/test_models.hpp @@ -0,0 +1,53 @@ +#pragma once +#include +#include + +class SimpleDynamicModel : public vortex::models::DynamicModel<2> { +public: + using typename DynamicModel<2>::State; + using typename DynamicModel<2>::Mat_xx; + + // A stable state transition + State f_c(const State &x) const override + { + return -x; + } + + Mat_xx A_c(const State &x) const override + { + (void)x; // unused + return -Mat_xx::Identity(); + } + + Mat_xx Q_c(const State &x) const override + { + (void)x; // unused + return Mat_xx::Identity(); + } +}; + +class SimpleSensorModel : public vortex::models::SensorModel<2, 2> { +public: + using typename SensorModel<2, 2>::Measurement; + using typename SensorModel<2, 2>::State; + using typename SensorModel<2, 2>::Mat_xx; + using typename SensorModel<2, 2>::Mat_zx; + using typename SensorModel<2, 2>::Mat_zz; + + Measurement h(const State& x) const override + { + return x; + } + + Mat_zx H(const State& x) const override + { + (void)x; // unused + return Mat_zx::Identity(); + } + Mat_zz R(const State& x) const override + { + (void)x; // unused + return Mat_zz::Identity()*0.1; + } + +}; \ No newline at end of file From cbc42b0b677fdd61b82422304f479d56e4541b13 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Mon, 30 Oct 2023 23:03:44 +0100 Subject: [PATCH 04/62] added variable length test model --- CMakeLists.txt | 22 ++++++++++++++-- include/models/dynamic_model.hpp | 4 +-- include/models/sensor_model.hpp | 4 ++- include/probability/gaussian_mixture.hpp | 23 +++++++++-------- include/probability/multi_var_gauss.hpp | 18 ++++++------- package.xml | 2 ++ test/main.cpp | 4 +++ test/sensor_model_test.cpp | 21 +++++++++++++++- test/test_models.hpp | 32 ++++++++++++++++++++++++ 9 files changed, 105 insertions(+), 25 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 81542049..765bc07b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -7,7 +7,11 @@ if(NOT CMAKE_CXX_STANDARD) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Wno-unused-local-typedefs -fopenmp) + add_compile_options( + -Wall -Wextra -Wpedantic + -Wno-unused-local-typedefs # Suppress warnings from model_definitions.hpp + -fopenmp # For parallel processing with Eigen + ) endif() # Find dependencies @@ -16,6 +20,9 @@ find_package(rclcpp REQUIRED) find_package(std_msgs REQUIRED) find_package(geometry_msgs REQUIRED) find_package(Eigen3 REQUIRED) +find_package(OpenMP REQUIRED) # For parallel processing with Eigen +find_package(Gnuplot REQUIRED) +find_package(Boost REQUIRED COMPONENTS iostreams system filesystem) # for gnuplot # Add include @@ -30,7 +37,11 @@ ament_target_dependencies(${PROJECT_NAME}_node rclcpp std_msgs geometry_msgs - Eigen3 + Gnuplot + Boost +) +target_link_libraries(${PROJECT_NAME}_node + Eigen3::Eigen ) # Let ros2 run find the executables @@ -77,7 +88,14 @@ if(BUILD_TESTING) ) ament_target_dependencies(${PROJECT_NAME}_test std_msgs + Gnuplot + Boost ) + target_link_libraries(${PROJECT_NAME}_test + Eigen3::Eigen + OpenMP::OpenMP_CXX + ) + endif() diff --git a/include/models/dynamic_model.hpp b/include/models/dynamic_model.hpp index bbffb89a..b13bba84 100644 --- a/include/models/dynamic_model.hpp +++ b/include/models/dynamic_model.hpp @@ -17,12 +17,12 @@ namespace vortex { namespace models { -template +template class DynamicModel { public: + static constexpr int N_DIM_x = n_dim_x; using State = Eigen::Vector; using Mat_xx = Eigen::Matrix; - virtual ~DynamicModel() = default; /** Continuos time dynamics diff --git a/include/models/sensor_model.hpp b/include/models/sensor_model.hpp index d2dd2f51..886c2aec 100644 --- a/include/models/sensor_model.hpp +++ b/include/models/sensor_model.hpp @@ -16,9 +16,11 @@ namespace vortex { namespace models { -template +template class SensorModel { public: + static constexpr int N_DIM_x = n_dim_x; + static constexpr int N_DIM_z = n_dim_z; using Measurement = Eigen::Vector; using State = Eigen::Vector; using Mat_xx = Eigen::Matrix; diff --git a/include/probability/gaussian_mixture.hpp b/include/probability/gaussian_mixture.hpp index 6ec3e14c..c55b50a0 100644 --- a/include/probability/gaussian_mixture.hpp +++ b/include/probability/gaussian_mixture.hpp @@ -12,7 +12,7 @@ #pragma once #include #include -#include "multi_var_gauss.hpp" +#include namespace vortex { namespace prob { @@ -24,8 +24,8 @@ namespace prob { template class GaussianMixture { public: - using Vector = Eigen::Vector; - using Matrix = Eigen::Matrix; + using Vec = Eigen::Vector; + using Mat = Eigen::Matrix; GaussianMixture(std::vector weights, std::vector> gaussians) : weights_(weights), gaussians_(gaussians) @@ -37,7 +37,7 @@ class GaussianMixture { * @param x * @return double */ - double pdf(const Vector& x) const { + double pdf(const Vec& x) const { double pdf = 0; for (int i = 0; i < gaussians_.size(); i++) { pdf += weights_[i] * gaussians_[i].pdf(x); @@ -48,8 +48,8 @@ class GaussianMixture { /** Find the mean of the Gaussian mixture * @return Vector */ - Vector mean() const { - Vector mean = Vector::Zero(); + Vec mean() const { + Vec mean = Vec::Zero(); for (int i = 0; i < gaussians_.size(); i++) { mean += weights_[i] * gaussians_[i].mean(); } @@ -59,16 +59,16 @@ class GaussianMixture { /** Find the covariance of the Gaussian mixture * @return Matrix */ - Matrix cov() const { + Mat cov() const { // Spread of innovations - Matrix P_bar = Matrix::Zero(); + Mat P_bar = Mat::Zero(); for (int i = 0; i < gaussians_.size(); i++) { P_bar += weights_[i] * gaussians_[i].mean() * gaussians_[i].mean().transpose(); } P_bar -= mean() * mean().transpose(); // Spread of Gaussians - Matrix P = Matrix::Zero(); + Mat P = Mat::Zero(); for (int i = 0; i < gaussians_.size(); i++) { P += weights_[i] * gaussians_[i].cov(); } @@ -93,5 +93,8 @@ class GaussianMixture { }; // class GaussianMixture + } // namespace probability -} // namespace vortex \ No newline at end of file +} // namespace vortex + +int sum(int a, int b); \ No newline at end of file diff --git a/include/probability/multi_var_gauss.hpp b/include/probability/multi_var_gauss.hpp index b9bd056e..2b5c87aa 100644 --- a/include/probability/multi_var_gauss.hpp +++ b/include/probability/multi_var_gauss.hpp @@ -1,21 +1,21 @@ #pragma once -#include +#include namespace vortex { namespace prob { /** * A class for representing a multivariate Gaussian distribution - * @tparam N_DIM_x dimentions of the Gaussian + * @tparam N_DIMS dimentions of the Gaussian */ -template +template class MultiVarGauss { public: - using Vector = Eigen::Vector; - using Matrix = Eigen::Matrix; + using Vector = Eigen::Vector; + using Matrix = Eigen::Matrix; MultiVarGauss(const Vector& mean, const Matrix& cov) - : mean_(mean), cov_(cov), cov_inv_(cov_.llt().solve(Matrix::Identity())) + : mean_(mean), cov_(cov), cov_inv_(cov_.llt().solve(Matrix::Identity(N_DIMS, N_DIMS))) { // Check that the covariance matrix is positive definite and symmetric if (cov_ != cov_.transpose()) { @@ -33,7 +33,7 @@ class MultiVarGauss { double pdf(const Vector& x) const { const auto diff = x - mean_; const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; - return std::exp(exponent) / std::sqrt(std::pow(2 * M_PI, N_DIM_x) * cov_.determinant()); + return std::exp(exponent) / std::sqrt(std::pow(2 * M_PI, N_DIMS) * cov_.determinant()); } /** Calculate the log likelihood of x given the Gaussian. @@ -44,7 +44,7 @@ class MultiVarGauss { double logpdf(const Vector& x) const { const auto diff = x - mean_; const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; - return exponent - 0.5 * std::log(std::pow(2 * M_PI, N_DIM_x) * cov_.determinant()); + return exponent - 0.5 * std::log(std::pow(2 * M_PI, N_DIMS) * cov_.determinant()); } @@ -65,7 +65,7 @@ class MultiVarGauss { /** dimentions of the Gaussian * @return int */ - int n_dims() const { return N_DIM_x; } + int n_dims() const { return N_DIMS; } private: Vector mean_; diff --git a/package.xml b/package.xml index 12c2a811..2d39cdf4 100644 --- a/package.xml +++ b/package.xml @@ -17,6 +17,8 @@ ament_lint_auto ament_lint_common ament_cmake_gtest + gnuplot + gnuplot-iostream ament_cmake diff --git a/test/main.cpp b/test/main.cpp index 1a8ff99c..ec43c686 100644 --- a/test/main.cpp +++ b/test/main.cpp @@ -1,7 +1,11 @@ #include +#include int main(int argc, char **argv) { + Eigen::initParallel(); + Eigen::setNbThreads(8); + testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } \ No newline at end of file diff --git a/test/sensor_model_test.cpp b/test/sensor_model_test.cpp index a0c8252a..c870b96f 100644 --- a/test/sensor_model_test.cpp +++ b/test/sensor_model_test.cpp @@ -32,4 +32,23 @@ TEST(SensorModel, predictSimpleModel) } -} // simple_sensor_model_test \ No newline at end of file +} // simple_sensor_model_test + +namespace variable_length_sensor_model_test { + +using Measurement = typename VariableLengthSensorModel::Measurement; +using State = typename VariableLengthSensorModel::State; +using Mat_xx = typename VariableLengthSensorModel::Mat_xx; + +TEST(SensorModel, initVariableLengthModel) +{ + const int N_DIMS_z = 3; + VariableLengthSensorModel model(N_DIMS_z); + EXPECT_EQ(model.h(State::Zero()), State::Zero()); + + State x{1,2}; + EXPECT_EQ(model.h(x), x); +} + + +} // variable_length_sensor_model_test diff --git a/test/test_models.hpp b/test/test_models.hpp index 3c085553..066e6e27 100644 --- a/test/test_models.hpp +++ b/test/test_models.hpp @@ -50,4 +50,36 @@ class SimpleSensorModel : public vortex::models::SensorModel<2, 2> { return Mat_zz::Identity()*0.1; } +}; + +class VariableLengthSensorModel : public vortex::models::SensorModel<2, Eigen::Dynamic> { +public: + using typename SensorModel<2, Eigen::Dynamic>::Measurement; + using typename SensorModel<2, Eigen::Dynamic>::State; + using typename SensorModel<2, Eigen::Dynamic>::Mat_xx; + using typename SensorModel<2, Eigen::Dynamic>::Mat_zx; + using typename SensorModel<2, Eigen::Dynamic>::Mat_zz; + using SensorModel::N_DIM_z; + using SensorModel::N_DIM_x; + + + VariableLengthSensorModel(int n_z) : n_z(n_z) {} + + Measurement h(const State& x) const override + { + return x; + } + + Mat_zx H(const State& x) const override + { + (void)x; // unused + return Mat_zx::Identity(N_DIM_x, N_DIM_x); + } + Mat_zz R(const State& x) const override + { + (void)x; // unused + return Mat_zz::Identity(N_DIM_x, N_DIM_x)*0.1; + } + + const int n_z; }; \ No newline at end of file From 77e4a5057f815f99312fc3a1500f8d21f2f23afa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Fri, 3 Nov 2023 00:30:22 +0100 Subject: [PATCH 05/62] added IMM. Almost compiles --- CMakeLists.txt | 15 +- include/filters/EKF.md | 4 - include/filters/{EKF.hpp => ekf.hpp} | 34 +- include/filters/ekf_algorithm.png | Bin 145686 -> 0 bytes include/filters/imm_filter.hpp | 154 +++++++++ include/filters/kf_definitions.png | Bin 204368 -> 0 bytes include/filters/ukf.png | Bin 189171 -> 0 bytes include/models/dynamic_model.hpp | 10 +- include/models/imm_model.hpp | 117 +++++++ include/probability/gaussian_mixture.hpp | 20 +- scripts/ekf_python3/analysis_py2.py | 105 ------- scripts/ekf_python3/debugtools_py2.py | 6 - scripts/ekf_python3/ekf_py2.py | 101 ------ scripts/ekf_python3/gaussparams_py2.py | 72 ----- scripts/vkf_node.py | 377 ----------------------- test/ekf_test.cpp | 38 +++ test/main.cpp | 3 + test/test_models.hpp | 3 + 18 files changed, 363 insertions(+), 696 deletions(-) delete mode 100644 include/filters/EKF.md rename include/filters/{EKF.hpp => ekf.hpp} (63%) delete mode 100644 include/filters/ekf_algorithm.png create mode 100644 include/filters/imm_filter.hpp delete mode 100644 include/filters/kf_definitions.png delete mode 100644 include/filters/ukf.png create mode 100644 include/models/imm_model.hpp delete mode 100644 scripts/ekf_python3/analysis_py2.py delete mode 100644 scripts/ekf_python3/debugtools_py2.py delete mode 100644 scripts/ekf_python3/ekf_py2.py delete mode 100644 scripts/ekf_python3/gaussparams_py2.py delete mode 100755 scripts/vkf_node.py create mode 100644 test/ekf_test.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 765bc07b..633e0d01 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,10 +1,11 @@ cmake_minimum_required(VERSION 3.5) project(vortex-vkf) -# Default to C++14 +# Default to C++17 if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() + set(CMAKE_CXX_STANDARD 17) + endif() +set(CMAKE_CXX_STANDARD 17) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options( @@ -73,11 +74,7 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(${PROJECT_NAME}_test test/main.cpp - # test/matrix_size_test.cpp - # test/lti_model_test.cpp - # test/six_dof_model_test.cpp - # test/ukf_test.cpp - # test/erk_test.cpp + test/ekf_test.cpp test/probability_test.cpp test/dynamic_model_test.cpp test/sensor_model_test.cpp @@ -92,7 +89,7 @@ if(BUILD_TESTING) Boost ) target_link_libraries(${PROJECT_NAME}_test - Eigen3::Eigen + Eigen3::Eigen # Makes us able to use #include instead of #include OpenMP::OpenMP_CXX ) diff --git a/include/filters/EKF.md b/include/filters/EKF.md deleted file mode 100644 index 654debb9..00000000 --- a/include/filters/EKF.md +++ /dev/null @@ -1,4 +0,0 @@ -# The EKF Algorithm -![Definitions](kf_definitions.png) -![Definitions](ekf_algorithm.png) - diff --git a/include/filters/EKF.hpp b/include/filters/ekf.hpp similarity index 63% rename from include/filters/EKF.hpp rename to include/filters/ekf.hpp index c5b79521..57431a0a 100644 --- a/include/filters/EKF.hpp +++ b/include/filters/ekf.hpp @@ -1,5 +1,5 @@ /** - * @file EKF.hpp + * @file ekf.hpp * @author Eirik Kolås * @brief Multivariate Gaussian Distribution. Based on "Fundamentals of Sensor Fusion" by Edmund Brekke * @version 0.1 @@ -21,19 +21,19 @@ namespace filters { * @tparam DynamicModel Dynamic model type. Has to have function for Jacobian of state transition. * @tparam SensorModel Sensor model type. Has to have function for Jacobian of measurement. (get_H) */ -template +template class EKF { - using DynamicModel::N_DIM_x; - using SensorModel::N_DIM_z; + static constexpr int N_DIM_x = DynamicModelT::N_DIM_x; + static constexpr int N_DIM_z = SensorModelT::N_DIM_z; public: - EKF(const DynamicModel& dynamic_model, const SensorModel& sensor_model) - : dynamic_model_(dynamic_model), sensor_model_(sensor_model) {} + EKF(DynamicModelT dynamic_model, SensorModelT sensor_model) + : dynamic_model_(std::move(dynamic_model)), sensor_model_(std::move(sensor_model)) {} /** Perform one EKF prediction step * @param x_est_prev Previous state estimate * @param dt Time step */ - std::tuple predict(double dt, const prob::MultiVarGauss& x_est_prev) { + std::pair, prob::MultiVarGauss> predict(const prob::MultiVarGauss& x_est_prev, double dt) { auto x_est_pred = dynamic_model_.pred_from_est(x_est_prev, dt); auto z_est_pred = sensor_model_.pred_from_est(x_est_pred); return {x_est_pred, z_est_pred}; @@ -46,8 +46,8 @@ class EKF { * @return MultivarGauss Updated state */ prob::MultiVarGauss update(const prob::MultiVarGauss& x_est_pred, const prob::MultiVarGauss& z_est_pred, const Eigen::Vector& z_meas) { - auto H_mat = sensor_model_.H(x_est_pred); - auto R_mat = sensor_model_.R(x_est_pred); + auto H_mat = sensor_model_.H(x_est_pred.mean()); + auto R_mat = sensor_model_.R(x_est_pred.mean()); auto P_mat = x_est_pred.cov(); auto S_mat = z_est_pred.cov(); auto S_mat_inv = z_est_pred.cov_inv(); @@ -63,9 +63,21 @@ class EKF { return prob::MultiVarGauss(state_upd_mean, state_upd_cov); } + /** + * @brief Perform one EKF update step + * @param x_est_prev Previous state estimate + * @param z_meas Measurement + * @param dt Time step + */ + std::tuple, prob::MultiVarGauss, prob::MultiVarGauss> step(const prob::MultiVarGauss& x_est_prev, const Eigen::Vector& z_meas, double dt) { + auto [x_est_pred, z_est_pred] = predict(dt, x_est_prev); + auto x_est_upd = update(x_est_pred, z_est_pred, z_meas); + return {x_est_upd, x_est_pred, z_est_pred}; + } + private: - const DynamicModel &dynamic_model_; - const SensorModel &sensor_model_; + const DynamicModelT dynamic_model_; + const SensorModelT sensor_model_; }; } // namespace filters diff --git a/include/filters/ekf_algorithm.png b/include/filters/ekf_algorithm.png deleted file mode 100644 index c363fdc12846ebe9d06010076832a970d1a213a3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 145686 zcmdqI1AC;w(l8v`PBykNv5krCY-}4F+qSW>ZCe{B8*S`lW9!YHbDr-0YL;xi7A7Cfc1ZUQDLCIYAWLlbiN)C<inn6HmFj7j*{ ze_R)FO&1k=GZ%M5CsPn}J9}GG24`a@Q&T%<3wxJK@LqwhPE7wgi8`4Yx>(xV5vy9- znu6FoF%kpV7>TW1?JS7_%m7wmYn!hc7Di@PVmf93GqbswjvWXHF$hphSk)u@eDl$n zU?pSw-TuhKS?E^;F>GWZ`MQ(#4;%YwyQQAXkD^N^UiQoLUmhb5nyC~@Q=lLb*^Ca( zNCb~z@Y2cj5&2?T4Xb&i6`JG@jve-o{0e!u*+(#jIH6*s2~y-}5n`mZsMno#LjU>s zRdcg~1=;_5sg_y9z{~-38(f@w{K<2lC7%tYMVkm|4 z1R?By`3eC;EG5+tO%4}6;J(@SUrcRsb*XO1uQ?DHPD(l$jxpI2=i0Sl&qIz#d!^@x~yV7*(#3snnN?k5pg67<6K zcE*#SZF*3fjMF7SC`44;-9ssysTr~vKbcUvLIV_LZIuQ896FdM{WuFtej|6Xi{SKq zW2D>D$Ak#;muXch@m1e;xQtik&8He3kDdnb=a@UO#ZI)QIPdTM0OwhPi;+mHA5M-WhBk`SJOQ{j)#bC-#zJx#dj>u*6-ht9zwBMFP& zWfx`Fs<6odlw)M(7aa6n8!XRJX2jsOjiio1oljDknu<lC7G+1%~xeR zxp)uEjnfoM=SZ0Q(~Z{e;x@D^NtBl05>2usMi|o(KUlj|N}k*BnK{??371Dzjzk=k z;^t(UnldV6bA0dao7+L98m2Aw3RBk?;;=pU$Zo4HkS0w;5!v2*;Jxc$z?(+OWeH{P z82YB6o=zmgjQ07EOAj5xiZ=|76erJB>FEL%bvK2No>UZlgrtHI)>W zh3}5|vJ62d!zycHt9&@zdFIjTj%MbgxWJ5|pZ>lF=|vZE4@hv?(&*7swRLS=gFg>Q?yQ^W zD3Fk8J<2hi?BB2h>uF@qjD(pDnGvY9#U~`Q_&Qv(s@+l@NQX4NlM-yQ$C*A2`vy;z z%kTva--8}K9cD|m%`-Ya;C&e@O(gcbe{6QgU9y!E*w;0CjtSR?v2iGH5KtLM&ep0_ zK3d#~PbF}hnPRe9cDL~x3LW#_;fYI+{;;|D>#T0QaEx%}<%(yUW`{z??Uz$&U0GEv z&uT?yk=R#xrV@sXQ$5ef+xijY_qug?`?F{vMh?K5N^a_Z&Ovi&*U;!Qp|mQR_1)0S zF|&P~tv-J=-%Yw$)2P%0(C~m>^T{Uk9n&$6u)*h%kVp`hI9ku}<-+~hls2TsPg1yU zeYhN(Ytwfui1)G0=Mgk6?_3#9B|hV5egaHID=OOYBYlV0BZ%W-0+uQaQrb3N^*U#JqtaeJruofi?{3)T zsb)Du#}hwtAhcRX$m_<(%I9#{0o(l>@{?aPL}-B@B@EIa$kr_=s2Hdc25PXvrEsfC zk#AG~LY%#`dE>Yv)9_pEM*`6}j~gKLVS-4PETLEKOL0HTLka}rXc}vH{_qVTlItB- zNK5?50GZ8^)4lHf_Ud;KM?}M?Y*+UX^*Lehdr!8kOj0syK1=WT_C&ZYNg(Zi9(1X9 z?hc19D4Rc^Nev+V2tUUT3m=KHN)_sAruQis7t}VQoeb$;LojtC`@lP z66f7j4rNZG>+;s;7jp|<-ux`xAteE#NnxF|bEf;1(^fVpAB4Kln3H3(8ObjDVZXDfC z^d?v}RRwT;hLZt8$~Zb?LbhyuV*5V6LT`AlQ9TrWj?DNza|rrb=hA~J_lh;P&1?z^ z7K=bl$4AKNk!CgGE|9M^ub;pAoHjFpGxZ_sYwhVrTA0A-t_tO$Mv zjDE0vY|K1gem*(dO;Kh<2=cO%KoItJeYQ1^I(}epJe@E--Ov2lJ#7Q>loV7FM-gj!PDQXY>hYHpPsMxcnD3t=YwBg2 zn$pS)%qymoXXlxJjIgI}y}FltT=0L)hz3k8xqBXI2p$pr$tEXS2wf4vL3;s*s%Djr z`|Jx-_+it+ZoJ6W@LRbX4_tXDnkTJ(C&u(k* zQ-=#VVN4(RPj9J!(vAUlpCPNp)c}>1^rmVy;zO70miNfxl*U7Hh;k9=3P)ox3V__u z^z*%Y)}Iv63j(IS1;inwJCH#J5TL^9O4T@SJaRk)REACEE{toyD5=N@T$v=I@dTOC z@H4$g;qWu);4L#0?>{lmfssFl>(R6TCDCMfWnO{%$MlVr_72Z4cxk07`}8T;$S$Ez zc7Ex(H`}1@Zg>bK7&W5+S*lT~NtUh~)Z+AL)y;hy&f$@LFpX4J%~0vnl$f8PC>;LvFECGSwq@7q(8R5<&b3-#%mNvE;0VOD& z8Kww?3(fPNo!BEv5|EEZ3#>|x8$h5k`+zUY?*Pc#Dt;f1Kd0vGdsJ) zlWPP^Tdv(lBa(p2c}rF5b3Vh{zbw_u)YsRJSZS2ulUN;CRCdR|eRHhdqZ^GPoVJVs z+bPif1%+h8H~Z)Gd*kF}p--z}=mCaCMbxBlq@)9-pG+Cl60r$yFg?p9HNe4N`iV*i z1cS44dKsWw^2`s-FkSg9gI5#?kV2yq^30?mvX7N_;E=-C_*T>0?R&s zhX?)pE*5C=z6>4eFq)|dnvqhGHP(gq|tU?$8#=+R5 zb)L&WV$w67%mU*IxL=ch7Pct(qqq}xa^AjmQ3z4PNfkb=zHR2mt=B4ZF>aSRqE(0k zu#LR`7DFhBaUi;gjw+gf35P2alP1hW1a6PHlS6oekqo7oLJUi!vD5ERluC<(DyhXI zAQod2Ly{O>*~+*1#=)Rj0F_lV+IcJiezvK>wuMn}ktGFIw3%S@AqpYk)U-J2(VBen z12wymB=c0pk|d!0b=kVaAf$=Jq_DL-`M8HVQGl_`P?XHEh8JPU?D%`)(3 z04ZupOb?59U}!Kv`f7Q~JxJx2o6qFQmWbc7S!MsyWhl()#+~jK` zI77m>-U!3LQv0t|aDil71t>~Nin8!@HHOwBAvfxRqA0?RiWd+qXXxSiQMEvnXpq3@ zs!2_&NE_c^mnorFs9I`Tp5@=PX?{iqGb<;*S)*rS<5j>-c(~r7F6`1`EsDq+Oq_86 z9dB0HDIs9Nq>&ZI!h-rX{ zj<|YqiE^D>J;7#{QrNmTm#$VW6{YxuYBb1fKUHI|>k-ZTZ46eZ(N6(DFHTUME~TP?GXS9;K;TjtyF5QTv?)@2pJq!1AAJjEB1Ra>v=yx)+P zvxTRSuZzgTr1q`7;L>D>H6_X+OIDaJ0{i__% zpnm^=y*)CN&?AC0>Y`Jq%$foqQ={fw4(MN&cA}$2oJP;TWP>3Dxr0jTRgzIb&r8z|e@C8LBG2$x+FMj-$!RtW7 ziSg&7AYyBa%*c|7F;WOSfgDJRV1D0?HD-_;hz_7Xhm7Vfu8NZA3L=82Xp*=XADFvP>t@Nq#hkM@*zm}#nygyzEESA5-^}Q} z2)UZ%5+VYm$jq>-9-rUSr!PpMRpA*=Xia|jfK1nC!dNTQKWRh-jh~hKCe8|kBp%8cO{<-4^u{K)&AZ=8rXXs|UXg#p$o$NIa}N$t)q92F zPP9%kL$_n-W`fk&5^`_2m?pQI8N!EW$yk0yTXlvo5NDT*@Is)hoTg!6va6nBR8xfN zq51OROKZ>ZuO66OCI?kS*E<9)eY3v_T5_E4;L*KWWKz-g%gZ9Nb+9iDs(Vwhdoze} zuaQr{Vp4Y8%O(y;?~5H}rU$`2Ia_Q_GzmYbyFeks5K2twnDuZ|70weriY}_|Y|2H- zS1(>Io4t|)`w>{&%-IeQ9C!#;e42W#LaFwkQlmvXBx5ZDt6-`LTS1T5x?Y!W%EZDC8#|)wyPxt@C=Q~K z5SZ(#bC}p00_I`-Q}v#dH8qYGr}RbY{u?w-bsy=QMQBv_0=ZRz-$-HcPLIJ@ofqh3 zkH)mXHV4p={`St~2|k6tN`he;CUb7-8Pb!H@yfXoozJzF0O_l)|K9US-_w*L3+#6b zZkSBwk!O3ReLipb_IF0%HRzhW|JD1uxn*SBDs_*r)=B`io4~M_*9o^vlJAtLp4)FaHd6R*Ks#+0&T)^G##CF^ z!X_+0S?F79y(s>j^PhKx1RI_hOzo32SGvP7TDVQzre+oPsI|ps*m_*3z>ttPmV~06 zEFVj)*5bKlwHqpE;>s~2^2?)U5C54hM3T0ou2#EEZ4)eL{`5r=J(trGLs!{4jA zt-`hTsVo`p`H~w<&bh|exA=)2j95PPy$>5qM1wnV7M$$lR+}7R`FWt*IGO zxLs|@rw*oxC=lU=k!HnG^74jRfQI!VJ)S~E{{1VZoZL%iSIOYOS8Rt!d_JawubvLr+=F3bnIa+vsuwXnnpm5DNl8;t^qC*Hsr(E zXmXzK)PrZ9G`eu*wm(V^v7p!f)K->jnQ!GZMgGkD-3VOZ8TK3&1xWVUOY z&;-k%h&SBgB*1V`C*KV|RJXWhHnDjmHXf>5g=8`k;cfpkgZwLP0RQ-+CRnjfp&sAP zNkUX|c#_mGumnR^M-00*KAhWg)^h(I;H2yOHX-5hfj zo$#&7!*)AIy(hhTYgQ^}WSh{NCQ8dOry!2uC~&QB?frQH7ZPelWMdGYkMA9RIY}6s z{AYk{h2@8>(>b*~#>d>_=~UBOTi?p+6PUCADQ@^6B=T{|)5&_xh9xWO=vV#qw1H$r zSaUS*P9efSb3CACr#o&8yPeX?z1}hH_pu|IEAY2YBMoRqk3k`SI=P1NvfW~lZS!we zYt6k=!uA{6T~m14$p$Ky&GD@7y1hPbto|6-+x7oF#MM!N>ZkO*gqTzsFBFw3XJuA$ zcS^T+z+!?FtLd2N&wdfIz~MWz&W2SvOoIqxnt>RmB9k@^sl#z=rE0AE>iWj^++SQZ z!Ip%9yh8rxTpfz|i7;8qwzGGNe$Rue(qqXJ68SiFuk< zRzt+&{7~Sd#a}@)pM{Z$L)@G^(hLL`ZAjYJufWugs6xJwZikS`OI;(LqJl?h)xYe| z3m5!$w#g?}TCytUZ0uETPS-+D-sq|FDPHbbIrs5@4E;}%xi_~8DyH&fN++)Eu};eQrgTG7%jA06vSg9;mFO*2$FFO6Q&4%4J}%sMN)3MnG0=<>RNvDpMLjXLsRTk37Owh z-?J!bn(MpJ&NdlG=3Q$(&yU`2)*#4IA9N#l`g|U+p|`A6=$dibO;CyS%{(b(IB*Ku z(H)!~w^q4lJ@E4ktY{TBq7xJ{=zCZL&s7ufpfNaUJ>>IB(kXabhjzz=WEbb2S>ccsG&0UmdIa+KJyGnzuhACW^ zV9ed{3{jsX8f*QEkH3^IJ)9nO!o>9*Q*DOXbKJ~?g;+?09T5X|NJwJlP^uVF*(j-0 zfv7$U*U-o-cE2sKLhmOuS^`GY&@q^VQ(y+2;Qr{eaSPGL(N2)$##<>_?8={=YNFmj z-djhs&}btQ+};Q4kF)c*XC)>fX0)L_EZ_-+GRX%m7|aitj!3IRDN{?He33{p;u49cYv|GKI59_l&;wk?OeuT5Zfxj`gpp;0{UH;Qk(gQps0IoS>z zX{A^u<2_SY&4Dn1p*dLwZZGC{q;cO;Y29D41Rz;@nrAqa(gWqQ|(1sxp0GZcTJN0pBM6zfn>pvHpFPC3&0 zWd@^mO-I<~oiASGJ8`WP@Ioy7odu|kRYGluM`^Y}d8k^3WsGl*rKQ&);>IRVYcs$3 z62Ex?{#TvCiPiIl3|0bt<|aXojdyZaIkx+T5V@7mSukm|4pVsn&k-n0DFn-xtO>`! zt>9&qTbY#RNri$719feJKZydHg_cN88aW_S#rp)e10n{^%`d^nFVC1t$v9b77;2IA zTN}B4;ir!6g6)sCyyQ#81PV+obsR1L3)!z@k8BqSQBD(beG)Tm9LBMGQ0WbcnIRT5 z$_DbnQ@jpSqxqtFTNUdEOJp$JJnEZpZ+o#cqy5XEvZA#;S=|rZ%QZ~1Gl34Rf=>OT zy&R7B368TL=Gn>XO~D)lqXk4FR~dv7Lhk0|OR}z&Z24E=XIu{fVWAhaisZ}Htzfpe2CZ%1z2A%9w-E)8f*QYBbp<+s7gEp zv>2{ZYW%_Nuu5*+nOE>T-n3J|U^f|39EI$C@Ke7E2N;14djF+p z2d(#sm=3BE`|Jfq`34Tz9!<#ndVS^x6Cpj`**RXm)P?i&EsErR^CjJG=S`P6CGn=5k++Jn}w+=T~k|@ z7|cbBlo=_zdzM=kqluNRLd|%#p?xrC`-wNv4p}`}gK$&nxGdG{GJE?5cPEJgBjHLJ z_wC&r`|#@}TsF{v%bj*cVH{F8um);U&_Zg`2(ZLUR49R5=s>f=Q#7Yuxo3;Gy#>7C z@0m1Y5(BgK2ju6f{;ZqV_l-p$?P{Xss3#cNdflGu4a?6n@mTq1iy504@wcnqA`N3t zAj4)pCb#;(TmV+ZK@Dd{2%vPF|rsp*nBR?zbNU;WEietbNJXZ_%WQ!@!M8T&SnYHz1cGAO2Etde#Qv@5=E z*1qq**oxHigzwXN{j^IDb;=IKIW3>T5+l>o&8*nv%(|qXoBAvZhEC*zO3oIz1a_-7 z^8ctwb%1_HLAff-`GgP>Rzj4W6iNfTBEVniM+Dbh=|4esNJvm6n4Fz61qGh(b-4bL zSD;b<;j+osQD{7tH|>lihPqleYf99te|X*`UA|GgD#v;n<{wF|{ktXB7HEMN-oVv$ z-g9W#fg&uP%wS`!86cvPrgC=;#~ptf;Z@o=Jc;n}9uN2ngJGQuNAqSCRVl1#?DuS%g@^{Cz2(s`v%?_b!VntiuCJtak zSH;7KL#D>hnZs`-L4U{_#U)JtoHd1I;FqvEfU@Rn;kL6=7U&usgofXDV!3(d+Jj=!UlnPJZ{|Bu z#hpX%i)YkrePRk0@Nkt@u&Z}GVkENp5l$u}tLqiTdBo~~Vt(nCmlW22MY3;%2tl9N z4r_*Wgv-rkIBTs`wpfO=+t$o8+z7zr4iVt#KR<^thK1CzTzKqk;??u=A^Kc}IXPm= zH0=K-HYX0#fzY7`r3XC<`wLtKR#;KV6jBW<;b*UUO_#s_+ql%@WGpkhKe-fjU^soa zly}Wt9x)PK2h3LQ`KQ#r_!Bk40jKwGts~H$-nJJ(ml*0GKRU$MiI}o1C7^( zG{_-@iSNMqMu$m+lHcG}nP6aHVFyqIF<``S#g*cRcgoiFeeaNYfxyIgaadebCB=AG zbg~Rm5~u5n0>Kp|2V9p*)tQIiKRSRk<%tBA3-@4M=38h`!37E^P{hFSiomL|@Bxj* zn)@|`Oh_c6&4YfooS>5au{FdRdWAZ^1RO?E3KI7T5xih3I-ODrlDR&zW z%I})3svzXJN(l)jo^2qC%X3pW5yA4iq`;=FWa7ZDpebkrk8UvaBxwNptnI@|Gl8!7 zU_5xRLg-0o3^oL;_>v+!qB!nyD;6d^8F&Bgnrlt&B6szuF;k_tVOJPW(gg8guL zCSE2$2n}qYZxEM@D-uTdisFJ$qC7K~I0e_(_s`xU(X7Dce!pZGbq;N}TWA6uUGx+~ zJ)7WEw>m@sC}|=&85}4Ci7$vS&JDfe_Cg8tlW=$#NMbN?UR;yc%pZ7EVT@4yTKY}H zw)6%yYgP-F1bXzr7Ul!jFtjx?$M6Nxf;s1kG=Jvi_J2y zt&g<0BsTjQ;ut8W>sVe={y7?7#PeEt4@P zR}uw&mR-@r!|?1S%k1ART(yW^vy&gyf>*2?)$x$YV%l5N^f5`Iv}dLW@);ZaWJ}3d_FsE7U05 zk?cElwXpMb>#Qg zv4_&PTAhMFWebmTU;+dz1j$is3JP5C zT;f`Qcru~IvE%odxQj}5u7?M)uJy%40SZ&EdlWaJW%rA#Mb zf@27a#AB%HNvedIc8P)Xi_JO7%15)bT-L4IFW@#=b|U%o@dx;L_Bj7yMW?G zTFER#9`jL~%WQzP*(^Qm__tXm>~c(6)l(9ak?Uma>R;G%##rTZ^thZq>0msj3BT)7 z#EUv~vcZpL=Qfvnu{1vp?EoCHT0#wF%; zOr<<?WMO3qzy-aakO&yOdV9Q~NP9MiK)^Fs zMar$~ahH-APm)H$X7F*k4?beT^PN)yAe5LS{r=6ipuyDG(JtqC6rJ?S*)GT{v6d*M zg-d?||EH6w8(SX|6(VD2KTrXM=P7_wRuD#aKsdp-RJxl#pI>oKmuTx^0g>Iy%Kt2< z*Is{l#KHe)ktUS~rbdEzZ3vyV!AZagFZ8HUVh~3~NMzXtAfutlMWA?|jH4<~lPW#el6`_=hZJs_!B}JP@hw72wjLr9W&z)I<+Q?vJlr`&$gYd%j zJt{zup2WPckeCFWl&^Ccw)cuc(7D=gF66PQTHjMi;1hAj{DT|cEN+{13g)>3^OiKh zUglrAgP=%WpS$A=zn4##TcgB#)0kE@uxO#^Xwg#r7j-VaiUWq%VO?^DVVP8BNX}T| zj2U$^ct;FrX{q>bfW$_v@>e3JCrQCiBM;j*yD+nL$uwCLpg1N}cw|JC#n{u+G}v^- zu;s=uhPRjbD8_>VO%wb6oF`UVt)nNU{K(aDD;`^gnpHF2v{_KBYKc;r8;m)_ba1uY`9MtH*1$m~TgwbuhSn+#QI3~Hsi<&t&s zI*H@}46L5eu`0D4fzt+z<8C9pUgyZ^Jl6sc74x_?QnkhIdam~k-JKWxuEY=u;|Jyw)hQvJFn>zjb*oZhxHkI~j&mZ_-ERjWmJ>|79s{h7!kK)Wla|50_!$ zvfCnna@b^CGD;Y1#7j|+Ygr++NiNSObhdJtU7N{^_MdexBjPi#-xJ{E?6633lx1U^ zAvwP*U;0&sS($vsu(rwAtse7r;PPB0r3HXB`dTd+{NUP{Hl-vFx};B&jA`lc#T=>; zrRExdl?Ge|4y6kz=r8Vpa*S1@Of7tlS&Y?nvWT##3)=6{fEpU=#HV{AF9=L6VEnI` zL^%Ruz{=&Jx^VlvJTIBc$$BR05Nw8hSea;<=m0uje6XOmJQG7;S5n#7IwCji#v6E(NbsQPM@0>EM9A#HI zv-dsZWgPYu7M-LxKTK||*oOmo{caIoB~7Efg>6_>SK?GX^um(E!Yvb~8E~K+Vnh>Q z_U(6OAT2yh0PjY9gLa9owNh>C2^V6;0p7h?rkmSSZn;~wiEr|_ScubXi59IQmmQjm zI8B#di8D#vK~{pYud`Db+G zS}|{#;#&7;n6dHH6jMW8*HANE($6Haef2;41T*4ZZG$g!a(_OLz_Q9Ao`WOobTpmQ zJQiAhd$q~k5*z5%NA%W*8cn1-A+mE%FG}M%Lr^-|W_RnnT^r^RA1_?|xbs1@eW3cv zqB8e%%&ylQ%kPpgyd`Y)d$fN$SvI!2T(ZayOm7V&E?&#D{W4;Da|qq(K@u5+dFWBc#|ErMpWKnGLjnm8j0v<%@b_$ zEt-CB@zX)ZxrF$RZSB7nE>vPG2s6=VdDgd2MsK5If7N%nL`+UPSIPcP&lKCfvm~;= zx%*4het-12-%3=|xWM6hSf2Hl-DnZd@!n&NvoZI~ z-4Oeqj~HPq0V%})0= z&oiXfzXC>kCxmJf;UPSR&!~^iSh%-*qa=5*U7$f`A-i*+R0kZUXL$BhwT_}#33#vg zIX2hZ{XTy;I;P*lzVY!_%<~2KR*IZiWNo(E*SVPn6lWlCR}0@;L`}!pIX~{%y0tt| ztLn;sDr60OMGy(Q2buhOCVtLIRuI)MaK3X4M+8T)te8W-r-ewCKou9>`F%UUx(BhIi+e!~=5Lw!tO`Y);h z{9<4`T_)*;2{?KNP6tqe&r5<=L7b^=fE*IWql}IlvZ_1kacG5ACV}n45B|SpC`eFG z-^0ykSejd=Zf@{zi&zFu89TFx9FG)w4<3p5cMj#DYjtY%3|`X^S?kG_2@leOUe zxI;tq`ktlknL5%X@puJ`{P9M}Dd;^^)G*;&4y@KHJ=rkOJsFteIrH<1dnC%O`<}{0 zaCh9S!$xOcN1mg&^%5`HD!3gq`l^}?=GGjrfII7Z1b6v8*MO~{(Dwq*D`Bh>_3L8G zC9;w*0BuOpJcBGYH@9%TeQIqTF|(Qwe7rCGQ~%-btxW9M)a@H**Le7yz@!cr8isI$ z6;*S_$?|!WXQSWQRK_Mp<=>M8u}Gv~NzjAJ2HHm2Zunj%I1HLZ5Kuf+u)jz6AYl*< z05SmJ2AebYbp!vzCLlVCM4wuPz7$vvmuW|KbULNyiOt@u+a3ccpR2aG|crbo)ST$Z7FZ;h6wz5gvVG@(XG>zoBf)kM61mYt1P zv_-K*Q8tMKqsMaC1cV$?tFhk6wL%6iGH39@L-swMD?z9kh+T%NOdAfliA82XI$B?4G!*&K=ulCK#`IY| z14q{&x+qWOSRk4ty(E;jTkb)tFVOECwaila1Z-G2<(Vg?i;kt2Slaio|I`EWvi;l!C*Ts&LbSg~A*(LDDP z$M>Z(rb=707&CQ?nHgS&9!W%GNr=-HVUse8qwYTZd7jU_8#ic-xUo)bE>#MWMpjg! zwtL*nU82lfDh<1Q8naA`EYzGqyHk|%0k2X}FW*sALd}$%h9p)ba5a70Vu=3t-dwdp z9UJ62^Y60XKR3|Cm$nB}z!3SxK zm;MwSl?Qvp>bfR;iNaD~WUXbHcIM3~Zx?TpqKf#<63^r<`+Ng34fvp}N{7I%y&1r( zM99-O#H(8hI6tNhr*4=q@D04AAtsekMN8ADICX>tV?WIvlVFFPoMK!<+ZaBO7-pc7 zA{)j1@^%i|{dwCh%JKs(YlYGA{RZqHIgnDHUWD~5r_S$Hu>JiS`t8;@YG8zS<0;Dh z`OI1kjz%vUA9jFF%sUrS7$sQaJHE$MW*pbqg9RNf-o2;Q0pHgUFDAGKTC6O$h^aN- zN0}*NB_ut>JoZ=?m?>p@*v92hf(5M$i6v1Wggp*`iP2W8UqRw?xpa9-**AYJQlCG~ zLW%KeA>?qdrGya`MXNOQ>myI1M0Ua`-!YBIHUA4%5t^GaVicNO^2YrBwc4k-@Js_?6o{Rrv>}vfoE)MBfwhC3 zWu(zf8XpCbIR+Os5em{fGl+(m)8q_&J#){30bOoU=`03y;5Hmt#Zx8x7dL#BEhcd# zsbXc_b|=VDN5y1wM)^-!Bcts9v;|(Rq1qyUQTyM*R$~7TWWZW7_#Zm|&D%^SQuqJ$ zCHY69ui|kLjza%$@Ic}&H!&Ej|5T!U=Ou;s$AVv_HV0dq&$`W#n&)_KL; zbJpHSY*Lzfll+k&OyD$|J(>Lmd`c9xWr?%3+Ladl@9R;J-K?fjz>*8}aGLRD0Pf^W zXa>?R8t=0R{u0DkN>f;^LWSDpOT&`0BnTSKTRS%RiCLebtkOP91l}9l$Ndj8n4}PX z8RS9dyN7bJ?y+mifm`DXz7S!LZtY83dmk6;e7!p1ni{EShEOs;d1lTJVuqopbycu5TV<{pmZ; zG*r`!rTom+u5it0kQ$OIxhw(l|0T?qAOuVtpvjU@TzGmai!JbPuDj#f$(WK#V!w7O?ec}O^`C5tJ&NEYba;^kMdK`uc1exCS zWKRKb6p1sET2zCKn-47J@3@0wBX+u`J^S-xZ@&QFq3cl@A=rLl zReP$b<<&DvGZsIah@KDN{;~Ph1S-i>``B1yzy%g{ic_*~#P!ANxi(ZvF@;@KwQ_k! za&)bL@|-KeI>iAGPJ#j-4vG|9!rS1+mO^4W^;J63uVXg%-#w48$PYaDuiVmtd6FE; zYyd$w+kn8r;&JwxYjv}Pd-snBEtqTb=@)WbEzUXHtYmBBi2n-Tz@zLJ_Q`1gnP>5g zre&%Gk;vv;C$w${c$JV*y9>1668*XGSqWm&WnFg3<=Rb>qN>glsp29@K@U^M**A2ZsS4KC?7Jp=ye>HkI)k^SFGX$rtC0 zV@2$O*teg!iMJ`yCL!Y!K3kgy_>Y?=0VYVa1EbXbH%WnULuFQHdOhaH$Y zM-M#>U}i`uYn=?JE*KB6SfTunqPhzH;un&KP>&o+D(LklzN9*j5YE#}XOtXAr#8uj z$|O122K^*}=!`iB4hw!XY%{4B2V@TT!{udz&nJn_s4Y~6jLFK@!RN=i>tO?yzKZt$ z6rgvU7>sW!IqCIiG!IpFPOcLl&=^}q*Igxhijaj5&)LPh?_(8_)^e<*=MCHl%zmV7 zt8_uYn3^~ESA0^9_!_

f)?4f5{=fI(u9ZO(C1me>IbWQ1Ess&}i2nRM29|?tr zHnskE5)ME)*&u^QqC?h^ai>AoXdg0o=KPqLmyWwca+aVb(e}g91)x}Mw(x)qDi)*X=-4J=!f8cCM53a z5QF(hB!}`tLw$uS$uab?jL;n!PT6U+(g7~bI=kYn_ztWm4(-27W?yXXf4vyA;<#ad&rjcZV;(_r2d;_pX)yk`p=S$=UPFo|)Z&-1?qx z-|;^+tJ_8_Xp<$u6uYN?JY{m4&3V3WwqE3XnUqepRidbMJp4G%OzUVA8)}XUJfT)* zI*89^WD(4R6sj_)b!{3>$H+se%ebXvBAunCQyj~JJGjeade^3GEx#S=$o<37ZSbfI z=fU2$d(3;qw#k_AL1@|u%|^5EJ5xdfm+ChB|1NPZO7h7R$c@0d*zwdtku^bdnst@l ztVz!EsgmW*S9~`LK+CT~FH>b3o57+=zj6qdh^v_f&Q7Q|$rBxr)y6KvIexgbhd>O- zE3>&ELe%}7r9y!y_&E6S2VQ~3#R)vxG{I!D{|CTS)6fA8Y8ya?7(h&{7moHNWR}RT z;U8A)!Gzo19OiZKA`0J7h}KvqU5PaI+p3R~DSK5!4<|0ov8XvnCeRQlVqKAD>RA<` zdpIZ60UC@HH2+<(ZX4PE4_4CD{NFnK|HDE=7y2HZ}ijSlTjm5dkF z{D%EiDmk{VK;b{UB}4h&*WKu(3?3W+N2Vf&+&)tX4v98So8G|c$@fhAo#OttG~34^ zcO5!PN~cf}0NY{q%$XZtR9swyRLPjtE}oVAo+1`ydJeA7E2|cExmG-3>g7kTM@6`z$~os0R&>WBC{L- zWbw+BvYD!L(JpgDqh{Q0!%6!k$aQ&bp)2rG;5G7Yyd~;F6c0NC`sQh_-2V4yucK87 zO;pHxAQKu(iokv-7G=ZA|`irwl9K-r>FfCAf2GXU8P4uT$$u zU?xw;*KtgM_ycIiCJbNkmyKQb*F z$eZJow~nV5Zp*X9ePEEBx&t2i6`(>tD6{G{u$d(Mwos~4<`+F)s?)d~uBJZTao=}% zNN!fP=ubpGyx+G-K9D+B9ZO9?oCfPAqN<>J+pOmX7$FayV53%GQQkm+(p>4seI@?G>aJZR#w> zMP!U8uwW1IUym3nGXQ1Fer+{3KM_7v1g^;8{guT_KnAr9ug)1>BfThUexZN5>u zhO1Vx$>7c00t=bHKv>dM?_N!p-oc2+`H*a5BVJg1t@Z8cJudE)vfVq2HLmcm0J?-5 z3Y|)<^kO?DrDx;>PV2_5{zBK}GAnwkx0Q~(6fO2Hg6vxF8m4I`UQMUkJE0zT(+ zt57X1iuUcUX?GAZqatjSBl_h>D39R5KMI=S>{V7koP%q4^4!Nk-p9eh42yW4suRwFP}b)g z7HwE;s0qb>PI7~?wZNiwQM;laiE@j{<2>te@3~YMkd2wg>(3DIYxc(5IWbxRkH<|` z(^Glp3!g)hE8!cGAxZcz>jPRw*@{S|G*GnXtRQuwDP>2GWeO!39e%o%@e+08R{q-{ zE_^KrIN44cl+4exQ-L=n_B-c6vfUnSJ?FTsow=w$}QDvAjU z6G(9{{O0cWCi0&4akqtF(Gg_3v{)2eHaOAp7nfpKY};xiK3I`>6B20Cv(Uhm1ibReXM z*#RtvZ`{~`%>22J#MWT*bh-PZm|uAQ9^Fst`u2X!W9Q=((a{-#_BPm6 zZ&V8fj4j5=iFA;X@{0aHe*kt_%-XzIS&mETNExALiOT>+B&v}5d~rNX8H}*JpVr2> zxY{pPX)QeO>79sR3v6}iDTr=@{P1m&4DF|7q=?{;kF77O?f(C=I09D<+q?G0q^c5K z70zrreo?|EGA?bimlFuBAD41g-ZFfR45Fb#*o{C>6@0qTI@_lN#{o_>>5Ob?tN2rv1Q&J;;a7g2`+XfwG@`wu%-X}o=kuVEpdd=UT^<-k80l;G5A?f zMo)p4U}nv8v^QXu;V@BwJ_R4 zTKj3ZovW)ce=#<6cmeGEd_OMMeNmT9;P#~U6uC~$MP$Ocr>@&FDBEvBJO*^Al)v+egBC2CR!P}x9wQLoF1F+U=mCi0`FI6Nc{d1mKTtWuuZ=Li*K`66x z2zDKhk4U>T62*ggB$EvfE;~9*e?8T;0wMzySkI>g{CazoNv7wndzGSXy$5GgLN!q6 zPC3re;GZSDCQjXoj{41boISm@AWo_GY1nQl-HyqOtueu( z^^_(li8)Tt+mOj##Eu}c57dOoeu(5y9~&(d=@5NwS$+mwFm=A)+AnY~Wn2gkfc4vdX|V8%(3bzES< zK(vEG+Bwk1rr2xk9@Qvk#_U#@7$L&zpivJ_qixur+A#an??vI#l7s_6Dw5b#Ifo^| zVRmVU#}+TF)QCP%8v_p#@^sO+rW1chbm$BI~!sCjU2NQrI<$}=oY?tGk(Rb&aDg1V3)h~NY~c`buH21xq;#V!cz!ui4-p;F+*>y2%XJBAGF2^+7__Ty#h-}%@nkI~tTDI)2^7SCaM z0=>>g1tyzqzg%X{Fp2FYzRI%@LBGq`wv~fO*4QjgtCjw-l))5&QKoUVF`eB=m^_5Q z1fgj6CeLPXxs4Ff`Pe|bx$y-0v6}Xle(|B)Q=hR?DnhJCR6f5;;`Ps~D8U|GiQ1$I zB>*`Ft)=e}&`lPT{}{>tLb&=CyYcb-u@g9;hT4sv(fLT@_r&9HnF1S94^t-6MN-eV zym4?@FHn_yXGyOtU)y+}h zM(qmU?){oCcM86#0yNFrY24+|Q|h}PZX~iMn_}5+UfD1Qi(foxuS3JpgE>exZoFv7 z99d6obqX^`^T;?ovhr{Hn-N$SIV|P^ z1rYUo>qXX4x~)SU&152|`~VG<;bPxK#BtO4tj=jA`vHo03qfo4{6O9)-JZosZDLSp zE3RKTs6X#i-i=A?b-0wK_-!NjGJ^QiGF-%V#s?H4fQITZOPFAqQu>txTNTskA~m6> z?G&=rS$}HN>ul}K81V%8l|&@PPF~EcbdChRtk@FWU)4n75(nV;-|$`^=ZQiKa^^)ZDjLX+jJhk40jbMPl~UB|jx}u5}+?&$mPM7TFmaqtBqi zI~O+fZW=Q1mOJF8omDkug5}F(KSsr?C%*n6_@lYD8)TN9PLV%yxfHr%%b&NAFbIQq z(?X8a0_Tj)de(rK>CU_K4DY~RAhNc*EQdcco>0zM0}<>R9sEp~q5FFk8HbBWg&-^3 zQzsPNbnbN1g&@Hd5m(K=@U0Yi8MML_?Pl*xlgf&SRaK2Mc)}l^L?O~7zH=FxkngKg z=}mY-Z%!ZBrcR|5XzM4+(Ar~Qks*^0NI%Q5o0UDF${S}s%cu6PWRv(SM{TDf%P@Eq z>2lAT)d*0MQTPimxGvEA;1iE3X!*Y6nasoUT?o$+w7%>3!WM&5#yBs}SZJ1594Y(U z!Xy{EK^qIWq&E>gLLMghb`R)aBF>S!U4*jF8Aqmqe!APSE@`;Fm zX@1&j5P7ob^q+7Sb)G6`PuGZZ1Mp1ci|qxI%EVFPD(CY;)FBO7kpA-y8x0nbP!`nz z|E}HL$puW`=TZK8T{~2Fciz`q_t$&31R18^!{bEfD{RZQgUnp>AMbtZ*4WYly<$WR(($9-xun2Sz<5 z;me4 z{%S~n(9m#)hQYzfcSzKJ&FEt0;jw9B)!2sKrAj@G0q=WocO8ejIOhqQtDeS?r z>hIUZdMk^&S)N&sj}(3%D`-z=l|;hXsU?lThU`L08p=B6zEY8XR$%f*tjhGs5|-gI_=)%ej#3Vtf6X)cjXl<=CrgzN(~%E7eb~E z)f1XdzjeCIhUTu68u^4y9Vgvos~sl4(>b*ik#0>XX%m(qwn31`IPP&hRhp%F-19Nj zeB;C7nuGJrCY!*@$Y~X$N{uZ@<7t|2JCC9l#9FkFjSi$ct&nd$%qvv}$L=Y6-KGni zu0Q{5Yieq)n=#3h%LQ{;5f%L5gq{QaSwp5f8-fSL$3l|*GSQt>-tz}1R)n_pii_k6 zaG729t`+Z>+XzWSez+fC%11Fqd`+pKzS^^ig+!DF4 z^>7-EqzyD!+0gt?6E^^5i^yU&r;1p1wOw{*0MmYn`}ov5#uI%W+#`@0uJVwa1pr%Q7p>=rPjcI?D9M2Fh?wA_(9-5;1dnz^- z4cSbo4C_50N+N()tWj<8H=#DgZi%CN}Q6K5tZd=yP_POnP0m>@WG+2PK>L4DkQnYhJH{;|t)qSLD zYZ@DBX}hTYXVeVu0l{Ze@c6p~@fl04if%Xi*HM=Df4rYMf$rS9gFL`fcI}Z|(V_znJ;55GBZ9rE^naEBW(|Y;8G=12nE2w z$q8+%)>W)zQZxG6#T}x6&$Eik&dZf4dBc&QiX-Wo+>ZRPE|wGssFipSZ~D z3Cv5!EBb8)q;*z64;p<9V%-M7#)4bEA9IEqZ+{Pv6i?81j1%z#>H_F6xWXL zufSfHe}-tQy!zgLN&E@7-leTr-Lz{_@^lg3rXIA=UB!oa+%X|`AaZnEE>sS?qWp0z z)jJ<+bdkEhB`k9w+-!B-$L=XVplV9V^jo)c)T~g>i9(V|ee#QLrUS{J4MJ8rE9^`{ zK8e2P3P%;yNhSiCgzh++(Q#$o4My*)X1He9zbbTY|I&H7d^rOD!Veg@F2>elJH>qp~3&rXsAdsj^IT{;oku+)=b)# zb~ew+-52&t5{I#wq7)j%`q-y9v~BNTPXx@qF43x%vDDSn^kfZyou~OWw|a<}SyF0T zv&!C{mdH^l+TCJ~Xi3>^RSOB}7W!kst}0Bqmej#}=;iF;Mx@1cyVfYjQE(A+m`5y? zr?^Vv05D0-jYme{e4@dRge*fdqug;HE*YJacNi=&e@n#h^LT^y(d}hoh8L!F0ngE? zbHcWAE^B*Y#W`UTl;~iXb-);zLIQSG0@cOg;>58G%}`D{Uab;66-6In@OkV6(>EJN z)$*^jd%X*_q_3r+$}11Ds_Kyn$;SEJt3JuMJ6O*&ij5C1dfX<7TY%y*m+@k_7VET@ zBz!>BLj7A5sD?asYnvBPtDR(y$C@#Yr)b>%>9HT9D8kIO7>i^g<#UwnJej_BpMn-G zkCJ5;Cm)~ZsJ(l?$D+BT+c40gn{_WCOk6y>;~%`EN)HiA8tMvYd?gdDONDUyh%-4a zhdj`FCs9kAp}O|o_bl6?An(}f+C}RR2iJZplTvgHpB<0qA_4o&I3K_D%&~IncMPLM zbQz2wXzCtr3kwU-0J|rbRKKgp2F_T2Wz~+RQ5HJhpO2x)HMa=21&N9B0tF=9(e=$-)&Icp6p;3ORF| zyhyF!yMv3{^6u_#XyAU(RRJVrWcSfl)Nsg1ip|O6%I*EiW#q@wVPl}3c4}?paNlDm z!rHlSwI?u2iO8oZ2SCFSr+|tGn8nbP#w9g%mMTVP{(l;b8XVf-|iWG(EbU zKLZM|)20RG2~KQRy+jY{$GYZC8mnwol~xi@X|l-UV+X-gHj0-;n5}2A3`M}gY&OiN zF9<5w?8gs)QJ>L&x5PZM>bMeb55mB8#zxgHr*_ddo-cdg#vCPj` zCRT(az9>IgtF*ex$?Aa3-OpR}VUsQ9Uh8{x+hTC|&2Aa>J)B1m&Y7%4ZEa#Eqqc-+ zM|Q_nkmYpY3ept?!N^d8Gb2dfhYG119RJws3#NpPcY3zIQ+R&pSIMjS?MBk^{{F z6J3%XBC#w-oYp!Y`>^WE4e@Uro2Mahx|zp8E9NUZ(Q0EV$QeF(#(D~By|PYhnDeU3>Dt|4I z+A%0t)wbxr^awI8V2eO44Tvfe&S$yA9qSKTBhKmwu=u{{nUTnl-$`Fc6>w=G9<+Ip z1Orid(to3!x5NgeXF)d#KmSy|<)1T70{xZyn@Itl{_uc#tgFKK%e|%)(qk`cY%Y5s zKdLpesC?XGz{KuFFVQ&v!^rN}w5fu=($>uX)dIA+bRQW-yz8Ym9|{YI{3aeU{V8(H zaixK&*iFL8=lx38B>Wzf;r+SaI4X%D<-1OaS`?-^)|Y|lNhkysAf)H>@8+uTlayiy z|1s@Vh{gz|cEE04jP32%$c=BEhcxTi5Y{SUx50#m~U7(d5avWs>EqyJ$$N~KX#B1#ok4_OcNFQF7JB+*ac5>tC z!8YRe!0j&b92!IX03V()tHoSb%R10L16}yr<_NEBloLn_AL@g)ks_KD#+;n9v+a(M z=3o$YzRfQ#UMq*KxxSqRN_w87=82Bx6XM(4Ea_P?1^0Y$_xJ{)JE*JJQ?I~nUrtKI zHgD}8?uR=G@l8Lli*9Q26f`ueQ86A$3X@i&wt&#b(oU+2zd4JF1PwQp1oQqVcP^N4 zCwyyQwC4{r^YO%f$_riuIqy>90_WK5zH0og5TH;pRoDMGroBvwDHh29F@B~u?+~*( z!%tZtcI;R=c)ap;y9a~9WtR?BQo2B+OQWL77DLP2d?$PlLg)}>r%{M8g)u|ONA79uhZk)DRvFs{7#uIFP9+xj5I)Ysj_;01x*%Psx$)#ZKBzgAlpXN4PJ~;E)RE5!!Pv%TJJo>CiK1MS5H$=p+ng|Pm+elloA*7R zG*uGA3ELn@PD)BsW7dKx5nb^T?#t=MEAIQ9|Hai-T;H%r$!miB)L@J3Ri8Mf6FJ!s zVl8>TU>aevhi{R^ieT#<+rtBEj0l+zuT?yOQ`V*)W-j z-I$+egW#_Y%A)k4BBR0pLgpz5f2PNyrW+tDJUJ9JQ|G=8lL_H$x^O<3hbC6m()M@B zDtFK~X~^3Orf3B!#QVG(4D4Xk<&KJ~#;##^H8n?vb;k}p@y(EuPTr_*wDvx?(M$6h zId}B@eefF#x$y6m>7iI2;|@6xMyk5*Cc^{DaJbBBa%-=wTR2n?g~$k;o-@|8)yhgO z#03)v-h47e5=iJ~`c6CHEv;N6>6c>Q&^yXAsm2G1-r(%y#ReqwV*J9z96+e0#*h}? zi3_3BPi*Q3_S)iLP$2}DnjEqRahT`R&6Fw^=-|;Ijj&JdkqD&tUKuNU4X?!@g{yU^ zt?W)GnYoPS+#P9N5hlPo@$$|EQVj z5y*TP%XfuNqFq`LcN}2I(T7%!@5C%~w|&ENq!SQW5FVrAPA)=h_h6y>DjxDEGC ze@)cNQIJCSqa}y=_+&cMJ8VWf$B{^)JT%T3IsJ8bkADQf+Hr15$AB9(KO=>>WO6NN zY!QFp0k3+y?Vv7r#wxh9e^0~X$ven4W_zvd-y}w1Vd6_d@Z_tae|t-glp(V7d=)AN znXf>+wma?<_N*G%B*#9k6<)-Gvy2yIUa!M3-u7dBWH$n%Zp~%+fM^+u#I;biV^g(} z#e8@`MPU=xBU=WtQro+h5XRz0zlWDDn!U1g3IjiLNzkhmLiEN!cR-L(YZmHGiRjPw zkm)@~LDS{4$t;iFB`E0{1)#6=nEN3{%nR}|lalf{FTd*$O0Yt9kOCb} zL`q+XW(MPrIiwfp!uU9(6av`9XD@b?1mm6tE)PhCN z$iMy;#m)e+7@B=NbGMz~TtAu!Kkuxx-@GH#H7qpyytvwLESpGt2)E@_wn|eE9jhwG zQ&Iwbq)99Cj+pKpR(GGbLS+sH1Y7+Fv!a-|Gf-`?VmP7y=9;)EsGpqdvsE}(K>H7w z@>Aew92ZHf)YkMV%W>_0V@%BiJNi8Q%=dN&0PU{Nx$HOEr8{{^1-xTEcGl3%?7$-s zHFkfroX;iB!-ikRhnIT(U-t+ef9HsWCVfKvD!AVaNyQ}rn-`*SDFs$Q%mYeo1)bhU zCo%0rL*mcxv&YHaD#-=f(l|7-Rl!@_u>}Vc4Oo;Yeb$pYoxMsuWNZYyWv|!1TLD1@ zExac@&Cggd^@&5mc)M~>WZ@~J?R*KI3Ymqn+H#o1L50n&taS201JFr*JKrm5rQ|@F z`*0Z$r}Ir$XiPg*LXY>Vz)5a7JwXw?)Xye7wq`swL`uSj;5!Wp!`g7m*_xF$z1HLS zhm%#WH%wi9Bs!GTC>gy`pP{TP2c9*;E^WJ30>3k<%1Y7?Xv8Wh(KIW~LEs4uD)$n>@wPYh}W7yGKfz*pQW<;F`7OszMQ2 zEO%}mlJG56$Ep~TuKUv@kAQwVBDxm=GeEU?ZewqFPT%d~BdzWT;X&BrpNv;ZdM>FY zzuQRHpN50glvAdZ2n#kWNMx$c5nFA`Wr@ntJG$)>y63djg9Q|EW9sb-$HQp^avf@ zI>-N-2d5ky76n?(mH-f+7doD4fByVu$eQJiea#(|R~O(3*PqrIL{@B9RwfdmPHVLsTc36lQclB6%H-Zd~n}P)omI zo7eQ{H=_ig@?iRm>sz*l^8uaYT)*X+*SO?JCR~XYQlS zI=@%%mM&c~s?{Wgbp~zTPf2NF@6m}Eym8g`>D-x(f+fe&kC z1}t3VsK_%F0kCW}C3&%8f&;pevwDH5SVOoR?MIPUrb9ky@ruQfGFU}KA=yj0ZSDyx zO)^0wO3gf8|FXO@4$UHGRnc!?^Se?btVBs0onQgF&*2FHwt3CIttlJ3ie`{D+hpfz z9<$Ww_!mN=ET?06({tvRg=#0e;-1!?vfFg?oQ3rIg=J36INnrtJ^=eSEOn+IY}cAy z5tK%si!4_?8|^EKC7L2*m^(51{S$L=RV(iz+1JL4*C_4Q4|3$r_kRK(KHa;&dcP?3JHN5FRmqQloW36M zNjD?WCd0hPFA0iG6Dkb!HKLe0ag|mLx=gnyYY)@jQ8(J;^g)@$$M3<$YxGPt9X24b z&-{y*lpK;&wIdwJU2#yeS*WS#Y(Hqqm8HOR7<@csCV4$d{UQSxGyI6pC=1u9`<7h{ z>sxpo52;BGD%u6u>pz$JD3rzr6voOytq9d$p^5bcw{2_3at^1ydUi)XK!wLrUTZUB zzWxcb;lFJqAC8#)hD9YQCYhw3=*-3S{#&NtonBJCSjKx}+u``+lyG%xea+kFw)o@s z$D5%fqRK!c7iW(okN)XBb%wypshz{51Kwg;D6M7ciB`*XU8w2;`i6k<<$b`%>mfAv zF?FL!jcE#m}7?5tjpK6eEWWFRlGYw9bQ#k4KsJD?^dZof%9!az`AT&9_Ly z_IZm=_q6g(m2U(WGw+v>L0*sGr)r0l*LAlVb=dOxqNx?ri(%Ba#yV@2*NPZMOIqoO zvo{9WYl(so8p8LJkFhLXQlyl~{?CQpNjCoef#8pAYVW`J`#TTVqulfJcI%HTgzN92 z5FhzY{zv2PD^W^Aa-bF8;TeP8M`@Vb11e3=mv%M0?_(>r-+kSd*$Mp1H{CXh@3wr; z-~2xq4ji;!BX*4G5jFGW^PBqi-t4>-1Jl!uUav3MbRVoXdO>s?Y{>^+`l;d|-XNqkZ6hycP?z`x3?rhYsElsyw1}w$@0zG-P&8Aww+xZ0#Q( z*D(hqF2#0R^LogxQCZ+u#HUNLFBa}km)UY;7n`kAPXZ*@S0w%uB=37MuSan*PY?-n zW5J;Ruz|d^VW#5)_yft`); zJk~Up)Ck1dv+2?~t6|K33r!6-g68mFRI-CQa>t5%2I25Oc2je5azLpm z?0RE9T`>LrKeT{lRYYL}=zbDv%$`X#b;%$Ew~InMXp20-pdjPse18`%iCt z3z#iqf3P;(%nGk4;ISL`hw?HZd!G4^YOX)0pPly;`mT=0sSLA`v`b&n)x|EG3P#0M z{rgW(Q*W&LRnP1E8zgj79YxZdd4-KU*tR@S?*^LcMT!T>?nB>T4e)lXm~_HJi3nZ% zK%*dDBUa_hJz`xgw`OP8tk%chg#QGom3`WmLT@7YdVsRbHnYzeAa3r%WB;S~TXsy! zuXEOu-?$)#3A;N>yO^{uut2(eEB4wlNWZ}RuYB7~(M+w=oU+`vAzA6H{d<%ufNSJ> ztQ2GX5Os8}$#?43+?<+;^>Hrh1ghM>ip6U=2eN;#JtdB|&tJngo=Ev@X1xSX&p53F zsLRU8+}##2)JLVk4Zmd6hvCDcsTuH;P>QFFD@}F|4T~Z9%(PaP=lEH6fFWzu4C!8{ z_G73Nc*_Rny9QUc`4iq}3u+lT{P4Nlx(Dj&6Mg9}*+1B{&>!g~@OitKqb4V8!jxI_M z-7@+e#bSlBWmC=I)1!_Xk1DHYDl4gQcf@>3!B*Hq5m8hL-;z{YyGAygnf`Y>D~xibP3A0K|e{-mwDC667U)Z=~^*feKZ zzp>h2=elK}RD>GD1W9FSvdU%H<|xNZl#(M>N>vgxHwd>}lC+SZb|Dd~DdExq>7XD> zJ+EewYtNzY&F!_Oq7CJ-aa2=cFjnX!n6Kq(a@6c;I5&`n$L{am0Iaa%hRKstF%_bD zeLiBlSj8HTXWR6>{_;1{cZx>cYTUs|)%~${y-xqdhlJ6iL3D6UXQq_+OueT2@#}+@ zbCIxYG>FTqHS~UT^6X0TzzaNo&SZbKVOENrY3-VBpHO7BZCO54rmSIZ3jFuFo#@Gk zkpkta1Q_MmH->JS%Uk2L!t+o2#289myGQzDa_iW=m?G<%VqPw`qVXr_6B()s6V{UB zlmZd(@-i@WNL>6VJah>A;ucyMV*B`3KU5)1@R!+6tIxBm*H&fzTLr$W8E}l7wGhzF z(db!tE%6PuYvVhDloHPPRq;V)wsLB+-L7U#hAxI$Gy*f~6tO-lAIZ%n`Br%D58tZ_ z4Q%XO<@(H;%M=gm3_)ch&}d&zjOXJf#=`_u|1g)IadU;f!N8NARDwkGgNAE`CoonquO^@&#Y)vS%O zmt%~)!@mt-8;mk}-?hRHzbK2pZwu72IlR0?UyAES#uxl@Lum={Dv8{51x`EOBa1uk zZ)ilS<}7XJEo}|_ulFCjuVWQX@44N)Gb*dw(gVWEGHfsII?fq{wfRP$;mmyl#|S$8 z`frd++^x=p4_4|1)+-IKRxE_}#w_0Ns%6FJ3HjR=TKK=hC$bs6U}`mHa1zj8bGT&6 zg>#Y+@2CzzLZNI2}S`)v`%BU0qdaN!HLkX zf$1h{JkAAz|ByH+fnswS1%edmW1+q=j9NprKlec5{Hd2)L?nd`ebUq>+;*HAeL zG%u9!$rwZ#t5Z|;FmzsS<29-)IXiBTFK_aC!aB~*n%n%(hONZHHeu38b?#9F4((#g zOow4BdTWQ%bz{}Uzb2sL`w-AJ-Y7z{f6*+o*k-a`A{rOVcPlmr^moht?tk zMQaE-#yOq;O6Q+Xa>DHLlBP4oCBc=M<)+e$^YtP@OA}+?1+9Yr$TGtdw~xTu1f9jJ zy0C#@WnNlWo{?6>=D$(mNhv25Ut#>!q)>+<_Z}l>X2@a!sMjim zQy%yitwmSYa$45&pT=ci0%Zi-{iPQ#)DDjiq(j5=NUwa`k7Ab&Q-L`y+_L~s)6x2? zx1VR*CXcps;?k@xGZXA=C$<%=b2q6mKSJs=ru3T8iE4ijT8N}P*c1KjRjT@u1*hFiSY=zaSVBNX+N$W8VI}o0SQP>&k+od7?uLC9W)W4eLgA zO!J^EKQ#WHUgLja7tf$U+d7ZmW1x>j5 z&G=N{M}_Und-|ngz^TF|%;r7)ss){X`8n(%v^j(9&MGuoAi1lPpe@9*HH#OAcN%`W zf|A4Juy@ziwkL^zeD}wj&i8DAD}0FAw1T6%JEyT_Xx|O&wkGW_-YOecXbM!IWhi&s zDGQ*NX2hZE$qhZVp4Ee07>)}d6XP^OXADDSi3O$1zca5isq6d}E8sceo#6OYt@`Bj zALPxG9m0y)I}DilH9^X1X@4Ic?G!)W~5>GnrT?L z+`-Jb2^i1BH&=;AjqY}n2gSvCZ&jn?d*%w!|mSjwdFWw`>bIzY*^acxS# zXV>Fasez}@kx*LnNi#8&N|O5NFgq`V`-DQn~Ug~N;Unk9$n zZz8%eZ9(i*s5lBNO1$^MvcW$YaY+Y5uLwU*g)ii(%go72xNPMmR9&unE%=eN6`%vO zfy^Wvf4-)l!`bK(+0OKGx-#-nWg<7@K^|k5+mX9rD3+3xeZAI|5TETKClTY_lfY$H z8C$gb7M2$*B$S*FvG&~+H5@9hAa8+R(7i@LTa2A3(>!CD(jqPrAjhxd9{Bf6h`D;f zYUvnD%^apKdS1t(?I~2-r>hV8mpeHU07a~7rh>E+hh@$s~I((&D zXCv=q5mM~T%1e$29r(9*eFl4xuC`x?5XkZZO1LcD1#ahcIBmabJl|6~aC67{L73E6iH8eYy%C9^X%#{ZlxgXxUw|JHI^!32X$dFu4_22~I=u1&*a4tj9 zItN{_XfqlId^%131ljQpQNUOvBp22!RZt-HmB|WCTcBn_k>(xZ*sJ~f@yk6Ma~w+C zm!x?8N1Y~lME60Pj|P2`)@s?TmfaiTOPKgpG#;~5eLsFyrTnSkQjQ^y2oD+RC&+j< zSM?cD1Sr)Zxcq*vjT}bjQ0mOgul3K&f0d%VMx?cbRQQQ{fQ+#LpVt@n>(}$9 z3qnF)b3aTUD&G z{CicGMs5wXrQ0ZUKuK`QH z{`}sejz%f>{HPVn9|VYyD4duBN+Y@4vJ&yI&P*2&r)lL{j#)G333n~63Nuu|5uo@B zng?el$9)2g#uv$05T$p9d`sjOFK>h_YBUQsDzbjh6?b1G_97a>GKm%RbwkDyJz8CkoDutO!j-ncx+rK5w~ggHx)DZfTro zSf&SIy++(&BC0t+7o>ySul% zM-Y2k$!R8H2LzNs!coG@WR=0Zbjyc#@~e+_F@Gya8N{$DDgSG$sY^-YkWDxjQN&1= z%`A70u1Al)GMcjEu?w(xet%|sbzN49YF#SoIJmyK(_J0ER&F!!i~9*5A6{g2*cwjX zsh1_qkmMi_DICyw6?w~C$9YgiQMMV$NJ_Y%Oel!l%-v=yDrg4RpQIS4;SS&;sq$^xsc+2A>CMTch$;4E@D` zl7Q!e+F#aHQ`GKZAY;K41(aycu2BLF6juq)-o4f6 zuA<$fVf2l0Ji-b?8GgoB)R&p$>TeCMD%!n@Uos882(z@8rntEph~eeObL3{4y7!NO zH=p~zT7drbRypOc%Qtk9pS&upreNMdzKO5am0XdyC!0E@>hu%INU{Oqm1|w>t@S!g zI@54YWUNXO=4C%CN=m|iF^95vTx&NdC z)0G~P*J3NU^X;uCF%bUuRR0{xsC|UnO!xO-)^v_bN^BKz4pUAw$#=NV)@i|%BWyhh zWG*6M6!gRP9L0M6WduiMDLzv6$} zq_i}g%Di=wtr;^g4M}~~&|p)C-TUo~znK7sqx6F5 zJ?pwx zuga&JuCu}Shn=!Dwp(63JgxH zms`fJ=vxdQ1Xg<>O>P8BXWm#$#eZmOObZcW>;m!8G7uyd)1s_3Wd@-)+N zAL(5UWeBZGr?{=@Cs93jh}agYdU65r;|sR@&g~%t?&WLgC*=m~A7pfJ@y0nT)vJ@| zE|}<4u=)4D&q!_XHrAyLOWWInYONoxp&P901T&NXD7cZum~VI7 zD*}}l-hK2*a*!^jx`Ef+-w2X2@{r#ANb}uNW%F5D&XX5|^8a~~K8Ymg`1}!Vy3Ei! zKCvJzl9B+VgA;x8swm6wzlZxpmXSVwDTA3-Elku0Az9lI>AyKCz8_`hTyIRO3~o%?ykk%io3fL+_ktA z4{pV+xH}YwKkv7%eVT)nWY)|xkKB?Is+DuZfD3^n#ScEhjS*lC_Sv;Ky1*5-3u>0D z`T;BY*Hw}|rE{r4Mj&cy#EPHQ5t7EZpsv$VeyYzFvQub0-J0yNuGY^aE-HmrMO!uO zr4W@wTI$Js3{#gep%hTj@kvc*BJwrkKpwFpw|sgE*Ghtfq@6h%XeB|!Ea_=n5vDyzMq;zYro zXX@A+gnn^piIO|JHN;|HKT}tx@lKJV0Tn0Wb-8y(oc&aS9?LVDPwS>QA>fL+OOITm zN?+T0jPnj>mYaZpJv4mJ)9D?CPR4||NBj-qso@4uTLt$$M8aX^8j*5 z`ikX(^<0bzaUUMuotHmC^CZzV5k-;nmJZN&Qmi(!W`WD=xxEvo02Mpfn=y>270?_ zeetwX5jTk<(`>e1R-0KI>L0BX|2R{yVXZ9w=^Pz?oQ0W3{kW=)J`yaj z^DxqUBI9U* zSOvB&3k98_B9?7mC$Ab4x9P?(Ffc)=EnQ+4vt0JCr_?&AQRZsf_ekoLzcw!88@3v5jFCEGjs8p9FS4`*X*ccM-0=QJ&>4C zLK?J#J;@C4vC66R_l}88DWsu9Lx*QH|8(wGWYpaqYid=t*^gJI+HC`#7q>Z^U7X~- zhL?q>E?s3Zl`F3H-L%nwM)l1cXwr%T9W+%@PsI2Rj05I$Z0}`v#{n+7w=2=(wuKo` zFQ5-pfwYC`Ttu(m-QYfrv4r2K%@>q1!U@OEoKgRB3o9weS2OF#EgQ#5Ji;u!-#BvkP}H<*K25}QJ&uhnKne$cFq2FjCqNI2rlvEpZrpIT`qNZ;x(i4wGU4*7ijpG= zk+$oKtHdoU531nOEI}?lHXK!+*RH=lPDD{H?DbkTB!J6Spvgu_{o|6-tgiR;U(%}q zy$VC~(=EA@^s6N<8vPYdEX{MgE@Wzjl2u(=#zI%kc2*32=o$FJc@k|K@c*6Z`sQ=% zFyQp+-r2n4)X2b&qNknZyI`|TzxegDWDr~bRdNDNB82IQDX0ClDIyvx(Rl7~nX~($ z>lprIa>f1Skv=6YB(N&I$(wnfmYhF_jVG&Ks|BJ%4^S%(moC1xu7KW7W971tM8d)? zq=O(r4ugXEj`4r(mS!V8d>Q zwl8l&i}AaYCrQ`FKr&UbHDaamqcu3#a*@pimjOMUsf6)0KHnXG?ph;kQ3xX zCzRRHjz(fS4+BInW0@N2wjK`UgiA^1;^R;ygCp&a2|`0(7HJs`OmVDaaXdVPgUKxN z-1vP3u)x5=L%dWw;|!uv85M#aXerSEq|VIafQkpr%<$sRB^KvXBvUw^vKbs7hDN?v zaYQ8oBQ=@vJp96^l^v|PRHeN75Y?gmsZ^>WM`@_RfsR5NxwK?M=P27G)-^v3!v`hd zc~loYi4^@oCo8ICIM2*PAe$6%(tbQ8WhGx|0oaBeplHgbMZ6t?6jDY}4j)_2KbhbU zhr3*nAf1gdjAW%AAH^P7QFz1`N-u&3WpK*~Qm1hO*9Yo3Ri$3Gb`ztpESWP)45cvp z9eQWuG>4{B%R>VhQbrldkpq7=K%;KpVUAQkNo|~DanzRi-}N{IBy1Th z8KD6)7SB&7x^0drdib{*XFVm1P!s}6EU&M}@7|zKllxS;OZi>CQ955++Wgug(13Fi zC}!n7Og4qEVp1{wE%Y+E`=)C+q`=+g?1+GWu>xS>gYWk~n zhERNQ*!z&+%L$CLciK}--j#b#=eYR9Z$HAf+HO2dSZuwN`j~XUB~l+OOF&;f^8eQN zNbOsWU=Ke4{a_q^I6K-H-YV@EQ;IsPnWJN0?>c%bkB;csS)Cn2@>cxO79o0MK*PM* z>l0PxwL2LsD04A{@~4eEt6t41v+#xk9t-l$;Otn?Vt9R0kQ zH?}Z*(PQ~M^LOr^hY>YqyW68CqSh6fax|*=#6330#6(l}hALx%QESkB<7hJDT?RTc zPlqNuvZ{4f$De+rs|P4I=;CrlDyZ+wxr-r5!Z~n<<2=lnzdEY1Z8#LwxNaaTmQWw% z5;-6OplaebmSAXHHI6^e|ajX#4@|iO?t9cab zp)t2ZT$oQuA`4fs~cFc&_M#ZIWtDy3aiP2%^ajqU09 z`^XzR_T3?D&QXe4Z-=IZ8zUnDeTwH&x}md()*~T1_<*_$PkYt4vTJNXq33zemjxD1 zs#@uyjaDl-Tb`FxPN*lsdFSFG?)??FIdcf#ZAA?u`+!bLJ${cqvkYtn=)<2{6_drA zBt#vqM8+Dz`?}Ey`Ytfkal-a;iSEOSl)<&S*6o|poJr0^Lo8l3YZyr^{gY9@j`;iT z+v%7yobH{sAx;r2IAnYT@k4ldl8plJb zKWuO-mpXc8BtzvPQ%LuK5mr(Rhe|7&a}u!Tid)(t&9laXFn=cU$3>(bWN$nNd_$ki z(Dt_7Xq}L&jHveeijdX7NPCmbFB4uE&NBiLL!D=xMnzTgnThKBh#WWQH1Y_fP;cj4 z$hUv;xxK_3TaMlWkdHcBhsLa*PM0rgnq!&e#^X^r5-Ub4c-;2ttmQE)xSl_D~Qyv2xxIDo^qeLBIr0`%A%@_AerQa zv>0NhLF{7|wBu6GW?gWKw6ok`5`h%{?9uA`;hrLy`$c8R6(J^)hnrH1J=qQ65kb5g z#^bi!hMYV*wnp)AXeUPU*G>O|4Wgo}G&wtb$Gzl<7{k%S#`j@<8qOTwTP@mXnuY$A zyDI%$GM2bzxx;DQ^ac5PXBOro`2mtxD&_$o#29Qt6brxILVBMfBu?ZFJBAdsmp*cs z9hLOCq$HyL9DBD?Zzlv13*x#~5|Mv^2%DWF%PXjZg(OE5!`=0ZC=-h5!%DO_Y-;C} zMH;D|Q3RsU(cp6=<`+pq1vh>-sH&cI@K~DSc!FB9x0!~=@kQZFhfzXs#LgSP>=hZb z4Z4Ga21`7F<^`5`XHPV7IEv!3{ctzS*=CFdnp}MAXw6mm zGS}ENuqlq9X5GJVND;H*RxXxV>wx_TzQg$kwT`DScKK0{8&9G^kK+F{yr#XI5tZ5ZRuk$c(G z=vT;u^$UHDOqrWf^aIu+rb<=HM)6v&$#7Qj@l=o2WF9ju_@>j^twgOg3T)rE625M` zWXETbSg&(;)kFY3iAie#^G_@jBa9Xufk?kDFTsR2V#0~51m;oZa{WF91xK~Yim7y3 zsfvhjf%G4#JhO%46A$(lm+we5&**qb?IGv~;YXn8&r z%MgjdM#0_iP;khOyCG<#dd@@#TO?tceeNhWY9%UBWA}F%uuQ=AU5$!NGoAY!YT>*e z5vzGJce46NHv|9$oI9KALx_=n&4bk&Eopr+Ewp!ew~S-)Ltzu6XDyAgxVbk6cV#dY zXL7hB?UgSof(tQ&!mx*CS~{8la!By_(KG`6vJywPRxNt%`#U3kMjtkk!L+no*u53d z4Q{-fz(Os%6DawM)fzQ3H2N`z*cBHzSln!G*up8xv9~*QpD|^cSbO(`rMcII?}-!` zNLv}+FrJol0&S1%&0j);${4_4zGQ*}Sy+GXqZeu8QT7%9SYB(icv5vlg^X$Rck7u= zW;0)%!;0Gl!xUOYr#THkkD-=OB9ConYJ$HG!&6}yTK%XEd%Eug5ja3QTi4fi8%Dx7li z>rWz6G|`_q7kevK%Wwvi2As~ZX{aiS|EB*nAa=MvkB^FCOVS)T)CadXXE5lIsJv3^ zXbNFK+sYz|E-s=HYCzD|mpvhVCDM@KC_)oKisUb4)!fyYk;Qwv!oPh4jLs#Bz~Y5w zg$aLi^0p4xp};XIq^RXYa#>;JGG2Bwp6%VjFx~8I)_*d9;>nc_R5vfK1)EKmzLap< zh;VQ$n830kkTG)ey46f7x0JC|14sxlg^g?gkz39&st}p5}HJK z5Ea}x*XL%JsT>>6cvW(cjlPc(=;{U=V&4BjNpxNv?waH~V8m7Y%^Gu4y|kE2%oQ=9 zll;clhvl~nvct(z>@WKIy8*jL9>i2G6ge>sCon%1ib|x2@5}u>tp*+wBA)Y5Qh=(P zl1q#^w>ft%duAvoGfIiWijT^eaC=G|g@t+?5V2nptlgq087`8yyheHHG~g9V{~#L* zZ5>@){(Yl}q{EdLC}BCJdt>_-?H zD2(0XT@THIO2#*+a)mF}q*4F*#2znzJxXc^WAn45q7Yl1Ew&zBo^oGx5v@}nD{vH9 zdhmC>9kH4y%jZ$X0UhyZ3#zs%6CEN~4G}DvZE{22jBOgE3?;?HI^uDpsS78M%K-OK z_67NIuHq5##opQODW^_2j6`!fC3?UJUwcWxi83zie|@-xxUY!J9Fo+sXm7v0-~S=J zwfK`#=)J)`3wBJfB!7|*!;UQ>ulkZ68JJo;kVM#62-9c<`|T@+-pO3cSYq<@XUzx9 z5F_K-JIhLBb=Qxc%wkFyurN`q0}Mj7EtZ=iz~?qqn_fXZdfyHne8vYMqK6EJnbG3X^*k250v0?mNL9X> zi7`^Knv973gh^M~y+_%~#N^9b>^V;PDX~{>hA}jKd*&|zzAsX-;eNmrcNr@e}Q!nS47^#BR zEOK{&(rM;OiX|!~jZ}rb(OYY!hx&%6_A@JQygeP)*nT=9%$5W(Xk0SS3_p@nOx^na zzI}UnyZ7HOJM0^>^Lst{+SXt`=W8qw6;2M7;SQ~UX0p+jJm2%jv1YF*Q=c{!G>Ook_A2%)7vtQm%yB5=QG*U|+^)4<#zQP25y~Qb3ElyTT$(iR}pX2H(G0!!h zAX{d6W$$X&kju(sPRh8xW$r}4xcs-``C*TJ1cOSN4nE@I=dLlV0}I;ZcZ)nbzbxTK z`5$0RLc+*$_LMJXc$@F2WU{cp^+6Y9Q`9{R{b&=(&}qm_pxw#2Ddd7_LlRBRaDFVN@zj)Hki|N`iZWyA{q3ChIQdY+{NfJaMqex6jGagib)oL{7DGg4`KPVrMU}Q6=wj z9-i8GJ3bmUh8U>PNp2R@7N+&-o?nWJ4OTR?+9bAx%+X@3grKdp7}+KS&|V^N--|DY z&S7BY`IanY2Rb<*iz$|j5e&;~Im1`u z=%u{#VEY?_9x*B7h6Muk_g^Bbj)_HDMI}EXUjrRslbDknA*|er(KyZJ@1Rjq4)gK! zE3ZqpFTIJexfRN~MAwr{X*GrbDT;38qE>Zdd)M)+9Z~8oQPK-EN7pFXHre|20TJy% z#lK_bsNI4^n_s3+f-)CJ_Bg>(agzfU{79FgNb^ptdS6uDu4aMEd{Q_VAu!m2Kui(p zel+L;zVT3C>0O5~*4X%2Y&3wsq?hC5+7-A`!&bxh=Y!%cB?A!yBhPo~CTnjdnSLfk zj1EX57IS746Bj?Sbrt%qB*9DQ2>6as=|EKI)wSqXH8Wug6xJ@-&hHQ9eTLd2ND&Yx zDCL1)zMjQ1o0n$-8psnt0wb+5wavr5NyBU3PiM102L#@806_*Fs;}taoPPGEiyyF* z0cH7z+$Cp*l58Wb!*z?sID6q9Z$T_XbXD8zCtvgcXv=(74xQL@j{Lg)y*izP#kNWI zEegJz)W}q-3}W?$#=|5p+F9og1B&tCYDnc8h3>YE7CgJ7gq(W)@nVwXxzXt^^5tg& zyH|ce>y4OKp4MoA!BuTV^e~m+kfRdEU$BqfL&tDZ;_R~7$r0RA1kq43obQVgk;hNW zs>9ZKS9Nhrqub=+Qq&b1-=Rj0ER{yZ6BSMm4B@3}* z(QIv5LeeI8%z+@xV4mQ*;lHQxK@)PMr<{k;zJa@9o||+1iKi1=DWaf>UhX>$?!X=W ztQj6d+7(NAyx|6ilx1x$lcDIZX)TM0cu*mb>^`DO`;=?5JVZ?4)C4NWcHRVx&YdLk zKt>8AXw#RXl72;lxeRfeBFQmK-e1x?aVW)<|0sQK*qwLDXEbPnPXaaV5#6u9dh?Cz z;-L3YiqnjRi0v(3s>N^MTtB9uC;=kWHRb`PJn^J==C-=%K#-Z1OIFQwp^jNawY;n@ZRbA=H8W35Z;{?z@E40m9N2EkSHglD08$|P0LbxxKqV1%RU9!fH8D`hF~W|0 z+!iY}+rH-8{BsqbZ^a0Vfvw=KhlXg~_gh{#88)Hm%QfEp8jF#duBmErfEQA=x{`Xl z8dQe6n{BEaArbkUJ*sDXtNIl;twn(#_@gv3r)TEtqb>+_kY1^KKSBS_lOdyZ8#$7qS8k| z0s?Cy_bvFZ$R}0LFiDqG()?mbS~D{)Bzo9N{sFEfW~pVJS^F32(1YNZH&+t8L*#J~ zVhbYt!ym$hQ0o=+MOXxY7@inRI|_-6te`KucFDyEnYLpi3Pzd73ejPx!tojPO4=0U zDQG^pRBUvhj7u&DL#OsyMXd=#Sv@1){3LODf{QYW01QN-1%;Khc+QbQ@s3@+mi$94 zvg{#@bi)I9`n7$_(7R&%fz8u9#t;^o-VXj&L_s+~=$0c668wG9a`Y?f&oicDWq;kW zIr-kzzG_Xz_fZnFV@FQU5WJQjSeQW3rwKhbvW+eGylkvituPDt}@hI4<>eEal6W0#@5Ho+oK*WaFb0O`}Er`S!P5uf&pvR;r z3qX>dsDBJ9K~4Ta3M8yrQ4H2*c_|h&)^=GUMYU}4M)Ae`o>j`z1M2RPXj!K|`j_FN z?IQcLaS6!H=~NL4h5WQn$QT?;2&uYoN(n)ml-(jIi0vU|+3wSsUJGiX!d%4NHsz9i zh&}V>tORVyoY6iZ#syQvpIqwue_yZ>{ITNv)K?#7#ba3#Xnj})@89itjSC~p19syx zWKCu5LjBkXt=}nJ1^C!JVXi*0WQGZm(p0!y5v-5;gEqt)w+Y=UgKoi zWxfRrIYy;gV3!aVY1kuTVM<_oy~4aIfuiN<&kPwTlj}nZMqsyKd*;B!i0R-cqex&a zv9!D-)G{RfFZ#EpsYy$BuUmKu-+GCT<&va@!_V}YC9+*BQ~LN}CVh@+j)&Nh+!eI~T%>V_F2fHA!Dg97?A+Rx`IX4+oOa-uML2Ec=n5*3U}U_OEDn5d66wws z;h9^QeUF0wpTgCnX=}GbWFl~Ztl3`f`VXuS*mam*9&$_<(=pJjU#C(;VYpFgzXK;l zG8g|;Zv)o2;xMZ!bziW9hj=BWkTE$e;EF*Z*_8h7P$4~frD-zL#p}D*YkI^?!Mg2? zqba|zn2H%t_~GeGxHxP-UKnbgu<6!5@;I)Z?(-Cr4LdaK5&G+!i(fKeNwB>+NJ8uT z^)j|}9#HAYP?2NdRJC#L)y>OH=Oze73CVixkLmsM~nP{5Jj^mKS&=}Sf27n zQC%_C-W>eve)?Pxyp_$*hzH{>~fTJfG`;36;YU2^5rs z^O(xp8pg(EZE~}+!>P_jKlk7H3#Navg!qE=uQ3c>L*K&7uS3Z~qx;KM4M&}6cU{>> ziMxd3=JbR5lc*bvlbBXim9c6bDRuGlj85X`)+P9TFX{69oZ?pRV|mfgdHxN%g!+0d zE-q^_sW5q_2c$p1z6EI8$+qN?S0J}F1>3!8O3bCxq8*`A4}>qpigKs*jbssQ1xvdH z`16B%bP6rZAjw>(oj-3!w+aHLFQ%7PO`osqNY`Go1$|!PU%Q3>auE(;YhUOV_`60F zTf-};bdLtac5qRb>SRCtUG-!iM5dDI%{fE+?`-sEFge$PM6kl5;eDTi;uZgC`d#?W zTFd5ASbV$Zxisypng}E!AES=|8;y=PeZ~BM%AsatFDmMWe<=GKUru(FQe!;9dHy1e z4*&`GN|o(~i1y0GXN4$HnFJO?%0|t&i*U+w zA*_xNT=rcKyvdsmW`6|`NJ-S)X}2;hf(pOGCC42qq0L>c9HLw0J zLnAgzdWWt(D$5|BNJ?^&J?bkwit#5(J#r036}n={4EoVV4Gee;cwj|D=E95|`eOWy zUsL1HfTB#Es6{P>M;t6{_erWBg9P;hds*C%AxJxtLkzf579{+lFPM>2P)6GCTVx#k z+MlVt3_UU|@e!PHvPQ8^Z9*GdtVI@WV^Xk=c?()euZ05L*#JF8R)dkhme-XeL>A-e zY&##xfl}99S+NrjiSdR@;D47U_Wn+3!^5K4?|bjY`qsuIYx{Zr?$KU*X^c?Uu(dzW zmd!H87Lb$1&cAtyW&YAV-TgZ>-?CwOjemsP*QAVe5IwCb9_PwNaUt|0y&A~|$Cy;| zES!#y6)EtX&*ci0EkQ!%r1xleh&#`Lz?t-X|KIyin}Ft3*o}|#zu?qUqgrc;cr)0b zXZQ1OTMZvvtUTJ&*^3s-JJ=_`Ol#?(NMRu%9JOFp;NdSGn+4X}3dBPP1JmpijYjdd{G54bc2G3~2l^$nirXME_wKEX4~Un&!Rl&|28^>Ev=+hr zbhOGHoTmn}%*Bb+eby|IFgH(r(ZT={4l>0%f8O;w&&pui`6Vi@PSS9Lww(8@4y^*% zb}Wojv0vz+TGlv!<0PU#{Y1oFoll4ee?{84LKMV{phA_KnN~w`O-14VFGBvWa%kk> z2>fqD{J#%6UB_oB{`V+Xa-@hpr2e;n86Yqm7HZ;zgBAXXx-b9{)6{H*Kui*28_^$& zl9nja$WV)~f^qT~4SKRaBMtjf2a&Ez$pRpfP?;3r)42a^?m)uoC8*A(nA?UT1Y)p> zK~|YOC6V+IZ4wAH2`M+c~XaOQ}UJT_bvNag&iwOW6jy zWTecqTg^)lyDV*zf^js`J08)<{5&G8M+b7u^d{1;7G~Dpq9+vIfA&Cyu&RnKl?mC^ zMc)5X40q_*!s9wQ-&Bnsj2yEiJ#kN%M-`s-?04yWeVnKkqo;#AW2%VFA?*F%au8vl zhCWo278vfR&RSY$wgpBBtQ2-=>?B-pD7j?c63?gLj=BXd*-*esz@~;4gCqezQt&OH zi}`^9sMlT?zYmnL+7MST8!@-FE$)|p6+ozF#=a*qcl-IcM{o8eQ5CWr@mrEr2?tKU zUGOBUANu#NZlEd(LRd7vZ#Qd)IFl(6KlY6irC%{&CBh~ikqM6K2Gt&{RLZpw_!F?6 zBc+G9GUMZosP1Qc#oq2$SlWq3ST%{h#of2}{aq`dYc!c;G+prbd%+1!cy35(ByFP= zRHQ-h_@41YAdj7wppN>6ej<;#w%DD?nVP|cMlFaqQC6PN7{hdP2R{ujgP|1CiUjTn zX?l+jdUnO*-q>4V+1N>I!Aoz1`%@zG?15eIONj3R%z(A6!`*8kei@yY0)*4hAWYbJQ=pizIxv~+G$iIH z(yL~ENQia1sclYRMt(S3wQyded6F<7e+8{g6_>23Ll>|hB<}0uiN*LJwH(k)QF`QhgtRfmHBiSeqfI6TMV?PQQVPJ|I5cSsv z009v8OnOSGZ3e#;L&qwQoPCD>7-fyx9f<(6U6|^t~GKc4+=Tk0t&R4Rx*uW}^Z&dUri>)qq z$StXJt)Va5fC6BkgV24I_|9%{P`}C~-zWHl;AA}`N4tz)#aM)Ua+VZdFhfj2tBIg} zo>=I`&hx#HO_G2HUY}cLh0Vd`D5L%m`w7N`45uYPqpYDxk@}z_9XwU$EB(5gu3atc zjDtOJuuKR5ml+pd7e!G?JM;4E^*%U@Z)|@U;)?xBc6GQxdCt#Uzz)C ztUeq+Nt1$bhqdCiJ2>>xObIUActo*K50 zbRx+2_?L?O)Fh8>wB#D{(I}tBLPat^szk?S)F?+uSgcfwaN$P2-$DVI5Fj!f9Dosb zMT1E}FYcCWOd-L0Vpy>~c(g!pPv{=&c^$TS^LIobYnTL{0#wUdoqS5aTx|2Q$HJ}2 z+-7Qb_hPYl!Fs;1yev?lBv`O~V{JDdgHaPe%}n zA+a>jzyU!c02MtWQdG*Up=libhxr#AAm)Qz=C{0?LH~FE2lV&H&)hmNqDMAjA!*OC zrD4ac7#P18L)_mn=tn8K1U}&n@KQX@_ z2QgHseJ0@Ns7pi&mV@uYn@Ck)^hkFjVle|q0m$=d*#{FJDN$#qgg-`GkzCY!dMCMg z#quhNj1*1#$75z=Ao#+E893a(KP$Wp_q>NI#8LVv^|QLTxE?!tx7G4dBhkR_1I}j+ zE-$JX&AH{;{yOEp5-ISZ9Ix^}ojNzWb1w_<@4mTx8NE>Qo%%hx@5qQM@w`EHeg}9| z{#B&VGgsu-G}ZgYCh-gJRa0Ei)D$VWZYuw)ArB^o3Rmg^H-Q~vy<(lC3(_M%Q*VU8 z-vRPw0p<4pGw>UJe|{9WTM}7tk<}B%Ggt`9j30nZSVwDN7TnmXSoTzpEzHR zR%I8nr4Hhs_U#0oEc5!iX#UtptO>f7`(5e?ILPeQjB^}Vrq3?cettp9*`Zw738>eg z$Z~=Z(6>L>#?&{Kxup)0S*0@re*DB_{D54cM&6Tea>AFIn-3C*ff%0m_v|gczx{a3 z5(`OYmL)p{n))_ z>g@g_p!Hf~tsN^V0q}HAwNSx(%?J50P#__$tT#JCGLZliG~!)#Fs^Ob0pF7czW|b;BS9t_4Xv{chd{+yvLwB!Ce3J1}nJTF{cTO zq@|?f`bkgYvGG0{Q_TSnGGVYix+hn|Uq+GA5S;R*^F3;e(Oj;9#VmOs9>prh#j?fZ z_E@b(FUzF72%K|Yu+3aJ$&D`Xmi#OM6Jwft2L+g!nSz$h&u2g0(4E+PA|OXDSTtNZ zojV>yv`40~OZYeNl?6yPj3GYPV?Z~_SYVBo5;JD2>o=M*!ABD*YW~Q+xY;&P92rzB z#bN=AKnZ?QiS6g~y=TAB(=uT@+YUcSLywVf=4pSPdYS8|SW=_!X&rspgE97kvG9wv zR`2)0)@~h!L5bt-d?jq@X`RBii&Aw>`Q^U3lSYNUs91tl2&6ten_KFd5`24o-<_O6 zLr3=;`SE^CokmXz_xus@DS}ScB1EU9rm@StFNuS-k*vv^RK_JX-|Pc8ckw5Wt6G?eK7J(!9lICQ$*RS|eE_1|@Vr`{{>`CDrr%$P@Ly1=c;)M1Kp z6i4hrAn?nERv2x>4_l%F@>Tt_l`n>vQMRa8c-~0CmSYZ)m6vkSi z0_76T(Qb;|K@G7Frm8eDUPd{;zASpoE|)mw8x@Z->b8v{EM6b_XmnY_D&;jMnaIaw z{gEI|2|+&L#T6Ae5RMBC4&t*wKp@VGwtTc&fLeQ$o7R^}M5l1-4-Mk^hkreG1qor8 zn#zeQxta=7qu{7=NYu2CUt6bygfLQ_oLG>Pu9^lyM^>BSq-6CSkHNPu>^5I)lBMBe zEsS5Q@{YX8!^yRZB5xQCy2gJYWZlL>*^Cl3UMV(dW4iQ*n>o@La^cSir)1o`{4$Ej zCyY3ayPQ{R{mT579DK`AxjbRJL<+j8Mi=Lhz+$6tc5^<7(V1@7S03am9XahTwh2v9 zSu+RS&kEQcbGCnLCG~lK;tR7)U)!i^usEBT0UiYMhvyH zMn`EV7y))cytu>`l%}-M0g|CjU&2o9&Xvh_M^X;xepEFYQd^b;ofeJoAwR(xs3tll z3Hzpn-IZvX z3tgCvj^(Hf>Bmj14J=B65{jGnt^8rF!eJ{8*bZ6hyn^IZ#cnRFkBPv-3i=Xep{2sr za%bHyv-A*@7?s$s7niqX6GmUDw+F|X$!W{lCCu$fHtX1KmXAL2XN7!_EQ!+6HGCUI zO?CG=&08S6gNI6>s%aa`V^7KnN*U*Qcm(3a52;HP;D$k!*5*~9 zD%~MCi1xt}{!`?tZt-3gH1$!uLbjlN(pqWI3%j#N3Z;IkuDkzjee-7X{q6n~`KIiI z?7A0PU91?V^4=>r>%cL^r0DDq&5Pxp`}E$WwGJ@unt5fkEsMFJa4?zG}z5#hD@5DhOV&MzNd$!!2Ad4RD9C0c((4t;yiCnQ}*s$XK(0_d67IEG1zQx2{^-ojRHHehez8F zf>U$5?D>smk7un>2@!b*WK#oa3|{!VoFjfx^luT~K{r+cB3+y=vy6V)qe%yOtO@kj zbh*XZ{{R8#X)9t&Xz?|~CFBat)V0=IM_0~ii0AK@J)e??WvEh9ugAaS_gp^SBK1*7 zxaOS;iO&&_ihWxA{(~@wls_~`AjUk&94E*sQQo`A6zO%a02%B6s+=)oC7>8(ZcCO} z`C|a!yKbiZKyP0@IvZ1|+i@Sf;TW^?jK0*>1nDePVy|`{W{c=zH4l5I4c{7V-XQ@E#I3<)r#UZ%?DAb7=mN zlUK%bt2MGAIAtvA{xn>gFaXSTQzD@je?U4xaJmK?W?QFpsbN8w@j$Zk^J?P0eU zsdA4vw!+wFc&ozTWOl_W-(0;;+Di6E=BEE!6Y^D@f|aXprc)#XVN`UbVHtU@dz&y+ zd7;l}(eTt02bnvSiE^rMdUN}XEzl&-W42(EZ@Y>kpJb&qggqlU=%)H(GyzuL)n&B# zPH0|*w>#vh6P4ec^1h; zF;+9zHKh;Z`cK}XU@EcIU4I_0uCDj;81GkzwLItF>)ml>KByq5`1dkFLy8SYqWwym z6CnaD%}~fFn!peC?!(-w6K(Vx-$;7qZ}-kpIRD{> z<=>_-mhh6%Qnj<&LJ{^cfm^69b5J2J1#c zJf|&(ZJra9V!E?R=6HYO&A*JQNX?vhc7;$rcI}g)EFij|-c!w=6pa*wXEA~HS|46y zAz7-TIV4kLJN^OIv@%?$ZFFA7ed!|C$?ZCQ;>>0|?YlJZ37nOc%CAVMH&Zn?3{^~0 z1Ek1BRm)>?Ndg1?=+DWYdv~7o$MntDEg1KIE3jA83%;ll1nk<`CN=SZGorH11eKR3 zEUai9PEwzNvnkTcqXi5jvy{;%`V$$r+0;n4*m@Rn@)6`j9wup0moOAB>=!9XtV;i( zsVh-TA;o&>DAk(o{<~tiHwSf-_j6x2W?VWiWV$)fJ}+82Fd$#J@$0sw;f}fTF7YRc zq};p}oM+Z5N2ggscbllfDX3@@Y4egzM{8Wq-&|IJC38cwBJdzXGxLSUdGwZrc-F46g2+<}LJsQG9S-Rgb_WdP@<7+^KE#c*Jd7(W0r^AN2Lr8WnN z{tF{Dzhbw!*w`IP6q|X?;C^?Iovxf)YMWS}%DoPwLG|$qz+}v{RF4=fP9Km;sNC7)`T z?ixN)vADoYtJr}{RB7D#&B)m^|B|4YDTBv3p+wf|VPJGox+%xpTKUoRzyQ=Vj(Q*> zfK~=_{aAXxn8*VlY$j+v=FB32H_mKIqso&r8J%q$G^{B761#Fc^>2B3^`Mmn+Y`!I zcZ;#Hf!pW6_oTp0z`?F<7@b|AKKa(c-_|2)2Ng+K=i+u!Ls9dZEMTBMbSLEgf?@*G zD`#YJv()e+a$(3%$ZAjG)Op7XwQJe=*Y9gBilAXLBk=uiL^(MYobE{&CegzVaq%k%-#6*a{y-)Wp?6pe=CpgTk1O3G8rp+~(0V zFJJMu$cQ!KVkcf-C)GjP61BfDPoe?+UK!#=TCd4XH+ z&+Zs4{_`;feduK!xEq!dFBzT~4c39WniXFXxujzWvtB9Vs;4e`Slp4m2Jt<|kvVuj z6IsnsXT8srAK&|i-U;|kNsOfv%rhQ4%MTb7tk52b;n|l6rB3gCFirD#`-Hdg{`KYT zj&ZOlqT+~PCGDw?ZNNl)opk+QctNePh2AXhbD!E0wGwE_YOeCD)vvIDeJpuyQDzfL zf35kH0gT(D)9>3y_+(elEb>;`V^td-dH$~__pO|Hy|`^lAzEN$^AugzAej^Iwe`+^ zE#ItX1^2d2{okxy*PBkVa&wX^L2MEhY?#z^8l}lukz+lG%S`bLoEsAgq8B5eAp(|$ z%Z;#?ZH)`3;{1eWR~I?46fs0^*mXYdZ_qKW@9#o{`-js)1mZ_-M*;E2Kf>2vF%}sZ zlld9%h*3`o1H!AaaG3SXT`j^&5ukma*YtJikf0D=>Gmk!)c{g9 z`EUypM`~ZcsTRRr$vBacuAt>H>RyZFNX&K$^{?wd@g)7Zy=f<&+Xz z1aeA=E3p$Sd+y_>(Wbe~ZdTb!iU4{PTHJp3{v&-3lUpg0oM2Mc%Cx9IHLRS4^9;w@ zrp@29pDFuV&b4xDv&Lu z8xyJsvL+JpD08Cg)j9~ZHz5}E8{bbcyAGA+uJx6vU?k-vKn=acCh4U!{>Gf^)h!)F zP6w%oU}CTgj07$dEMq~@#A;)mn}w6_0yC3XSnsrA#73ZFmkn zBUj&ykXg>oXT80Qz@kD^^>XHFXV=Go36@x%)y=J~4f-26Y_Wv;?siEb0+jOkArxw? zP@AL?f~6r|1RE$C9*4w5LIMkbBR4FMPdhcClEa`f>hB)YC-(cI`H=Xm(ftpYrOI%M zNeQwinZY;e?uAPkXehhWB>c)~NWfRrNXJfyJr^I({AWZ+WcItVO^c?MpsDMDiv15k z;~xc(E$P^%Er86XVkF|XhaIBl?4(qKFgGLBeb)Fd2xbx_$KduR9NJF zc_@cXS;V<6mgrnq-zcmvl<>biV9mk9IEpYzB8sPOU!&GAGc~Akmgd;`oyT3_ksqUZ z`Q;uLGccZWE`Q_Sy`1rNOLfxK8e=OJP>GZTY&&N4mdVhBUrr#Wo+(Z10~VPhD2V@} zd)<1Q3?+z;UP>0r0*~VS=V=IBtw_k6I$MS}wg`QzC1{k8%(7HRg_4RtgDHtILn-;H zIgTfoV`>z3Lt%rUchRtI1i3%mE@_adS^ek5*0%O>pI)ki+)@)yOw1V-xa+Ymy34Ko zy~7rN-16!kcln|`!v?GV$_H6-al3E_!2UptPiKD=)caGxYGx;s*7#y^%EB8f;&a^!~GM!%(bbP zvbZN>K|eVA$lQ6)5u>TFhn*oF$oo+YR6RcxaBeM|SE64CCLA1@zKDKTP(Cx>x_@$! zx6W=J3XYX4(WTCDW1GCO^poPJCg9@b;n^yJ!)_bb<{j4E7~l%I`P`{53M(c-XJF*F zgSnW?zyF4>z_VU+d21OWJtU+7?9NqZ5??p5jtH_ch4A9VUMJF-{U1+f8P!%7t=+a1 zE$;3P1%gY82Mz9S0gAg@akt>^ZUu@LcXx^uC=R8#`*Sum0-317+(ha2ugyyfCTVzCdrYn>?hM*7W8**>fvWF{kZzk_h17+aJYlit>s za`(pf8sFW~YrSESiJ1tL|BNY`tgMcvv8ar95rhxW7yXC_Qc$U`cCs>$p6@q%-TMPj z%Bwv$_RDc~tHi|$2NX48CEcd;BX}@{rT~nlWTMRo(b8SRuYCYGixM}es!Xo~NO25Q zvy4*Q^2wV9rRRZxX|Crl5y-;5{3g{wPFR^`v^a(N3RQ06ooO7(Y1&?QEzh^V{%dri z;8T9_L4ZOs%RY~yWR?~HZ3dtA345lMf!q#}DKJ^!iQj;eU;InWur1r3j_!oYtQbxn zllTu`L7Mj(zZlKUf2U1EM-?TQw16zR3t1Q$?NQdaor+r+aINsQv|Xbi4zGHz2AJCc zRljUeuLW9P5>B2vT<1Yi$1JQc*c{U4M*c??kSdz(S|7K%x}k+4EShGJUF3YisdWa- z_tD=ue>HPoO3P^EMj3KFiSYT{Hv}+~m2hkzv`3eK8rdhsgonHmS;oHaj||VAH0I~6 zye<3?8XbNXPlSpPBMzJSKj%a!rR&UI?P=|8y+~)s@*!1nEgmyp!e?Q%I7yQ$@q9@T z1p`{XkJaee_&y%0Su=F_zWzyGR7Jldk;CdAN;vf=;OYEk;K)JxB7{fPWxC8@+x+z! zRs7e`q*Z!q#52COeE{3Wa{<^CDGV%#CKxMtQy-_EY3Xks9IBe=tlNzle7;{P;fwQL zY-zUfDp^xgM*z6rD?QA8mwWkVl&b_uKnzLHHQdiTP>y;nnG{YbK;Zp3Z0HaH4&j9= zM;83mhcHg|uRzY$M;%bTS}}w~ng^4IjO7;T8F@$foq<#bQW9e6dL4r0k7Ku038V?m z!3Vs377gaMiMufe#q9{s1v75s^a1RkEz_@@Lm;APb}U?68W8OBm7Ku2$7lT(`3-Tf z3Ct-$S*eVKUL$u{UNZm!{}#3h=%1KpkE}Dk@s4?ksUu~YZP?GXboJ-NuH}aY|`^$4n@!RZ9HL$Sk z&k>6Aay}QSi=ew>BRSD{kLF++?_;o7yjbHXkzkNjl5^QQ0=v}pg{k9gbIq9&X;KVg zOct786W3~eXc`lz7Lzf{*dWn2K5eq?EF@^m?(XPBUBeImk-p#nNO%3-LA|(p>slm`Aj6Rsi zsgOn{qMlzNkH~{?7{RI9ta97N;2e4{5#%1cWEI@S9;8QWG?C;C?uzG!jn0M?k$2Af zS=Uf~HWHg;S03@k1>%8l4Ue7fc|R1I8c)}7b~g|H-5^&w{in9JVd7$$(qxM)@RtiV z&u{jA<>vdm4yumts2dG+)R3zX*<;c-8FxoA0`McgCP zIB}*glOhC`QJ5k~E1)}koo?sYlXY?-X~chLwvCco8GLxgs0njzuN({vg21Xs9u zWtHMzEGQLU1yhsyX5EIM{2E!Zrci!b^bfuwlt^ZUlA`Kv|AD_Gpt7+$HD$j$I{L+w zDP10jyYJ75kFSV0mwv_a^f|>F+GR21ZJMx;U|H0i7ue=kjwwMtD$REna!{hu!@@+q z>ZXHzyxiP-&uj_rpn82eKc`}k-}-Jve(^7Njqh(DEJCGc0RV4A*XM|4sO8F~%rW!6 zd_Z!DY`0R!N^wm(#4bFh#%yfU&xp$~_mdgit1^_Io)EPZ@1hAE#|^zMy-4sN-!Q)x z&!JgxfDh|E+Ao&+)*pS7O+K#fx}?G|f_;unde?+Fto(ib*Z;88I{;V0i~;!uHUi@#6=nBB~wt zEJa$ZV|tiFXQ{+8w0)YmG@ER8*=u0qRjpZ2kgTom=2&ZGB=-A|&vX3SV|tuGc!z(i zhXbps^K}KW%JV;Jkt=W0VzpiTgLL-auWu_p)ARxjtO{pNHD7?Pkm6KK_QvQMCB7HB7 z`|A9hc*((>t+XMZZ zpHlJjX`Sa=KgRuFD7Ctv|XteyrzvrOkPUmZr&JW0hG>&R- zkM-Ii9+^(SQo^w<`@Ab>;Tl=O-*N3`c^H)xv~_~<+h26!vL5)!+oCtZ-l1odGDJ04 zu4uyaCQEa)PQan*zr~tZ!+F{#cr3K``&eZ6{t(^6!B`IB z^pdDc1VSu15E^xy;#A#eTaILjKzb3f^|gl*Ga{7vB&=t&_dNy%0_g#fhE}1yJY*hu zc7j1h^%4kKI-3y@{?(T%o{#{dP z^b^)%qRM3i$3&$0Mzz;5k9Y$2?i}&Sq5@lu$o6U8-O*XVRBQ*YH67^JXV>vQmZS8? zE26y+u^t#5gPKvMRAR8+2@gx*&x9=7KaQNZqsfmUKswSp0c3dQPtn}+%weX5w19^R zOZ>+Woe9?&lZBOoB?F4zf{Q71nyci^w>v+PA~kU=kC@Lo12EqFr}~Sgy}oOSp}A(N zN(P1MrEpw@ydH-1Z%8Owe2Ie{Xd>0h9nPUJvV6$6o;<6UVA%6bWg??FlDIfW7_~+{ z7_L9L8|nbGjQaP_BONS-%An?rh#@dVCvK8ul@8sVE;L}Jwnm?Nr|v60*WaXn1%%TWNdDsc9*Z9x zCV%5~`iGiI$&_!oPS*`lQP zZzr#<4yDsq<3B=RCun=dJixf0kU&AoxDE;bUbM${r01#VBwuM^wc+%nRAX~$E>5A4G^Db%YuoPq=xVwf>Sb)`#sR%~6HpX5tyGPE?{0@a`TAbLn(D#_L!X0vy+Th?P)N{{8a|u&)`?v1WOqWQeDh#-67XEb zG8^97Q0hPeOMp)hAHEWOcp#7(1A z28PK=JN*B9!s9E;|^4xx_Ae+dlf**V=3%CUOsb{FH}evjV>l zZi|E^M2zt*L+T?xOQ);Kh~ST&xQ#^%J$GQ>mka#;33-?s8L5=$?CiZ=@{1!sxp>=X z?>&G<&T8*yiMVl$DKWB$L;~sKOTppqP0DF1-2U>A4153kh3yJylIuL$#$$#sZGV*_ z9Fl}aZD<#Fc8xBwxJ7+pg3T0G5SOARZmHBRXzND;eiIw6NTf_ndkZLuZ(GH`j>4U; zf7#wL5!KZ-J^9Nkl%`ej$;h5oaNh9dDV~3&v%f}3cyA~+{$Y2C45mFTD7OZyX9YC7 z1hJesdika7MFqWfcF=$@UBOynEhs1-C1oX{`ExU)E~1zTo9b0oqaYW}<=a>ym{^hzdMNZRxfG3EqQ{p)`j6M>!FoRbUICJt;|pnS>cbK#xx*p5(J=-brF@3uUC_~tb7E#4H&JCM%lg#Wo;pB0r9qdM_RRemCX2~&xyN8SVvF7(Xs%;&doN8p}cS+ihsT)*EFQ>W> ze%&(5dkF6gy}%q(;lFb$xb@taOFjr(wLR$&^coa5KYa3cvkPx3Vb;)NAXi8?M=7*3 z)+R2zUgpA!kwIX{-WP0BDcoLd&5XE>qQ_NHaniLR^!jEO3H}n@UoUz8ThW^O&z$bc zpTCGg&s$3lZ5~29eD#AyFT-|{)1n>=bwtp|?>R$?|Hwu-1awr^NU~kF@;!2%@_SQj76XQDjMt8e04o1v%!C1}c!4lq@ zF*CpHO=^Z|)1aedLx&+_=Izf5iI3r~6glUIhG6A7Wt%i*OM~aHV-WnLgNN=>lA~uV zOggff-=%HsgHwv(h(+Y4ql4f7a@(RE_;?r+C__SC6OO(P7-xSYOq!IsmPW4sm%n1S zibpo>`;P#pm@5=TMH=U0gQGai*NZ>};B@a4tI+S|MV-mVl*E+$SWhVr50#X})v#R~ zV97erAA2fX(Vmi>`*!qwntO(^ra1#I;cbs|%AKt$EPPGdVdhkY+6U!Z%kopoC6ol$C=`*S44TpEOS9D7_NHsDaqG@ka{S^vKD- z)05`0f+K@Wv>3I3KcTlNHtCc>)3uA^m}u}C;19V!K?P2Xcso%1BQ5@~Vt8tZ9^ z1QbS!kXATn^bz|xRi<4U^_?^unP`JqGXcjGGaC3#Wp;i4sx)_pu_WOKD^>KcW}-1LDR2{9=EM#Z&U{W3@=0VFePaf0_s1SweO@Y7TL%YGjm^G2`}K);1op?C!kCvSs#BF%-=6C0~e%kohxlEJ|!c zV9giJ`f*bvbRwm)Y$;-5sz#IWP8o9-pUBeBW>xrd{B)TL=~Bo5UTPvaVX8t(d`ahG z7q@@oW_be?a}?M7!kL^Xl0Q#)h~45dOS;_^tNyz!sN@i&tP=O;sK?U+ZiDiYk_d=k zX7Xa4vJ z2PQugpU^89Z2920fY7aauCJ+l?oORtL_qamR=6;KMH3B2g4C}*D7BCGCPZGDm>>Yt z2U&h|AmM+EjL;yp3gbg&5Mg%H@Q5I^)C`5mB$*?lR5CG!`jfWqge{PsfC>i}cU@eo zDD6X< zdo3VH#&w8B_(bKDyR)DG&8N($AguY!CXb>yDK=`_KxvFWFc1`FospjEZ$b8iy?LNP z#Y`;a61x{|wh<5hSuSSdlA&1=!z42JnNw->1)ZV8qs^~QLdj^LG#+~*eU#U|X-d2? zu8i5zuh0leSG<+Jbwq_YTt=FAo9?Ov>($Qdi?eEA`BIqR)9^O0v=&kdnzI6^ls;JW z#^{t%+R%qt8J9ai1&7ljMl!?f^|VXlYDelc`7|3;PRx1PyN8+Nk;(+ev!bh)?0`E~ zQJBb9{C}=rhkyUZ5XiK$twwfLf*Z0zu3IhCVNvn&tqY?3MoY6tMJv%B9HhJ3zMf)0K%wLdjERz|-xH~})XKF+%A;#zGsv+F?+aF63Sqv~M zuVA}2q=~I~bzZ&4eBk455MAz`6J=1=@EDsxCsG*T8r^$CgWixna5g8jLW6u8sd)PU z)Gcb-R<)Mh9o!Ldp0Wj+FCXDV@qjBRF&M6207);$KwrnaO>}(iPUd_K>jgQ4M;lFh zyc&etZHHF$2Vl6bX;f2HyidnBaAC3MZ?MvpZl(`SO2Qol__I5tnt=#z?$AjvS!;V&s{fw z8x?7)y_wYe76g3%mj3#p)cVj7e_sX{Ze2C%y%wlGV8`R+u~bgH`is6Cc*ym|Zy?7f z{Q6Upq^cug8LAYMioWUWqVnap(JiL3oo_$q`o1Fnjl@_vQsePj{7yk%0Gmpw7y|Ua1M# zZS0UZMelKCQ+2_PVT6=3MHGrA4omhU{(F6(soh*QH!?K8dAVzQe5Ke1(*+U6? zy!od=ejVu}eO)R5@=6+fMBm$Rc(`Ap5f+pIWbx=WN2fiaO5$nYVnu&6S=u_^KWlS( zq0dv)TY#y_#}--itwy!$%EK=gDL)7r+GHpUQq6vza7MnvV^4;j{;_>S>(*EF62VhJ z!;#R+weAN4sIDo_A1DIG&pbY%UkXZMo6uq}{j#d7Zct@W(dw=dQp{B;W^yW^Vnzt7 zEnxX@F!{Z<~>sVFg> zc!NIN5+B)sJ=90N=S(E;q5O&Q^XDQ#^B8Dc&2CH?a=jDmuKMd5A5im9l&FBXZF%1IMEF_AebYKs@+Bv1P#H@g3 z{{x7M5?R2Ce}E$U9G0gM>{7ID_B>cOuZ(-O)vR(Mmk?D&qg@pB$UES`g5V9h*Z;)c zvqzQfp>1%gT4SxLX=u>wTj~lVK7G^!9sY9BXbyKL@bPgm1+gm zDGB;;Vn|0Ql=#F^)@p{!kV!QwIY8Ip_M*HtHDhK7W#lf?u2opV-a)yoV>1;KvY*Ay z``{_S%RArRAsg1&O6`U0gD)BHf`TkkW~vW>>bQyAaPw|VZ8Uw3qSS4YhB=`rJiMv+ z+DxNgH?=X~WhDT>O1DI?OF{^)NkYy;b_KqodE{PcZ)L{T0lj7uScf2S1}gz`JDEC~ zDI{AQYr1JFU5e{J(27UjD2D}Zg=Z{&jZ|c&Wp>4_9GC&!0|(M#LJdL*AS@jjh&_@j(UH4(G2 zx9{$}d;5`vKk(#eWr=czUXlumQ2EHF=|hWlL!i?v8t>KFWM@7uoZ(En{{QgUj_60gO|If58N zZx$y=wZ%;rCFv~bS{HKkqk_+X85%<^DuL?`?}uU*t26=0-{L;(*gNL&Wa1fX7E< zRE(C+!BsG&COXjpagbig>Z++<&7_6IOS4J{CCwOdW&zcMGHpT!o<5D3>?eyII4Lip zwvBw9${j&;JSMmRaZ*%5g-2HePOs^*eR*|!_wopMC?$2O8z~(_wB^8742NQ5V`IhB zT2k;g$}!8^^~|u^vCU>T>&R-*uYJWHJ-sy|E*(kEs@yvM!{Vw7FoTQ{shFzrc=V4J zoZ1MwpQkYs<)%DZI-AQDZUvGCPjNfyh>KiS?`7Z2re=GvphH63GoYNMbAJJboCI~dVE3dph-#@KfA~+RKAUInHY#< zY!58#e*d}?6j<4!-R>AWAUJe1nNClivV_8-cWle*ldN#lk*Br-a!FlYHKY$%*xPax zJu{i8ZV)Z02lrR0G`q4g1-p)Lr#lNG5lT}PoSG~U=;$pQ*Hp}~xiaIC$cIvA0J1_Q zW#yn2N;B~UqWtoIzqW^!j@9kc>2jz{!fUb_?rmF*SnWGA*EBpN8C`7|y+vWLH|sD~ z7@b8=<3tF?ynKtRqmn_y8;4)?I)H~U=Q|<) zBB@f}6^5u9l(n;}IosMw_`!>v%Nr-p>Ivz;%F49~87GTVp3UfP?p`i^sA&j${VcEc z9s{iZ$om{A6l#(&7E#!9+As0#V<9Ad>$#FYX_B3k(&(Jf-(dS({4 zh_(%XHIb^HWW;$4+xaR-1Lwk6&_5iqkbQ)huV^96I(U_!$eMZlRa# z^M)VoR8PRIjt|J6c3`ru@^SU;dE1{510S zgIB4W)!%@axdeYY#?yZpcH+mS!@3whWIj!T_Zylg;$nq#fEQB$DcL~9>8=hKPKRhh zDkO0_J!signVak>(!H1caUB(RvdETLdkm@X8>MXI90l(I%!p9fF}7U-Z%qPl%2Y$* zgccTB3$7-~6+&Hk4c`rh0Ey;~r;)_r7q1z85K5Vq2LNrbhvvX!8hn}{Mq|u~-S)tW zidF>RG{SWmRTO8Yg)*Cs_RvQJ%Q;`!OF?{|07hKgqOra`Bjpvv*35lKXavl~k{MRY zw0T7$!)OsY)YM(-3fR*{h@dVkretBx^ro+qB^O(!LmIv=3Spc;Mn@n0l+@srIJt~X?0{{2O?!#8mCFI_Wh z2C=zCv&4!o`IjBOJTJ^=+Nc;HTDpQFzW`z5T5z>8l0=|54<^E$z{bhd5t!<;`i}mgvoE2k09hPx&Anih6-&jnT_5rv;@Xp)vc=|% z{wUelH|@$q+;Z?Z&O_7n(ywcex;mle~qwA90eyE?5>Qok%nz8RE$A_TeLIED`GN}`yxRLqf@AD>{@)6aXhAxTlU&PMH zDEFCUxv9^U_%l~%Bc(NFl)3TNIcM@(?2g<(30UStYd(S25$fWN1k2iO( zAhVc4(bAYTMm2XZDpmer9=0MwOk+rKKwqy3UT>{aP5ofu33V2EZV6?m-w*@CKe9Wb zdnyxXfJd%@I_8aFjb_fRIFYp02EWanm;S9}7o+qsaV34B9FrHdS*q@cZkX^1PQ2;u zBC&l5sB`zbw!pmO#CFICM!JF}Qe}uHr%XT7PH!?l4km<5O$*?!&QLFKAR(4|aPJRJ zw_-HR`gEob!g$=3egXphM-p=jGqF=k>y-gcRlM?xpw!$ubuX!0DcaeO0fHu+IopWv z^GC@Sw8o`2BMqLZ3W8-eMMxR90oo zSYVNb8vy3Ov-WR->Yz# zXVM~BjoB`ji3mZ?_TfI%L^U@^Y-!H^Ab=sUK_DJG_2E8lZgnQ05?zUa63nIu?Mfago$7HQO;kOa722P7+@_3 z`uT6lT8V>=orrZ%R)uuer-^M`Qj&4bdTyLSzV9(yYI!TWA?mow+=vV~j8i6itWnv( zTr3bx*b7^~Y!5`R_ZI@{lb=*>OjX9$s1VwpLzOI1;iomu50`MoJ4_hiWQu)M7H$vK z3T3WKg+)U+eTwmna*V7v3i3o~kF*^IOC(w9*_`I%qKTl(qhuYAyv`0E((AIA{#~Ip z+m9=v?!1xkcrDw;&k=S$>|;PAf9!@xU0sVK>)0{(p*rY?z39)|Ae97jN;zyOE6pf# zC3ApDXBL;d>a*1ZBvZu`*?GhKZGP<=J9ul^GK%)oH}nhZE~usF5eQ zbA0`RZ`u`JetVlt4=i7?Qe`R-=3YmFKUF}~7}2e{Y5ng3-I2_miwG%?AI9x4))q&$ ziHc@J#O~62twi%#w>0!vc`|<<+z*6C+IH|qxyF6zb08J~r6x?3e(Y33_>v{w1i&Mz zC&a$9znq0dq?7d)V4Y)@PyEf1xevwtSdA)avz`--tVOBT+^h1oom$lR>fhx(!>-X9 zg9RKu=%jLyO}=v+LvPj^lnonzOWfJO>M|~BA1|(yr4k7ceq=Ak*`5XbH}X6xO>r?A zEA&rRI7e2BFv!;}C8bniMbpRxkC|ayRcePQ$X4}=*)unG?}y4Flg%CZ%n62oBK+zZ zYmv8LdzG*S;RUv3oF({HWbgH5y3J`vFyOu)?KH;Dmq9c=d+zNIaax@r#HF{$cI2?` zq>;8r*A4&euZXgOv%hZk&7Y`-sN(X&${5zjV*jC|i*)sxdPlpYyc$J;RuQu|<2-)` zdigX!EN?VV7IdZ1xnQDBQ-o4>dR3u|1&5U~sJP&mIINbsI}p46it=6-2|I{2CxtJs zZP%Ip276d|XEc3233=W$Vlkal&461kpPt}8zVq`-mciR5@kiRh;vcP}?Tw;bX^u8% zkYU;-((FgnUN#dx>jhi*E4o~MG1bIL&XRp}p);T56Rdg3AzM~ugX&pF4c9$=A$u_n zM{AbquA+jbQrf6673pRrM=c&BvCy-l9=sECHRBc6(-!CrQ5XW8Kq%Uwt@>|`P$Yz{w8y%?iUWmc0Em@k-i<)%M>0tZPbDk=b{P1@?E z=4YoS5Wqw{ zS-sW&n!EbsOz_MEM@&?kB#$rXWrzWf|QSrfr>N@L^1XLYSpXwoU#w>}(e znTVYxdavWbX!J~{Wtzg%3F#(fdnL9eYMAjO}s39BZWZU@@r5Izkg@ zIq}QCF~PGTlnT{SLz@|G+gaA5^sy>yG6D9G#>o)-Js)OkWGnnx3VEcc@jlhyP`otT z*5UhE740Smp5{ZIHehT-yq89k&FS0 z#lA)JF^GXKPUWWKk8J2p%~Q%9B>m2tvG#v3TKw2Os5 zf66}Cyw!=Cg*M3_c+iXSC~E|VwTPPG2=jNx`+uNDqF408E9)9tZ6r@cygy2o#oQTY z2H6`ANc8!Ko6Q&e{4QPsQJHm-WHJYmZ~|A%?rtRncZia%JNmeZbX?9?1&*PiN1n^< zi65UX1Z)mCn4<|(2D#iKEU6h#u%(I;C?~Ka-^-KZC@2XCGO1MZR%Fpt<_1y9;%>z_ zE^I;0&^w0V;-slI_kt;9hzr|#F5AD^t|pVlYGu4-T|p!l2XuYnV~5{#>W!^J2d{vM zkiup9Pwvs7u~i2Tqtk)kY+D!Vo--eRz19WlY&)C3q~z!%^T5QKj|Tq z;`VIH&41PP=z!C7Hi{9tWj;5qllzK$WRmS$er1F0d>{iTbJ^6MyBcWzgSLX$>2i= z)xs)Jo9ysyc(a<2{nI%Kfu?tH(t-`L)+m}qQHBO)>xRZA2NH9v0YMA18Ko7)U%$4; zmG-sKcWx3=H`tCDLsbs#@LTwFbiVa|^oBicpUE+rq}bL6Z7(t%;bog=*~ETkqa_-} zp?&x$iJ8I`3TFWFk(FN+aM}Nfr6P8Ib)mP>y`@&=TQf8`dsVqL&Pc$#+0d6DFC@VD+_w|j9XY)i5 z!`#{F{4p`<4}(fTvK`!FP8Gtm*C$!iC=Nl250G)Y;p6;;?vHwk)_bN?lIl zx45_(9xiCuQ&Rx_4{J;`G6Rj&un(!PKgVD2Gmnr9RRyf7v+xeB6;G&!KtiW~ zBrtK4)Tx`8Gl4|@Zrw>=E75_~2CIA)LOy^r6Y1b}T0A#muj@tn&b}0SyrFxX0e83h zkv^+)u)beUwbIbnzga_|blIQqT8AOO@ETQLRs%HT`+=6BXs{EJ7GBTed){>9zVud& z4v8UR6p$e+v{+1zZ8e$gHDpq?PcYo~`9K;~$@P@1b%K-3ORO&gvDalo$~i&#dnZc8 zjHm~R`g#m?^kKM!DL@(uBlP!S(k2rK%DykA-HI6fldQODiCw(QG*F}_6^xRjg4_rx z?9vc(45UP1EMczQ%1>ifXF(niNHQ6_P#2!BPT?Wd@U3{q6Z_%WB)(`WV$@YCv1~vr z{xyGEB_PUfg%E{3{~y3|DqElqQT)O|@A^W2bm!aQA@7|?cW+J+)_T)hPbpdBzseMQwQ9A&&fFM$GXW|7_!aJ0c1r?~Udc3wkw!u+0Rm>CQZVhKr4a+EXt-*CGzQWV z$j3(KV8%S8;BT-R&LtPJxWq327)`_#vVA3HQu#7-MIOJqGk8Ew- z@IYPydh0+1nWO}MRHVKTMkZ0!SyUMKb&B(T+lG~l=fBUZWJ3Nij|O(^E4HJymtDU^ zd~cTkjXD;wF(8J=&_(}TC|0pkY0}t_`~zFD6B%5v_fUj;VFLeq@Bh4Tut{1sjo|(Pq~r#LjB)&8_S3?qBh4*9VZ^7BN-Kw|2I7~wsc~B;(z~9{5TLP_bO9GG&hkR z%ZZ;R9W-F2sELGB7{Ms_UsUesurh>Mf_S(%6g4QwD%&o^o9!|g7>i{2zL%9A>N~RIN7|S*rowN6tokn?+2Z~!@Mj>2jV;`!?E&(Ue!tW9<13x6@+72`F?-@Pr$ z>`UIECKfufAV#atOZ@Z0K6y)=_`ndpp4MAb)mhiL5E_=e-{O{qTx!hG+4|O$C12aa zik*AB;6Dmd=LIs3fs!A-8L{IcTfao!zG1Mj)vvP^oO|m!5O~RP9yxix(bT>@U_7V2 z`DexbjB2`)hjB`N@0PX4-ErI1P}Am;JHL6njhw;UXG;}hec=J)(;J)HFO$r~SN^sC zdu7}Ib7jczN47mbe0qZQ@|>TWo=tv3dZVg3~t<_f`HRgL#*Ro51%(I7wKhFF+uMyqA!(r zNjOPz9UVO1w>?Rla@IBn$-L<~XmihAHI!D!u3&R@5AR+_6it^(`pcx}N{C*9Wn>yc=e38esvEt$lAHr4nveKZrPFvv2=jP$CM-*bai6Uu&$R{Spwi< z1^(iKd!@$pk`gB2Bu72G8%BLe-US)%cS+*HYBPv3W}BDWZn^wxQyJHo|B^IPH!`A-3d7=);0ADzTrIoYcl;tGY-Gx5ggJ{?38 zOj6$>KOvI(zhY6W`;M&7qq-e$UTi3-bFcMl!X9?A1ss?iCX)FMPUw_q3g>-(KkbNI zt!+Lh1_&_Cd*2Z}Upn{?vh%TUlb*1?Lr6fwZRzb(ROA<;Bc!-Ezw;Zor<-pI`c{7U zwKViZn_ud&2;t)g%MyRtcd{SFa77bD@5g0+5=DFna<%wN87VM*a{|IyU*FxXtNO7S zi>!*Zc;jeGmef*)M;#9r^b&tRAMo^cAO7}O_q?weZAtd z38URYG-F}809Bp^_B;_;F;z5FfV3!WuV@P^t9%5+JDT#d?9jaih{|VTgqcm4?oWiep2)e#i#nOSY`nG(;)d|j5zE5m(FSfPaoswt1*{ceyLRY}+=Uuci0UR_vnUtVqN7xIW( z9_Rk~>FjEQ-G3;Y;IBGsXc>l{BDo?mxxoQt1Cd^q{%;+V*+u|`5U&!BMKJjeWp5f8 zv3Y!y%^z#a#Z1`F`ZMFdeN}|{!nN<~8y1HB#-1lDR5R78u2z{P%~Ll}lhbv=I^}Wu zL%|s}()7H8;6W3E(&!FR<59>cD-{@CeZJTIGpm|U+r-;(2xYK#$ z%02Nsv>vgci^Ru!Wt%HUwqu8i;9Ti)xA-C5B-Iu1{VFHsxtQWjOJK|)1A=o!kRIm+ z>c)3U!US$cyII}tfyL;K-~7vF^pJZwWE-pSlrYdug*bq!Q8sP;B7&9g>!M9{6DsiO z;$lj6KEnPW*$@-^ki7O-d5MR0>%?k2gX>_E8umL^BdKgxR&qB!V}jG7B4$6?5sWAQ zHq@6&@N6F4c;9@Ni6<(B8*}Ipw-T^m2DB+`v0nJg+gt*?xr85-bRtn#+k5jMsdR`!UaCgePWj4_o44Y z3MvjugO8HWD>dXwqi#@FI?@V9sF2TxC16>O7bh9q;Q?83%>5Bf__9@Ft9q$X<@?nW zO~`KKbgNI_(FJn&IujOWp+$a`k$&{CN`b7+3 zh=&;d!}*o9z1~xr+qhxy4SkbT@L+p1%Vb1h!VxPylB#55kb$1DSB2P$`t(pi1hN#| z(2HKl^{=I8n+W z{&TNXAVzV)0t`XHs4pFq$k20`^E|EPC`WkVT}TFzvFLq`O<@;U%Y5(2LUTW7`U!ZK zWKONyE1EixcLC3fNF8L{_jUQ8@&spuv-CunnVHaN_(gOsagunE4z9C2$hdHfXzPdk z+jByvbodX0^b%}27)R_XgC1r7Qo(+sE3mv~mIJa-*O;48cJ-mOm#HkC{QSIE*hlMq zq(z|sZ)!3P6R&Q4@7O7syC%ya-ir`S>9=bo!`)Tv=Q*-<0e`?1$QnJGl+f!aRk`St zTDL{*QlnwIqO$*#R93u&+7i%r(H{=<^c*o^pj`yJ4iDjSN!EOWkw#yJ?3(pJx{8Xx zqd8&WT^KHIr&c~9gpnn}3Cxx;;-0g25>m4$Xyb-xfGO40>N7!ncpc&9t=MpY#84=G1#A9ffV5+%72Ju&Sb>~jYi2d$+tnt zd^YPsK>ik^VKdwAm6hf$y#4nzBDfQglCc8t_sTl6g z*B8yxY_yUOIr7yI3Cv>?*rk%??!U8`upo-0DY8N-W%K=Fi6912g~*vli>rJCf=omY z{+XS2KT&meQ<$9m9J(>;nzB(yEWV1Em!`Nn4Q{!gxjST_e{(I9n^f)cmgUO8LXGpf z9&Wjx52iw_?QhzAmOi!BSmyARLOeU)=)kx?48HT4Q9us3;#?eKrr*?vk^-tV~ZOSapc1L7iVmQzdb`&Y}j3@N{z=j2uP`Nk2wit)fW(s*$obEZ0KB_`>Le% z$$syh#J`P%?_d!mWe0e=#7dnI>(%MvLK33yRPKB~o+PbIyvyqyG$ZeRvh)uKi1_Xs z-6T|ZHKd7b=PY{nhwbgQ7x6cSemm9kPF5DH5U=h7@vi_i@mbWd=7DZs&&Xp8D<6aw z`>wGXyyzf~{l717Q+cOG7w28$(u#P}iC@b(FCO4(6`x4s&5N75w=AkgEEFVr%C7!U zm0@7CC4jLk7q=9TI^jM-O{dt{ch3Yv<)1-H>(yD1U;5ecp|i-4!tkSAsyr{Pv)`4Lw<-> zV%>{bu=ZjfWF zJ^`c9bmh&HV^LV#BjsvfCEG1Rz(!fYj2A6?9PsziH${(_ZCY*+&i~`-D}&-_y0-5S zAh@{kZ`^}ZL3p=%E$1dx^7{iET)b!>$syovEar_EyjUP`|SvIhTHLP zA2)b`{nmj>)v~3^CWA3dzR=(&t-b`+d@WXuaTnk<98b|%(d5e79UJ7ihRZnfjo35(Voj*G2`T3t#e zT<}7wb_K5*T)Y&q>s90UjVLn`wVY__0Zw;gsc~-*oFE@E=5tL_;)7}FCaVHk9MDqF z)_i^cHlD?~3bwQo&MHFRKAIg(p4v&j>qR~1Dg>-vqj!uH&uHV|H0r7%2)Mw} zxbFqg^3VUAOQf5uz7BH=V*;qD3#?F?lqljNZ0rtfi6R6FIfVHTKDV1NO%!<5CkF*t zv>SN*>)V`SnANmZ`rsmfzg3b8DhQIJ}S!!Z={ZCWTAZ#e+J1Q(;nle z`AWKT{cmljvV5I>(GsJj>N#b@{=NeLDl*(p4z!oANmfYZPGjeGd-tV{F z*kUv}gN#|?Sm#okIfO@E%}%4TRY}Y?(lHn+yc-E7oUIqF6Er6%FV;vJdUAK@Y#fyx zhg2Gh<#x%x-2hoB^4i&W3|6;~5`s)E#OjfjTIjt&e*js`m}NV}{@vXKxT0@4smYeMez{13@wSdQa_eZddQ}mxrMxjxIP|C%s*y z!o62|*>Z+>KHe3F+W0sF$CjwZCXU`xY+fL^3LEWm^N3z8GMk;lv1>@9-(vNtVEAd7 zG9aI_iX+V0be*y>86%9vAOV~DYituM?KEp4m|7lg1kSBX&h&_rOV+dXUNANz<|!r& z*v@-m2+`M3){gi9E4gnB$r@CJd~Z>uuyn7@0Q*alUBe5_)W#D9?${51#;M%S} z+xx7ID2S3gioW=62Tm_irE;13QQkvYtl`bsO~i?nP|u5i<0dh)^Ox-N3s)D2kr5O2 z0HHNhgvX4dd*}2Nda3q9=aUj$iXdw$%+J_m?=J7~b?Kn;KBudgVRWX}^GBl*9Jvp= z$pV&!w3YOg#zx~5+C7q2)sxGJc7bSEkw6>Q;LWV{jaL7$%@gW)Qj%LM&*(x2CGd;5j=A#Kxrqduys}(Yp9^A< z5g$7~zlUXO7X|J2EaA%eB;3bU_q^xtN|(>&-s^^}0>m_64ub zK=9|*C}Pq$m4HC|!I}h|z9yajDGnwk4HIonjCQ3mc%7}1zU8rG7@pjeBWLC;-g(ko zgTvAF@8tT10fTCjI)cSOpdto*2wk!F)So$XUmz-OBmJ9xRDkPW=o1ogwUV8N^#aL+ zB7KMXyS8>YZurk9JML4Ftbx+P)ZbE-Cb7iDg(UtH7g-b=m@s$Y&iABNT4|rWMc&TF znp-iQ5!=RP`3|6WZJK@sM_Oaf%-&O$xTKVnPCc^qWyur9nm&_<*U`s~Q$bhE z*|J$&&3~AjO zG=3zGII8G;!XT|QI$$2SxoG(&U2xB=$)3A@d4-4D@>UM!9 zIiZOoWe=0Qk(^xx{%5V;R5mwtQLKT8iir^?wo0>aT2#tWGi zCxTNJQ-d{Qp+vTX1&-*gMF@OjsgZ?6Fx1u5#i;|G!p^3giXspmx#{32MevfmeR)2_ zb6>Qfh#*$!m8md;*SP2BT`3K7&oUGZ^8Px!0|K}it~^vZH-_OoENlpE-e_Jm7vR#i zv|@fYm2CJIW)whj{6X`2{*4(<_MGdf(W2e+3UTawsE09py>-i=$PsnoX>ccuX3EXyY?P- z1tixQ)Z9Z=w8j5(aTI}^LgaB(y2J{UhL+5}ea3AnNr=x-_}~^sn$ad^?j0MekrY)@ zAWdkEHFJfU?t|F|Q51JpLrn>FUjuevI6TS+UGe{L+?vGX>6EJJ%PW69QgaBy3`($! z6Re^1Z&FQ}4Lw0jN&*jYa&h`2!Ifd=#9FB^1<^-72PR?HeUhK38D^RgDfOCT0O{Q$FSN#3V~@?bO6XetvZB4~@x;3Q|SM zY`DT0iQTB?31w#1V#kx|-Ymk5`C4#xs{K#&;hlUGs6%p7m#%NqS2sr;WqL#%8(&S+ zh&@}{91K(@X<#=oH@icUkM5ksFr{%Yhv=+1demhLuVYBgzrONI%i)NNIme|=@i@4w^c=yHBz0bA88z1VhO!k_x3^kxqqPgTCy_nk5W*bzx6k_KaV> zUWh8p6YZUjKZh@0I#peo#<@TDi*_=^CjKXqn`pVpN5nWm<|puCAS{MAQ0H-np$_{c zCqV!GO1KYG{;h@Ph+JSr6? z|6894?Kk%-?~Yq@U-QxiU67Rw+u2+^E7oACSz3h+WGLzQ8cV)+a7efT!aYiwre>B~(d__B8H;RhOn_mb<80Q}|it#u|X#-H@K55FW33-!yi z?3EaJkD(FCA7E$G$E!$9{T-yW7*gp@1doCaf$G`-sII?{@hK`NtEpk)xcdda+&TESuz|7$7&ujH6lr}IZ)K&ruG{>&pDJ3jI7VkN|YTS}G z3BHwz_C8d>|E&S6bq1G+vN&6`PxYOa1olrKvUe>a?Mj}$Dr1T7OpSbvSEEm~CYrrY zNQ&Ru&G{~P*lU(jW7sq0`1b1VaRxtCJ$=kdHrOgAX;?XcYJNqskeQ8zCu)ks)@MBq3|8L~j9J$JxYE1DlmoL;VhVvr}iC07) zmUxF)&2hdAB_*aY-{IbEP%qbI&P4Rrf%QL| zi0;b0av%qAttOY)WvqG)0gP&Nwn)D%>P^A_^*`!xC_ZMbB^V)>UB!PbGq9K(_nn&^S?1e zgeKYpOh>RqOc&$G3cRL$r)O%Js2o`waY%cNRFT+FFpa!wBbx=s`Fv#AfQgLtAo=SY znhZH_xH$#j3T31nWP$VeGo);dopO;fav zOLR|9JuXB|>od0SQ(BI%v(VF{cl0qmqkZa7C8@a?2~JiF)pY|zArEb9jl(WfPE%f& zL{mS|$$20KIhH!dtP7YQgnDI4o1YOiS56^)D%40Sq*PK7_w%QwEW>QlmP_?DUvDfU zr>vxruuWUMpz=_t9F zXX8{PoaoaHG)5Ba*ePy7G8Q!UUoycZVgHS$N2}s%H#^y(u0sQpjaDqYy!&2v=`>jb zh3MwnJ!0=Qax@l&@dJ&51W%mZ7YjIV(qTvE$t=VOl|QLeuv>9dsUZU{a(=yQpJ-+0 z9#5#IbS;smZL&U<0~CS7OZ%2M9uhrLC!eoBZiJ%&)oi$`@S_i{(AdM|202%Qs+$Gt z=*TC2iKGNfJc%~33M-`r+~&13InTj&`XxP=j)I$*&FF?m8N{2*;;ecb6uXa z;ogQr<*N}Yl4fhNE9Vu`*<4sN#SBH^xr7P4vt==y`Jsm9>AHYoibz4z8A4`RF|5Tx zy-)iDNKdM`JptuJD`)?DUrrZ0A;J5mOlV77S`|v4ej}=6OfZ__$q=;P#Nei7vqfgO z{YBYGuh7ZYpi_2sBY^|CY|JL~K2l#ONm{8{EyzdhavK;i%g81((4Q0!Kb$8t{Uvir z)j&A=d^66;m|PnD^YX4&_YWcQc(TX$nc7DZ!LK8dSNgrNoNb?EkK5x`x`(?2$!>;+ z>u+>3IOT$E7X5mI#^I3h_+mp5UJFLV#oQRXM4FWcwdg3T@qMK+xA-tP-)sjT?0DfM+esd!5Ly28>I~% z!9Bj_k&QL4U`oWo>LPZJ6+csh-Kn<+D)c|wdv95CBd`10H$#^Y-h0~3<;I8wVivB= z{d2pKMY*9hA3(1|Mjy?Y9b0yuMLe)~qW@lG15`xb?$sNx)v9PofN_XvlbKMOV2)J? z&L=1LRY6D*P8H6KJQ(3xRA2JAx?ZymfAAXmxy64;>S$yQ9~y;llYUd&FWn*e`I|PA zu&kc~4uMc}LNvod%hpb;-I$Ha?xA4kP|ZD-4&P3rZ?E=tSzfC4TIbZ1Pw+jY94jI! z$mBG=H0FG0Ko#9H6EmE!f`o-c{up&Ari@id1cKGaMXRiy{X`_u9J6-f`o~4&&kZ2< zqcyzXmfeVOlQ3I8?%XjA{#^fU!>GzS;aeSs;(H$a4Amr2Nke@{#22J!9=w<8s;{xFxy4M5FlKN*um{l-~)0yQXn_}d= zOxkFe6&D{4?%_gzuL}CgRXR}N+GiKWJ;bKz ziTx;^(=t6eboaQ*b8++-eBJaFNLbRgU&En?s}2i2<>Qs4m&NMzi{D+a1lb%nBmIO* zYi9{6iL<6z`-^>EEYK>^pxZ_HAXX8PhCj;~tfxvL+e?;+KqGR8>rl7ytP(pD5|CS# zKZfCrnNe7{qK-t2R>$VqmQg%l{d+;GJ^-OGsM7klJ*@I81ri^>W#b##+w|N0_JiuO zv6f%P+il)k9H%2=gQ|bnRYZAE`_SANlcz^~tLN8&^HWkXzLt?w4q4nJ9sM#5XhUvB z56e~U@`*bkJWGahi4ItK$qmIt3}Vql_tKlb0#>O>E?*^@Z&55p8n6&rBf~<(vbN69 zIZHR@wB*Rz^I_?A3g8nsnnR92Ni1|IO0ik6#pbXfH5C=Y6Hh>q`AONVkz_-z%zz8F zrhmHAvHGl4zhg`Fawqr({LS#*T*b%CWbG;yP8yrus!JnfP;a@(Gke<6bdG+0BXN@b%6{mvP zG_|#@m0aEAxFxY%p=^}n*w4(A(Y~cgh=Ba#rO^b}h*T(vlvFTbgGs?CJsdSH*~jba z7f)|MvH#JkZkk*JK^#{!WybAe$Fb4rSm&fWn=ua|{C zj-%h-0Gn>$^0b@hb)|T9d)bfNZXl6>Xyp^ec{b0xy}y;WwHJT2xxXJQ`{Wlz&fv-- zc+5;B@8laVl^pqkIe$rwZ#hho=h2!CGpL@bsi|$qq&zoJRt7+|(1X2W1OGFL+wRC; zCUaRL+%qZS#!XGlVzY%Kk@u4@W2Qy5h>5#u@MqbDv{+qk><$fKWvRQ8!bJ{+Y^C3A z#V`jm%2JF=Ey7r|^{Nz!jjGLn4$&hT11(a(>Xi#)XeEWQwYn>*0Ob_G&w`~RZa0=U zm_OOA`wiK?a*L`efiQ2Pt}KcKz3lG;5r`tzo}4h#5_s`+K@N9bBVjP%W|rc;B6Ule79e?zW4LE1 zaQMQYM9)xN?O4C)hVhcXC^K{FUKvY|D=Tp#aM(#UD<93K34oK37qaWXLN`5drzD~^7KPG!62h~+ihI*Dc+K&m#VTMgag!D(m{Z%j^aojz$!1jo0?G-F6;g)A z=wlldq%&s)`S+gBgZ7&^y8P0%j3!28rDJFon?JR*a9ZKwGKvfR6Iu}AbhneG`6Ka= zE9t+3mEH1mhVoP^V0fejYpmx{y4-`gpTrHUbXPV@Xi^Sf*8~MW<>z zaTgR_8qyo{Itcf&74X|>$m$?zjKjk>v?fRWlp1-zii8vpD^hE)`zS6mT12-wj@DHr z%abFJlM&SBl62Pdfa`yEN^`c@W2c(H4(cyZs-GFep&(!(l6SULeFoF0%iz$nr>4;p zoP>ZiZw`J(+7eg-kLgAG$mAyb^t{`_yEhkz0HuR%|`NHp7gJsx$7cVM{pb zHn6x#y?IH!DIG(ruD#_Oo95tnH)jzV1l>VrvLfT(dmRSsd9UVOu_4OCE;1`Wc@~$5 znq2}dltp7`#Jb0gxM;5RMBElcf>Sh5btf@J(i)UX)jl<-EhWH9W?x?1UDwNR%K{w@ z~_tCN(pvF|N%T;UVt zEIv22eMz#Ngvje=Ec-^$1;HvOPt3dSMGTZ1FY8vfq-xRGYMDsjNxJr&u)SBgWu%N# z?IRdq45iIoZ)5h1de9(IQ;FwFpS=KtoaieK>RYUW3dRn;(9P<+eOfc*i7BD*Is!VcUtS-=1#b=g1^??WZR?gWzgIVS8MHU> z^$uhzDuq7!Va55unI#jWlK{E&=cbD3o{hA9p+F0Y0|u-S4qN5G52E@=iHD zfu1I_vT$5zZ}(B479X?36~GGOwV0a_x$aV#Axd*iH{bV%u;oQND&r)Y!HKKSvfWFo zoxu$ehXcC-Mw!{_#u&pWEJ$2*7L`#{98d5|_8l#U`ny0f3|LHM8cG>TD2QSdsWBb6 zneq;{#hjjy4xj=wp^4fU!u1RBud_?r0v@>vKaD4i|i%SDumM5+ZyT0%i075O0OAMYVEs#GSztk_xV;EPui zp#cUah+B#%)7n^P>8nD-XwiSu$Pp@1n2F|y($GW@qPA2-Q361jn3-|I70vMsMCLIP#*Z z=4y}8xn0}moQa{PK}~`;OFiAwx@2zGIz0#X|5}^=ZT*d}Uy)n*WFxxh{L(Qju%fJu z%aNXFk(i^UldJ^7on@fNci`I6f(oQcM(Cu^M7t$Pj^XU(Z$br&)*$%8uw-Pg1HR&? zB+Zsq=Q|qS8cK#iM-_|*xW)*!+w?feY*GW~Rnnr*oZ1G4#@-dLD1V|9;d3$MYg?c1 z-bVfXkD!9zpp303J)D1twPT25R=dzcMX?dRt{ZbcaAj3pij zWUas?B?XxORaiyEfC89(gpPLJzy5h^pRR6|zDv=3$lJEU*m&Xm{dUc9=TyHGi8JDWA_$HMEjcBlx z^81YpRs`zM6|sX*q$wl^*#@RN_#?1_stc_JMD}(SEm49fOI0oG2gUFxWL=AoXlha*U6${h9d zL#%beLDfYgJU@@Jzj$LMJ~7pjCsn|w)|#-G9>T?xQHqSFe?QW2Y1~aC(~PMDgP0tr7OaTfk7u%m$jyL%J@nWoN=i_njsaQVS3 zh(9^flVSF;ReQQHyk{14a`R8iJG0ppHV{aJao~<}USwaYP(cffUIrxM`7H{hQcH>xqXh|>3E~iEXYH}OjK~>O zp`!_}Afp*#)H%fE_1{ROg~B}L0t}lUu})jVqm_I}DRnm|*E3?gU+C4yigw|4!Gu)kNA8wsY^4;H-L9X1spP;YzWP;T+w1W9|3)kzbQA0AtNBSruKL8Pq!S z0~xQA8GuN1QIb~>0Y`oo?vZTciS~EMq=ocRTSkxVqTc+}qhe~q5=ky%`|yBOi-u{0 zE1|mTEIXV!RsrDb!HIHO<>^&%w6A%342{~Wo@v)FX?$TYh^7`3&(QpQcFOsSNgpU! zdhl<#$S*gJb^zEn`Je-yl)`7i-!M=$(RnvHcB)oB({yt=_3%EG=*9}uO6sT*q{-Ai znFfV66_Mp{__nv?I_0TThYB)r5#Ukq*!SJmn|)dolTPgj2h9dq>TGDR&i9)yKmrT< z%N$0SdR`6>$*VWWaR@k^ng#%n)z%}GzYhevAJ8y`ag^oZ?xU$6pfLrRU%82yK4=R= zNYrQt(1xs9f*cS>D#Pe)%JFczqu+f35HmiM0C86*J^*h9k7`=ix+a6#l#RwMHwnrMi3vkA2IsFp z!k`K8rV?EtT58H_zL)o(1P714zSD6>t!W=Rig}{{JpWMOVbvRyM*+NjSMq6cB=TrX zHQbs8u>vDiGm0R5My=~fK&7bb9_f1}=jyY#%vdL43}`B=Eg;}p+7(w^T-^*uI^?Sa zG>&ir5+o%yMFs6Ojr+~iy6oUuVL!XlIeLE~-%)8!ssaW%S#k262ywYjbnKcHpKDYm z-G7-R7P9;iFa$mtL>3f^@UMIZkU{hrN0{gmu({#*19I;JySlJJCp^FJ-8s(iN((5Y z_xegK{yiE2GG^z$%aOa)VK~h=&_-j4Vr}VVGldUAVf&djYr{&|=}IZX=#8^r<|qmN zT}l@4e_ugK*iFWoV=grXu>~xcaAT{`(GbftzbT5sN*5ZWRN%9t=o`)611LE-LD*>7 zY2aJ%7#~tc0s_cK)5VF}jg>2t%NLOrqOaeYJo6M?^sKwLdro{)IWIbliQ_!DTrK~| zbP(&D40Wr4MKGU;uZTn4L=FDLed}mvZDJiSc#jw_@%QvLB_-wcSUgxX=zRdW)y#i) z*ze$B&LP?vi;v?;)7-+i^aKdGgXxln2yKt&*lN(EyR>V@GaoztnLILyfeVg0Inq`Ci|b>7$Rwe^aARk*TYIz@}~Sd5hsq68w>rqY9OC zx2{`qMnSz$@A10UW-J0Gig17HUB@2)-Ad3|Lv)s=S)R%Bq)Mii5Q9#5zI7D+fnUTC+wleI z%8|>V#ZWb_x)uq3bC5#m!v+KGl8{m)@_U@%ISr3iz1s1iR(1;2aA z(cNgfPvGsK!aIZ+1q-RSH5&A?s*Uko?};UtlS2uAg`}WzjKH%d%11mw~UIeZ5Y3A9&>#*b(cjQ}6@+H{kZkmJj$eLI-Bih)ul$ z@uZi|%u)y;;{E9usDIjA*9$HQ!S2M0pZ9+tV{=nxunMjkU){w&T+s6Vy5)JAW8Zqq z;%K+_{epl;=nb)Ssh7NR`a!Pd%v7!HxKzRaGfE7HaFx=?=Q*Ok$n>`aON9lM<-65U z{mV97HuYY1emQZGRH29<%Gk&vI3Qa(Q2KhdMh~fU$S0&JHP2_L^Ii=w%O}EJ8~+qG zPbk^{?gKhnc{draxU#0TG3bK2cjvV=T&|q8={Rl(HPyUcXK~#uI!&hA z;Y|bqcTsnD6PI9u9ieHwP`$^o+h5P4M1FtxLZzS(HlZcqP(53Zx?#zvOI|_KzFgc~ zy1zrY?yjLj<6@?IL(er&u)E~Mh^P+zFA!8kV32co3g@y}hKC0l)MNFM2PdD>~Lqn z=<)1Lu}0PNbir`(%NJ3AP05Cw4vSc^G~n>f>MzmOyyZ7vd0{NM4AMUYXqLt9S*LSY zwY3F;`%9g6URq(pPn@2aOFw=QvAynLVl~wkD5(RBU0 zAvba&?2JVAAMVA+z%rlZn?F@&#+M--tVVcWML0tn!C#b8f$(<1u2dQ_N2nAKp(SQ2 zG5>BqREV9QsD`GcQsB)abc6yu;t+c%2~OCqAOr8dGU!%kT8Q^AXj812pG00n9;R?K zV3(41!r-2l;a{*kSx@RZP#rq|7W=S{U-nNM@nol!BhEfwx~}za4LBbGQ2yP&NzeuZ zry_Ao>C-eQSb<VD5+4NviaI40fXe$W-^GZnOe`_>F3wDDqHs{O;{Y&p%34^9v(lv zUXQ{Yjs4Aj<0QM*_~=(|ZXwP_!Ph;VgZ^gtdeh(W{Hl-_l7`UR7`yAH-S+$r5H7g7 z?fr6eV#C+u@tc;yC8Bg-AG7H-d6iL|jBoE@OYkP^1GfuFf*7W&UgnXb)9aY~mH~$| z>LVMhBr;TdfbUa;Jia{VjahCxP6k-zRy#iF<-_^q<*gL~D>Cw}Nbfbn!YN*yGV`jS z36Rz!zwdI6i(Y1G?CO#cg}b1At5(p(lbknw`itJ?f5pVx72sFC$Hvj-_JXvo$zgp$ zKJ@pOr@)bC-Z}H!^3781t*4{rNW7!-RgvJ0VqQ$5Ms3sm)Q9JbW*YaSFK*n)Y-WRf z4InmlO2zl3P1#_Wb25iB*?-~si3QjnwWHGcav`K7PFynFk@RX^F@wDVT_1)gPBpDs z@s4~^F((n?JXbruglD14Ev1Tb6o*)G0Kh30f*3?I{IUkQrp;38u9ZqdMJ0K*I&s&# zPqhsC8}|V*z<@&IY}Cr#IalodwvJWRMPhm@kit$pz4z&&7*3Sct=r>FTP?RqkH$WH z;dc<+uzU*?Enm>GuPz{_@u9!~q>*VEk%UdOM%v>j_{}>S6BtRHUED@?!It#yC$+W< zL;MmS;#b=HEBXJ;@R^s zW1oJ-{S8UqVY7B`U-rygvyb^PbfTP11?^p(+wuaYB9+s0(%FuM;otu z0`XAzi>e-@b^CqdZGKqU_TX7JEnA1i-&^rbqjgbWm%Y`PQ718fK1+vcz|VzE~p0(0=SCYv|wrV>)HD)|04)6NUiNb2)FZ@=U~v3s>{jfbo~gN zxPcM^pniJX7&BxTwgbYNC{r?0vi|GEfGbC3nHvf^2@-3lud+|o@I~#~mQzW~$BETYncmo4!SEQtP2z!^Kv`ok`G?j!J;~ey=*{io=@C zw!AV--?72%5wc7b-dh-Z@%JGr?#f3hhp4;6g&8U1CzVNJQqPRXSU?OTgA~qzxJYK{ zfw+P;j^4k7q^TB|P~_G$nalYtg~kb369D1%BMXYUiGNNkZoGwh;Rv9XK4OK(91W_h z($8E(>V|C}A(tJQ%a-z(MG3Bin?ByYz5`+1+6~#QS&~?QWRglIU8_BG+2r72gP0AN za}+XQ5uwH^HA~mHDT04yFkmQz5QLz)+LVRq93Dlo%QY0<0;Qh{upub4a%HZC8-ur* zZtb7+mJ3YA9#Fwt`qm=8)WKO;jfKXGYiu=01|&+be-MYTeJH>e)Tj4I_WY7)!xNIK zL-W}Sb~_7|Y-dE7^hG#Cr6)61Y>E5u?MFon^fHMQmMqdb2_}>$9JzF+-8+u(h$r7x z5y=q)K}aCw+C+{2jm5vkMSen)>7Y`@aV^nN-u2FqB%671y?j%?rJY8emKObJ!V;Jy z5zNh29y|*Sq+wt%9)&XobG!;xPq1pm42$8dsK2UaIG8fZYyzOby1lDdD(>1SFmRv6 zBsb}M4B2%WV8#GysZ9@JL!gn``2r332UOgM1PYTY^z&C(V8VrpArD%Hp3+6n3fwV~v1{_fs02n3;`%5_F z6m>N8Hd^mQhk$Zf$WSvTaj<3!Htkg^Rsgg;Rv4_XP(rEHBuA}g0ZgZy>Q7D&_XrSW zUR*k(<9MNoR-Ov*qQI{PO6CASRr66d?jHEvdn7)@Da+@PCtqIv|3Jlr;yH z5SDzok}YjbD>Et^&g_n^X*Wc>GU-v)ZH=azf#NnsoXe6_Y=C7!<0BhOiT_)AQLyP# zQGmCxkz;p%XbQaUq+{eq$Kz8BZ<2;|Il?&3l{wJ=#{!5Ps=zgG73eSC$RQ>knI*j| zGRWKS4I1H=Y_@2yLqSxe#M6OO%L%J4I^iiT%(p=FPQ^rK?r9JS0lP%;Q86HeREwml z%F)COvBF2gDBJI;e5ioOEG#Q;M4v4 zsAi!2{+D^4GXPl^A_k&12W=D#UPYLV_rpC>6n&B;Mf6QV?@ffYa-c+-f_#z5;eoOo z!9=*ulWVLP0z?g+wI;uAEgPfh7so=$7_ zYjII!BADik5~30>EHC*&HnmDsRtrt|n5}1+$#=-`GxRUIk zYC}vmr4DnRV)|zjl>+5veUeQfd^m9|3<-)PwS+3tI180!*vbg)5Z9ri05GFcG)hW9 zuXFrvzb;?vpNO1LQCD4x8x5_h6D`FF&v9^61lQz9XjI|aN=uwUOBE9k>*s9qQF^y! z#8Xk#Ci~dbXUuU*gea*{!br%@osWd$fs*HnX_lRh4=c(}2IJSsJq^kEL^b`)8V+~$ez636x?Z<2Gg3@x zqS&7twY5pVEwfQ5QFx0~(v(2Ri;XPosP+xy(O7*XNRjh}JCvahfC|?etN+sr*<*Yj zu3F2s`QMAX?5vCW?K~$EDK#~0UDet7kinaPQQ^E*J(11p#ErUkLBMg5D+{}rdxgob zNnBsG!H^9$nj{J_I7hMd<)-ZUa-Q&X47X*=JFlmGso?Th@y&!D3F?rq%M->_B+V^? z5XDHT7$!$6`ZOQ0yHRYAEl>=oC%+=zc!{V;ja;B*9u-BBRHS2snF7ZswBf8~CE*KJ zs=8Z7cWFnhubSM-^aX9~*-_D^U#T{ta1uX9;Bi}*7FluR(wb&&KN|gOSgD-QYKH9` zL4_gp*?2XV@JAfsB&CuhzR%Oo*2PLFmks`ZIncxC9yMZ@#{N~5KY^7)cPE|K>(;mH zCj5F#T3T!@#Z*(`u2UOFjjZIJOjiB<_Dn1wLTWxi9ES=NZ&NdRtMXn|H8D^`gGDb- zX0mJvoiN7p#9E!Sl%w&x93U}f3@&daXptS9ck)q%di8<>aP#Vr>Zu8Fa6xc%IjmP? z&fjcJGVml^GhB;tZkUEWRsG1+6AIx%&y6^UzMbLW${vmr-EiqJXH97h!1>IVZdICA zo_c~AFqJ@{-hkO&-%HJY!Y`XO(NDz~&U5~=FYp){oh>F+8GFfYwfK>~B??5TC8rH*3g3kIa)NSVL^j&e zKuvr#N55G@^hr7&j07!wHYYx1ER8stppr8GuvwwpoZ=XR_b+TzxN!iv9d`%@PMeSl zNwrMcqU#xm7BRU0^NPIsVOKbb0N);{S-ZAbOW)qaioO_8o7r4|6dNIO#f7;LF?wJB zHz?`Q=fgb2$^G%$yWkyMrs?a->^NB2sHokA<7zD}Vp}_=M}kZgDR5<+uAzy$YczQZ zMn9pp9dk-%HKXH9dD{Zce;>wg$~ENq&O+ES=E=;>T3mFB$m#OixMBe*)q&2WKk4Hf znV=t=Ml~&crxrhMwgT)rr*kNOc%HJQt+N3{%nBQV)3hsY3Z01zInhF~p>J|FxG9Xe z%sL=3X9*@Zl;J@Sdq&*XTOvsqz%^~Ck)J+nf>E~~fhGo;t~bRY7G5o8G}#+Z5k%#Xb@vMiy~~>rLlVEf;?^qBjW!>lW8@j z1LVHlcVEy+8$7vas^6l{G*7D+*^(d9a}?po!ja>S8{69_erLv2jGN7eShbL+01%8juUem7kw=L%oQ%#Z&&_m5Pb0 zeu|{^i1vk3@MyP&ccY!xOsl%#zN%-htLGJt^K|E{tC^aLP|bYzwI)|AL-w|xlz$?` z^DEz-H=>G!hW+_(ai%BR>TM}$WI}1EG7jSZqv@@p;^?}r?VAwX2@+g_LkMmm5ZqlG zcXt}M1gCL#2<{NvA$a37?gY2s?teY+H~tgOdUWris`g%M%{ebne4Mz5%1)s*TtZZ# zf8*!2;+Ix~W~giaaFWFP7F)gh74(eyoOimgDiT-9WyWv~i25VicQ3S&u7H`!AoqF~%h_Mj8#;m9nYg z4~`&`DGUY7tvn@uCBx9bAe?h@W>R{>A(G){*Z(l%x9&Q85EHv#kPrLFfo4iDBo+06 za7DAWa0X^H_ge+y>9FR88uBiG=onRr{+gcd(yG^2Z(ypOYaU$P4p-kH>(eMXvqgl# zLldXYHQJY~0g(`A$DE?UFid=~I0Q2Plg#kOd*@l~&X$DlK9h*%l*rSmS%}D1^KohN z99R)I!pL=S;wS0Hq~Jp#vIkr+GBhpe*Z^Z>N?K%5#Gvq&-{(i%DVpWlZK^!-|L+FP z1J3i*91uHzQnBax_CpE_t!*Fa8i{F$dh72dIg*;lmc7#nA#Y0u(04VM25 z5MgzJ7)f%Gu@hk(#$rIka&77({ERclF;c6UKLInj1z40L$iG^eaT?)@%bZGG*$ zM3;Yt=MN8OiInERb_s(R8W&ZlDI6EB@tj;l6|7Tzvrg8j8g6Y9-EJ+&Dk7v_Inazu zb_fIgmJ<}%+&o1$Y&-D7w}x!F)$YzHdI~eeE8|hAuwW-dZgW|4gLQQ9<#a5{gtuR2#Pm9`u~-x3*tn9xiTX2dL8owgzJ~q zl`$aX2(IyAH0%ti&bi__YgNwOq2^B7IPkwCj?q*wjc|{iPVuHKpBK{M^H=Ftfw@1u z;0geRtJ4J0P^5W$Eu4w4Fz^UbY@vh#4U-eLOT5P$^YYlQC7m6C)PQZpa_p1xDi0w~ z_22l-eYlxy-G2|L{sZ|H_*Ou7G3H@5!nveEzL38^B*tW}bP2z*EhO*tV^wOmj0C4G zn6)E%emKG`RkJU@99sIQ(bPyc{@wVeT*b^UkgL<&5Sl$64oEQH1Asf=<4GpYjnfJ! zV5#{xMr-|VOH+SjrJ?Hga1hXB%2q%KN9Y6kdm91Jmo;S9mv^HpD|U0>e`ok?AGVfI zd;*@OgkDTy!+uKMIlkHwZ<4RR1qXEIZX5cCp`CS(BQWggMw)0dwy0)_4Xmg-%&R+meku<1GJo0o-!Hi)W|Rt)bHpa1 zLF;af$}gonhJ%W zT%8sp*m~Z5(9*U@wL}oVr7B3;3=&bm)7B4hTdC+J+(_ksYc7YmI*MKu+wFsA55asw1=vd&4BR> z&1CT=(v^#rmyFEaqQ^sH%96P$igIgy-~H%W|K>n84l>G5$IM}jSM-q&gIB~w8?8~P z&^%XQ*c0nzGqbb%-B369(8y!2^rC|_0Zc`iN2!1sfJF8`0AUjzv_f&Qnd{)1`Fx8%_-THgHu{xCaANwiA6`O8x`{%0|n0Z-#GF8hpr(0Ww!jw<{ zgjDzT-Cc384t~je;mK~)nLo7ei_pGBgQ)E`Zt9ondV^%>lgG#Fm{!}DjN`L3zGOsh zT}EIoD-ZkuCZ}S%l!L+2;qc zNK3fxmuuJ=5P{}K>PZ^M_k~r|zrGVbuTo5uCgH5^Qt8R+0qsXp;)Syxp~ z*?V!Vp?mrFXNyvg_;t9aPS~XGCKD(~^(qUbS@+i&^p$F-g$C;R$I4pD1HH(a6l~=0 zc<=aLp6)(T$xzDRPH(FqQK3Rus3Hi&Rm8L2L1Jvuv?r`no6Z&#PWKfl--pk8gCE!`0sG=t?FWQIpb~J>=wj_fk=9) z9?wCx|2DNQ$}!yxB{lvV{thd@Cr^uswjQm4sk%>6zTdi__>1(I<9DO~)o(hBT2Ap! zDGA$>Kg7-`jUdI`$i{^q_g>I&MM`)~JiFwiAc|TJ6pXgTM>UM*GSJWQ*>3c^)^7KK z6C>)+G|P`|66R$QhIj0rG58IYqhivc#2zD}HLl9$(>k*x{%a9PC>X-EJOccxb@a0T^w>2)% z69rIV<)!5=#17L$7xzED=C19`XG;kJNf!M3d;t$kj)t9ocFhTO0}AFbo;Q)Vk%q9ed9GCC!??3>qb zxr~U_PWk3ItNi>@rt)_ZX}GtT>A~zjck9)!%Gw95Bi&HWS3bIDN0v%M0?U6~wi(K& ztn*oNypLp|i?onex?Nfm-hsWc_a%O?XcaM@vvNE3424jkF`!=3&?#`3b?g$uvBN5lW%&vpZkZDKQif zvrZiG5Z35zAMLu@&1tYGh^Tzd^3E*p4jK*K+>C>ks)D{M#Yc9p^2kU|%X9s$u+0kO zicCj;iV8%?vr{hPE)~Fxxo&BV$fssJ`tb9ygdjEs1@W7A1ms`yIf+6Boz<6G_(&FN z{?^gXFAkT7<36k3ayVmM4ZH~%2|^dlZkE65Ep`1VipF#!1Jpn4-;UM<)=$YGFjgrs z_~us0xDmWBFM-0zQGzJxx3`C6r_N4*76cY2lb>)*KJJY%$@3eG0+~U(WBCHr$knk- zKfUBwYYQ`F*Z>f?hk^G8bcUKCCW=wM~TlJ7ozwchg1mJPfiyaxMJ zC2Cc&z*DS4JgKmea4AfCnP#l81WQz!Bf+5n{xSEBoqm|$I@TwuAZpcK?S@%h9$w7b zcf9xrS{`##x1!AS@_xb$xflv9AQCyFx)Xkh+jxBy6M9$>c8=p_6wrFutzoTGtv{!M zlTZ}MtwVkndPQ3Anw~sLby!p5QoTLXFvqzHx!te)59dP+dEMQT<9+PgYrxK1JLk^2 zULRPGMQp%xlNbSLo+5*!9PF;g#@{kvRhjmFwv&uVN!6 zTuVPESv>wFlaZYR);rpY0B>(apNmOR9qC4s6d zJJapmJ8KmrdZ3yufFXv9Gr+Erkr;3c(iGKnQ(x<^1JGNW5xcPxn1{ie1+n)#Zx4p| zcW;}qt3)(o8fYv2dN!A$KmURcIORlmY`8WaYwmTK)HUZpRZQBY3>i}PUXkF2p?`mQ zD1?bAAz6CUusDO?pNu4PLeRs+=&q9Ft5nP8F36seL)RT;C8f|${d>pLLz>*9@#|$I z0$Q&LaCBZBW34oNBds;6fD6D`R&tr z`9bB&2RXe*4`~;tg#Y|=F4)HYBjUoC@MRPi$q5-l0+MwuzC0iHZCqt;_zzC>(pThc zSJ@JR9G|%Ch#s^eOX z-r8$ZfkBSB+TPw+-pZ}O4Xg0!yOlxKeNxB6;mbOI8dIxGyM`sF2HXybK@ zlp^a&G1i%iA%TB**k0(RkK(>>sCzs2^^W~zI6#DDW*zZWL!oBSedJn5QV7_?Q?*U)kn@udksL|J7YDH&?yL z)7F;@yXfLFGgpe_92BQ6`xI|l{yta2R{;U;nFYhb z=f`)=UT306TK*UATXhaw4)*oVy9B%rYuh~ykOpwXc=N{AV=IrFu2?|)J`-;E-O>qj z)HJO_hhKb!oDfE04Xb1%I)PX|NE};dF`L+bywACTFtYQLFqSk&%j6VDOc5I*D zCk1TxVQBlytBVfGsS`(`uURrbAgA1=Rfapg(YCAUg1@>g|Ei~Ice^AT>f0LkHV0>t zUjFETQ4NKODH7mo&TF+S&eqO;`QoqGH)FzXAxOj#O*0#+RKN5`bFMzX4#1~cm{{Ku%2?c|rUhKj&^VQUnZX72-cLtj59C_g5cSjGXo{v51c=?d<`Ne9v)ZeN4o1 zM8wP%|AXv18A*?0&l})uKJ;ke7f%zk^|x7badmy~aqg=;IU}hK{t>fQi?>@kGuiP9 zybX@p7}nwj$?uKHc;Zy;vnH!_LlPNQ7iqfSM8*PV*>bMhXQsxC=*N6G=Jdo#MD#Em z5ev$NBlTmt6t^Y^q-U?dBu~BWryJtUGwB3wyb3wXn|E3@23vbUKfZN_s;n8Ej6B)Z z+=Kr)zCA-|Xaw&AvyDe&3``GunX=o$Xal&Rl$TMyTxL8GAL$8}UC6q(lxuevevzw- zCUApwKh2=;yyNg)UB(@E&9t+x`aSQ~-B$X65lziRrJ23pYn1!rs{c7AGs$t5A^fQC z1vU#KF$92o4$`i-`KM0aI&hZHvyl+;dAu+Y3b0~atqA`S#6hD+{VCEIATsWTmUR$wJ7aO%tzD(!YoER<7I@U}B>RWyC)>OT3F z{{yTj_|16w43=FE|WD~Ve^^Q#@!laTAd{)r*s z$AOcmpc1H5V0oHpTnFLo7>miJ-xumDXwLT;8YSR9P@*%ZY{1qBu~Ot9=g2AyR>i2& zDLJxT+&gx`>p(}?L2bMx*l%uLdi_UU-(^HxNF$41Q`_&oAil@%F(xjF8^updK2wUU zUNLa#k`1vGQVFH5i?U)f5{w{1BPmfW*wVd6tQj8puLMJLubz<}NJ&_fbUS8otKjlO zIF2AeFb$QioBdWl}w34=PHo#*yUK!mDBsTBY*4YdOSg%dq&SPy`L)s;iCUHnT91+ zC;!*6!HM`akshq_UGP(ee0nr4^-)?fQ*?2}qX|NVr6_4=6w;>{L^SH*Klbz1yy|*S zB*NM|Y*^BRrh$h^(uhk_fPz@V8@AkgCSCJup=q(hGaBu4rbXRkfsaQ^IP-AGyP&QV zO;^rvXk;zyvw2$UR4Lp%Ycw@C9~`kC_GJpTc;p6crYWC4%V;kJa|vv*F=#AZ!9Msz3=9p`cG&H{Vx?f!{c`WIaA8lJvqtdYsGP%+CDLSLN> zVH`He?d#TXUIdyuXywbt9w!Z8&ax5P>qA$*2>eDLGsEwzHnfnV%t5%!c)A24u zpn4~rV-~}fKMyZrUH98?ePKYQbt}=7S)tu_aqZngO|3*96-bn*{YlHVQp4WnHnE_c zdU7}jrT!xLmCr0eKwT2)`t0>57KMehjA#l9YNw>DS9;MdkK6XHqKRQudFx zhX{ckM>96u*8EHpyoxSf1e|BNPGGJrPinShTNe9jApLvbzSaV6L?A<>pwlbsoA!>y?r( zxLZk&TjrS+>-4L1go$$G5P;&jT1jo~=G`{}|2ge^TGc(StDQAjOI69a z80APu9P@!E5S6_6whB1GwQ`?3si^C~W5Y7J0EsQ5*97>;30_r=YCl|LFC}kzgQh0P z#*<6%<>AwmFn7Gjw57n2D+dJome{{QtX`+*x$abN2X8oOb6tUa^*Ju~&b96qzj~u( zu-ohS9bvmr^`*%GDqi!N7_@0fRWAYu+{FnxVdB=+Y=_arl{8_KfKuD_fquz z89!Aj{x0~+D|lT#(-Ra9$8B#5)l-Tizcr9u?z`6cg-~bUqGpcS)wMN=mz=7)a+#q5 zFCHV$-eIRd>*E`j1HfGJ_NdQ!;a`kJhS$ThOAjUi7ErAGi`uDQ&`%j$HxMSh(764ST+wEFVQ z8b6e)fzU0m9mX5UOrk_Q&Ny9E*eCA-l*9&EHZr!Q_C9L4 zh(R%n#2;m|CNEWnPJQK@4eGP?m%4g*%3~-1fN?WUq>x&dTW6dOLu??S`>|CJ4W-2I zmi(K^KA#DLPNm(3(bJLFM3p9+e?!>{2gE@QBrr7i;G?&^w0SEP%je}3>vQ+TsmR=j zWJHbC0(II+l8+Rd4k1CS$G*wA(NXdJ$nYgX!RC*|i!@_CDF6iv1gH>vtMeWFEo{z_ zI0a;RpR65Qbx93j?>Ix>Cf9wqhusVgGbV5S_Z4%KchNLL-bqi%*fbW8mzF4v@zZaO z4fH>+M;xT33)!@$Si$us-2uK12Uc7g70U1QxGZ(Yt$z{X8`ql0AG>a6~4+j76vxb3OKp&`Y!)TbwvaKkpav#NjADRb)%Q>PfK?15qL2 zeG_U9938tZc*hOHzB-Mln$7(4>_p3?D`ty6xK0)H(2)G{aPwZ@gg8Y2zDIfaq$lV% z_PUMcy@e`=wQlmXc6YyYic2OXQ4-8TC1a9L^J!SZOhaNuU0p&HFE}-~-so2b+5Fj> zrR7_c<&YBJs_@^XBjT^e`sL*@)SdUuXi~_4RMQimdWpL-BXT!Am!iN|k=Vf5i`$H2 ze7G?Dp>znrm71R}H_J&tg-DKB@O~xtVt$t8JDdj%1e zPx&gb$FCgKCx6ork9f1*ueyvL?}Z}vFiHr0O3R%giEh26ZD^z==8jG2bv@fisFRkq z(8?0>%EbzJ^6_`G%d_ts3INbtmy>5;P}N!`1~V`yO+YroWLOh%_gDGUjeX#gO`1o>Nhz{?H2V7kvo$LB1= z*BRmSb%#`iN!A; zTG}Kb-z=l%;jDF9_f#LSmzx;O_Zi0wUt*3O172Z9IXSc8@okNgNx<79H91?%9c$9- zv4`rVU`X&Q$h4$BCa*K?Qi+P+5^s`UPT_rtj7GC{`IlBrSe6}FriS;guQFSL{`$fC z_N(r32P|GW-_rM9Sa=UBfN%R!CP-&IuTj0I;Bqbt%K+XyCE>c7=#E}biF)q=A(fuu zyw+tPofPMG^1x8vd6T4N)I)pY;p{o~ZQ8u-P^D^7yR8n0q5F`Q?c(M6C$W$DcAqCY z*{#WAe#weIt^9dpIHi>MV})Z~mrsA^i)##Kj+5Keu90I%qa>le+QaA&L&$xaKb}*9 z*P?fJs4;6treQ}lEXvNa$J`P6FlBP2QR*o4x5{VKj`#a5#YKC-L)ym66Q|-N6gPqlqgQ>=hzl)xL|LEAZAyFcfD34Q%Y&6 z+@yWLn8bJes#zXd&zNW(>#QATEmyhW_h)^Atf?JChwgpeuyzPX4i2J_f11j(M%8hb z{)k{nT6Fr2&$YLoWL^xP!1mE!vDY->#f<;(lDuSrv*@Jk?CIBz#)Y0^2WO8GxgpM} z?kieF9C5OCn7O$}SbJ;^TRW-C%Z^$O>Axus4dTx)lZi=!1;~iOuDM>-fipcWOzP^J zSGdJol(|?$7#6`rk&Uy)`|IQ@nHAtn))eF}Dr!QUO~6%+n-5mWqLD?-2ht08+;`i% z5DgWHFpkY1Ps{XTyT9^NIgj1Sa%3bwJ0h#4?k-w6C^Gk4&yX6$Dl zv6~Y1V1D@pxP}=GDZH&dcRyk=h4O{@HZQh6-OlT#K_IV0CE?Vg;nhRI{<77&EzwLV zolYd47bh7HoPn=D*5yS@0r;FtY-jtiU1gJX3;(715H=^oDfBGty|d&a{aqvp&ihm| zP;bkEDVxH@9Ab7A*(vb98PtRiN@~cPX{Pjl3tuw&Bk|eTV{*V<-zImCHUig*H6t!B zI91Oejm9QqaGFD6TTW3c2`3s;&ep@z^o)oii{nk79Ol4j&N(6fDEf~ZfBWG)jL z4AL+54@flpS2^uMs8QYge2(pg)Y&>RvgT7sfypoQb^G58um@NlX-i0=R}fYKpBSX>9D57zqDx@M}m)PJgVEYzq#f@hejxQcl& ziP=BHJ)&W={zBeg!fDt^Oo}{x6lAV((pIXiEp%RRkf2ldrRQO?c`afVZkD8l3CTmG$*qjHvt}w=?tM@Gw4SLeaOYF_jud)~ z!?yi$)>ra&iMhu16>-cZbHt-+;J1{;>q$G>f~-5oihj{tSOVb1(1;M&lG*MFZ;MBX z%+O4HJ!6RQC)9V(T%VF@0F)!H!}LdUGwbhfZBiRwWGY#Gd>k)Mm2U43-Cb+%6YSXe z?eozm9&Qft=_fJy)|P&$HCip_4vR)`q+!U5l~7CWlu2jd7ls6D`-9*z-Uo_R)lb~M z=)1q&N8MQx3VMP6^xP6F=$4cVQv`8*iWCbagp(;V)?#kqM(a~HxExCrpJCiSh70Nl zt*;$_@i?mm0+lzdq^+fasuvONszW?kLR{uqM?u)3bvJA<8a*(QhAv0(W0pSqF!~M< zoP8GXCj77)#Cpc{CidS0#Tz~?K4@-=JDD*0lfwfXRVhQcl#f?tyY7=-w*Gm=%#fg8 z+dyA7SvfOPIi0c@!X_mRxfC8k3kkXAxUbhw1zgoJ$+7Bv@v;b2khxb8WWVe?=0NbD zGj`JGv@p69P{G`F+-|1JC;T0+UNG0Mja*Jl@R5iAh|=rf*~6E&dpcXDgI>!VL=jQE z{|mL*T_F8WSjru?>c-=K>bh?=IB-K``4sEfwq#^lF`R*!kruZHm%5$ij9gbq%Wh?Km0M^<-Bq0*Z_(>@&$I2OA*leb3VRIqT-> z-`ZQ+%!b~y@KajQ3mK09qHPss@qem3RMB5r!_lZ=1MKAuH-u}5p8h+GR}V?YuW4mg zd0H7P+$6K=MEZJ_3`j5JK_KXNuHO~p)wX}jd8NPVAezbK9#;r`=oX){nI(;d6bnxZ zy@N#lYbfJYDBKnbx`L1SvTo!zV2Zyz*lyJvX^guE+Ur2d`=2e z%K0h*r4W|K`SmZ(jawL>-kJBFp*j?^#ro_H}5{i7jaP#;O=PSLf^Eo@ukHdRxbO9Z%{Px zkx*^c=#Qt(FE=faL3f`8#+W1HC@qx0yJ+)VQDKvCbIYNCb|O>W42 zCqD{qf~o18UITD@{1`BE8T1vfU^{0V5Qxz&0=co7p+qFnWIOwL^*E8o6X7343%CvS zx5>;~4@ZH$2X1bHy=)3JGg}N0)ZYG$c*v>*2OIyfBj?DJ=$Dbq>0SiWg_(@_60nmF zmo`Nn>$JpN$|A)O;@~0m>6)KKx0CAm|9L1GA{F{-QnX^y*y;pfpoe?CNm6H@V#aK; z%p0yDE(D@T^6-=1p*$7>0pL%=w*Uv9JZT}$~jfCnT$9dT_HcT zDTvxE+&Wx1R(cADJF>ijx?B6FE^AZvAdU^$ z;?Q7YQB|vtF+X!l0KD|9Nc!#fF)RAvT2njXpAVgpaTM)sRU#N#!G zxfEABu}ZBO@9%XGj!%WpZ#9$kzgRe3hbsvSZG)Ak?uP=*Kt#rR{$n+7CpeZPn2+<5 z58bc+A?~~N`tAge15V)a-B&S1%$z#mpxHJtzX$SeUq=+q6HX!j-hxbsjsN1{S zc~lIA!4|%)k-I!tk2c^*7m?YgDd5DU@b9O`Qd;aj&s!?0fBEsX{m$#RiHR*gh{N2e zZL(epN$@M5W!he0E_0o3LsXN^C|64JQmaSmT${}HKr!KeGT+$`IosO+V2wj_Y12we zQ*>~@KxalClqn1Oa>K-RT`a33&%d+mBIb< ztl1}G?y*Xq&j3AmNXgT^q2FDCUg_OqNQ~KhnGGGrE z{%>EDKB|bEG_-Wby8!H4C2|aC%31BpAm*J%YT0WtQ5BfS)Za_NQ9Vu*y(1;)c=%u$ zXuD595ed<~#X^6|o0XPAqUgHVevYbrG-QvZ4uwPw^*<{4fcZ=dC zmaui131qpF9Y~XqyN~zQ(TdCb*Dd9Hlhn7J^u0>e&}OFeQJ$W?KrO<%K%~Gz#W_GQ zMy`4F9q(skRy1kftqbnNb^K0kG4KjFCDmDd7cHoqhBcw0`o)S)bLeOJCFCs{a^gg6GANPbZI2NdG-UM44U74Z*&*0G>8j#2gZZ&7)U z9C^b^>tMzpxV{Qt3E8*+luIu$UK|bt{Tb|q>c#rYZ)SEncA0ETLfotZ(%vw*gfDgp1qUJW&6lM9-AJ*bmWpOS@E+P8g4F{FrFS0 zHufB-cW&jubYL?G=CWWTbUt~f^q&ZWOkxxp(=cu9W82SV{nfAKv{dw*`Jz&vC1_-Z zoOBx&-qX~_%A8zI3>#Yz7*h`43^a^g_&=Qvxz`2x*R!um6Phhthc+yz&T^aH#Wl z?0d9|>UR*wESQdb+I~Iz!omW&30%)_t68%0;^5mQOU_A#nP4u3VHE-%pSr-TaVQ;U zbun(Bov}3Iqg(6}_zw+a_;JD0B2so{P-op-4zp}b1Zu_MzNoq+Hi6G$*113-ox!R)>&0fw(_+Fmnuf;{ zQ@#C>2%?gw>6#AG=r0aq>i)}}X_;g#okN?H5v_WtoJ~FxX|g9HtNA{7GY)3;=ce?J zwwe>OKwGitSDrbGXxZ7`#?M*0esfx)Q>3%YsB78Z=CK}0b4gt;VUA9P-@txoD+j;r zT4oL1kW%?~T(^vR!35Z;tlT9c^&qcxCjNYu57S&FEE?(qe>6E01oxRD!h`9!WrpxY z@@ZIUU0^*n8+q;veNOiM!*P`1;ZTO)1at(ArZO&jrg4m>?#)(0FWH>_eii7>zohLK z(_1A;bTN#)GRjdDi5%?ycWq46{vuv}AObufIkb=lh{E`yr|};)?MVJF7TNbQB6Aq( z3KIAnK*SlkSfIH0Gz)m9Up=Je5Dq60%p zN!B{_06r7q;@}L00+oWjjFu4-EbEN;exe8)Y7)d^y@VU79f$;7OXQQ%LcG3Xo^^B% zQU(x=mWdlxa}b78%c{bw$JH*{DMV#84kJa_CMl{T(79rXkO4Rw87{uQ&=P?BIQgMc zP-@~s9UBchzN&@@fk>RX_}ZW|vuD$oJR>7@?gLw1Dk5pL9ao9O9Ntt7(wOA8y{qtt zvOtTEeB+}#tXd+uIGUz zWD?T&2!|2yXQp84I3Q?*C1-+aejGPgKR^84G#g#Ayt>%Xlseu8UF%Pv2d{t}7@5V9 z#m4W|58K9i7$1s#xb73a+_~V)!LUD4di`-FOjiDidDhiAaO;i~Hc6<4oDgj0(}Ihf zBJY10JZjy`0M^#2QgKF@en?s}8`CR`*GMfT;;@O|ej>U`|8Z2-f^p>)cTGe?Hf*=$ zChu|)40a!+-{$w^sfyMhrJ_%tOjG)_7b3M*cj!qQNRey@G)WlOL)h@WtLrT9RH1@&lN)OTiU)T(j?9+G~b z-!`zsXt}R-O%Lasp-TBd624paeY@WW#^XFdD7k6N7!L?ZP%)W=~CXSC~EVV+VlnY45e{O1=JuC zQnqDdcsA?L67G)X`hanJOYY3!4}}ePUwobWZVg^kwpCA-fZG~nWPn7aQ^ZFIXm*M= z&*fW#(pcWH%vGuCgDhRWCRE-M)@S&;k1Kz7ted-;hs;5uSdoC&sL-q5cLE}-MyAFT zc>mr~UK$1o@XVkqlXhK*sNes+P zjEoA5BMl5GltT>qF-g;{bS1n(Qm8=d*55Y#f3!gv1wSZ#X}?Os^m}!D!jOC@oG;G8 zNQGYl9vYv!^T0eU1#O;n*ZULkU-%aUC)38LU6y`L8x-r-%&>v4_e~4EFpg|9S3%yr zbI)msVISzCHRgGa?Rad#c0XM_N0u%=#VFn_<)+COYOMP`k$<%%(6An>4|pI{Oh6Se zjqLmuc0Pl}_jb;h+UNn=Xdfc+&^k!-T_1f((e0AzdZX0F7MY*w#Eg#4da{Y!8)0>P zJxMaO5Ri0>*qdfzJ|VzZ_`ZvO#w{YQtezw)k_rhiS7rK;_Bllt5#LR6DwCaPk|Bw9 zRTE8X7{@Ocgw2kj-Y+Pjq{RPnAK1q?NQgc=&pPTBSzVP+jDpKvCTz~ft(;m>$+A-V zKs&P(Y>kb}M`DE^mXVQ&Ve;%H`qA9VTZW5&_dJME>ncjV%+%Xn?fYZs|E~pb*V1Rv z@4|=@4*S7yXf?-ra%1oAQNy2wj?K&(I#+0J%V#+IDj)Z~OjX|}@yR9C8?Z0yTMYP~ zaz_Ohwt0@;EhgG{W~x~%9=M0tR7nTs1 z(n(8aD7f8V9D{;bC>JlyUQ8QopnlJYdcyAsNFNd zSy-PZR+XO#H4MdqG_+Fs2d=_ z!yukR&7qfdf)xZUvWEP_E=P9i5e6jIg@_~6CZFYpVj>=z^vZ} zuz&CgTo7R2-L$lQo>HI1Iw!M5-WUH5K+z=Exb#bh5$74@MMaUxLwmW_s>v+STE^D} zDpL>ny#Fyjgk=<39>~HR0Mfo|Wv`oBqix#g7^)YU0FfGN=reJXl$iV)-XdH~Ly>L^ zYJNgnx5uwcCTF&d^f<^}2UuMF`hJ<+4^OmoBBD$TQ1?Xd0>x3a--*oCFGMfjMVWAW zfhvc=xwcKdJ?9si7U{Qd`|@KrV;USHV#x?#b|dlu`GTl(ud57QhgO-@a7yhdyULj8 zxz@gA-GK38@j?zMzz;nf>~)x+o^mKat%<{yuJ|$fQ-6j`fqq{C2gGbdFpd4%e3eZ+ zjm)+7Ex5;NMB0h{HbvPjv6`7Oh0%+HJ`G8pI<{KFxRtSQ%u*5u)dX|P@PeL^wTYWk?b4|Hm| z45LoVJQC^&p&WJ1!+s(?4jP74XHT-o05c8(%9~z$9ZY}>Tu9+J9U1K+#`(oCkM@m-S2wM0!@wXehbC#^Q1N_!UebGnHtV8 zTUHNS-J10=!NM$zkAv?bOw}qDXQRTswm35^!s|i~7Z+0k<8EXiNy;2fT!acRmB=J3 z|A~vC?tR`j|1t21We3&A#VUcO>pDtLDuh}aX6;6N&C`GzTiP=6x#+u6hd(P{o@BfS zt)@zNf3E6Sy7@%rcE>wCx5Ep)zVLTOvf_VW86MzJU|Hz#C4V0P^T!8VU#IY=(HQUi zV!S+}t27*q+i%TH3){I)-@Zj_y@=ni5tCyPx97e!vjks+R|bz+Dc9Puc!{P<^m{21 zD@4rLPCPNrK*aUuU~X6?>*645XU#OLwr31Ti(~6<`~DMFV7K{5KBbac0vEj&*lcCs zgGoQoXr3+M)x`OVuTzDJ3jgc`1-p+w&`_Nsa9L8zeLYjgC@FN7o#rY%ppN^p++jgv zO%-R0&!yiN{~`Z>5ke!LDVtzo&!(R#Na%g+L9c0}^*GBT+`~46^$+A{EEwr2+_Ezw zsYSZc=ggqW`Nb--rd9l9N4g|Pgo*azvPZyNf)})d*O&vosD1pgX>e~QU>jCI6V0xi@4F>}|x_ws@`MofLqPSKHmw9ry-K;Qg_TAl1oL*TDMP0%#@$?YvEXZnYlsdok5lC%DhuotOaRL zl-+DWE<`+3Vy(`(kUfKisuZ<63+JAbm6hX&TUj0c$$WzC3ni4!Wc%~_qv2WI%hfv- zUKj?3*mKOJih7SuLEav8nLAZ#fu=P|&sMc+t`?#O+2n?o5o=&pXU4>r7^p1|kH(+h zVbav^n-;-)s5je1+huBAz4X3^A@o3r6Eu3PdCo1UW_sv-FJJi|&g1Hb=(ENY=HJEdQ1dTGFNd-8BCEwn=#on|Hm4A*WB8X`%-IL;&`bRuhF4aehqbIysuz{hX zBy93#omE9JUpElD+k9fcArv{x`n#Ymi>TLRe4 z*MN&YO(OoEhzK{n`phmj)^=_z9Kv|{-^R~Ofe;61De-#;@s!B$y317xz3S7|? ze;&wVG&$_$K@v;|aTVs@-L+e) ztE=uyNdUNLqtYC%U23>Ydv~1D#A(XUXIzC@(kiRUf=01d&JYMk=5J)|$+2lNS(1E) zGcT50bZGSbot9kAnzoXsu`CERQ0B?|vuge}kBaqIVe}!XAk?pm3-+?`%HfjY#e{s{ z_IADGraO9PM$qXh5$+ccUED?)HYo*KNi`IZ5~Sh>R|H5FDhrJEt zT(&3V`QgVLCQ-y6MncZR7!(5{xaXQlwop+oVJlDA+wKh|^|Lm1m!_|LIKB0*s^d44 zuab<;w(|gh)RUL2)a+#Z$g(hCF@%8VC=*m?HHovpb&# zQBYEi0L`3BcUqIIfa(*kH-wQ4(4<6M(9VBKl8QiRLm^au5jj7Jq{IZjz^c*1k$26q(3)eH3{WImbM$opzre8Iy@elmugljz`%OAVI>8aKmp6 zN&D87liaD$nBk#DZ4g(j=!kQ*M;;X$ojAMrUVX)P_)gKjKRwKEruKba z6A-!Dz?bQw`x!GrD!H%&f4;F}1^7AYp$qx3Z# z63UVmk^JlsHw^#f;vLdJkAeDz@exmfy>5Au8e{(}t&Q7BZ6uV*qin+KTe6%vc3_JE z#M_paL0Ii>bgV0xgj`q9C)#~uIA$ku<{-yMNr`&S*vGoHjCW}sSoo&8T~VMwbR2ve zhds!dFh`Yo$IZvRcUm{NXFkB@4@y>~t}Vcem+4JTr?*|-d2Xb> z%%%6krZK^ePoT}qGfqQjg#@hlXC;4z`j;J3gW$U1?UT04ozpClWIbXsu3uE@bIcUAz%HQ*o>OMc3MgFmJQ4= zA5$jXu-aCk=9B>t0a9zTcL65bQEHmffhIGIoEXn%7^4lZ@L z;P}(%I}<)f_?1==;wEEUq-CRqcC{U0@YrPbwMKhUJ28l!K5)p)r*^UvA3X&vPf_$A z;aa#~E(1PhEG#%r0_@?I6j@1o=$n{6!O;BT{Nm>S_aKPr?J_i8oaDN?>)w8&eXyt| z$knI&P9~3e(aq5|@-8ZXEReLk#09F_uC$qNO(`ehgkDt{L6cGzNUtu$Djg0qSorpL znMB}kd;s3{q;(T5%h_exXiMmVuF-2Zhjdafp0tbz(Rk^M!wFm_1hAyU_B7U$qL`K| zfe?N|w)XISTYwxU0qyNFqh3Dy`T;2B!lqJRz$pz!F;(F2wP2=HAX9|bGAFcvRF>zT zSAJL(qI;nb&zIIDsOtHe#wi#VtBNFym10662{2yNW(!YANjZAN5^9WGDBEJw`rQ;B z7lk`P_QFg>CuPk}`t?~yKXob61Rp6{O!t%IQ@Pe$C$SVMg%rp%H_)I#)6$O-Wf+-+ zl^6j!JgB)fSj`k{=(l^Macon2jPfgj_ZMzdkqoT&OPG*>ODVg$rWHf2Rk1`_(79$x z-2>EbTU+Y7UwWD*2X8QY%Q5-Gp&QfCqH(cWuI7?>N<4;Mi5S}KNehT-CtuC*bg@Z? zsR#IafJRkE65$ak{eAHt5;;ojY{KHoCSb+inV}okS`Syy-TwdO1zRp&t>~)pP>ltL z5WXLW=Zo~6Z5*6^^K5TXEHtH&$P;lk!KtqumQy6trbKrhIR;6)&K!t};-^*RhEf!k zW>>NPW!=yA^?e@-2~rjZdB}26HPS*b}UUP>{3|) zK)g2F;!3+?vCuA+Ofb|$HlJ{GxkT944fL#1rH*N-EK!z>Gxit=h8={zDAJ23SfW77 z_`@pm{M@^>%1<>Zhn~OZ-SGMy5+o>CU5YoXMV09a>UPN9Qb(%lqKVI8vKHL}z z8vh^p1>~@U#X5Y1*Si+}^>xDo0lF>=X>P$izB3!_&F!W>yn@VRa8E+@p5g~oPxyvu zabcgi@#XS`J7)8K442IG?CLGZ?BZmz&Huf@D~}UeV6mdBSYNDJO@9dbJykjkD`uQn zSR_6EF#ATHXFY3T(+}QgBO^ljeW*XfDsqgJu2uOW$I#YEggx1kCnW*;2{#+~ z=rlqfB;#6ZC2QFfX+}`8x6PRcw@XvHxwCy3cyj|#u9Wn4hHx)9*s(eli#N1839e)4 zQ(0u#14m#-*`c&EJ}U=z0Mvtn63pPRkaR(c6i0)%Tb_};uCld!b4>47U+IB#`5U3j zLsSR|Rr^>fvc1lHyqtfgurTeXZ+GsmTKAl<$USi2NJ|b~zOMh6)_HYlW{|=cD~wdM zn0-}Je$)0@qNh}G@y2TF99dE4mKun7Y@j9uaD|kYUloFZ}gnb zO*!A0R=Olm_>+=;BbLkEDj^3J-;`4@9WrHcQj?M7tf!UI98h_aLYk3sh=?eyVc{sG)W+s`vWCZur?;K z3|UIz)hX_s{bFb+ycxTzVX(&}AyRXTerP*ltcEPen6+ zML$XXMer$d)RH7-T}?1hy(FD79Im@sPze1w z+OV|l5EJkM?tA|Vy_GmDSs!>bXEG;XG(`Z4Q!ia;qi@z;V{8emg*Q#jtIFsgrTCUI zL970QsU|h638sNQOv^d!UTW-2L~QW8tC%?vNW~DQypKT<>XygSy-|Sb<0iJiaM*$B6w$-zD2vXi5xhkK+>Wn5JB=N54(k?lbBof8y;+^_5IY|+ z!J^$RW7V%Jv-D#(zoV!oN$)P#`KiP`2?HT>V^9eggEgZWJsm&!Fb17nMVJ4 z!76r4vWJGMHbAMoPLbZoLp(-?>s*$aj@IEgMxCC1RwNmyh=lEfZg%0QfjUvnOD3(W z!(>2g2~3Sl9D^GiBqT|lYb{rihB;0OtQaxtit{+nRI6829;{)<6cC9+Y!LF3qXNjG zUmx**afsjd?-weSsn1iKq6k%XaFs#z7>gZ}#Yhdb<}ku78VYw=aqpc`#JbYzR8zwk zwREVznI}=BX6zX`;i23**`7t^RVqta$4XMeZ;*RSBAPTgcnBq8A`K(h)q>JoR5Ymt z3O!haqS8aEyRhTL98JSS)K&}jFqibAt~$8$uat@TPGe+j;?n#(rn;w{PZzz%a8fG* zI{LO<;-6N&iAY8PrK!V3()NpWNq~5oii+$=vWwG=v)|K;X|9~4w!iEuMbUm4i@Ip?<*u78YV7Q8OfP36!q85@f!XT+OtR02DV4HEo2ZmZDGU2Wc;=1xOG<(e3=$NE zCN#zt6?qlApquJ;DDSNVt3tT56l8~*2(_Oy<{+|n@Cqz#DCK6CY5{I|32;b$?*CJR z6mfBDLrx`WY`Q~JuSnt=_j5j1hmA&?!qOyljBOeVPZa%C24+h;RTkmwr2Qr;Sg%Bh zNizZ8wpP`Z=64LftkxZEqJI>n2lQ6~z!mq0VPGAq3~}h@&amTVbEg#)m6Kz$Stc>Is1eLOc6bF*p|@Hf z?SU42CWAEyHcBo3M}a>>f`a#q2M=S7S=*!yc{Bq((LnI`_iKYd0Uq$dFynK6 zpuM$H<;r2I__pjJ5+yXm16Ds`BSaL6`(w=YC4VhARNqh&MZ4#Ctro^BBb zJ`ohGn+Jh%?oo)~_Q5<5}->43x-Cqr{v1qE=N2@o_m9(^SZH6A&NUnC{BXWz;*nZSI zoixAPO=`{A;Q0ECy@m+4*NElr{w*>2O3faH_Eis4s9RPjwcC^&t07b4$GMGFy#}#U}|EIAHzV}@l_tuj)$u248oy$ zLax^f5;38;?{Pq&q{lrKsE!MW=+#3Cl=)9poRz+!=jext{$>Fnfc~?pAfp=fRDq5i zwG>SOhL>xf`6)UWS+rQD@;s*uw2M#&HoytrwL}}QQApr)0R)o5`Cr1KK^ohc&pRp+ z9|#PWoXt25DKLPK0b|Mv&a<(pip2rzxcc~f#^T#Z952rKi0^^BPxxn*R%>4WXv+4284h2T5N}3ffr&nV7X~)s zOxD!W0~cx+7xubaIe@plMjD*`dfDJ&}~O|%CW9EMnDsL7&? z{8jqPTuNM%HMM^zHnLZcm?&DowoL9GqIv%7`n&V*;?n7mCA{-JG|n<72}iTjDf7%q z{dc2UE*QeN2!|{dG|446;Pa?^++bKei_}pIskdr}GU&MAGK&&@_(AuCIGKSlO2&NB z5T!_^mhZiB3MSu`Vt_Ec4{rw$+mgZ^OrM~1yCb^`okrt9(uLnhdi0&>3pRy*^>BC5B7NZvsnMd z@8A1Xw%hwowA-Q9nDoh-#{t8FHnQy3A#@|(C{9Pbaih6ogz<5LmzQMQ`VO5!ZKa|7 zm?;zp-4A%6ox~tPT5jIzXPBl@6ih3q~NX$&aZ+fuvKJtF!`;z^#laD6POH{7# zXHFII&ZH}74=gEEl|p@%{&LEMIWvNg{)>VTLq)Z>%=s{o4m=Ch`QVi-n6(YjnIOAz z=wHd8mxUW3r&Lb1pv_-6PLM`cMY`fggUqZA^J)QTY0wb1i%q0ShfFuE(#+=qAb5Lo zyVCdh;z9rYiLZ&F#)NcoX!hsu7M~0M`_Hat+xJA2U_N4GB?yl90XsPjnL-hXKN}1+ z{$qNDHs6X;RhjIDa!8NBcW?29>3vn-!Lw9I{fom;{ZG4m1MS6&dG-cl3!ByV?oUbJEDAxcAz0V5w5R=QDyjQzH%jO1)hg6rLe2 zv%T(sWR!|a$-LDZJIr%o)l~!=60Ur31aJ2DnbNs*6{0T$waQT+GtboX6@Z&n88$b~ zfHA8!WRl9&OzpCusjF$?+0vVb5DZC;UAI!?rqhPQvQUb($T~X*jM9Cra2}cKq&M8Bu^$#n=iR@e%8o(FzI@p5#^%Is zXP$( z$jQJ=X{r(w z!L--@f4Km69!S#4`c>iSAq7_n({6oZ<3qckJFP^cZgf?HkL5Dbl|zX6dsa*#an|Y% z_|#$hWGT6=!4fNNMIA-uGbXrSWLAcro&4WGgePAVC44<9D&T=|^bPk7HXgtyPiCub z(X`sYfOJrPBpU~T#L70aU@Gk3&2GWJ+W+CAsaU_a{kD_=<&p z2Wri0*ZEpMM+GkiQ9;tt7o0hsvl0!5shzI=nC=;w-yotv*b%8H|8V8JC?$g|J;StG zULv)di_<>?uQFOVa|LcM$)^~gR^z4`ao%9Ic!!iji=k(Uciw&~n& zb5e|d=Jo9XbC`kT6;-fiRcaAqd@IVeLDP|xzvx!2tDBcg#1UOD?EiHGTv3etALOg~ zC*lyBIeQ5n3nVa;36>hkKrhn2$CWONp?C1&6{Sj4YDcgvoiRkchcUiF)m;T1k@m>j zBsc_!2^Sk=XEt|ybfBHltOz}05K#K9n~xU^`gJu9J066cSa)-$-RuqLDwmZ4 zwcp<82sE)#xE8y;e%g71mZwoF^i1rn;>SD4&wU-fze6O#_?LE-I)0TB98RXsj!}h)MVKi->ptCg3%MAaRs=++p09*+0RK^2e24y-T<}9X; z5=t?bHOcI0y$Rm1%MjtB zcy32;zeeo~yV(jQb81`&Fo}efXJu^eG70L}hkY4j=3Z|+{T5yDfoRjr`MZS4<|e1+DeEx9 zHjo*`eH6`|DpImX+bHJef;DH>41G-xxPv9+e~4h>e}H;-;v}=(++O6|+^ODZ>l14W zL>9PS=mJR~C$5mCr>Cz$DyIa9vuhkL7_-lH3XO0|*x&Bvaa#a47|DIo%$6JzN=T5K z+*(E&Drw`Q9kkaCwAXHU#T%Z)LING{1K1Oj)Wb{1`*WW^o4!|p0qgi$CSi9*NTZB~ z%`zOcy4clkar!U-!-NOdU2LqzZZVrXa&+Rhc4r#Sf& zMq-O&&sOHYM{5P}`?8sHQlLn8#*sqsJ;M)%L<<{TW2;Kx=8Al20hdenNHEs2LT%({ zmpf;Yv1nlQa2($3Fho@NXKy#AI+4TmE%CoMZo`}my&CtVm_XwCuu&CllN%h)62{8< z_Ld2?Hi>Ds;V*+eF|%LT?u-IPuCdcs33#(eroXig26#qmSfy0V6Qs=4-<|67AMVTJ zO-m@v;BesZL!iZfsU1U4i3HaAD+Z3ag1y0yYepp|;O>Y&H<$h? z^pmj=d4T2`h2I3)7RD6jCr9c=QnZ<~CrE6)#QG{Sdg(8^}Vs$L*dKzYFrH z6*YNB6%*#+IaF^kY1RYc81Zd zuxRIs`{~3F_HY1Y`Ht>+OPI$8TL%40DgbkaVE`F<6|f4W!BrQ^p+H7rFBwk z`rUq&()()sR^u7{1!X~VbuDjZehMj!e)tlWzZ(cl21-erAh1855CJ+dAHlO|^%&8l z_RM9{PHk8t6hzn1bu5nm0^jUNook-VCfR(_1%{sVX(BQtFMkNXMlsu>fNVZVb4|m{-Xhj?r=saKCPoFL zyrrk-iITuGWbOIzXE!7pg@0{Vsq$B;DXM(R*un2wzXB`^99gO0mo*at$-g_1R2eeD zyoI4^5bgvnR}rG71P1~0N%SEK`Df$ULXSi_Vc~CInezU(SzJIF% zC<}<%U|T>6i`lWXMyD=2|#;QDO%DkDDwBY49#bTu<2^GzOwDrU$!EA%>U&( z4`Dmv_(H~;WdKz^9+e}MnR}{Shm`nx6UtQt{jaM7R#@TeX_dUXDG?%~nax$>e_Q-| z^>U82{%9Gf!HmjGWaD+o)iHZCK*zkt|6F;D;toX&C3wtRrzSR^PZeNL0Hf zhv<9BaF>y*f_Z6GWJ62^w;rWaSceYWZUFhyDehpSB~|=L{Gu|_12hX>V_y8N34nT8 zgO(^FgCWQPF9d(jNKSM+gb(;{-d2rF;$ttwnUg2+zlq?LmfZPolYj;9w5H85IkT5v zoE2}hVXBU>$WdtZv#L+G$9x98G<**(6UR^_2Z4Gy^dR07IJ>RtS3{ks`wdU#mA9B? zP)>m{^`w5tc4kwU_c1eMW3@w*eF4bm7G9K#@Z$fWe$`iE*TC_{8djOv&N zei?0ZQ4Gs{v;1#p(KPxj_Y?o0?=f1&D`(5c$!9B}CP-s`sU9TaZ# zR|UVsG=Oc`ZWn$qOa9QLZvd1SVpC&JWS~ ziv9;YJyoXWdFeV%&~C1(X{;3)4LqnK`>*Z~1ulu>nC+hc z_zWZGyas;`j-b;nnCEEp56=~)ct$+{in%~khP>!U&<068wY5*#s|s$Dk?R4FBPCGHDI%-;|`g{agS}Wsf~}?2IUb=a`~5Z-;J@p4u6^e5l@cqRPL_9d-*oS z@FLV_g{&_5_YVnk#pta!DE_Aq0lRAbJ|_JwftQ13O)D%KzUu2llU)m;3?MKZ-ZZQZ z0H7k?xk`zD%UEM6b%s8C2N=63fe9c`Q;;3WNm)?cs7_*lmSKubDPlR)4ZXIQlX`B2ZG|Aq_z#fFd|4vRotrn?e7MUn0fqBNl<2EGeOX7O*^Hnm)xn8Di zFQ+Ug$1oK;Q7a6=S*1-(Q<+5+>tTKrAde9TQT@PB((F!`#gi=>Yey{9%TcP%F=eSe zz$lDK7e!5jfcR^3UCu%8!mCPSv1Nne?EYA!OVyf<7#?H>mZ?>&JwlbQTmSe_ryGsMK@hrPpnEWrUJ5c1CqA+#pcx8}C@UK(^Q$T^o@XJAG|Foc|J$15 zT8j_K1bfAp7r+yBq-N0B@-RuPZ03st_jRvFx8zeJ)+1D^r52hIc!Bj~*s?KxI|5|~ zt>+Zk_XZD%Uj{~JL!Dj{0@nFlq6TCtIFh3E={WUj;1k?i7#q7l~^h;gW$j9b1PT+?O;-~QV<6b zqI}+Nmul0^RUVc!W%a-Md2|@q(Ga0&Gea}CgoV+&PL`6Vq?#F-^K7y{6nqs=e%yMvUaU0RuZ0yZ=eIpB`YIF zC8>5*7rWjVUEq&2)<`nrtgdyv!B5KUsEZbWBPS(Ofq9wu`!xR`Bq*p9i}016X-?zE z>(uJ`XLm7t_c8Io+k51t@qNra?m~L;CScF@itf`381E zHISxe(5U1|K={Z@j#%4u5e4b=jSQp!JBXI-TLQ}ax$@csgVZW_Zr$M3A7jd7jaHwq z#6n8vN2h0frf@sm_vHtE4^UpSYxb7G*qaVT`S4I{ztRcshKqm|FveM>_s^6nn3IB& z0bD%pkF{M05VTF+(TX&!l`LH-GPF#Q5=$8PeFHZ+I;@l!o=INJI4dZVkliWPYG`g1o%p=(BbDZt z?+NtD-l&z$t(E9d%+*{R!rFr&Sp1)-_jt1(^p}@3+)Sp}I0~6^te(FRCb^(xTxqtD zAmsL%r!gi2Ec4wPdx&D{rt9-opqtN^S z79WnBc4jK8AN4c08W7IQTq*YecgLAelSEmRp1$$?(Nrh?)u@VKl3=1^9WT`=MGPjU zsOT&^o2=Y7`C^CFK_pG}}UXwX}b4#NtAVnMkLP93y z??WgzR}5>f``!=Hj@WddhD>>XJLGmv02d^WAuNF9+)Kij7z0UsNc{QK*pPu!L#wvb z1bIHsFA$mQ4Xu<-jk_};j@U)`e)-dT zctFdt=C{%8Q268kjt}z(YD8wd&#ANbg5r}V*T9_^ViBtxZ~6-G&jR9@Wk5JeS#Hiq zF%tDe=d6_~yR}O1exW+t9-8LIwPQ<49Lrzs3kNGF?^sBcUnpx@&01Gag?kqW zA@y=2_28&wkxQam)(Ww(+eIKmrUhpXLht;?sXoPqB*{*5ROiMl_i?+(yitLgVY2J< zeY?LvDRySuRkL*0T0{AKZQaDqz@gY;HsgSvLz-=Mvv$}jDfW>cBIX%Cnqd2yv8ObU z# z$A4Cxq~I^JntLN>FdWKZI!ZMRVGXS!p4|H`WcijnMWy*CzGVR);bhVbCR-J_iJJ_r z2*|J|OdPpJICBvCCdmyBS-uPn2%rp}&86}F7ZmNDh4BT=J|#vPe|`^Zr9ae#&@thH zkD$v>^K>fVj${ilC>bk=WrLnfMs{SKhrlBs7&E3tIO_ghv&<#59+Z}+L?flM*3;o% zLA@09*qCjZ7G%*;B#izMk<9*+j^!UKF|80mCdY1OQYttoNA1b@H4_v^8y^V&B!o8q zbPi7{P9`kOLKv>-UZ5;_&x=#J<%ik0P(&y`nnroT;jx^v$5wmIJ%-#;&)JWmU;L3S;3x)37eLj^ zDj+RKXhjG%G&rO!0|JPHFd#2_f&k5bSl;%Ek|p*6&5c+O7kz-no-)^*GT6c(4f0`V z36Zh*1kss7|3Z8Y4kze?E)6V8PbrGjt*Nnrl8x<8i%(88+tm~z41&&zzIcRIl*o_- z*Mf89a5&!IUwFN0x+A3c2ypHjf?`74h_+eA4&{&f4Jqh)hxD)5E z80_Aj%|g}Y{(-Gctx6-cegZ6v=J(w!yURmjSN@kkd4Z>hHhE%4%v2GVkoidG6|DHW zSm8AE$D3JhNrbtDsyh1}j*ATqvsxpic4|j5$cu%m{t4F&0f|TbP%YtDrFXF;S^UyDNRsOSyj7IsWhW1a{hn} zgb}4vC~>xM_HZJIcJnd|zfgw@N8(Yhawt?TGS0d$lO-qd<;ZJp?p3^C8FsBBi8wOV&Sto;ktNTa5Diy&qA4L*m4yRlUl-RJXunH^u}Q8zMmD z(C{3%6CnR!KGl2o7SUYIz{5?z~mJr`&m*{?NCWUqRHRU-UWL$M~)AfS#(qAd+v*2+*ooxm=lHos! z#LE0=IMjP*#qXz(8clAgRVxCQ8Nv7c1DsG7$vM|XB#E0FW*4IngCf<3t6qYAZ!X^A zR;5*W^z|CuWw^fWU*>mhb-gBc?br%Dqznq8_0!b+RvDaP{3B;u7iBqbPOr`kLRtQ{ zy%oSGidup&=9DlP^ykE@d|ZM z!vA*z0;rM{d+GUs42rWRC6H~kf)CTn(PA0fDUq>NO#KBLtud5_Z-Ypr&gy?9>^U6JtdNkX)piIR*WKP>^CIra8>+D zSPJQ0%=*XPJ-ha4%q|Ps}xqjR0xni8JKk|8fD+!r#WZ0f2BJF9G1C@C+M8@^>XRC+U0z z`pzoWkL5LxRk)AiKhThuP}iiJSKl-nxrNFRy_0z=f+;rY6Jxz#w2$o{J8TSfHOZyAJDl=2il-|G{1x_`AM@K9jt-zMThrc{ztjl3$?tn-Jtr8D5P{KK9%C4oq%t z6y#q;T5ek<6oKpE^=yZJ3y@E>E;Zs;ilM2#4vaqxQKS;jYu^B5ZfsLOzk|7-C zTEQ+-0GGUS-4X6T@R0dmGy>fWk4V#w&@!JLU_Raz_~O>EyCp)sa}2_q`Q0#QH0=fB zh&~Z2_T`kfb##!VYZ4-FGBSt~0v!b3CX7PSI(|o&yrgwD!(fGbtl3fnd6&>zCn9kB z4V%{cPfnW_s~6oh;9 zXPMqSwvd=Zjleb-lN75=<%B|u9qTN5lClUKJL>ihXmjP?+WErjKLfkk)iGe}(=vXy zhY;nJG;tC#G&~df=r)uCnQM`XQdnhoWRcau z)km10gShb=9M}fp7Zqe7#Dk7ZribnP&6`P*b34usp&GYLBqqQFn_hb;Db=Krk!{~F z1nt#!6S`g^ce2uE{f$9tz!jxCPVbL7rpAwo+LwD2zMXnna#>;1*-stap&Lt7R#xUx z5$MP%5u`B=*KCyckh^h@o`8@+!a!$y?Pds|59j56;4_1G*LNHjsWe!bL2r)$7OGj) z(xSX!G$m$(xSvd!KJF6xd=Tow)Pmwr!fdFt&`;e3t!$`|J{LyA3pL`(VTNe~;G_k|K z34nktqXNe*j>-ZUtlC?ZP&y}_fI$1U!+%pHUEoklyyB5~9m=x`(3QEZYs>d(4`E#{)1@QS*uosg!sjN2jhK~~2ofmd!jDK@ zmH+*o8^P}V6KQC2A1LPt%nxmR!+BX1(9d11nl9sp9K1CWKO99keJUZy6%_^J`Dsdg zcgmYc&oO0ZKYmf)+wUQ78`n$1nFG(Z78U7^8ov)mmq+d`%LO;HGx}43T9n zhOP@R#Z{pfA$5;sBfS%sc@~fG4n?4=&~Z;ESX^|s>WJv6U-8U}C(BP0tx!r-s~0TH zG0sj68n0H^j`x5XfRG!$1L&%1UG~h@+B-)o6SwO*FD2F3=T5eFOxB*RulOc-r8|L!M_HjG6q-N%}R=x9Fi1q484Z9GRX zAy-dRwhN4tYgSIj4SMQ7o0s)hV*^nUwT}Y8Bp%l?M@kj_y*#c;?iXeV!-X zFOmt`n+?0pdp#Mhhsd)KaqphS&@mbzJhzJ%yo-*uk+yQ%{frOO^^}te*%8LI8t)H2 zM+6{t)r}1_rdKeynx~?t(dYA+X#JAb>FONowU1th4E5VtsHQTCDmAG|B92iI*<`P? z?i!bvWrJO~$%t21rPpTQIjRNfUnKDiLZs9ISfxtQdhJ3Dkp92i4vw&k9i%TAgwgi1 zAWMkPq})x@+4BEgtR4aq|5@t3Y`H^{`_y0r73?F%X7f3O$rVXS2@kaL)}fw#XSH*8 zUfwmciwPXwwGs#Kd=c3_f)fSDYqsux`(x`rnFEiNJ~3p^_&SYEceA|4j`FhBEN&Q` zyhFaRvHN@CWy053pOx(2*h+a#EVN`8=KOh6D?1;tXI5wJ;G65<%~%6d>z+$9wdEG< zPu1^dsx3@tv9*Ibm_R?^_fMpx3V$AXQSAMMIwBx{PxE1p8}-vh)iz%L{5lub0kk>5 zFbEfg=Aaj=yiBliHGh-6l-u_SZq!K>n;}JhP$n7hiyFWrji6a9)H@{P07mG|UsyHl zIGU>D>)q4e!+Z?4<2UhQ0fY2VM_^5@GEJK&)rjhrV}|!)y4(8>t7expimiBUwd=|q z(ZxT-UnTsqm!e&DTSxAQ3bX2Za+UoUS#NP2TY%qW(nd-3cn1f{Nt#IcjRRVn{jMb3 z>}5e(C(~=4BJFt|7lyYMJyHQe-GI!3KBEH z4d7&uWZQA$v!qQzWQ*vflVx1YS*aLIl-i{K@sX%aiwa@Ors@%2{T=mO6W}t8 zN&melVDyhKJ1P@H=d}L)gz4c_CGTn{`&!L2vk3X=CM%xS1d9PTx=3d%*Zk?$L)XI@ z>!19~1T>aOmNFO~l4P)p#Z6oG!!T97jR1Q%95^oV6@J-?#R=x7l&V6Yv-7^DGgl~9 z1ZW|rBtc#DtCTL!_QM6d47h>~`CI-s5%|@#9&Iq-r^2z~Np-E_;$;_hI~cRSXhX~F zVg~$mYuchqT^JB!DRI}A7Pe&Z#=Qy z)Honwd>HTY={ZQ|_OrIT>Ci3U0ylmZhIz!R*FX~i=F=D|ka{}5oMjw#bGxH5r&kX3 z#+Y-MvSqNqYtJcGyO?`!jHzQOFoybn+8GYDFv?reU1-&9Z4JK3bS8y`0^Kw}g5-A6Yk6EFc9bY|Vio`E$Pjv$M~H7rqm( z7Q-c$)2r^$|9({2caYb=92=h#A#)=*t!WGFRGv|Cu1vDxN&N2!*v?50t^QrGRjVcg zncMgBXYZ^0<8{6K!$bL}7po4d_DiEmD2Lhd>T_c`@T$$@S{Y1WLmV!wZ;~CHuiZViyzx7b zlk)8@Lk~|e=QrZv-PwKk>6!f&xB2#@+}RE{-H5UF?D}xZ8g{zEvn~fE54ERVEcKbq zsXlm-ZTi^R%ObG7U8GEknULN$V4c9qO-e9JWvG%TQ(XM1i@SK2#Wth>&s;9E6&MSa z#_r9aSDlvmI=Kkor_z~7rNFDz6>qkA*(AA8o_pWn4udl#r%X1>$UMKFx$;B&ECGqyP6=iw`UoaOT{5-@Es9#o^;Z8bBx}Y9^7jZCyd^oNYoI z7aoId(bHx2`Bl-ij-G&SoAr5m%GbSpMd{wQ z`t_1iFKT56wB!jlspCwQ7-lT^)PQR5)(Lmpui|wcvYQHeUV>5Dxv%7Y zeh?4=RE$sspX94?t~YDCP6$CD%XvB|T6QY^6xIo&#Dgj-=z-s5av^H<%p}g3DpjTs z*AkBMbfRc=>qx_8V3va(LZ)2G+5=351-b2P_u79`vu|Gk-IxCqwRfe{ypr8^h53dK z)iD(gLP{vl*+s6iHA>|R^5m6K(qg%L`e#eu?yU=vS4q#k_DAJ;@xs5_Mwwh4Y%q=)3H@6&K}bJH zR~DCk*&J2huB@KFfd_)T`DLIp6Bw_TsySE@Hba~LK&Y7e;ZC)dh}ijMWw$>aqbA)- z+y!^T5IyBI#ToaCo#Y6jlYK6kMQ)d=voi4e=bjSVpVmnIeak|J=lt1YVI(?J&H<9#h6*_?0EA(Bo#hwJO9;92*lO*l`e z4qK7}5u;VBlK(a7vaS*zOY9U<*~bB=Tn;FK*&wE{;?8O0tbsYMEK^ve@gAS@y{3;k zbUS_`Z~->x(PmsQ_t8n5BclcdKb|+d$z0{@Yr^voj#nkM(jyw*RaFbn8s!+u(lyiu zRAW5!#eDg_(&_UprS%!tcpMZ6zUgzMD<-pZO%4_;m2Wn&h5eAqld4o3tOmvMpiTG9 z`ER8c2ZdSj&yRVl%1%Px;V|}%b8S#j=|bY=GVE5nxHY%J8PB1ea%DNwY16g@2iNXj zWQy#CuEf6WA2>zjm~{`uFeH}zKwfTBRy2f<6b)-JGLOhqyerW|OFa8=`L9~~+Z#dh zWJu!$0L5oaBE=#x?!}i;8Ev3L928YB0CE)LsYqrZEpr1ig@R6gg+&+(eDrvxbjJ)v zk8o{qiXf4aN(s|TlwC;QbC60Y*MR0j$2$*v)%Yw3`Yl03IW#yvG8g78!4=z>js~ZuOly3^o+k|48ihb9v zl0%1;f$L3;2Doz<;uo0ccx|jI2ze#N*-hY3g$9Lw)mYcpbKDcq+k-w9NH#-1G)M!H zg^;tXTdah4?+3bqwA2)84L>b6MY>sd>Qmoc2Um`mB%gv6FWzC=|IT1cEO3peG?0mY z%w&?BsWJHY*5<->Unj17wcx#;6DPkpmF=X(kH%RIi^gwv4bM(cC|Cy{<|xL|x&<08 zNkLMS>?wa6xas}t*3dZ-BihYA4C9>xrPdXg!xfGqF9-#a`q=<&u5 z-&8532R2oa^-9fC`6gxlJ_;;C z+`trjE9LUR@wtI*oPlw!HExta455HdiP|82<>uO*;)554jFt){bm+wD^*+H?N`z{Z z4!PmULI&gcq?mR2)NXkV)PH_eQ?0{d{8vNIlGT?xGpQz0T&3s~LBiO@pLXt+OQe;l zYTeY~9P|-6{d5;T{eNyE#*P$H5(uSDGNj!j6`$!Y$Dj%tHR3fh`IIaT=vV?bKh`>S zMb5p0(?@J{(^qGb|P^Xa@m-dc0ry?)P?&*Bx%4Te>v z&rCutdWd=7ulwKMZqD*QvebHB`}-4lyA7Oqbc38MZ7Q4(DqMxsB?rvo%U0*G8c~E7 zollnDySyj+(TUh-&{y-j&)vg=T0qqj!M64mddjwy0ZTOL=m%*+Pi86OFn-<@}Jx^@%|b59&BoD584DrIYBH) zXP{hcjO|wkK4T6WAkE(cwWMDJtq+)a<(qWEZHRunSf;C zCM0f5bbIy6WV&MMqVjM&D}xh7u2ed@BJI85w|2SYF%wNyIXjvBiJ0?_4{Y>|M4>Y7 z%97mZO&A9wzeJ^h%Xw3S`}bYxAWGQV-D(+66(Y;qq)!il4!m2&?OSd2kvncxKadY7 zNF=8w%K4UCNiQSa8!`wqpkO*?fC1h}XLtWil1Go@C|5ruUhuKr>mtoJeSkz&sG;=O zZoN^MrQ+%PQ+R|AZg%c_+lM1UvMFF<{gwXHQGj@X>cR3>#d2DUd!GE#RO7xCZdDip zeH>EP6m@}y%$}{W-LGvgc2nAfVk=i6JsD{U39$Q{*{m#%j5iLaOWbVZr(W+oy^raS z4UWevAKUzHzCWd}@5Reqsd|&mryV=BCRJq)_WMzcO}=T54f$L8YWWCsC+(Bb7-Y}W z89u9(s2;l%+g@`-%cN6|l3=QhzM@Q+{pnIr*46;@up;a%cUK$F7mmHb=29h61ztRY zA6hEdN_jT^Saf*AIC5Ty+Z)gL89sy6s~#vH$(VF~KUGYN z)%pp$%LHmH282Qwq-o>N<=JX&`I;5$4){vnDz6+Dwrg(XL`1(g~CZ+1|U z?0q!1L!ARr3{({kYt~`i@T;q=n;lbe0(M#WCl2-jRwBkBhM**UVv$R?xDhivLpTTi z@1;xk%-km{CEQ>{Q?R9AOaZLxH5*H`SM!KjP3T()aab}2u(VF~;Q7~R7=gt44(v>3 z?rmUn@SMDTrg>MsYp3cK2~Gu`DKV|}1>KuLtxNA_?Mqj_Gu)nWRTqLk$Z2y#mowXG?>{Iu5-^LzefedyfLWPA@RV97{L!lw(R+5yrhH2|s-m?scSz5A2q?Ni}L zN4v+To8aHvmXpWG?tG37)UL&EXmS3v{(-RNT@(d`oQCLKrxubOBQ3zHoIb5c`baG=~cV_a%1Fg;toty=o*7=Udh4< z0Mtl(y?H;#5;Ji$XbV?vp=fpmc7M3!lFOE|rM9SO74*OEB_MHiTfaZ_g@b5^vJY^fnrdtk znnN*EjQzU8e{>^*G$d4G3Avzjc?UEoe^n}gN{AH*ass&I`!%V<_d-mWVww01@*_O=Qhj(1enHHw{BU9gNyHyhClIlQ*4a!()p6f8xmm zU~$+1wuF>8urpzvd{lH)LwX-#LgZ3=$CX+1p#g?ooC@Vgr>S^sQFmD&Kc+S-{czNg z!!^&QkjBFDNb;y;?hi37ra}IXf*~ZzNr8)kR;}XgrJvruvibLdi0jc(D1Nbn>))v0PhC3f=jMiPxv;A znKK*PYo4CmK@5DELZPSR$Nsmv)<*XSHa0W!`$M~_C_n!l3yQKl5FA6`KnsIR7zm@% z2LiVPYHkp3kCM`TX4c*H-v2te*KUf^CDgDK<7oWoA+Y9SnR~0qN5=c>SEt3ddF{lT zwkVKfW&((DHz*Y9T=k27Bq+R0K3DW_RT2;_H?SKGh7)l3l27&RC6>o=eFGCO#I!13 zFT7daIZAqkZuhQu2~DYr<^wu0R&aW>iRLWE-6LCloe<1z!E@%D%wKUMuJh6*sJ9 za6bCAumjVH#djch=KXU;znr1ha=v*zZ~NY*Ld&QB-|4kz0x}u^bxGL&uspPxyt4{& zbnITw@J(eV>rqTGQ{)r;Pm-=b&H&&Q&tWkYbPipp)MJYj|P8>jPcO!1dwJVO6p>pXzTOuq#f9@u{Uo!cJI z(T2lMqV_wY{2s;h>+AXZ30}TtSN+?GMn(b^c#sJ_kqo)d6B1FVlJ1i6bq3b_K~uTF zw<9`Vf2PuveCI>^o95@Hp2+qmdj%~59aO5%`Pp-+(~H8hb^5wjWg-Uu^w8iP4Pv_s zTD7t2x$ecjh_K%86|Veoiii#K?tu{czc=!fV!~ zpRqcmXD#IXoMcm_cjX?3j5X)3sb$(J1wJNdd0No^a zyEPq{5+@>xzs-I4u}Zqe?e&r`l$sa>k(fZoANlEGIKufqi?$6IngV9V(m;j}T#?%m ziRw%3_x}Gk3jiOd1E9|f={!FKy|s0TEr>VzX@!G3zz5A!9-BJ3G#5t3fZC5QK80ZI z+dDHOXR)}T;%A@LFSCb)fa~*{oK_cdPO|AM6Mb-&vG~T57*m&_cIMJ07>~QPLq3|1{OGX zz6cl{`0_=3N~;-*JxcWv%5wDd=yq(7X*HU<)ur*Br=ST%O{7*;F?J=es!hM$Gyf&p z(zo1<#ZNAsJohZ@{pL~l*V*inN|v_~qtPUR*b90#<=4BUgkcLtCS^U#ru`>>L|zq%nvRrBSPG>E z$QRRWc#PWcnK(4kKzEAQ1FK5&-qklgRm%7h=3Uk8{!nnaBy;48X51iIHy(CMz}aR( zM4+#d&%e4o$-tyE9uoWCV-)IL9HC5%lXNzmy!dHv9XG$ll%A_L80Me zTBKc8+7e$P+ZR}#pfKsdJ00t+34W3F-Jvo5KPA8HE@QgrQgmJ|<>*P}hoheNBoBcC z)=Bn1d}W$+qzE=^2lq`+z)(Rq+b$pR$!7K@RrE{uUo2e2#CZlzp6(vos86|OHV*uS z*8xnjwFF@E3-imJHh4@Eth0F+^baPEJ*E|I*MA@o^b}8Mw-4wYV}`)t%3a>+tBkih zR>5_LlPfM3jdY&axJaB3%Z=qb=DW<{%q&NN_O6AhuPZhmT?kmfc@lkfTi@KhV+cUd zJ`PP;&u%Lcj!@q}x?d_V$e=;h#VYY{f0+NB0R+N?NZ`tJYG}m6;9)S{5=*9xL*%*= zVXk9M2~}3B3|qUFc8PcB@ygLDy(Upg`t#)zQoWjJlN=!Z!hC4tleg$j-*UX(uXUp5 zbCcdAj3bJ}?|Fme=viu-oIh~$(}mdknF*lk6ZkP_F*8nsFj7tc!9zbOGYz|ssW9J2 zZv*##er1FfclAnADv;1+hE1nz)!a43rF{Ke3 z9s_BB)kUDd!@O#uHUnipN6 zfH*deA$M0_MpFwv$*}6p^}_z#!aoqJzfoR{tQdQQOD(~7raYe=odhv874%n24&NW` z{e6AtXk>1w5cQvvLHR_C>L;v0m(Lkb0GtLa=?g&#=Fy)A5!8q2=rOmVq*V;{OR~RQTgyQ^s6HfT^0q0^T!cb z8mMMxr|_lHDsB|^WzAO0#nn(=oP?7$uM0@!K9&?5r! zc|gL(RJ&_jl=*r%_QRQm0E{-MZznySO?DV_Ia1`{fYpYiTWJ^g(8|EDMG-VXrTlMu zE{}1CJ4N@KjD1b;w*V%;lNKtiJpBoqVILu54u~qLaLW^^ubwnfT)O{%OxZAAGEQO9 zja`^nem!S1hK-^)(Tf`#0u9EYbvj_m1X5_i`<_S8Hg)?vDtU-%X+AN?oL-1H!%0^I zmN2Na+A~W~MJNV@VT{1BXvme)P`?gF$2xX6K0;_~;Mr|)O{-^3I#7JA71x6@e66XP zKmz76_o^HF^8Wf}10=oV6+AN7`|HF)JIrJHsT4{FrTk8u?(F3-yeE-Yx0K&lrPP&J zCH2y~IG0Ji+G2R^1oPhT$Qiq7`g+A!xq7^rk5|(3$}pP_Nh8av?2B3;I$IR6p_ul5 z122URr(^dB(6C)s23)&kJnDkg@bC2xM?O_!8DCyh9XNV<{Io*a254!_hC1*>AKHro zXg+WW0OMZo4IOsY;?Fz9g$1b;ozNe@HLRR#-@D~)X?^p$$?CQiWvm&*J3D>xWeD$R zj4O8$qb`lYO_)S7@SDsQtc;P!(5JKG3E>E%Fha|jus}gq&SKxTPLI!aQ(%aUby!f} z-Y~{cNq~gmkKqph1E`Pa9W8L(MZtk<#~Lq?9C^(78n$jcAZFicF5}3im*F#9bYU{& z$5}aq!V$b!8FL~Ctsnv&{Kf7z@vX2+<* za5_AG{@$ZY`ob7qo$s-sri=lHQQQ%0|ue115U+#GAB5l#>)c5jqH2Q z2I)j38&Wz8MnV2y+#Ubg3QCQW7O>V5ci60z^ne{vI1 zNH=jwN({F^1hVRr4^k*kacI>5N~fA;ioEkZX=|Fd4Fh)~K*pIF$)CxJl1RCb8XSbu zF;gQB zLgj1Rg@+26jE&%XJdBX4vUJmDdAuig2a}mxC$Fa1-#9MAcbtURBm;74HTGg%W#u`f)YQ z6`0PI*lx#%MU|6imwsMY>anu zUOT8cvY4(Vx=DTBfP9LWS^~b(~0!~DnWvaWYQbQxv4FwV?BBJV=tMhPE9p|4xEWQR>aaLIr@qlccgFkYGK7{ zGllf-T1k?wj047%S{=ba?}n;j~*$kVF0L; z2z_o4Mf>|8F)kC{H=HRfC?}R)!gq(5m4&%b0Wc|7EC04JHV3L{`6$NhqR4VnXk{6D zwyz;-cey6@`E3~gjHAn|)p}KYoX>{5JwG^FNZmXk_$(+p>H#f^6}ZB~K(dr66}a}6 zkvj|oN{=LoB8u3-0qdyH(C*PI)qGA3itmUAtHmS=mg*EWduP}!=bm;_x*L>C#<+08 z99*Kk`w%G6Upi%Ot~Udtwjz;Fn9Xzb3(I?J1K-YGnS!BP0G9Es$1se`G;=%us}$Yd zZlcUc`FKI{0t+l59zQH}dH!ST>cGH4uCjk=yQtr&a?rnO_GRd0X*@Q1@ z!chUZjR_Wnt{y}C37a~LX>^-&Fw!(`X$UA(8=1t?Zu3B}E|1Fp++Wpf%d*>8$e4?i zGm}*ZpuVe+%$qXt?&{*y$QPo|Aa``)-1bS#<8hn+Q$PQQ-~Ti1kQP};_Yh+Ttlxpl zs9H9Ji=cTTuYR^*&h{g7HV99%MjrF(6^nyvs<4}T^G)H?uPHfDmsk~rLWxuut>(}t zDrQ;c?}j^A!N48Arjj@@Nx--4w-VVpI}r)qQ6Hs$VTy}gVXT=D)>aj)1y1guBiiKL z9M5)fyP0@i*pyt(x6_CROOy5it^24jt7M>LlXLQ?tnNJ7MgVrPR_}8+p!IOjio-be zcc!~*ujW(}0xg?b`Lov6*{w=Ia%(l<e`aU%?Ts!fX*3fCL$(;3LMhrM@Taha4@kN_#4JryHH;{N2eXz zI@!9%ZNDMJ5~-tsLe*f5mhhNDt=Blv#8)u)XMAv>Y=IC)7!V#H(LySZI^FuQ*vtz zk{|${XjwlK$p{CBE5>86Q2XUNGEK)#dQBI?QC5bNhmbK(+4osH=leV?l~&{?3^g8O z#|u4?r#D&7m3C{t9TYUhW`&*#Yr6|Wlk#XBzAZpHZBlMJ$qWSdasi3mzV z-4ReAn%GL;^mZ2z5;Dnmu{c^bJHAuA^7)>5IxJrp-RhTCzrSSj;5zINITQUec47m7 zPJ_8A$me<|+L&2deZc&*|S12Tfhdt*s|GuuV7he@RRPfBr9WB{DRByZ;KB8VuveIo?&9s3)J@8-~Ky>q5@m* zl1N9g=J~z7Th8BJLl_vVV|s3>gYWOjGZj&+moD7xtLmFaf?oH&v(_Mhp?apr(c>1t zvWuAtuPi>ckzz!e;q|_K8xio***5%OnSN08IcRE6AUK%S&hI<8f?j=yNFmr9oxM+C zo3GF+Hy-tN_fyxGZw>A#4k-=ghRq$3%OdYv-`KtGWK!-AdZi%4jhqtc{PCq2V3ul_X!!r5>5X%CXjCS$nQ8=xNsyS*2VjD><`evZ?@01P!eO$a2B_UP=d zGoZ4IUe!p{aFilM)}n<~C|b2rTC*Y)G;Ap_0t_06WX+AeS9(jyl)DEwbH>pJ&6K`c z;&3J&Nifvu%wllCQ_AeyM4KOP^I6J()-r=lSBG88F3}^ChL{qZjzx>Hth3XW$HJy= zugRHsu-H^06<|V&o@*afsuy3ft#V_f+G`t$j1(kffA?RKr<|bh&YxXoOsr`BRP*lJ zymqfGAjaF;4Lo%LgVG+3HYgSQa<43kW1+A-h_!8S1&|!u%{WFD&FAOI4V(+qEYNi= zq(frVdS46}i+^`eStiW%4)Eq%+qj9jmwCtE+8Dg5(UvEi7|6m*92KVDQ%;XCD$V3n zq3nJQnKMW7l#Vrrfg#k)vSAT4qNH-n#l~0j9=@O>h(^#mJup)8RP;?#dV8`6Qi`g$UAj1 zyiL>?$4AeTfU9)^WNbplDbW7J$m3i7u+HlPuD7%hv{HQE%X@EiQ-x7sv z;F^6YQ)!Esbng#qp8F-9G(x@?s&zCG+?okN%ged#RXsVJteJK#e+}0u zH$7b@+J$`vXnft9LA<2p*VgmB>OK#H1Yj;RzQ&K$C^{hATCOkp(rTpTt&h~uYAT(G zn`gE+4lWLZTJHg&ZWMSE?iamg{4R+|9CxVtdqEM%mPd zU~a}|zW^9if;<-K#RQYd@2e``tTv3rgZn>EB>kU0Z@O~+ptSviaatC1)j`<}pzEyQ+B(e@@rLHM`nY6StDIWWAG%DHAK-ncHDIy$ zc!nnByyb4UtX4AjSZNk4{}J={C%UYMBl#mt=iEOFYB^gMr?Yma>xPflk zVgkS&rGZfKF`%BXw^dePI1*ww=Q+58scdTRviP12ZF1(?ht@{J6ha9O6c>wuX^gPh zjpUUGtwQ{TnA)K5 zxPka7&rqAW(==PYCd$N0pKpD;a8MpGX4LwckQ=F-L<>2s^7hu($dU$|qd!&4XM1g* zoKwGPN^PQc4Iwe>r;i-yd*2H#r3t5IhH93$+`a#EbX0u}_=s?I%p(eilNG*9OQZME zq9LUW{fW+<7T}PuSqoL?4?-z@S?rLPU~x@+4IODlCI;rPRb_=FkDK6tQpRFA)H1qL zpV5yo*ku%g6?_N6MC#D~9h?rAQ5Lq6VbV*tw5W=WepE0aS5{HEF@oZ?B_AvK{emcO zb*|Bk@7>($j&O~nw@wV<7;yl`o1x>X+KKGFUFDWUpc2KcSS%67@X<-&V;u|Q2-~4w zR^g7ZrT_~);?yTdzE}mMLMLw>!k{K~@?7I?zUr7^-nQEAooPj>DrN-wZ}bPO**42f zS!p97uH02gv+^v->=F!5NEbP>t7p}tWrS0S8zWm)F4pca5`hPB!E!%XQnDLF>sj#K z4^#avk9K@B*F#P}D%fLFCDWBlf6*+9C>Z=Uz9~RUOREG{10kwPKk<<{I5+AavBHDb zhz7W-fj#HU3VwR(P*D>RN{%WdAKf3iyn}RKSmcQ=-5n)TKbKp}=Au|itO*Y9U@8&k z)mkS9g$ZSGo%;rG(2q*N$|O3*zyGk;M!m~%3+}Hr-yy@MhR~!h1Wrtw;pa0{5Y9No zHpNpHaXP}W-^KtuZ7jJcB;AxNyU8`J!7cU2aLsz{g;+){pg@173HPgs=yy)R=+j3R zdRd@k>Kh(8!dH>nh$0;Tu4)?I@1<{E#@eHZ7Fb%{ndoRP*Fa;@*?%oZQ{B@$vKP@v zgdKwGRS;Mi0=r5M-NEUNK|#~a2`peHuKuq&AfJH&9)eE?gUG=pu5#y;;W3M}f7T;9 zSZKM@@DB)dU6FK@PKA^9V1qokI70;ck@T*Ly~EoL9q|J!z0t0)JcR|>m<`k^@lOYR z`S76fH2iSnR8ZTGSJlN9$?{7!?6x(JQ^yyfo{imfXRj{2Ol%Cr>lS(RTnE7jjCH7e zl4k1Bj``GD*6~(^P;T((%k%{jqWkEZwM}YBt^E0->lXZLZi@uUD8RZ&EhnXh52%wW zV*b0^-&sSyomOjv5JlOCs3K+ak{OgjIaG18`ZGCNi8)ZgEo$MK@`d`ckj*t6Q4O+p z0oyZ*gM~rx?uMu@Cc#oUvNeU&K}6&}KEp-sZ@&8r!QzvrpSJyXlHB=jZi6msgD)iy zF=KmCA^13NQFGBOx%x6MQx=>%r3w~pR9O?or-&yGIY~x{=Sk|Sdejun3z$Bub}`LZ z#Jhy;;q2JOg$tnU$!qeiqJ*bf&eiTk_ogcvcS?Mgs}av*G4V4Z{H9i_X0T*@uut#Z zg*U4F<_vbs+00D;K7&ti%$`!;B|TY*Lg<||E`b#|#4K3I=NMQc^&Os4ji_L)c?>r^ ze>bPuFcT{_8^cQi9m9V71d2M9>^B%M7Er{K@E#q0olH#&EyEw8CtwBR3hTQMT5xsA z^IjMyNaqEy4TXG`H;zt5=FGIBP8HnW3VG^yaZM?_6^%uIQ=mvXx3d1`d5@5c_uxEs zB1vL5cGPURm&C}-IG%aB6s?dN-i#QaJfcnr~>vkRpWzg(P|gUd31*hpZ^{Xr=z(#$gPXg$s=O3_DnGH#l&b`L{P~!4 zzM5s2)j%Y*IND>ZkN|kpqsirYBVYUOjvkV?%2ysO%SPTcBc-T@P2(|0po#baSg*xL z?v#Q4IGj4&ZXVt8KfgMi)P)))nm^>*$Wnz+r52|ub>OSmW-*{U>dW%BE#}f9$P$_2 zhXv$XTZBcVg7dEg@@mwhlndt}UzDmOTJ3WBX$FRS$goltBVIVCnF=2XXWnh&K+${El;5BxLEKS;8kL1zQ(YuGC zH=`$Z`NMW|p7mDTPU6^fVY+fcS;q1)qp#3qOoST4HEceHpjip_y*3{{eDSy*G36Y* zxQB<<%R5*`_UmqdA}lNkUG9XZUn(zu9~b}^9PaV9LAOqY?&`ps9Eg)}t(hhR-yc$ zZ?aQi>bH;tgqA#p2PeW$c%2(koRW+b9`-vX|3wwI$z+m4a5TS{Q+M2^fRYheo<^Yo zG^QY8+_fqg*z%>^Y?Q~gBC3^h_A6;oHC$YN-ExESS>B#h)GKZ$NUV%9OS@~`eWsh;HyFO?FIF< z-=>p3gGxOb@eHqK())5Z1qH=G29RrEL!5}D`C#J?waBt$m}v+G>5!|2WKr&a{snBW zk|L=>WW7G0srBr0@&4Z|KvDuT9-pa79?9lwgaVh0%LDcO(e#xm|KCT&vforCIGLss zwf5YSbgD1R%W@d=F+cBcr4`&5B>*VlGx(|ot1P?rZxyM?IYm}>_Evn4{G5`S-}n!= z2Hy)2@5T4fSc&JQwssxry|=MtnV44FSP*!8`{w-g%~JxFXlq~5t6-tXmo{T2BII0; z!C5DpY1THbWyzoLy+BvV3qHf+DO|~PuxQF`7+SS{_99D-%|5%9w8)Zh}R+`sfQElUrqWgi^z_nW0v^;e`n~ zAvo%Drb6i)Z=xNyF`W%Jo-zZni8#VtNhvnZ1?^9{j_%Z$cWW`+j?;03_}ABaghlR> zP+ygXbBX>wk};vbL;iY%J5u=7bin6Ia@2K4p_h+D(5xd@pOvcBSk->x6(Tp0;dsnz zg24o)-$IBxPL03j1|?6DWJ8=jOE{;MiSjahTQ;I6oWO|71(1oD_Iv{Dm8(qg0O%c8 zyu9grRaO-)DJd#ciGaqgUzo9_0DrsX$&`{TxuTdV)th9^Yk3iZeXkikAtBr|w7CJc;N-wpv^D zh1l?0j%@ZACcm#&XYsqjck&^_rkeG04b?MGPfbP-1=oxyR3y6vgd;N%A4()lJ(J2r zvrfxY!0f!m^@)3K?^&POh@ncIL`@Fel(Fwk=bJxn4Z<#MEBP=q)Ma}6Jbn60a@30ncgriQHJH_7ar14W z4n|4FkiOT=>$4h9%OkdutSoRUN4&(yQ&dw?1>->Gh%%U-I;Wm8`qg9+w&Pypg})AR z#IgR(^sY%T$dq~nt19}wUz4P4ws84yyu<<@`XYonW1XKZ&r+J6U_1exPH@xaIY4>r zUjITkS0bq(5@UAm{f~$-T~;%(fCGL7dS^AAp5pl8*`eaIp*tx+ylP~i}GUe``(DW5pEoNT32N9l9ty<>2qbGJ7q=h zz}uLKjd!-kZxtaKjG4lw`<@M@(zy5ek0zs7BBsx$sL|{+EoZDRYox669x2?r zu(733d&W7@aAGa8z2EU`FKxNV+rK)<(10(h=zCp*H!$r=& zwDVfL;%XBpRuuimo;q-@y`lvKb-LiV!`)Ok%o=DLHQ4B-(Cm2&Rpu*4@@R+YK1^MF zR*ZuMPsK-)qaJliUze=S@3Lx3Yciq$5->G5h2q?zNyeULBPmV4vAS2TH3Ix{0&&hY z`3BAS5Lr*us=ATB`uVwKY%jlWK>Tw;lmadZJ^_-XDhHb)iV_tux1d-5$`=I8Jo=G} zvOj<9sx?C#u+*+HoJ*N$5=M~^(kK?eUwb4RUQQ7ArEsSgAXcMS$?T^)ae4tXNztAy zqCI8LAqQ$Hood0US2`$4)R*6P*d8G$RtZkEQmuBa8K#C~ z#bn#L_0v^GM0+@{aag=H*y_xE8ADQ9Gkm&PuXyH@tO^4e=~wyNv~8U})G!fm z9c~6Kd07)wi1v^4I3F^9n(;A(Ni~ul{1P8GA}^%IYKdmIeijFk_eAN7&B=t?y&LpT z`7+0+!9F+5q7Dr9xraOrxZNJ>0#`uaS2TkYnrLaeyq%FD$jnQCi?wa?t8oN`8}ga} zy(^#QRX+e)hys%6w&4;-L!jw0ZdB7zXlO>?_^(%)-~UAB>1G9wlF7Y6N4ubg5<5_t z-^1&tOt6TmZBoT@*~9KWF2SJ=`xyw?JHlR>c%%s3=S9^=wbFOmdXKOCs;=ap*g|FT z@ygV4G+rLoY-ROgUnCEI7$twbus>d^q0JV~za`X{#@>ItBB%RTuUxo4;NcG0z=-_mHt)Lb>e+40Jw)soqP$gb(_L1?WPCQ(Y%`rXJicq>%yh@|crjdu#^v}2v zkEkjCgzEH5)7C&1{oJ9)Ttw+m3Fnl81nj;M>^^0IruSy}(cgD)2hUvXzS-4Otr#^H z=R(5I;&~t_eJ0y+I8(QQ141AHE|p7~CY_>b+iHy&!X3>-?1HgWM_9hbQEC39i;VU)~eA3ARkjc@_F?l7J1at#%_)3d;jkk6B76%?P} zShA+>@Y$`cUDBh!Op&M=TD&7{){~!BAb30{jf&uja*)PLZ6DxqB9=5lsF$(awo*Fr^>%dfz9TY-`-6bX+eHBWzrHl7P~@V$#&yY#*bD ztAqNR7vwTHs>C?bsCzX7ahAxr<+&E5O{G+T1ba#P5T{;8Jsm!8brsQOB7zs|?Q$@p zL!&VHW3_Zz{W8er>MagvQY&c>1PfmVcz0fGFdqAQ^acu=d1t(TmuQL48{tF358U=P z)i&IR4BY=v0oHFQLf%b}zq+a^!A#(W{FC6dIhwDUd4TPhBL_|?#q4_wHJhld`0gu* zKa6>fFIMG?`RJH5*InOST7&-M3TsOyzM;#FD%`a&6m2+JSPns{{yek$J-*kYQ=q25 zS47k#-#t6qmc^s#QTGkcSBB2C(d3K!{=^6$w8F}|3G3Cn?tr7zgU#$VR z%$v>=Wwf=bnu983%;7_pm>pGonucqJ%9M&Lfg)z8Pui(N*c)r&f(Rmon-O1T8mkf| z9jK0?)ZJ!`Cr4MfZXjdwxBHV7{1O>lr4)Wf17n&4Q#mAziAe`ujL3+2=VbK0{*q7) z7UM9+d^TVe01Ja@gs{Rc{P%A#N%xXx0xfW=Pd@)X!z4dFrZF!54<`bX63Gd!95Zg~ ztH#|7Tm{6@UIISN=HjnhOr9uDNB#X)p?7xx-$DdF4rEG&4Lnx;PHH#qj_q?kEs-_8 z6)UM3M(u>OuE6GoLw`4vKV_z*)(Zc}OI{u6Tyf`G1y4pgJX3tA_yB?fU}YY4&QjNY zkuhJ=-%N?T-JvZs#;BU#UaWq3lx*4FcY7P6!knwIG`-Jig%mltG#f48-UwFr@%}mW z1(l7^s$|rvK4L4<@zqXxWFbF3&M@*&B-3TJQb+$B8xSHLHOB=1J>|bi&o8~V?Out0 zzx#Xa2U~M9PDvWbu<*=cl%GUPa{v4J(4*-Yc6xK58k~VDOrnzk0c?1YNHFll;piLa z3ky9OZ7v5j0f25Kt_qW)Ue!+l{+%cyaC#rO!YA6!Cm0{&xRruQwg&|dM=%yii#_l9 zA9-P%Qj*Ah=IQAQj=u#f?1FzMAScR-!2jyA-+zCfCZ#sn-$#+@;OEi3_cc;$F&l=@ z(C>Ky{AnmvN^+1KB%1hANdUs#sbHL^-l;}+rsVL~qL>XyIvh>*PloiTaqx?*ZFwlL zk6V8DP%vAp1~s^zc>HdvgFM#z@bvr8I5U!)5E1c-XOTZra$~&jS}1^lP6-TJ7JKL7 z@&VkaV2T`os21u}`x*Z|IvZxgZikR21HNm1byUJL)87+&r%M^&oFu&;b&9MkAR@fY zViTj`K3|&lW4I-B;F@u$x@RpGpk&0I?8)r5SH{N%S*l7hhssWF+@2Q+2L)r@TpR@p zi8$`QLbB4btMc9#}Op7itm3!eP8dyB^M-lFO5K7T9RQ@wHY( z)CAWiRwDh&Xdp-Is9mJ-_};u(iaD1>k6A`W&cf-FIR)WXa4%xDvV7>UWM*PN%_m&E zB7E}_8Ef~LIY&q#GxTqn#Ci}Ws>?CnbCT;gr|7iY_XnS_ngZxo27Al+kUMzZcNTcr zLpSatHZIQ_iaiMbzII^QQvQ+&93D5xTvmJm#+X5~J=#)3##DunRNe0c?P28CqbebTKN zJZ;yI2VG}x2!AAcqDk)W&sv!%r~@*{VITM~6Fi!4Ho5x@-j<9w0L+{{`uC@}t=q+) zGvsr1nNrI@tUwhcdaY@C+N-bKvQm>Hd@bZKH!`;aASUxVW+wb@uBSCpBO=h#Cj{|| zZ(O~c-fcaep0~EfdA-_3PPKRK#4NY9+G$N9!Zl#O`ZC6xSJEX-KRwT@H$M|(csAP2 zs*qmS_`<>V{P2?@4fHkmw!aLI59v5ljRfV0!rr`L-xnY5XFInPG{&o$LwY+8=+(%n6T z%9R-JkuFqyeXITTG3S2w^-%0&+|qpM7hC}Wlq57^2w_)Zp5~H;olZ90DEpUlYJUb9 z*s}*h4U4rB5J9`~c|jPIS(q;Pcv86Be@Dn~WPx2ao=iVtsjWfMG z@rkK8Z=ssOQ6URjwH7~^f(WZztIlH(&8tqD+#RzAnwiZD=+6z$VlW~JF=Ej&77$fD zZ7w{`R0i|~7z&oWb9XbA(c`edj8B-w-%dF+N&}Y4$#GF_lCuUfyIXfS%t@3E{n6?)rY;$AP_5vQh zwc_A3SBV{6fk&?1Qqz{Y!wl2x8!KI}mBQ)^@LAG4tHt19+vI=$Ak^^0NLYqVW<>lD zeL}R>$+XEw>)Qi#R{n&|T~jO4gaj!3sYECv4iNvFV7xIClrvSHyhr9VWc$bpm(Q5- zSP7GHyL=7y!N}7ur1oEZ*BG8}gW949Q?exOjR@2+1$(<@AFqOii4wXC{7VrLrR3mT zJ)jIO15`s!fQ(O1U}?<&T)v#E>37ot_jMYu5+LItxgXsI&#$lc!vsqB$?8~yGud7; zAS3j$bI_``z5_U6CXU1F$t6;!LesRhKhA&Urw*vo8z|&{mW?MLR~n5#@Uv#PzTmB@ z^25xzC5?-y1rI5gE1gz}WW8aLWriv0a9RRtU?`Y$c7z4fh%t$|y({Zj>5X>64-t4iUlfH%P zr{3c=6RhliyQ~$T8KmY-+jsORdB+Fq%=HbWW@f4<%7nB!oKjA$2K*AeaDJ;{PhogW zJGZMRl9TlC^+2(qw;{y_B%i%P2z~KbkZ~ZgiDUidnl{r%GiDOTU1STP4VR zPIlPgXeoNiEU@!aJazkBeI`=xRPsjE#H8xkHadAd@>rsx!NcZoBWhqIjAXAgkZj_- zi0%Oal2BIDJa7KlJLY;hpdJMRkL^w&Bd@EM*%6A`C=1QG64m=6_&yd9Rs|}`8?0%u zTTK0s)@T%h_nfraZkRIiniu~)twt(pz4LXnn9%Nqn@h8pXI5%-L4a^W(|w0uW;?vG z>@Y)!Rf&S}%YmzpP(l3Id6syOX50_fcrq{?BdaRYm8>0MJFb3U6ajKx=hlA~6+&vmRo2GQ)pD}JuPF+q*RGm`&wv6wz-#t1=lh7BZyxpD? zj${eAM_{~CI6|xa9`^1)Ap|+41x_?4J!RHh(2QbG(F(rDbmB3m>#p+JC4-j zpHuQ7KJ#8;OD*_|gkiss7wvTg;j)Oz>;Us?QPgc)mxPonMO~=@rPL$RDH5;eZPZ_}BjL3?` zY4O0!T2{K#)R2-!LOsu1fxAEjth#zFpT492S2{31B5GF%U?P`%pbsQ94hUJdu2$cS zO~2+OnfPb6*t+!7gvGqwX5j^#%!oVgT=Z2gkGpoZo2kKu|1dc}-ivP&CXp*xg@%Y# z-7u`xuGVgtYiYMWRdCX`?OQ%w*ik()Uav0nVm2JKg(CX9b;w7?x?ES@*Wg2NZ~wUi zvYHZ;Ziyj7s?xBY?k2%{A0&EDU9{h^+bEM;=pnehc^rxRJ9)ePv>l%>W8IK4R3vEYpG?FagE16@_553vGO#fGV!B!VK zRwW(z44W7JSf=cTKFq+mKlE>BxUhVAPKH8%672mN9C5rAPNbXm8#Dr}n{Z45TiVKQ z;*j2A3yF$v46<7^R8~KqP&hj2*C|&rv-gW9tXiL4(TRJ%;&m>Q<6f{!SJ^-flwn4y zLy<&etBfHF8N{{WZ0BcUI1<4m2t9p4~q`7P?8sVU8~Whq7Fw7;RwAcBn(>s1(UpHDr$Hx=EsIi*1%clQvqs{?JYW^2~)FzAr%?h-_^pPjwb16*vV2h@4@ZfwOTrc-lUy9Z1qk^u$941 zg>>cd^l4**6h}>B`{jj}Xx2ntQxCYH&b|86dVggGc-&J!~3n<7HF803T1{a7k!p!QgR-Lr>46=?ggf z*yDTP1=%tnf(OcIVMlCr?M~5qORYM%84idI=T#siy(jnW=a82BGm#M+c7=@n1{_(= zsLUR-NzVJpv6^`@LyZKR5wjor=fTD!@6JgU)TEE;<7_m>I48D{7+~YCUs|^G8*Tp% zx-M%(SxxC$%ih@m@*BXRa(ExZZ}O;vnKS}CA_7<2q;1xZMnb~7=RI`DC~-@^HA5+O zD5{#TeBbEY6}!26n!_me!wo~M6pQjD0vzBBvjI|`tkJVzvbk{qazV$c)&|)|+uSf* zGW;(G1OU7Wa$LE9uHM+wkZ@`R1@p*w_8+Z);XAv58bTfvYw`Srk9E(Ge7gKKf*XlM zRBShuH`H|4MxxgJ^v2K*-w=<2o}Ci``)o3IZMhDWy!?M!8<~I%VY6OWf1thet;+eHJ_(s!R;5TC-i^&>gp;HSRoiafpAB`M65fDBf zw$Jcr9e^l{xR!kGHP{EB6~LJN{W-N19r%3sa?|`cWDYfRv0ZjSfC9E5jo-f}e4|!^ z4-ct8gTYSJ4XKc<;eT01J*0F z_~16j1thk6xB!`csqhaAQ<3ZkEu(rj&0w@%0wdpEuLC^tLpK3O=iMCva;%`l)IX2n z9jCZ=c#3fS(Z%joDrcPaSFaF<^Y;bZwuuR1RDrdKiD=_6^#CsOBWpxCl_NEh_a_90 zJX*+>%!-WPwQ}p8umu-dVU>Kv8MGJR?DvWPsu$EwQt%$eCF=8=B-^-|>S+De@#~xy z&ZmXfFA&zTw^4!NM+Uav|APiY?TSl7OT+KC2bDjB%yzkkM$5@ORJ^?wF4v7}pw;%8 zdy4PFjU^Fp9_fh_|Fa&@IkDes@v_S%iOy4_`Ln|v@=@Z2S)#=?rX0U=zMAGz5sH^| zP8t*uMDVV-(s;N3*zw75nx~PyLVpsn3UQPSg5Xdd%`M{^Rphw@8)_R#fzLI%j9F97fl^-(r z;63-C=`U!&uU*@Ze8|?(f;Abcva+=@^>g{FJPBYtEePO<_dRyH5a}SlT|EoZAy&3h zQvV;!j5rj`qBkzyVb^d+BF=zoW&dVvsQDo3g!pG3L|kIAN*x_3ZD79WfBy;=rhPd7 zOmAg5y4-%bO%|OVDkzu19FJ=nW(&3FO#Sg|2=Q^&GtAZdjiM=5sNt*;s6LRu0>s@N z1Jr7d)v>Lu)h)~&S-&4X$7v7=rly7y5$S0#s0*15QWL;!eseskzj8KXe4f z9H;E+s|dFzyfmYzNz+rn!g^Y33BnFdG%q>sS`74axs!V}ZAL#!+m$B${_U#XB)uTb zXwX-{rdB)pcMQ`~l-?+-O=T*>9AU2R#{`VKGUJrT=VwD$schLd%398;^s+aY1MV*I z@nu+%A#WMZb%wnWC8gQeBy0G$aV^GNF|oaKVT)I z>roe}^@k7dF$<#$367SsHWUhM(33HkwFPNe9JLL!Z5r7}PiYWe&01x`@dIIS+m#wz z8U}8cQRw&ucp!x_|B`vUYQl!AD`lC_jy-dXER(I%2djYkyAgDjS@XciVz+30OvXpY z_7A>VXtb})PDJG5TCOiRY1=9!u?96yu0+k=J!tiqfifoaJ*C9v)Eb(IGT7rI*|46S zTn<)9#<;Ulj%55KYeC@M3+Y9ou8knBuIx|Q+Aj~fv)==*LP)W&pehhbxMg{S42mt@Bs$eGH7?) z+j@NSDG|Sj)29d(H87mI1U`yeQBquUccGQa#-L09m8AztCli5yk`L36XM^lpn?YwT z3jj*<$D)-|t@4A3Re^u^r*Z~I9MRfV=`UdM8E z-@~X1qbP1Uz1<5HBLyM62NR^R7Cg0T1qOw48VT#sXr%uI{}^xp>};CHLgu*-J{y+5 z4dE0Rm}6nOW>2kLvAjM%6#|I-^?DVL^CUYunl;e%st^D$C`wz+2>l?ZLr0&Z?Y+VC z4FGJugi)Ql5%Ow_I6T9PCP%-~8}&waaj-Nr=FnLWMU0k3{~o#hl9!M3uIubN7{)i> z#0PK(vT5scK=n)vAySEVDg$(du5qX_hUHSV8oBhA3bN5fGHMfQ09OkeJ)3&6e-mldbmfW`Gv)ci;ZL7a7X6uY=DY#6;U;r&d4R_Qy4~7+RMXzGZ&7itd`CqZD1- zvf1OhG68MXETR_A3Fxn{Sb5r~T!*&Yb)9vG;V1RcxTGi0(Al$Oo{1K<7(qv;zD=7kX&WU~@ud zezz+vrP?g+AK_U=@!??f7>>h*ikTZSM16X>m_Wt=3I1M**%RErKx%T5!q^g3O=*+? zMKtL@A>=E>kfEcc_?N}P({IzZT9s)wDZzp^pfAy<<0RN9S+NMxL;2Ho(-ozJ^_=;J znn3Q-I^D)a!`0nC#REY}U$K7}ZJ1dnJtRgx^zF18NaDjyJ3h-HK!!kaKVs8ufo$!4 z!{h8Kf_+INb*W0A(X@6nL|FrQr;3@S74yTrEcshC64B;?=Z5blBN{*~O;*iD5Nwwm zHNYQUpXU1{O3CGluhlG9zm{v3F_`12na)EdglK?Q23Kn(x$GjWsL%@#!rZFOvl!7j z$O%4~^UW`ERN~Xo*)m$~B=o*9Dg24{wnjHs!_;a!GI|Ny1)2s!RA#BsDOzLF6ey^y z9Eb_((_F;-l~m@ZaR;eId?h#_@m69ddP0b5EY5Ju3w$NfIC)Qq}{*8 zoYWjdUKm{cEjXN37PVK!0-<&qUWTrj=9)@rOELV{LuvN^M&rfJMja#bcH)!x$&|>- z?$kM{Ix>f*JP@v4u?eNhWGW4Q=yqbn(*#v35%Fo$E1S>$O-|U_yeCblmu_AKyXGk? z??I{K!F~neT(?+=NQykwDg+~leeTuAxD(1hua<_4j6!33`fQe#&XV(r9*=Tvgfisv zjnNe0gX}^-a_LI&hi^@&9zN&OyC@KP-K`}jZ54_7`;5+XjKHwreoN@ao0GrZ>3|d^ z2YD2vX0ViiDS^aXB5M|}CuCHdo(74AZU@AnrPNW>|EIXi<|0ws$D$S&@8+qPUR?Zp zP%n}`3=PRBJ{UAz_%5Y|8%1$Y_R--p#njSc`o@s4__IQ9Q|*{i?Qr5;E_Ar9j@9@e z36Y>so19ZCK8CU0Cq-Hc1)rK;(HyETtHXu~lpNo|G{ONge^Mew(v*G2!-E(oE5lk@ zrL~^B2&41Ho^psxie&ntgjyV493osVo&EdZ`t)dNB=B3W%NdV?J3^U$esQ=BeZGtA z-s9bxP)}0Wk%Z76%fDttU`r|KSbTgz>S<7Xa9Z#N5Yj(M$=d?hy1UBia*%c6vKB>C zC@OxB}gGPjZL(UI5;Zc$!g~|+7O<@b}nuVt>ejlv9{u=N5czgFJ zsYq1RLorCb>G6je5Ubh!n4+Qrq+i}qobIB@$rKs24~FXqesiojjIYFnlYNfXipY$o zr6>JFn+T3t_NNT))US*W+e(Ya113rTl&;Q&s)-dQkyd;RvHmJDC~Y2~a%vOT?t6QG zwbcqQH4Mn(jC=D8R^{K`RWX^-(=1f3nOQfFDs9)a*J=N<78l-l8lt?Fc!>A)l-Nvq z^z}QlLAM|>t-p&&F<vD3%p7Lz)+ zoz~j>W5%#miIOKj)DMjA5Fn2yzp&BxKH>6f!?l@nav@;tA|`~uJFN0OS;-JY1zMuHM5i9K%>%7z#L>Qo#cn!Z=L(bNt}V zJkKTLhWs-MxV{Q&4yI|kWF^AO1Us#Au^#Uo!&O!_R91$$r5Tj&6Ph$=i=c%gge~RD z2V|N*q7hjPF2SdCPx3tMNLm8_MyHQC9OcVGb@%5b(X9bn7_pR8Q?732t`QIk!vd4p zsY|D_UDT+Kh7|M^yNGG7O+P?yt$lDho8hujcuj=P{^SxaZatauN5Q5C*Bk?Cs2*8e zYN`QTZ>KX?ZL%VH%TMqh=^T@`V|lf|s%&NDWcz*NlN&J|88|XVU^PW2)sTTD^cy`Y zYGkaT3B2pU>ksuPHlezR6ZqG)vk$pG2J5mg&eyK>R_|_%Ib>|+r&=ptt4!NzzW5!8kelI)6`+=TYY5Tz zWCLkxQ?L;BjVS>@8E6MhA+OU-Eg>=?=Ie~HCir6nA81fxD<;{-pOZt}IXP;M z;ce|XTlN*4Bqt+(<6N&Yv;{mL?S0p*So)Ns&XK5;GQyh?tqmTCWQfE-<TYU`-Ff6moRG5sqZRulzQlg1$jXZA0iMDbT-fR}Gw4HLTRJv@>lpG74sEy_j) zqr>g-5`JzCQkCs$V-?rCkW>8LKq}gzx%5iY$?;8QpAs5dW(?SVVYZn=uD-%sLFB+0DDW$*ND!X%SUNor8i(6^4bpq$_a^^ zi)V1N+XH-W?`*cX=guacHsS`@lrRPktKX%=Tp=LsO2)dCzt-iW)M6Gqrp`50T_;nH z!4CYhuj^u`R>e$8A?FS$ZAxD*hSKkOXapRxxVp=Qnvw~Hl2ZapOZOhs1JB|Z^wG8G zXo7J&;nu5B#l$}Cs`jTeIN3ta1`$-5#Vmy0iizJoeVjFVxBPiJ+DKGe3ZWF5KU@*I zN_I_FUmQ_xf6?cU2Sh55C9hlDYZS_U&uuyi@cYs={`{YE0D^1Uy2ylw+~_>p0(#`m zmN&<-Zj7YUbh;6KulCM63l1!T_3Lmu^zkT0$TJZVke}-iYxDu)PbDEz3x$$!T>r|| zUicL=IUbv?gOpPGsb#FJrf43!1)5ai4xQ|N-VZz84Wcn&eXpCmlxgWDD;lL3O}1th zWmPL>(^lMdoOyw?Z$3P5zq3xar)^ARq`LQwNW&Us`W=(F1(!LE}N&LcX z{>5kXRg^5r5Njpo4b@S@+2<{!WqbG%i8s2T&5SW=w1v|(PTSYCFZnFm^=sf=6%{O2 z=fNbQ+ViYB4GlL)=I71D%IfMKU)495cK$&go$3LiTVeZw=QDKu2;>9P#hpnrlxqxn ztX+|gpIRt>8$+xHY{U_IV zZ`;kMHmC#fnKZYk8ktX3G%M5d*3;A|g+n_P;SBsb+AQ9i7&YrzpE)Dsf3V;3x! zUBxo^PKG1rDdP36$Ab6-#lg=C_jB;91Hxq}r#33h+B^I}CnLqoZMGfe^R`@c-m8nO zp4W%ik@Mu9kO;D`-Mdsy=gZHiM9ud1bbaX6bc>{HOp$m4QK#N+zkze?C;WfquebR$ z{0x_KHa$-+b2TPElaFw7!^9d^#E+k&IhC-+xT@I*M%s{Ak0RfOen$uW)lfBH-!)R> zxtPw=ybYHoXlG%X$vRj%R}%gp6wuvh`pg<2&H=Fc6%_DfO?kq9Uv+(O+M>c?5QF38 zrpco#c=l1mZ_$0fE#WgUMk&vyY}FZzS*kKe=d%s{f$ z(9oZ@Bp%ttL{n=@E--M6XW{EMbNL3*1Xepj{!|JUxSoMYs>nJ^If zNL97}wpM88x(;*q#b$bxZMTE*pC*Q)9<(h3sZt+(eu4!P-qtot!{p@9nDtm^J_dUREYo#wfn8O0ixujV;Wmf@vHsV-`Ga3d`GEDR4ig1C&FPspC$C9#!MIKd!GFl% zv#B~}XV1uRqMfiaFxEBwH^D@mo7b6^i94n^-ud?9f&0t(;$=^!DihFCYK+Aow zdYfS7FEbw^RU965B-|MYm30-zY3t83RfQqO4-m?6NG8z1OCKu^hrHGA&QKjTsEanT zp9Ot8H#>zDa_u+jRgjoxVIa^@U?IND1Vp6?4*mntNr~qiOhk*?PIu8wjQg;MqVAPE zU;MRY%&bwSak?5DR`jlkj6oMekn2#@P=qMb5&E&svZK^XB1MBJ*;`teoSSqUka1gG zLpY*URVov@&Te4jW{X52fJ~8j%u(TJrpp~=-fx*vt)j|Tq^7T3(r))11`V3ZuP4QI zLstUI3%ZXAHjxfo8;x<9u=83a@dI^a#?t81;_goV_^L57SbO)Lyg1$M1!4P&sVh|l z<8G3obqSWRmFTk8%w@uAs%|OqTZG#+wlALIqg=!CI@EbXLJ!Rzc=+$`2|=s9v#PcS z%`+en+}x;h;s@o%2|di6D(G#k(hw7~4#wCQm(}T5#9es%?^j-WU`S)%% zD$(7_Vvnp8s)Uw`EByrjdC5U341Fv#raQ@{%4buj&F?IaTt)+4&Y6?6A@cI#W!-Y8 zwqE#wAzo-iW5ruolz*@&+jJu&Qz`~`33i4e!4*G?>~)I6sh!B>q&ndPjKK2nyhc_xqpJA242}RjS zg+fd$nvIG*s^`RMcm0V|S6Q`5+~vn8pquhTE&R=SCOx!$%TYUzex`Be8pfbwjw#0= ztAH*o7gXA?mhodp%CavC{jfyRB=>IfY>h1JE@zjRI4|eQ9yQKhO?S3u-A-+q;3gM% z#EXZL?n$NHps*Nvs!luLks`eqZV~iYD3@s?8wx%VjV0*kv*4%2DXM&IV|1ma4)`RT&u@;+v zLbee>cVlT(7c3!=#Sd|zKVehRE=#{Iln3?bXK2!*Fw{bK35Sr6O`_LPBd(X1N%RWQ z4nx!m7tZ++Ech8YzYH6GTbQkOK;VV&bZP)h_M>C|cj+#?e(N7l-(vPiHt(>D6_l19 z=-_Zf25x^D>gsxff`ZcPqM}K-AY6?rz0$-I^railO@oi<+1E=I70jGzg`#}Oiv6VH z?Qr5SdCX^n$nR$9kPd&V!0pNE*2^;-br@D?Tsd)IxQ#1;yiwWtk_m{dbT@}D1#cpa z_#z<#T`d-r_moU~c8aN1mPjC*-lPwHmG(B7EN}EtX&irYc0MJVRLYm@KDtX+m6oO# zDpoFRT~0`Rh@?%VZ=R0`!Ig#ws;1cI=jTp)A`+9@_y3M@rNeK#*pDNK|97zYKo8FY p{+$$&m#+H154iq+p4xr=&y9T2SX_*6BZ&Y2 diff --git a/include/filters/imm_filter.hpp b/include/filters/imm_filter.hpp new file mode 100644 index 00000000..daf23384 --- /dev/null +++ b/include/filters/imm_filter.hpp @@ -0,0 +1,154 @@ +/** + * @file imm_filter.hpp + * @author Eirik Kolås + * @brief IMM filter based on "Fundamentals of Sensor Fusion" by Edmund Brekke + * @version 0.1 + * @date 2023-11-02 + * + * @copyright Copyright (c) 2023 + * + */ +#include +#include +#include +#include +#include + +namespace vortex { +namespace filters { + +template +class ImmFilter { +public: + using ImmModelT::N_DIM_x; + using ImmModelT::N_MODELS; + using ImmModelT::Mat_nn; + using ImmModelT::Vec_n; + using ImmModelT::Vec_x; + using ImmModelT::Mat_xx; + using ImmModelT::Vec_x; + using SensorModelT::N_DIM_z; + using SensorModelT::Mat_zz; + using SensorModelT::Vec_z; + using SensorModelT::Mat_xz; + + + ImmFilter(const ImmModelT& imm_model, const SensorModelT& sensor_model) + : imm_model_(imm_model), sensor_model_(sensor_model) + { + for (int i = 0; i < N_MODELS; i++) { + ekfs_.push_back(std::make_unique>(imm_model_.get_dynamic_models().at(i), sensor_model_)); + } + } + + /** + * @brief Calculate mixing probabilities, following step 1 in (6.4.1) in the book + * + * @param x_est_prev Mixture from previous time step + * @param dt + */ + calculate_mixings(const prob::GaussianMixture& x_est_prev, double dt) + { + Mat_nn pi_mat = imm_model_.get_pi_mat_d(dt); + Vec_nn prev_weights = Eigen::Map(x_est_prev.weights().data(), weight_vec.size()); // Convert to Eigen vector + + // Mat_nn mixing_probs = pi_mat.cwiseProduct(prev_weights.transpose().replicate(N_MODELS, 1)); // Multiply each column with the corresponding weight + for (int i = 0; i < mixing_probs.rows(); i++) { + // TODO: Check if this is correct + mixing_probs.row(i) = pi_mat.row(i).cwiseProduct(prev_weights.transpose()); + // Normalize + mixing_probs.row(i) /= mixing_probs.row(i).sum(); + } + return mixing_probs; + } + + /** + * @brief Calculate moment-based approximation, following step 2 in (6.4.1) in the book + * @param x_est_prev Mixture from previous time step + * @param mixing_probs Mixing probabilities + */ + std::vector> mixing(const prob::GaussianMixture& x_est_prev, Mat_nn mixing_probs) + { + std::vector> moment_based_preds(N_MODELS); + for (int i = 0; i < N_MODELS; i++) { + prob::GaussianMixture mixture(mixing_probs.row(i), x_est_prev.gaussians()); + moment_based_preds.append(mixture.reduce()); + } + return moment_based_preds; + } + + /** + * @brief Calculate the mode-match filter outputs (6.36), following step 3 in (6.4.1) in the book + * + * @param moment_based_preds Moment-based predictions + * @param z_meas Measurement + * @param dt Time step + */ + std::tuple>, std::vector>, std::vector>>> mode_match_filter(const std::vector>& moment_based_preds, Vec_zz z_meas, double dt) + { + + std::tuple>, std::vector>, std::vector>>> ekf_outs; + + for (int i = 0; i < N_MODELS; i++) { + auto [x_est_upd, x_est_pred, z_est_pred] = ekfs_.at(i).step(moment_based_preds.at(i), z_meas, dt); + ekf_outs<0>.append(x_est_upd); + ekf_outs<1>.append(x_est_pred); + ekf_outs<2>.append(z_est_pred); + } + return ekf_outs; + } + + /** + * @brief Update the mixing probabilites using (6.37) from setp 3 and (6.38) from step 4 in (6.4.1) in the book + * @param ekf_outs Mode-match filter outputs + * @param z_meas Measurement + * @param dt Time step + * @param weights Weights + */ + Mat_nn update_probabilities(const std::vector>& ekf_outs, Vec_z z_meas, double dt, Vec_n weights) + { + Mat_nn pi_mat = imm_model_.get_pi_mat_d(dt); + Vec_n weights_pred = pi_mat.transpose() * weights + + Vec_n z_probs = Vec_n::Zero(); + for (int i = 0; i < N_MODELS; i++) { + auto [x_est_upd, z_est_pred] = ekf_outs.at(i); + z_probs(i) = z_est_pred.pdf(z_meas); + } + + Vec_n weights_upd = z_probs.cwiseProduct(weights_pred); + weights_upd /= weights_upd.sum(); + + return weights_upd; + + } + + /** + * @brief Perform one IMM filter step + * + * @param x_est_prev Mixture from previous time step + * @param z_meas Measurement + * @param dt Time step + */ + std::tuple, prob::GaussianMixture, prob::GaussianMixture step(const prob::GaussianMixture& x_est_prev, Vec_z z_meas, double dt) + { + Mat_nn mixing_probs = calculate_mixings(x_est_prev, dt); + std::vector> moment_based_preds = mixing(x_est_prev, mixing_probs); + auto [x_est_upds, x_est_preds, z_est_preds] = mode_match_filter(moment_based_preds, z_meas, dt); + Vec_n weights_upd = update_probabilities(ekf_outs, z_meas, dt, mixing_probs.row(0)); + + prob::GaussianMixture x_est_upd{weights_upd, x_est_upds}; + prob::GaussianMixture x_est_pred(x_est_prev.weights, x_est_preds); + prob::GaussianMixture z_est_pred(x_est_prev.weights, z_est_preds); + + return {x_est_upd, x_est_pred, z_est_pred}; + } + +private: + ImmModel imm_model_; + SensorModelT sensor_model_; + std::vector>> ekfs_; +}; + +} // namespace filters +} // namespace vortex \ No newline at end of file diff --git a/include/filters/kf_definitions.png b/include/filters/kf_definitions.png deleted file mode 100644 index 97303ca8ee4a103f298ac076788de8c1af5584ba..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 204368 zcmZ6yWmH^Ew5}T@1W#~xhsGOsho*6NcXxsYcM0z9?k>Sy8z&GnKyY_Be0z+u?-_Ug zSz}49T2eJ<)jOYxP?VQKLBvP=^yw3djI_A&r%y2CpFTnTgNOS#@?iB;^Ra<-5tUJe z|1ckT)9{adJXZ-#R}}|yR}Uj+vriWG4t8dYE+)=qX7(dwn6sIY ztCfR2sj8Ko*(civCQ>#a6REYEy%i}N3mZGBjqS$~Rwfp9QU(?_78VP09s5t8NI%Jl zi>P{Lopf8I5=v#1-HSg>UbR%BbZo6zX3T=_0V|#DXP`Omrssq%)(X>m^s#x3mf9!=74McZq$3;%_zjhE7a%aay`oH@$2Vqh*;r~w= zpWVGkY5D)PX)gKy-)UTf+hS$JVoa-ygpsC$|F5JEmMA>(fG~W(w;hJK*X~GZ!Vxfa zqAuRpBO$2#4}&2O56}DeE7p|654+YIU_k~Iqqo=<9zSW2JgXU$SdCi(cg{9C!KEri zN&X9=e|_$`TNASVUG-*gKs-GDrbS5#BP)-w^Ajh4{r{=eXWcVrWGa)(iZipV<~e!9 zub4c+49^JH+0|9Nb)71*K*(CmrN=vKBKZ7Sny!5LIIZN-j*Efjz*_=06jnqSQ$jOE zB46||J!@hTyt5;T4S1XmPzOhK``FxpXK?cfA=r#In(H2W51os*Ky1Zol zsN(s~4tbYhh?a)t04sgwz_n8^bbzc`J4U`#tXy@Rk^JLjd3b6CY73Zs%*@>AsH`&B zGN+^yC_Sd00w{`2IWwK^&-6BZ@Bb_2|9R5 z@^rmbOIy3Yp~|7t>VIy^V-R74iy0*Wn0Oj676-}=GywkHK9S^WAr@0=CBzpa$iN{A z!^4sSiR6}9ffCf8K?t@J!jLPXU(28As1nD53kxauXDHyIwX2tw3&LsB$r_U=WfU_a zSZo1AJ*tFB;xaNR!-F!Q1iEkdp;jiE*eP(e_vTl|KBGYDSd|3T03#DExR&zkD>;p* z9$6gU)FN~`AaGz1CEJMQc^=*kA)w3P6DALgb(pEW?8^rAT3U( z!7QAkMFXJDV7nt`{e$vX$*#Xh6It*4kpNV9bCb|lvIv!tDyBI)Yt5%re%Ev|lU&E& z2d+Rf?x-jM2YoZUat=S_2vWbA+Ex3X&LP2hXELOE|LpRm&~AYVQcCV zJ3~ue`Fi<$-2!#ox$LCy1^Rc0f!=V-bdc_}dvr171Z+o5{_*46V(Zv4278gPS@5n& zEQ$ZPckg5H*nC`h&o$S}23AeEw7GLJk*E zNYK|4NomVa$?>5u@~wUowePnWo4rC3-p~GfwQpD0{(3q?ySivvw6`D-W}YjI9Di#f zgGqzo=))FquAgUW-1%93E@qj*D;<}^dseS+XMmZH!N?T(!~*$l(kJZe!LKTKKl7kp z=AgdB5nmli!=6P8d7&YNwvIYqVFZ*Em{F}rM(7ap(K*efXtNBVaRok{iXki6fb4a^g$I=u4u zKWlKcFR;|k;hMTP$?QlABLZl-V$-*@N5{lx z58}pbeMuebtJZQaFO<svV_9B#ExFpq3VHj5PLsbUTu8W9TTFio)0 zhw<<%mc9zhNMOST8wn@Llr3F?6HA}cS!S!CL!Q`T{*uM)pvG}|940Su6Ne$CHlH)n zDGyH`kSSGB)Rn8-MW0vi+^WHU<8;p#F)<6Wxg;D*nk8}ZT(PKY9Y`GUKH2CHUv#1K z%Ma{T^h&h)@rQ(s_jH~}Aq`sxn2FQovx}&~~!@45~@T>N-Fi$=OdpQw5KY_Eox zUJTn9JUSCU|Epr5tX6;jYF%i5=50s8vrwz(DZ7Ci!L>73L&xkp#V})yqJ7c@IQzVP z#Q1+c+Sqb!_-MT6rrGSq{u#xr|NPz)pN%TgQo2x0D2u@FC9{-2;75p4?p~Xu0zXb# z6(&e>5JEh#OTl^1WZWUao zi9h1Ej)3j9w$E_|mHGY}*!lhat~yP%FQ0pLpAdvl*e~cYqfm*n=qM1=sbCYKN~OZG zg7HG8;c||zcHEmjO%2xR>dq9NSc?kGY3^OCS|3+|Zei*YmAR3=CSPkklK&;PFW zdx<`~89|AQnvlrZXV#=iS%j0p@*>@{Fc=IMtum&Y0l!gbEqCFD(!+iicYyXoB;Pkg zb_lgOGm4vSfI*pVb>+{H&iF@IevG}oWr8FH0;q1KCd2e%pU`e$0qercIo?MIC>xAB z9I0CEe%WqQ1L3eGnz~}<2uHS)hlX*5)dKDovQ=GgJ)AtX(c@DQhM>dml%i5N7FHx~7>$Z0 z4elYyTA_2x^{$F+WGE%z4(}78wY|PqUsRiO78&IPO1-Q~Mr=LiB6l^!a!L@rU?(=3 zsF)=_^ey1@7_y6<-UUm#(CD(blQ~3w&j8W$>-n0*D_c&Fg*1a3P+|oy2T0<$^&#l} z$2DD3ykK!=OgGNr_W-xziWe+*$pg9l02cs9&Djs-K<$$Why)Z^nz=#E@^--l-2`Q!O0CK_-s zP{Kp{DF(H21??Jr=xYzy+AS|E&R)TPu{T_(b90YUuaA4tLB4&rp7vev!EmB7ru-K3 zd^;DHCd5L#=BjjaRmI{mpp2X;)|o#PGckoT`tMc-Ia6pB_2>%EyH&H5o=S@PSrpUz z`);Buhw910^YneL;`66-$Heoe1_dNF+wD7_CB!Asj(p@ZKy`%C$_N9qy~ch#6Msvv zUvE}Tv3GoG{CQimN#0-BJ>^>lwS;;cySzAa78+TLvtxK}18pN`_&u7Xvl0f2WJGZ- zXs3i50fgS$SLNBIy@I)wGwXG@FA8Q3WN-)9rxv-l8e`bZV3vPX2EbE3euw`?<1bJ? zQ<34H<)O;x~TR3u*9ZY;Y=|zw#4sutVjA7Kfo@x)FY4fqcv_~ z5c^*-yuE7l?sCPMn+ge<0j=3_4=phxfCVAIV^oi78iLW8#3Fo|GxC8n&MssYro#s%DDVtg7RpHK!GSna%je%k7M zP)nh@{g2q?!Za+AOGjJ-iJN)#Jy(n_2`sY{Pa7G5-mWG*d$8#O8riDbQe?WmvJ#linj)u|AUdzW|K&O}eEUH?uoXv&04LaUl9Y z{~3v+1hul*5sYxmC5ac)r6)-vprZ^p)yoA$P)3-{11b1a&O+=9bvSb@jCz!X8%4*1 zfimGAZZiNK8l~BjQ#l`q0hwoQ3U2G2N_-}{*sS%R=oN~tXX0Yz6N3{&5$lLL*x^kJ z4JE@S_@;%PILK<0L^hM!2Ob|*`^XH@jkleSCiPdP{JGb6kgst$V+nqcM>dy1h$Q4tVq6b zp0C0knSilD2>aEx*cdCzLlC(MiT`g4AnvRH z%Ge2;eBscQb9TdLb!@aOp<{6}0M2>?cC(LZByZ(Vf{c^95Nhmey2Yz&Rkj0tRymU> zpejogCY_1%7Z7H^+0pjP$Yk=*kKr5%u|X|4IjkkNWWGdu`|$95?L*!(+4=h)yuTON z4*DIxhW0t9Bx9WWhMPHn)$)ziWy?TY0Se+p#58h-1@)wkdQS^S6p{i;{J?(vCF{v1Lo(cdOr#^+fr+vQs=S8bRxG)Jq7|5Mzh7-nG{wm# zr8F?|VeFztq`|+w#e+~FmC98dTJ{=rTId4lEP|WH*W1`}EuF~9amokeve~GoH}RL2 zgJZf0>df`^+UCuePF@EB#QbLs0-SYBFG;yCFTDC{BWZU>L}!hy%~O{$ac3(u(vkcx zb&^YVPRdov=T-GBs>LcE230)dR5IKaoZQ=%7X72DlYwcDoK%y5Ceg%2u1&*cr6PN? z!E3VajV~vHn|p85(Z9;Jn^W7JyXDXj*mGI5Y0s6+4Y`==796eG@UFK%!r5*ZRHK!& z`J&@7gRbu`^i+e`r5Sl(viMlMA-~}Qi6a}lbck>oZzw3D#3fJ*Y@1S64YXX4+nZzh z^8AIL=Wveil66w5EgA8=lw<7_d*3`Px!DX~A}TN?KGa0ARKTknsuYrh{4GONl2!Sd zB?^W2*k&OcneU%d*Y%I7YM30tneZyO=4rNS_w0fzvY7D1V3s6H{cPpJfhVsp$<<=Z zX`g(G%i%i8_-B-UU-D~_8oi8U@4`u%(Qc_a2 ztkf^|vHqjpANkG2j}5Nk5Avnt~F_Ly95s zWTpu0-QeQp;qh^L0u+J~pX?&4|K`HS2LyHDnwmpY|0WzRmSRxX-!H?x&xtPlZ{1hA zeA16`mbLUwXYDyHIWvIkvQ5@h87M@Iw+OrOl!zC_P#M3-2Xk}g&pS?VL{E&PXU0&u`!!kWqdD9%ZKX>Z(&nt`bTP%>EcZx-pA}m#-ZZ^#v9+JfgJ`s`pCUGHD zZ)aO>Z`a-_!1!5$ux&eO`;R@EUwZ(L-R$aapW1EasT(R5WL~tLWaSZ+%|~)|Hlo+^ z%CSlK=WpqBCeWOWJPU0)^aizsC%F=rNTyhAxJmBcU#;Of$Nnb&(dhxkJNbjGQ0P`o zO;v(ax_Xkr6SC=FG`r{wG30LNYV^+j>$DBr)EU$1Uwvq+6|D_Q$SkT_&gypTuI9#2 z!!}gzO7NyKLT@V~Q^3+eXoUlEoac5|hNWQ!mP$=|dC!0ZdpWI{6!I z@_k_1aE#a-e&c6Lut%1$Cvi%99l5wsFffvPpVi1c1PLXo0{fd>C!xS&aGbwOSeSsw z<@ijS>#p4*CTHiYR-v_~F581ex~_fr4O0c@ie~a!!zDH+t3@ z!exV7BGa7za|p`MKetfo{JO8!gBzTITeT~H=uApR zXplR_hP6XtJ3xOqFZpd?Xi{ad+I~DVjZ(sLOwPrb7u#%#kYp zd2*AXn@v99yU=->m>^VY>1tXVxN-aFS;F;KsMx!)yy7oPJqHJwprR_I>C-7+Vn>F9 z4hF5lYf0G=HB02SC(gv^RIzvBI&SV-zc;yonH7WkOAg_Sgs9RUC(Gut1|Rx|br}q2 zzJO6Vzuy?f>6c*;5Mybefj=Z$sGhkZ_9%D`B$r~amh8`nI3dBmTiaiJ9y%4ie_OE9 z_sisR*xXx62&F>*dyP=q>3x$3UEvoo%Vd%PH z2}oyEXEAkd82dYNetnirQBs_#+x3X*(EUAKjZa)QY_deay~TTQ8b3J(vr%)HO-}bq zJlWe;{J_Z9w(Giy4;>F2*MNmFJpwKf44~aU!i%L#$CX=)h*Gj{)NbAii&yfs`v7_y&=@Z}?kOy`_`B{qPRUy||nn@hPyfOpz*fNnhl$zfKf-rt*K9#`1G* zml?adP_L<1uejuj;Z^6ADB-1P^&885+h=@B6|y323b9Gqmj)OIj*-#mkX)a=-}A{^ zx6=N8qI%!gPVdN$pX|u8eM>QTw@*|cAv9@u=dw3w>$??lVU0q>>zUc}&3*h`(&CVEIlPSN5WIMHhd<`J89hmA4WdgpOD`ziK1%18y$}PxibilG>eo5uAoGUi068OfsPV)MNL;$=prT#ea zzU|O9hpu|iY3qAKu-S<-ON6QQ%q(PFTvld@t_El4^`Vp#ZTg>+1?>=crhW)|ZA!&w zNAZ*CBtm~LU&Hu&p2M>PcBIaAw=I@=fwixJLTJPN`}-uDg(M1T)Vxdk1XXFIdz>DP z$Qu>Px_Srwxuv)nF%9nR76d-RTv_CA( z&~ev4=+}BHS3n75jFZB2nhP!Q@p)y_?z)|NgTdqwf=cP&|ugS zA35=RIPZF&6U>bBIn!;EA7W_GcI|zE%5LR}iFgjnIy-If2U;w>u-6z^JJ~FXQ6waIu=6nUyj*5i3Wp3}(YEs;0MT%J8AN-=@Iqi4Z z&VQfH(piTa4ql9X@p;)6IP-Z*^G`3DOkDTepJ-x4IlY||7sjMbNht#`Lg-HFcfTGI z6GO5M^3Unt!<7~5t$eXR2TL=k5Ngwy~7j^>{9H1?^KiM9cY`0o^N{p_I^k8 z7)IR;L2_kcc3A|{suL{mqwKmdwPpO5wBoo#q2$8)&?D$utPGx2{A%biQ#ZG!MmkT3 zh#{xh&b&EWx%_`GZHImMhjL#Nq~Cdj)@fCo1WuHbt*b@b_jXpX-Sa{1Yk7;-g3oyA z;6Y)BImL!V@*w~ zWwIN;9=Qn;4e=bapeggp0p#o1mM3TBgoYMdpV!782MY=0UCT*87Q4DzN)=)yRbm3I z%6ZdK6{lk^G9C$0L#KDYtw~6vNw@OZI}q_Atd#Kl)RDi2wQ|`Kc-)i39X}mFF$5k z!8nbY)RpRGn0kmcA-gGbTp0_QC>hMrdk6g{$-*EMAi)Hql7aQCrAE1xpk%k`5Z2*X z(%aFGJ|L;MBG5L=I2}|dU-(ziQ8apT5CBlBX|m!XB*bH{?8MAYauqZtmL{(NR;p>c zp-@PttI2YEiLxC#t&y-_n`}{GqR~YJ;U$X1ZC3T|0)F2H#q*tMhj;88Dks85mRT9r_P1egq}9YBG7NZXo+-pu-_jA$KK& z5FdhjFSHTUgTZmFtE+1}XLksRYitbq5$Z#QhDbnAk_{C|a`LiF;k{1QqYEUEV5*!@ zgeZsj4KCDb8(RR8ihu!+J(rlZG44p7Nr~AL)9y=WnM(Om`7&swL*7zzWeC05J=?2N zoD~v(OD-XnFg1b4L6_I zCCSu*teNZm@}-Mabq6W-|I2nye~ou28xIU+L0XBi(S2UUKX!OaTUX#*U0vNCJ0tdf z?mRg=tM~UDe0zpb9uQkvYF}}_B)l%J_(b~=WAS!_?A%HCw>FR1xQgUgvzT8(Ld0t& zUrzro3qXz5<619}?M!COmb3eeV2Qs2xTsTQv1F=Ms#cwe97L!?#I&|k-)sY4LkuX+ zH}-eErF8Y}FAK50WT)2ge&}_xbBr+S^B0k7pk_1rlF&j6@z8*?wKU1V9N5WH1fw*v z#x%>dUC#rAIO0<$&7PrC?ZgSUAPJrriMo1?nz<^zg%i9l9_NbsXO6E@8s*6!eRzVF zHX`z1@a;#skdb*+qcvt3VuU?U+b#8NF*cTK2@pI4Snj6MLoIl!AG=#k!G5l*7Mi=IxcdKE#Woj>NsR(~h+9 zt6a4Vh^X2H`|gq30MX3nnUSr`466PP zSaKU@JgzKC8WLladP%Rgh7wj_K}wDSVW|hhh)I)wXlN#)2sv;a)W2qDkprwUxhsV0 z*Gl%VE^m-OL@qWKB9slxLvO*%pb!cpFp82_}q~F4_Lw8A;uh1dQRfESJ z8z6uzJ&$ zBVuhbIdrH-k)~~9m$H!yOR2Z>ukGzLqsm_uROwF%q)UCyv{%;@5$^2*Fsp8gm zf4cy4T+P@B6VRYzT;Ju7jhr1hjf;+D7adI2EQ}n~v|Lp9DuxHGVOJK>(IF%q4;x^0 z_|aZ`VK45_ogY>Cjkp(7B$REu6Pclbtj))l5zxm5j@wu0=-`5OuUTiJBy zL}eAA*4fA|`}UTDsm8-HnL!n-FG`l22Mz5n-1}$0h|h2azBtx*ZQ zw`8er3$ae7J7Ug1wB*&KI&sbhH3v^Hy|qcTa{W@6FvYE1Hipm}d&vT-nIJ3QC(ky~ zHU?neaKM2TL%Jn{8A0}{v^KoksT;kKqY117eF&u=6LkgX$SDd`4`kv|$Pjf*r1TCQ zMs@gdjdE3US;yy$MTUhn4*E(OWJ!!+h_Cxu@!;GK8UI`wDVV49pt*R{)qck(=nS}; zFg4npcBY&X0hD^~R68;r*`Z3$#c>r;$c1j4Xny!{ho!>nv8%8YSv){;fIJ{axRDSr z(%%T%0giV9p7{*6PI`{7<7!scp~8hs8^rhMPPPq;XER9?RFO zuR}rV{H4Xa$az~JvZ_uwz;x6dyfGjUJItDDT;_Wus-3ea@dF5wfdrExr$5uJn9)y} zEpal{6*;v$D3<}KH^ZfqV%1OUlv{tSYWxZN7L}Bf5@vR!Nlu+J1>YYYK197S!N@jf z+$z_|f($d^Bl!Lj)khc^k}NeA3`}Rehbd{q%*Q+Icq_0c`y`illxIappMf?FWA4)K zIPtyu&RA%IoT^kP*Lm&KsjYRUPIF&oN#YJR9xWR6=vIsc%ZkO+vFRCo2t_E)p3ifU zH+vB)BY^zkISX|-D+10j>?hiN=wi?I#$%kbzs6&km@$uIzMhd=JcElR}!wr4oQBs-l*H_1w zLy4Y8ua<3X!!rdBiM4c?c+q6q=GZpA?~&c7GCRFW32jTY);L4z>#LYM;&-~FOD2_z zqQeV*upnNT1n5^PI@CIDi-xJs@!EJvb~p!6j!8F@7kg!Tq51i@vB!hn{ zq?s1=7i-!;w6x4jy1m>tjoGc;ZrRHJ7IbppqhK%-?cB$4udMA@lBe59WXRfSqojtW zvix2%=j4!9B+Xsi7v`@f4=P~>sHNB&*QJH+uX-FjT@<8@RBE(fisl^+LuQZ~7zHWT z>l`})9CWQZuDl~R(7CR>rYi(2C^XTM?B+kk+SLjh8zw=O4@2cG|B+ID!alE`Q5w@+ zm(1pmuemGg>WybB(q_{8KZ~|rSWf^9I{MXpSN{)iqMN;;V~dJ%E!8fyH6;b(IGN#t4C2diK@^d()d>i;f?Xmw@GjZsfqIfB1u&5@dBT4;^y0e(Q*oweorsGJm-ej{)Lj`}o{(<+k2b$7ZVWLZ- z&0o$U5$AZmNe9G+k~Nk3-d-8kUtnPX0B!~gCm|jEkb+QumVV)MHF^fFHfs&qrW7sT zwy_|o^%D{|9-eHIn#*CblA5+;(>RFyOwh#7SH>jp0uHp=00JrNYzXR00+au2Gdusu#?l& zmGX2|w-6Oz{RGp_y{78ost_GAaJ_I|*XVQyYqM+B&&f9DK4g;g_Q=7Z(fb}|)7L*U zpc`~FkFT*@dnsub%Msic^aYtM3JS3SGrgpUE-$Kd2?Yg(3h0`H#qm-|-qbjQgsN*0 zZ7-ZJ?_`xe{f|}3o6eZm(9!Xilhf!CEjdu9O21=#e*$O45~nUk7wtd%!sr@BRb4@5 zm+smr^|g<#xFAF|d4^dVh_cPC8AH8)mGx8}U=nTt)p-zpz3de^`S;=4_wEiH3X@7; z!<%!gdbxGsaTyd&>QQnEFDvZ4HBplDA6b-(JHr;eWq`ZyU^P_H|PZ?;M3*d z3+Sw@g4SX@9*%Mi@|B!&JHC~hf>~CKUF7;KNO zx<#K+hxrcWmxvv~rT*y}T^r^-=7y9Znd!hUM@}vt1&CR3 zrsxbZVCJ|SJeXWQepdST{P21Y|U+BF?kx~1;+@81taHjq5E}ai6sJFltf5AeA<`|8@qLg zFry@aGFI^o>N)Q0;xf$RJGXV6&$FEU>ka3!dgMYx8VaR!yCNKW1fowt`k3nSEWd-2 z&t0>4-glJWf3Z0G5fbRO`+Uz#@y4r^JMQ2d>~)Q+RSNZH^}Df^|HGN?qia_=kQA+z z3>{tj-v*wO5Cb=<;xg`B?iod+a=;z zBmK=EdPF=a%0z@dN3gla1^)6OpxH8M(gIQcFWUD=Q^%mF+?=|0w^7S?gfHC^P6KAg zve=Qir&oXwphyXNp=zmZYy0mM?h;`u>`;~br7B1n4xMIH+o$ql?hy1C^`L$AnCf~3 zwoLXc3)e{e6sB)%VxdrTuAxE-N+DDgr&Q{^X5j0%GBkLU57w6*JB5c%DV;n@C4q%9 zZAzx{5~)VR|Jw}g1F1`C>_G|i=&*SFV=8Xf|CYgGoB|(DS-@)BoWvE{h z09okrVOjDf_nb)KBwa|@=kwKDB29RnEEXnFCyNXH7& zxMOA5qJXjyBQV3IXy(>N_}E9X^yL1t+@6bxGY#*>Y!r+9h%t!8k+Q{S@iMcgI|G%vcd(0HmI?uTRgn# zi<4g=mQbzW4J{`N=6AW()?{n|lQ%@~Rpl0sD>{MEVF$Gk_SLLvlFPi|LQ5Ex842LL zuoI}^K+Chiv1%3bx>_bCyTMc5P^+$!P7cGN+s3QVKSKu-(Gs_#k8};2nd=*R#*1Ua ziltyzcfK?K-dAn_=r<|+i^^LIp?D@Ya^ors!86$eTLU}ZL<2J2%)UZ``BggD91jngaRU3wYm=BQ;pXHSOg_Dy zk~4AqcpH7-$4tTZ?8_*?CzuE?C*~7^CHsMpo+Q0(W4KeZ+TWtb8bPYk;Ty%*e-nUkxKqsJ`pZ1+KbSzWnKT5Cz;KZ+ZP zS7No;Qj-ov2O}4F5;ECiQ*i2@Bo=Oz|3nZ-rT*^|gR7w#a>{tDDTmKgl z4YcJHt5krl-F6R_Tr3{p$)zQisA{d#=`iC`BokHs2kZo?QLN;!agT_0KaWd+jy%p8^xXg)aHY0da*v z6t}P%WQjSbU^>k4XA{VCRu~|jlnQDKOXl0&qlBvJr{sgZ=~L(0?&T-uIgw)yw3Ogx z*Pz8#=r>5f!0SU+c4uzGawmcwMrP6i2`hgVTe`XC@)|BtBE4oe<&3DPhj_z#a3h2o zM-~RmhJKK?y(t(+9EVV?wq*a7V9-5h(fF)EVcILIrP|OJ!8MRAm(EKplC}FpoR}VD za%7pIaKqa3D)qFlca zpsFPb7mJn~6)``rmO(7tj#>bL{eNBhOHjM9Ao99C3*JEPpc2`No5BbxkoH`xOrrE*x{*u>WBU<4%Ep z*eq_J@BH%b$8sa>+1X?bqfpgh%N$9{P0aU`XvnJxYOG2@Myy%#jkYgf;#VCX0AN=q z$o>ZLlPEmE$K$1V2JV!6yq|Gu~_X{vV2Nmm3I>qv-VVJS(>09jqmXuTFvSmJZP# z&cE)|!=5CAN^%mzP)lh9A>#Q9c27hRrsYFJKgXQIMzeTa{4#u6L>p zDC1+WZ{Mhw|14SEXjjpjgvQOZ(^7#DipZ&ApbKcJ@Vch{Ca>H6KAZ(6jZcZwmZ>N9 z{Y9~FBOcK)>E9(1oX06c!1JCnb&`=<6jsANwEw;RYEYW?1@+6BU}r83H%ej#HJKU0 zXKavv@_vBa%wHr9WinGti99-l&BNgAXA@YupM1mVo)6WnZ4ItL#hDJy%@!&e1~30; z8$G$5(0T8-9qLGlu3mu^11w5P9`wlC5o#plSK0!W7F*P zE;=ES#pnLt$qVqYCA;M;ju11K?Hym&cr$%r3LE=(ViG)DlDn0LO`p04e69A5zQv*0ot`+Igr{c>-QL5qau>xWgNX|5%ZTAM`es&6KLfIr#8IaY z!#8NwPl&T!IB%u*R6<9>_*eCQt>}t;tTgLXaJa_SFb}l!h-~zZ^KF%wuQFP|VL?V> za6$-`B0N34^1M$%V(uFYlOBm{>!rYu;HaA4HTDjBO+*vpB9)12m0RnPGF^@II{@1BWXnoSG&}@cU>>xA1T2KB2#3(_|w! zsIer4IcF|y%SJYa4K0FsX4Yx`CcaEE&=QSxC%kfezvM!r6%dI-@ew85@X@SkyDO1X zu(gip4do$pI;! z(~Nf5*1IPT^kH-=jZG84LzeDG?&~)?2-=v6CFny+p?kzmjs^v`m50ib)NYz>Z`7+H z6W=kn9-&0EE2Ar;^q5e;uJGjSJU|T{CMCWy5?4z<)I^>bI9`3I_ff3!TLVLaG+$td z?`@T3e_i~5ochL6GwtS45@@tXc#-#)Sy1lU-F=7;T0$}+ z)Yc8}w_mP~2Ar`J_?dR0{GO}* zG78`Q9@lwPl68iIuR$DLsK5ib{mE=%;{q4p&IYTn$Ak&*o5kQW9;f zOgW^-H|ltKxvhS+kXoNjK{yNpZ>!_{yt~gWZ!44dvw#~1C zio7vYEf%xAJ1s^`>)X#yUMQ7IMYo>08?Q(u6eQ!w?SP6aJ6((0H8*<{WPqIFU#bRk zh;CQ^69L(|M<<~A9yjd*#A(G$cO4D5atbSrmZXr>moBj~l>u`TZa*L>JuQfI=8aP9 zj1IW@pchAUyJqV!;uWitW>H8|B&s)t76<<2h7}PZ$8XYb9S;q})?;zu1?x~}{6rsQ z3q%)t$ch%7ho)cd>KgYTBe2|Hm$$(CX*yTM%wFbUS(|p)%o~#}aCaZelS}zv763@5 z3=#1)3L1)G_`P;AtEde6Lvc$KNJ>Tzw(iDql^c;Ci5|gN>kcT4MS)Q=!r35&F4L$j%*4sOUhh;4CZ%22>17f?HGGYTHyg@LXJC}*#W0j)5H>`< zx;L_FEv;c>A)U3wg$<468r`{Bvb#6Dq6}AJ(3XE-QPr5{*QJVbw^+AE-YA?iH$~b~ zx)q$nA-ZIs==rPx<2N@v4*cy&u(??@I!{|fu(8Jx(~pXSB&T1N*z*&J|7I?GQ%yfN zFO~K-$W)|*U7< zyd8#I=*PM#MzI6{86fk6hu75X?Vq}3VpQ38_zU$iT@EYIFgTDI!_Ak=n)CT%vO@he zeOfXrTJI?+OTJXn&M4^C0~tRc*3@0Ix-#v%Fm790p-PFqFs*e{>T>-8Zw29Y+%Q<1 z=(l^Osv*T!lqeluT_0VQ-_K$wR1ejHOISfW}buKih*- z7c>XaE>T{Ma@E~^&GMPkt574QCh{S%R+*Y50smq~cLT+(=J9YbQ$kZZ!2&oc@Hew& z_%iU7G7g3TdgSx*tAj&RpW885kwk#rKrqTl0{I0z5ln8D;|aPMenF40ffCD2RzJyZ z2Ytg%LK`X+r+MQ{L5)#FFy$2Fsq@-IuY#BM4_3Vo3h zMId>s3W3Pn3C2*})EF2cS*xN5ifj%3 zyp8{twB;*_tLiQWR%u5B09@g=`lq<*rCt#qjFhrYwc3J;h|Yc8j0m(!l?WkYt>V>WkOkQH9sE9FBpjaK?SRkw`E2yL$M+eq zV?W&WdDd0i*!URLSwic0OG^UF;}4*eWUl>AE+Y1;LefG!VP;=yse*?>4vln+DjY5U z{?;RpxEwcFp&kpp#ha=MP00lD)-2_OPMW}(|PFyR+fDG|y{ zB?r-dgK`wYz24R|rm-%j<&*Js;QK{oOV4&32BMX~Pap?s096E*Q4@>!Raw!&VwkaU zSztaYFHB!3W28iFreZuwc(ASVMY$ChNLx_h;Q~;K8R3wwBu)*oHB_f8&MN?Ze__6o z#1-pzkWQ3P8MIRoT0n3X5sY&LYh!Ri{*06ob&{GY3yjhbI+dMNh(fy@B$JMk5&|;} zZ~lPC<`UD2cEBYIfllVKNvo#lFG#B#Z z6_hb#+A_%koy%C%V$EPJ{`1#sz!oXLoWbW2>-mVrQ5XaLb~7)Kefx5J?|%5){mXsX z^xe7mdYyXTQVilBxncu2xDiCBe7^3I~^JmXh|w&PvA>@V|zG0K@qe!u;{607>zP`0swS zkb(-aLHv|dQcAP5WFkUy^QRrLRQ(RZ=!4|$7|smkT){f>{Rp1VTZcuGrSOXnjTA-sS>pK-lx)?xSB6{OkQx`D*V-9|J z$o)rs6qUcmz$D9X1%y{t5@FTzswB69QSuD4>WcpFPtSeDS>~yc*$TxsU^&4N&(ttH&dr~5%gGl%c~vST_w-ouq_(7rvw3Mh z<-`4#IZRdgap;H1?-5cEli;r*6>m(uCNgtylhQTP%+Td9hQr4KlQblChtW-vr0pi< z(lSZqU;-jJ5(L;8WuSDv0jKEuep19Dj*I48>iZQ1p#@iklSql*y_kTLLp}wc-eB>D z?%}=IWtUVL9_?zbD&$P2?70C%Ys=)vKVYll%Qs?Jd7DVl5ZRKR-p^QbkIBbPC=a=U zVz|PwAY(#V`;endJvU)Xh`PESL!pwJaP+~$cEj*?#g01yo}oSmh+g@gCwy(QV64?; zP;k}g9p`RIq;ak#-K!MAq(6xgxH0fK(TTI~G#!wlu{Fj+2`|e*Aj^sDlKA@l!Zkow zsC~A%gVX77++F3}88NQ5aNIEe2B)BduCXziGwlUZ(9rchHb5td>XCYBk$c|R#K-WH ziwrha=KPU)Obvc>5;52zw8<$YhN-9b6p$EF&%ixKT%=j$`@v?zUS$OJbZcluR;>5P66q(?3kM zTWTBK}@bL!=HVKAZ0|*s+l1^GS#9OPu1a&n1OU|Gnn1q^Il=#qNa-*rSX@IjtLEGP3(h>QZdTejFwNOB3m^kTQ{kUfs-R&($VO0Rih7!f4m0|DXJJjhEf;J!Z< zESvuduEX({3^2^+=l4EFu*OD`?R);FEkr)$ctn&XmzC93Lto#V5#!rROxMXXvGihTO0?oRpacG02;cj+vDd*B zAo%BZ`1nHxJcN7hgdz%H-LlxC)85SD{~UF@PkSW%+?jtq;NIgmn6$L?&^7fFI2KPk zcI}-rW8M#LR&CN;=B#Geu*LejV$H^f0$$U&`IlUrb$(Fy8DD?3a!DrRsp`rma+ zyUS9_&tIYquLu%!q7 zWEM>B8c!mV5DyQhC5MC(!A$4}TByoXbAgKU%i#pm8KArLK<1I0Pw4uVy*qxxEWjcAS-6YjACMYpc zL^N&?ax<|k0qp=cpnxI`DJB?smya-ZVosg_7&!ksWv7(UOy!m&E>LdR%DUgdu@}RKo zf$K>#uK{!sctakC1QMjsS8vI322J`n(izSk721{bP{h9c3niFBzxDkLHQWjU7J8D`RVY_rT4)bGdhF@d~3N?72@2xOnsG zOkf)Ic)$C4gjaP=>Pqr4{_knj{SAI5Q01mLHr5R6p8kHo=aixoTLA=nN?Dm~@Mz$N zDR9n_KG?SmI;>`CbTU8q?ryGl59N?4g)_PiKYYD%e7(9R^P#7Z1v2j{70I`W9G+L~ zUOuj_Zu8oD54pSc)xON{K3k(+zdwbf6pZ4j?nA-AN`z8lbvIp4Y?UJX3*h52JlkPP z$Pb=Bo6$R+wM{keKBHTa7fg!}M7n&=OxU10za((5=Q2(fPpl2kKPe3l-yobmVffcF zo6EyJ$la#j>XtN+gbBfI^~Y2A|o*s>`J|s{-A$?lUok$SxXKmt9@idG0kjr$BcX zX2jd$BB^TaeVt%;+pEmb*0PjmM@L`i*6o@QyawLbhjjc7Lh!S-yr;#G@rgRUj&C8k zRV#C)xn&_i@@n7VE%D5`+acoJ-fR|I^^JL|%N$VC8UH^)6UhYgXPX(m?UtFR?`T+o zKHZjno~_~%hH)9WoR|MeXn~j(!Y@2%cKIq}+9YLq9SOnXAI;HX*!_VPvbusVuXa*h zx``BtI2!n<&xBQ2+aa(Ps<#&$>M8sJ_|Jhp!e!>i$$kbn!(MtaI)Z6Gqo=ShFB}dJ z#j_|sKL0k_=u_{qvJ1kE(o)_`a(LW^4r$4`dEv$lvkh)jE@`q_3kj*27;6xl08O}z zYd=Ce-a_yRgG#R&V>4`^H`q1~SUp0xQ|0Kfvvcg3I{ooX_NxUjH%X_&DUAdrV$(5` zE%M-D9~x4XBu9CO@$4L~ua$UT@7So8stoVZW;0W;V<=*Ga|j$;>jw7z<+5-&FIih^ z3hbQ!;#%HCCi)DMGbN<*<9}U{siL2^$Y8GB%x##adK5e7;W5oO&t$QdE(&8zTq;EB zGPVtUhf4XJw-7&;!6D3X@VSoN2+6rULgw8M^ZHTuiRAF@Zae+I02m82Owo7lo-7FA zNm~rX1K-aJ-|bbyfKH%5+OE#I{k?s!pXX$Mc>;)rTth&^pPU7~P0Z6FpdnYJeZ54B zeFp0NuOXQ)uK0Ij`0|e7-qs;jU%w=Qgkq9s*Y;ZasQ>*LJoXZ`oi~4610?%xdol}; zW-_~^W#u@u`vxn~&)K;iKXJ{g+@Q9N^I4CQk{}L6K3zF{6~w&UbqLAsgVPO<0IjQz zzA3iWdut4#s>t5!-M=%JI)s}WroNsra!=>DxJ3jB%{_t}&e;GOOS zOoq?*VcT-NdXEn17B|~RqqLS*%+FF4QX-;<`h35T3Gst??zOCKX{RkxS!AI6{1Dip)5pB zUflR4PkjxRR^KnRE@zb6z}}4`YmUPabpcKA(z0;E-rs};aW@J8<^wNBAb39~x^CXY zP})}D?7pVH`lq&9CbK5!5p@JGzYA)$Y$r~ z$Qs8kWhd0CGVTPR8~DSq)2?9hf@4I>4HdR6u=NG$BuhOsqHWwT>{%tn?*A<4;u5GK z&2_-NvH%7}+}d#3{$C|HsDcfQXAsG%i?D$Ks;lPV{DOk<#>Rcc#hR&5#IS+1^14bc z$xFBrf58qJs0H)sztq7($zPvyWl{nG^PGpf`>`8BKTOJG$$*_h9S`xOQTB33*m9=h zjOyktWee8UA|4YuwV>wMZNr?sH=?^4svr1R<=9Jhjt7GniX7uDav|p96a~Uc&E|5RDXo1!QRgYXTH_X|PK{SMD>dVd~Bt zhlxhQu|Ya+V$pOx$bRU%LdI|s+GmIbL9?~hPtacsWc1IWO*TUIKqO@Ctp5aOd22f> zVaa30CVW*0b=B!SQ=xmI-B~+8CDZ6WmSe?VCej*$sHpLUq~)xd9U_=av5o{nDRE`w zV|6T)VZY)lAXUWXSbv`W8XTT0bb=aC!pN+B-K(S1(1lLovDvJp1x-nOmx%9-EvZO! zrr#qZ2NxCo>g6KcCOPhhSAwVu{_iv!hZb9{?UxabDq%OV!Y*BQ&2HtR+REQHOe8dT zEBnTdsB?I!7V5%}Hjc)Oy$AF-l6+q}fk1c)IxIRZ%B4Q%62AJ>?$V>vQJVQZ$gjNgPEIWO%bR)k!Vyn18<4D>?CR zC*;!A{fINY@JQO5H2f^aj3ROmth$Zf+VSczQtd`7hZW?~Y&q%{X9?(ipx>vh*R> zdXWhwWe9NLyR}=Adev=ar_X6`sv9-TZha?ASm34b%Z;dsYEC0MbT3g_ZN#|DlKZ6G z2};i{qB_O|#H-FjkdxvR5lbGpeap$fM>&@A^@SMKRGT{v@qQ9H5+r3YKXZmi`%5go zGpsb=ewt9dA-McL%`IWhZI?%Oh5v&r*@Cs$LBeVFz7=bhqndH%7 z1&Pwf=D~ht<)wuf&I21z0z4h3eS|c-_ z5-5=#hXo}9t}CF1scS)CJV82XLHoU`r$ih@VVvCd3#5ZUJXlf^n=?ko39rzEOcId* zDuYR;j9|nlvF`wO%lVgtbSAk9PR_~=ZBTfz#c_IYFyo6>Sixp+IK{bOMXc0Ipz*+;ZmdcU1Uk=Ah%$yE%f( zt4w=rc6Gb^Wp(q}CXaV7l@k{+DJ;iP0!6mSxv>~zjLB5Dj*YR2dmfmbij0>X)hiRnRA zpd@E&4dq~Yh4>WITGL!Suz0RYZ{{w@%zgCSGvxK!wsqSkC%c_K@-P8g5J954NWA0% zM!~)1+cK1K;(D|lNESw#36%r^RORWW#aw{bgMFcaIjZ~Y! z=-=of-@0`?leoAyGlY)7y+WBb!r4l^d6uwiJc1S2?tIS&toA0ikc_fOOKdQ(qe^_g z5BPb)*~c$3-A^b~Ul@CwVI_=^wmO zzaz3LyUYeYTdm3bHD;R2*t!6A2OEYj=4GS79tw7*O| zyoOJ9IEA?CvDDNxH1%i30k<%G2-n5*VcJ4vPZ~O>`jW6F$Geayokyt9C?trhQfCzv zl{KrZjLLoh`0#!MHe5%hOvXoMNBTPFw{Jkq+6@y2lO%yA(UM})u6e^kazx5;S=W^f zkM70JzA&w`_z=dGbWR$v~ODPp`$kIW*A3F{aOyj%EVHe}eHYZT+K?IkFq2vUs!q`{OnF{2qB{A+62- zOxEBjVse1(OSxm2=w=%s;B6I>(RUR8`f` zId=5UEjR${6yB3MNskjvEj}heG*U8_r&8JYiJb2E%)bdx`%xY1WI7J@(~`cuO)S2n z5*MT+D%Z(o`SVN+&&C3-IktXp-z-8Y?ZHJ@**Si6$Sgv$S_Z!_yooadY%G%n*X}tS zv?*o9v9S_QpD3Ab{`|jC_gnF$=g>m81i*Hmyo^cJgF_j9#n=pN&u%W&u$?DAd!goAC%y&0n2lht{o4cb+z(W!g zCf4iy5AWB2Zy&N5vKzhfkRtIr!h}8GK1?vD^EE>4Qp+PHZ7GHO`EJbPino2r zg;B~cz1~YU`S8$jCu~`=X&06`exzT{eS_Ak^=%YpF?>d61yjvetQLCS8CrH5I~O8Q zI?5wP3`mdI!PNi$b+1I7(au9QF!#rhweP^rMZhBwBrGODs?D3vt0=1w9{|fd2Uj-P zVjAT*WDuOS3QW-p_eg%}{T$N~%@ZDk3!WKN)wN|(EM%HF&z!j|@%kLn;a!!IuUbD` z%qm~+TpXJG6+TUNjXyYt4K_%$5ynZe{}(J8R3JIa_zYZqh9?ueWlNZ3sTpY@L=wf_ zMX^nX4^wwoi0Ky9t>MR+DUr+~qnnmH-+;bIOKAX|*Ni1MClP^u-p%9Gf*-#7ePT#j z0tr@po+(Y$436G2`Qxbm5oEjFn~M;CX1=SDN70B zG$=^HYEI&pB$E*vkE!obs#4ScbcSkNSeWzg2#WjQqvr#QYQr|QbIrO6N#cWzKNG|B zP)BfCH~JST>dk(*Va9u4WuAjk6-a4C-wO;1#wZlew=XyLDvr@yS%kgAS{3w7jDp`{ zR(?0@`(noeC|jxX;HK$F$7HJVbQz1aiOv|LJT zhEW-9p^-7?w*@tP`0`LrR7*3*5Vec4;dis%nSvqd29f#(gq8Yf6)3Hw*x}IPl1#g; zqs?d`0FHTb5D9AgNMITo8c~~d@RGos`kA`Ah-R5c6w-3bnufV<$S?{pf&U6A8!E7hCHaJ9_>`P*?&A_@ov_W2S%Y*|> z2%Q``gDIg|E%ktmb+4^Hc&X9z7_S=d?wb<1ABcfaUJ!ZB(ML#Wa{PO5#=oD3buR|@2wxBKXVS1BK?u5NQa=eRcRVa$$x zeSXBmaLCZzPI6ssRLrr+AoS&TtnNxGnF&0T6J73-)7L2vskcu&P-GOd7(Ksq-GSX% zHznY{G*b$@E%yMu4fg~q2)unoddOxA{``HY zkWY+5L#yMP!wpZ_2m?zM!t=Rj_k6bq!Mn*lG{I8)r^?Wdg-J5zWQHtz{UZ_?SwN?C zWEBt0*#pVwgz%&?uDqh<@U863^f2|w+aE2$HK}20blNCE^OC|lG(yqUDXM)Bc-_WT z!-&8|N_&Ux`2eD^_oTG3u-n$IG|3MkWAna;ejTy5WnL`rKhT$tEvajIN3dVe6Ie)+ zTIUDEf4+4cs(sl<=xu8DDmo+R2&JH+o8`=bI}Y(h%|EQPyIT7n9w@1Q5-ng~^6{su zNa|8-@gMSr4SORqq=-91h_EvaEbVLek?af@U0xx;ELIzC{elM74ykpuD+t% zVg`9q=hc1Ae%tD3ZJ+XsO_-f~-~ZtKIwpL&N+LHmZ@@g{7jlnw)X+c|HsJpmC~OhV zXpAl+ps=439j0{7)o5YBi-z`aA8nEy-+~m~F)Dq3Vhe80waXni!cP=?A1Xj2^rEk; zsS&R>ovqdyhK!79bh`$F+1xe_?a$2Go$k!mHS6O-{&4zSlYBk>Ai8tUjK^VPwSrx+ zG(fU-IO1bRasRs?m39FQ2oD0s8@rBw-GVX#GR4hpU3*<$JKua??PDa!Q4an*4_r`S z+J5;9ph2tlUiwAX-BXTz-CKRWe9%-hoz}Au%uUN5WUk{m`aH3FwPRclUpbw9{Aq5P zF{&&eJpv=puC*?G++wD97s6g}4%ad&I^XnaiV)yK3fg|f^O%uCzgurm-bv-#OUp{c zrR)!k?Z5vIFyfEWa~?XEA8p`_vkV=jc>M={F$rq_8#o{YRN6c~5!JXb?s3@6wbhQ^ z<_bxv$mbvxR}+T)@B0R0jdj94EjgUvEO`-aVzu6TfXOFj4tO8#DKZkYRN5qPEK}QE zSVW<{ob!v2pw`njf~tw#BAxO9H>teay4TpP#~w58%%(y%BOTQK=nmEC6c}#ZXi@zY z$sH8DpiM3=aI0?o9(8DOJ8q8N}oFH9|}+hQ-b2F+T}Sua{>a(R%@ z|FM%Iro0!8oQ&q+{Ue^N3_Zd7A)DfJSRi9#DQsLNr=Jvh$@SrrRaIulCS$sXG-pa6 zldOP_xB;5GY&y9=op-`1(qa1mJ32;6DSSiZbdg5z|dm zWPSO44fvZ13}|r5=t*=mcJ|GCFMH^FW`6dY;F{X|yP- zsJYZ-OxOS%tOo}RThj1!PUJ?xb6rmSMblVFL;5OLjO|pCtj;s8>^T-8@O8S$XspJ@ zS7|anQ;ST5o4N5h{)aUAXY#4zN_5FIHplVi97yElHW=jCEl|)mc==a%sGpUe3s-h= zZ};7wDrU-!^34Cjwt6IaEq}&(*4D#K_0wOwTyv>|MbnwvW;Hshq!ebX$D+af(X)OP zGkP}PvaOlfpgEN(EjX~H*L1AUhQ$JkxARD!8?|JnaOHCL!o@)Y(c>BfjET9uF-6(_Z>X$55K* zM>OIUC54NKi-JLm-(ecf_T0Hf-~H1z5BD7hKeQmyql0W(-ArRt%SC9e?b8V~vj{W5 zX!;GL-&_0)Hn^`~S9{jY`3?y(-)m^@ilJwnRL#L0%=cBl7%L6*s*o+qxy#3sM*Q@0 zh{Tmt^Y_%P&r_l7$c*u|AL_agOAj@4h$^n;tlFB<`n;{i9P0+z=XFaqGpF^(>;&t~ zBB#)*O>$0OY?X(U8GlHHuaGj<5Wl0~N%7MJF( zatOrq@E%7&M{ROyrKsWScn#0kL5X~8ZyRzQBD3f1_+F5k0bOhoYYKFTkA?4v${5eM z4%PlaYPDGLf>h>YM91Fk2(kKC+6z;)=YIQ7=7;6v!iiFL_T5!!4luBeamP8k<&UMrHXyUZxMeS1o65fw1`!A{?F!aOT&8v6i z1Xv;l{-EP{f3EjZX{oqs!^Xz_oE&DR$Opi1DbjuD4F(S1Q7F_C%fhpWlw)L~LkTT0 zNfSsNCQ6Jmj{?u>Wt(KS%GHz<$v>Vm!9axCsF$3Afi&NK+!>Qu z2R-yNCF8fUGL%Xk;{ULLQ(oloATCoPUK zuq{Z|%?&?(-FCY^{l1lLaFj@piS|9}+eC11mhR2*h*A3|CikDmV~ujByhTa=oK2&k zRvQ)s1Z&)=zoz8^WcG}#)6N8aEH(3}VAXX*+(|;A^YI`sk$Ru$1ardX zr5W5^+g9IdBRy6A!=rkoLNPJ4oftwAd>vez4-z1Lhxu1X8Z#SmNu*(7GNpdL zvQqnkSLZqUaM7|Cjws3x-2l_RerDE0>AprA1eLteU%RwqKq{*Tfs=5z@+GDOG4eu5i#ok72pk^d%#V_IIZS!CcMd0B&oW zuVAf8-yJOE9LL&!eK*{Hman**tDSz6lO-?3JYR&AWCEZ~)e2B?ELhAm=dXZ_H4w-b zTtfS>8rcex$RaA!E{F{*Og15^T|rGPQ-@hUmTN&OE%QqXJPE^~+(;@g2&|wb`p;O& zf}{NfD(gr36n2ZEx03dIRm9eYDb~*fkB6AxKhEVKIPwK^Xb< zJ`-~SO!0r3(`3~5`3&7d_8r-J@A`^D#$3weeGLt{;?*zTsayEUw^<56k!ex`$-^a~ zhmw|*QVUc36cJDWmZodaXyL%+$U3N^L*Zlf-8txBJyBvDiKZ*FE7%aN-PzlqiRu0R zt5!`@evjV3s~wx0j(K?qahayW1h{K#Qf#$9Z6k%`BzqEKK+3jRG}P z7arUktwo1Rkkd$2CTfJ)2i%+SpL`GBF&}4?wU;hHTGpj?RaLIxK^W?vhQ~}H8(c!8 zOh~PL;}YWF|D`}jwDfRo4WZ?0u$_O+Qz`ZmA5v)!ZE2O@I#f_C^L)G%!||@u&3DhX zvbt<&=Nl8C^>%*Y$&!I-le5IOl8{uPGF0dv9u9ubjB;XWT(p)uWL&knc8`yn-VfEf z_6vMB3b~gJ%{(�=yreGS02JopDi)UQ)-#NbbVA9fKn$W890Uur;{gD26HKw1-yL zP3yJ_Du;$|FbWigYZw7pQs52~BT=L|mFUz^Qc|vaHtp5`dYdgl&mh`VkfnOmU(o`A zZS_)-XmO?6d^dXc4^Ss)R8bf|;TRKSW2AXFMAHj`%Z@qlcrFfV0CAW7Po+#vArZ@@ zL=7a9mG#Gc>13uQn-LjHxPXeMB{uXt{$&B@C?U3g*dapGK)SPWCIniNzhK66`mtt@ zX~uf^fX9%;qh5Ef6)ht6U;rv5AvBL`00+DaUYI{_6Z|^iX^6S{x3ZFL?SswFDi^wfMtXozXB}D^FM8}cw}3-UQ-`oJ$axw3JQ1Ki>SH1bDKHZx5}di6o=X3 zq_zg~2!JX7@$rLFyW}K5$YjlV#Sn~#Wy0;{r& zj(b?U@WM$^K(8j8MyMmk8?aP0<@0l`{VRmC>@$`MOR36iC{tRlg~xrgVCcvC*9g%~ z0@21^)*5ATl~34$L>MVw^3umRc!Z4W8RnDEty6M%%z|dA7H8F^D%u~3B0ahWyNz7V9=wxd#@xy&P^a0d~Q>;9!Fb`Qf@6JkrQ*ke3 z^+fJgUY>dVJts0mMqFN=WbW&7#*YJ)JkQ?>U516FQ*dx9cjK%*Ww}x3EGD4L)ub(nn)NWf}Q{Uw}b=nkd2FitpD9 zMRqF1`y+`7cd-&X{008ZBoR`Aq%dS)*a4m6t+NEG2rVXxRG;8K%a@(04tnD-^af^q z?1MyAh^Z%YH_T#C?lEEUT+z~_J$S!moP&qJ$%mb66H4#xTyk$>J&IJ%-OUd9?c-y=hmZw9ZR7?h!zvg>F(SkMuu?} z9dPnuUHv`I4ii>IWem9l_Qr6~It}H3x_GN(>*fS{k^Qq$FWbX7n*nRQsw&m&I}ua^ zPA(sVW95%_)9I29Eyu5{x6BD%L$CCBDp+^j>s$W*?#ETjpIrAz5$S)=-q2M?4O;(r>3MnNv8F00uk}-`5%_6+%>9p4}TepMkFTOaFiW zDL7sso=sN{c4S7%+VNQgx8%x9Woq+*06?HW$kMzz-tYsJXUj#T3gPzjf2ykN!S)O| zzlOPjD&xOvz=D=?qJ0dMZ%zI@|Kb)AtkB`*?Qt#(2Fp7UEgr|cjMM4r=<};7!Dmn z`1|1aK69>|Bn5dYjl$pEWZL>Nj~ohvm=&*j#mwr8&2EEe`es~Cd}|Z?t7s?%KL>yf z@;_m@ep|C9SU;F_?JoW}agCdLdP^EiP5%~!xQe%SZs&ZQNe{p@s-h&Rv*zE%#nwyh zqZELP7a8977;dgaZRVxVX?HzMit!lyN}}JY4fLA4-zP!-ddYcSi%ACHAus#-W=wGZ zIA8ge#(uGAiat()_NoX^xmi@Ykk_G|mb!jVO*9#Ewz61WRnvcx0>*=Wc} zKuKFd4N@0$8(DA@O%(=D?*U*vFQvDaZ`kjr|QccHa@T0gdb6aZ#EEjbI4X3qAuyr*%2ie=I(;2G{z=byLVB4hG?=r z3^~d0bsSxvNr(tyIFS%>n?4iye7+Wu$$x^;|EbPw#`vbjx)4rAcw6uH2?|0gHuxn1 zbtiLS)c9lkYI+^D1^W8wh-`nF#8YsUaG1Q_wI~%uW`0 zVl5=IjSHaw$ss4K_P>!Co^Gu1#OPuLiG_n=iLjW+tROo71AFIc5hm{$tt~z=c9#Nf zQ%6=TvL26@5!S;i6hn;@wl{O`sE|J+zXbaGcQB}k-qDEOA0a+>Uc+}@IH}ay)=!-s z#?>-D%hJP5%~R*gyj6gJqWytusbcu>msE$U0_Ur{#Y4~c<0;46gVd7+CBm=W>X)Or z@Vh!A*-6cNN2sYL#w2_Na@yI*`gj;!n1AK|lKX{4qGiX&RWVoQ=1Ig+%(I1TQ18#h zWlDs1EG2>h3#A`IO%0LG$oTE(nJTbg)Fl0L}d~#lOK9GHGceI`VvB3=*HOF8P zFO`wPazfQZ1wl8Gp;T*2pcT50l8y|s{8)0ZXvJ)-%00^YD)VBdY~wm=t@G27gu!)d z>{UkZkH}=9K@q%lkku4XNh)+u%_usBZoNT#WOfgaJW_tioH3Vh_6n^k2T;pX{`|eu zgpABdC^M3UY##}yMmuuww$8oW&4S2sv6obe*W{)_J2K_dQ~i1NHS~4!#|+`=^Vio7 z!)GF~`8I9?d$O>iihO0foQg=kVxE_5uZoIlqDffsl8bn8vCn7WByyq)@vVwmUvdYy z9PTMFFHMd?gM_3*&H#$Q3fj~#na|j8OQSN$Ari)wYm(0A6zvlRs46=CCN$ za_j`jLl06%4lwrI1u7cM@7c_o{F4-PE+(@N{H4W(JB4Yh)10s^aPgXx=-QKm9p(yrOq-u|1`W~~fsp3Y!eLmv1v z3MfA#!{Y}|+I*(5m(+-LF&frz{e<gu60*-VDYZk$#Aj**eRA!OUcGq?1#W%IQG_ zkj`A+lB+t%r&R_1nIk-|yv-0@*Yz=V;WDHVdG{w!d8b1+uT?G(-|u}Z1ow3jCQMGk zrohG>&eY<8Wy%5gr#UIy=R4ha69J~*X3ng;UW(m55xGmnYpxE`P!vEE3sGHkm?B{Y z$JrSSB{DLV^m>-++VR(QuAf=&I!1#e z+@FVr(FT64kH?5_($85zKOXUD&s%pu8WSO$U(cuKxzA+`oA{pFu!?EN1ADE4K-{V1{;Hkg~ z?vl|FYp4HM%~9N-Ye&H#@>=wVE=l=hihSC#!f;whjr4>oXP$!O?<(NA zla+wFOu^~^B9*cq>O}w)5gl6HFjNxAd|I$21XST$?TeXM?)}q50w~bo-UR@TqAG;H zevy`pqt22GDL*_Ir+Z}K#$zdiT{HXSEyM}&qWV5j8tvq| zgZ&PoRcFVRexX8?M_7@?I8qHVcD^|q8-!ZFQI2JHR#|u zQzx^SkAFQikXvx(Ke(R{Be{ttS`wv-`$(4RY&09A4@v>dW}JA;Tzq@=_}dNIxLMwh zSJqB19A-FCsYpZPY}&j01BwEN@X2*nld@v^>=xy00(HF}CMuob3t*k(it7D5hF-$Q zebA0RhQo&?_rUzQaZpr$4}0})H3lR;TmYL8A$1t$Xa9pk_pentc5QxZON_8LvWj54 zJrOXmC|CVMSB3iEG#fRDUxR*R*1v+;-Wq;vc6xrHA+eAa3m60_b@l@&Chwv5Rf%gu zl$0q+#;S;<4U*r)i^TstLP|!`#7UTvZ6=IriDX&7SUW$ztldI{LBQBxRG`BeT2z-O ziO=Mj5O)$Fp)N&dsSdDOKiu4)6P+R-s-vMSfUV1x*?M49j@1}8bQ~BNfh0SYU!kwE z;<-W|t>ra!aLQ7{P0#Q2IW1b~Z%ki5>v$eg5pZM96GIv`H-u%_EL|>0^A02Bsj>mh=V}<`@kDgN_=FT zD5~+^M3Z`Q#FEGmGEqwLvEBzBTA{Z{((!awD_sZ;g(S`wQgRL9LJ3I<_*vr~FD`@h zlzW;Q-m6a#Gsv*VFz%-rrlQ>(Vz=RlV=}7QcRxSN7M2Y9VSveI28KS0(Ts+Lf z+sL{(r;2~utQhiLT8T+kc5VZuUXqp%E6k6;R$dt~q3>Yx=k9A@fq`s=-SlSjkk;Ba z0yRZrrW0#PjvN$vvg8GSa}-p1L&Lrv6{&|VG{XPC7l6e^f`e!O*jV`W*ngzEr-{ya zqt_mvr%Qkg2FCwyu$kdmJhc{T5Xqf;KXW*+4=Um%awR{kG7WI!|H4DAO{+eLBEdod zC)CS0xFCRxHD2OmI!3WGOCBazTo)@M)W?R)(ng@!N0Hzx$rJ%zGrq9obV?m+|ZDSixgxA}uAu`+r zl9;rIBzKIaEyDn?l^#K(pSKZ2nz94hAWa6_fSITeu*UnarK+cUV_#^=BMp0*{Y8eI zJN0K8Ewrd*+oY=Ja<9ny$AEQlV=iR+3gWbLgDkWaaJTlo4=1cn;92cu$ICYOBBUiK z2FivknjBg5S*{Ro5pb@2Q3ts%-w>rt=pDoFjU*0Z*yR<%16LLT0gGkUDK^zH*9eh3 zg3?NXhBL>|&TTTUc;B)V_sovSd|Xr=z1{mq=ICwH@>~(-nGM}A9Dggu>Y(u*Gs18= ze_kI6FOcn0DN!CxaafllOQ-e$^K z0rgh?6Lntu;qe=nqO2v(%yjl4m1QE`zv&of0aF2oSq@=9S$+&F-&@;za@R{ZR#!I0 z!{hsv@k3qSM(?JJOVj4wUwVN+$5_VaEPHO;5$^$D+HWDq&52~LkygZl;n~`gd4Q)^ znxG-R@_zESh_Q&|6cCMbmPkNvKi92O)x>F=32B5s0#ZtfPoJyr_+gRx#200LVV@CL z0ws++^bmH~ZHOdrs#!m+b9)X7knCkMZaDp)0-h8FjTkOuEZRz8n^$@L@GOWEcOBY) zOPf{~GoGqE`)EJO6b-1!u8W{5l%wY*8M9Y%{n|hMFEe^8xMZd0=p!=2;5{T?t>)^|2YeWD`hg{A4qTfvN z#$VxhvS97E6lBJ(Zzt)=qgaco3S$wMxBT=n`#1B72-s}gm?)Nm^dyr3gBez42bBQw z-oC4k!4n9AUSt;w-E?h+DEy-P|88P>NBLE=RVTtwmGiD1H0TX8(}yD}dr^K4xTV@i zhzMJGdydpup)p|)r2adF5n`K)K4XaP&P9(bF zcK{i)6&ue#2SCDUYRw2OA%b|N4m0k?yeuex#57rehH4h-FbWxZ8k2MlO|+!}9?MGy zx+odR#oepJod9}jX`!{q_-Rvftn?Wy{K@rdR7MDF2-H-uVBeAonIJvuXy`rlgB{V( z#>@r|ULulb-Qs>yrPfg7p|%JK??JR>`f%mECx)kK(~|kYnFTRQ%|fIX#mAH~dW@ycj=$?A|7?Wlg}x8^1fROQtdKd*c7G;*5D#&* z18a>T{ZirsN)yO|8c>I^ak>_Z>gKK5&P|VgF&0&~9C&6KsheZ(0cU8VbrN=yvS>eQ zHnE)sInpB{M=jIthoeZSgK+pC4H6C=8et0SI;@C&{6NtDdJU*{>#nN|eR*P(Sx)fj zm6lOSrQ<@ldHUKaF7}s^0a0{oeGPQ4)FNvI{6cnZDnRpFV@@q-&PCtwse>-(PtTN* z+nw&T3K~WetN=i6lWvrEx5Zrt0sG$&ix9N%#eKKPAjmW#COD$=^^11w8qMGQ)5Ptb zq0(pm6K2v9XxWA&sTX5iPxB9kD=(eMOGv83D)9*ra-vd86|f5i4lIMy#Q)|$doB55 zUSH4b*b5;P)tKFU_Op@TYO{->!Sa@Vwvzvw6Oll$g%XtbTfkb`2Ad#%!CgK8}+b{M#65}o-bWK;-H8VQzYSLzvbF8amz2GSNnnFHZuA+khRmD0bJyoPvL??~F4Xd#V2eyl zX?TfymuF&o2C`fuHK0UNiE^cXK^sflAd>1E`mR1) zFri1%Uz{?^XkOiSx#G@qHnX}`y6!u&tidtZf1UNIQ*rba z`}rs^50vZcp-BYO?yr#;NWQp3msd@Gz~F zwtDJpI*3t>>9bvQ_nC+vjK6mKm4sFtsFq|ct;Ud|6#telamy0p3eFyovi(LRGv-FR ze$KYU+O0kn9n)_Q{$~MD9gra43sHRPk#M2qh?7lY)SZ{GIj?=xQXPF4A?6%s+V%lW zU0&*=y`+XrAcTnZETt7)0=feT0q7ryQ# zbTYuXGKucvikm0}-#a#-qDTa*`&5%Q@(9!$z{#Xdwe>pm7OdM`P4D3R#Al!8D`Mkv zFN-C<;agfWsawr|1%dXAz1OWxxDHP`{Ag1XAsj(HrO96TL zi+d)4S+Q}-qujR235CT>*s0fyE)|l$$Ky&(yoogNY9i7IY{LwIpXD*i=B*}GoE5%} zVHX0TV)gC29Hwk}F3618nbne(Lv0-YHX%N&W}UdRtdwaB5##+Er!y)74|-g3cS}{g zx{g_*EH=16Novw-DCkE~_HGW=Hmvsl@*rj@W;Vw8BzKhZ+7j;Ny#coJ{tU;M@fW%4 z5mb|*bt#E*dcY%KG*>>m3n&J_dOlsSvEtM@3_(q8&DCg*4!4Bv8e_H-?)(-R%%9sP zH&Q<-g9a#PmxKE`sPS=)g+n|WsFHx`la>Y`Cb{3;6Z$Mn7$h|mnTkj|iml(j+kL9{ zBzNXrmX2I)ZmZ#Mn@tUovTI9ny> zTA2k1{H^}P(Lxmik277cY(Iq#%vLUTdc9CBekq{ke#cB0g7WN-Y^N9i8d405ROH|_ zV8)1PZKaCF9g_p5JZ$e zn*RIj`$*u+j^E2;$A70d@RLb5N0iza?~z@PSzSAe>S+~j;dxzte@;V4d3Xi5Qa*xe zRM66t7Avg8>QZPX7)Flfxk;gMP{RKOuxBlmz6rrg(zx}=yytYimj&*U=dmz2zE8e{ zi~9Zv^bfo^I)5>t~ z&fBb9=)}8`<{v)R0SCaGsHBI ztp!SV%~p9DE6f=x-vmeP7M(Rg^GB_?hMFoBm_E{~5|LqtOE7esO}liIVrS5?@kLYM z?dD_P+g(EPgtGVfk3yEMSoL}ig86(pUD4*<0!T~(t{ z6&ISW`DWp4zM_MEJaWr3r{_SWa>JiF-3!!NA9QU?aGy2FiD^&8x=|1 zG-=*{sMmc0r6!j!!jLk!@F2!S=(nF)>7|jU0v<%a)u^`NU9^&Z2sECX{W`O`ee?nR zv(b81{n60p<>M9;7VDt9l&Ts{;BT8}!BfQdZ1;9_{_`Qcj863JK5#7l?A)2n`hw7< zkDTooH*peXF+oFx@s8Wi{j6XTy0D~LWQ-7623mMb8Pezs<Bi+moL9x={)VCt512(Y@I8PX_w6g zUY?@rcI;rH=*x_ll=w6WY8lAOJh^(DCnWCebm(KCymhN82E^#4=sNRjW@(X~K=>ZXP5lwPkNa7Q*Dnu3+=N)x3$ZF!RMrs|7HiB_?N!e z$#y*^;Tz^F9!GnTjsN~_WGQv__{Hb)7RI~*akATE{Fkg<+^b(GkQN(|3Q1itF ztoO{Y0M9K>KmL60ukJZgXf(b;A9tQYMSPCVlyUp55bk7DtS8P%@>2bEWie@ihAv0> zb5YRu3u|lSOvl1Qy3W_5>W*eZn48sgnk8-Vy3{yFd%W*KZS!{bPF}U^Bw*cNLvo&* zWOKl0-r{9uv|pOnq0>9v+&plvAqoEk`?!(Yf#jDs=3IsOuMk*cX==RHWyagC`nlA+ zqQ-ikcS&AZ*lEU+(e-Zl>knA#44XY%@13^?MqvSWt4{2f6@#y24x8KZ#+GU-#q5iN zi+vKk8yh97HnYF0zi2VM{9kVesal&)v_DuVkF7lu8xJpP)7-p_ho}w~6zLRR{bv3Y zo+i}pJVJ_3ZHd4r93k01-jjIhj=TJ-?hr2ts-SZjK#sW{OPHxm7OWB z^J3VjD1rx5hfW*^0}L}g8X|-2&uCi%3BOxa$)Q?MBi<2EYi;KATj%}FxYV@b*anO5 zI&BvIpn;6~o@tuROur}h++uaV&NYkbFIG+F+xA-MEAz+?J^h>~Xs0-1l@k*-BX;d> z%+4$=A)N2CeuG)DgTF;!#(A^{MJ;SOI!9+r)RZHdNJlRlGefK6&2MXyALOplga`3n z_z~NmI=MM}4i8WB7wu4s_^yRC2HWwahea-f!O011iJ#vc&f44h-#UUWi~~m>|7FgG zvs$$wSU7GmBYXaeU0$(VJ)IWz#!%I4=Rz0%00Pb5Xxc`_4QumaJ%5#$Mvci=t`jcY zFUbaJD}<8`I>a`XEF=xc76T)G{UkI}(v?GLo3;48PS185FFd?KK=WgWF)4x%HA4nV zm87m757^_Y$*N_Ks_z#mf0vo&YW~7|;9?cn_rgJwInhkSYUA`w0KK~%r(5**U=pXr z-rkL2Gr*Ka0vj;@9p9r=RV#DQYrT`6XK2@*OX@K5QREZY)&=C>@HRKiT4ECL4P-4| z9E(9jG@?)I=&xblORBFrxZ%cE^SzE8&SZi!d==Hk2}nf>5*rRZ zc@MZqq3+;T18j?=p3UOrRY;eU^IisO8Gp3*ggs9`CRxw#!zNr90AkKKvG)23E(lr( zM7e?ta~NTlG1_EO&cJ$lb?Eq83yLa7+-Co53UZP5ujY4YU+}P=-6jbM>|FFRrjm%$ zfu%nOd|WwB>ymHxDFV0sr>F<#gZ6{?z}f_7KFG@4G*_9H{8Ojb^(K>r1eT%O*O&C! zYs$1}?8LCKFnkhWLDM?B0wSXIu&`m@-G^1NktnDRTL+n|51E8j_{1H$;Ol>zPp!~| zO^pBN(Xsppwrp)?L0mt@;zLl}`M!utTE#Pdinumy@SEI)XBa8^v+5_0Z`Brs5JDe96M21UM@5^$4{A4IC*{ai$Ow~91xpYr zr7M*gD1Rjqhuh@n3!BrxG2mj-&h?i%% z%OiSSJXw6!7cL|rQ*N&R`MSBVKI_veLh0FGhG1ZfY%S~d?x;OXJ1&~0R51-CauZ?J z0S=7evly)YVOQW<2w6M-{$uvpRfK-9=isE~n6EibB10OOoUM^^3|Mf&(nXH49&;yQ zH#(@lzgu2eEhcYXTFGiL>-s$Nsg^JJ0?1VhIo@ zD(b9+OumwbyI}sb`m&?_^l^iYcX0O|tExYGa*SL`d200Psp-+v;(4(J{9}^0|G@4g zj);KJzI{7|5;Alc$*K&!%Z^}eg?Gu(ZfW5Beyq8$O{bej|Gw?UF%4h=AEl>kFPRfn zR?Yy8v(Y6mmIEDzheeU1E;TO}H$1b7j@a%pL>l40tnkD+nEuRh=n{#FJgkScCgPvk z_slbt=}G@XL)pq`2wu4Fh=0dphpRdhK6|rI%kg>-erIQ9VDc!TvfOEIc*-tl&w$(J z{U!(KOVg&|EB6yz+gOE6d0wJzEV(x~_@BcB`VAo_aa`pLrG16M;JJG-fA1F@?|6N)h%b)(|WOHeH2o(Oq#4c+HQOe1x|Ss7yGyu z<9E32IvI>i_pg-MT$NE7FMn@9+QrUl>+({-2M(WJyrbHl+WjBG>^p zvcl&4zo~-d|GfAAyB2SVloqb0u39Rt1uYD?s<}8_zk=&W8UwrBUYi+AjKoq~7+|NO z|MCf>3Ip)b(&iT)(Un@5We7lPwJvn(_7G!JG&I4Cu%ccC6xoN9xC%PgbC0coJI=K?PP|02N1&2gK%-xn%EU#n=#>th5L1{*y1sD zsZ{KJ?Ec?uK$KDMnqLOjigjmBBKVOh!5qrqBEq`IB%c(@5o}61ISsBdaNBCZtj%`T z(G!&+?Cztbv_2*d0C!eig(gv?C>ctmhwbH9=M!FivNNf(@mCje_r5+{?tSo(eB+Y_qBL);Ifn9Gn7GetWsMmn1hI; zmBf`Fj1|k`3+sX~B%M^*`1`i6Se)C=Sco-SS@*wi82hB1kxAjeLx)Ew>ns8q1}0ap z%Z#jc<@(aEHY{S|nlI<;9eUuR>4aWNq@JSb&bIbnH$JY$5bn>u&Y#r&mFJ1|YI^O} zWbB{khWCCGW8`IMT7d;rH!B^Vsc%t`wGy zo*L>hWZTda|EXska(}kketYNO$YqEec15o3(Ah`Jdbvl5J!9Q(wpO%AK0_RLiO0Ej z4PQw?$;dM`L%<+eVT@!!^#qB8%cUr&*;=+4#-y^z3x>u>jp zdao8=hqPlw6nR+3bST3GQc;XlBO})@81+Wcajm(>bG>^Wm(}AbfB+(q5DEB}f)cHnzJM!=k$&Wm+@BL*?vg1jlX%0EI8UbE@@Z|%BOa>;zMviHeVsxnXW#Bo> z;v-hs=SZPbg$ebE0NWv|_`fGOXYbeHFW0Y>Z}aaz?gOty-cN<`izr_G^F&4EA!1|O z|3s7n-`_6+zY>^jys(f^otHrUDAk=diTz47uqg{NJn-L$^vNJU00|fT3BuV{`;rzMJi-{EmA`C9H zg?VhDL!0?T@6=*R;vDSj2)9ao<3qh!d9$K|d%EeA8ECeGPA>Oh^3y4>Rum+iIKLP_ z!??TmKKf)Vdh__M$9dA94$X5cyBthca1?0%R8EoM!S;d&jj^wArM=*&I92;8>xSl; z3YCD98U-pLQ7SybZN%1dc(qMxgX#+n+aj*UDv9B?jC3ZARKOos!h{DbajL7K$E;TIcA7hU)NQIv$E_8C z(x+=pP#{h-msDq{Jt>+lEDr;guvxpZceI|>{yf1$OG}wcGV_%Q=kzr(FhFQ4K)bM| zO|iSN{2;B@CsO|9AB9>i4P7!4Ck&$Rk0gZCuHA*3=EeF19+62lrm{|I z@)VSj!gL)X1;vFwMi^2P@wdBb{Mrd+Yop8-%NxC#8-dvNJk~!HfVVU9Z#$A7AzWp0 zH6A&Yywow(bg{va6+=$I9ngb%@FgMr8=aD>__VwG?hIy2pL~@%AQgp<-q2S@IO+Jj zFg5z1Hk77>NcV@Qv$-Z6}o{9<@KH| z0ljAOsx|d_BRG_S!@=!uIbTSHXvKP&c&!bVcb^m@VCjH3;B#9ga z%<+by%3kiPhgp?nGvWO_%hx=PAm8c(%40`WQOIA#Ye*)Fr*2OUpen`jH!%ay5Q|_e zR?nBLZ=b=zNbA>b{>we$WlId^odu&^;Gx#ohF7}{=JnlyO*%+e^r_BLqk9JOV-a;A zLaOJ+uF)yc>E<{46&?8S;EKZk&5N>ol6Ylb_@aPJ%_&i=@H>hI&->BxlK)VKhHBFp zGC70-yRRq7F6?*W$Af#wI;t(N)t$SJEH2GR!A6_bMd|WQH_30_?=vvkDRqEMig1nuT-rEPA17a-@7GP74Wr78SiYl@+ z2CGOZ<^kK{Fl!p7<;fIi~1WK;yb!M)NKSphtRL~Jmw06pV z#fj0?HA2Mmi)pnYfn~-yIu_#T7cVP&IJ|lPZwv>mNz#T6+VU5|(&dw<;f~tcVgfuu z!Vp@4)Q19k1wjSO<i+P(Q8Xn$gHJj`TDeST9In|0@{HON^e{gqq0$9P}_1{ zsf$1@a!M?h{99~Xp9CmQC3IE#uKj-*CzritLy1gG1zrZ8Klib3c z3N`JWllXR@J1dOw%_%Xr<+s0AQ0T@_8^@$MJi7WVyr&imZ70zdZ)NxYg&z!`^r`of zOVD!u8QQ0+P%JkzlD3j(5fSb2qw-5Y00#IilU-4^7dQHi-D;Bj%02L-2WbN-PAFE* zPl{1|ROes6aV_|Nc!`Moy4yM4J8M9oB|rZaGYk@4aHF-L_yi`whNo0bqS8R=g>B^s zPjSs@Mz4euJFh-bVNv}fH^TUxyXZq-^4h7{` ziz;K!y%ZTVW}ld95Y;?2vkbDgVOIdgz0(#K|T%VREiP)@f0zi7pvsIVAv(a!~_9p z0scUJnG0_RYD)+tYobxf$lK9@mneoiGJ|p z{c-c*Atc=Y0`k4WgW(Ky*%40_EhN~&RG%)4wMdpwf=0?zmV~|!oO%3T$>Rr=1qX%E zJ`OG}T?s0X6m$DD)-#64Ua#njU|>MHYP0FKz0=J3v8*cA>hBr{97)Zo6#tG08Y*!#743=W5$j{`9iwq0mqKd*!qM^eL)?u(NjkVC%X^n!){&J_E$PrSN zOG1`nlATQlz{3b)B*f~AQ}c_2P0`T<5kpq|#rXt{SCfr?!4H zRnf}l8Uy&5&XQWy9>Mlw3I!Kv*qz{(!<4x9EQ-g}YGJ;Lm-|7I)v z7zJ@e0XW*z5bN(BxEDV8 zzx6U90RY!AWwyWm9;VhZ;i*>U9$ijzN$vuE3uWJHyV5#ziWd&ik7(=J(J_LKH??cH|}7 z4{Zzy^$`|b(U!~2QQvf#3W@Oq-r?_E>15&Jokc8ou0Ly{)WK5d=L=1T%V#-#5tWzx zTqab%1i5BOmw}7Sl5Q~wf0=2?MefCVH8;$fG?h{Z^Ve-9Y&nm46DGWMGvXm;t+f@4& zApd}LXm|?G!ePm@$(mB7pPp;sy5C^^KM$P- zx*roiJ?yadUdC(*QKX_mKoYc6mof^%xW-I1E%SxIFQ)#|_ct-!CV#AtigHPQzw7kk z%C|bkDpi8Z*7H?4DD|;e=(BUs(pjn7btp!WTre>aKAJ96@aWgCq7i{eLlS7xInF%z zMNi!VL?9gC%Sm)TZ?*g+)B`7XhDAYpFP?IIR4#tWKC)=lJk>7cKq5>e#31p*m|Mx@Q zdf-^y4!qg^dGmd4*jB1D7t)V(8XXQ{(ZBVgCA=tNs+5Wpin5$YTyWr2tZVj+RWW85 zuY;`nZ^Fhf`=s(8`z9O1%|gwoX-;vXhfmR1bz-z?a_*k1DQHvbdGkyZ7yAzzNn5B@ zD|Ezy+DoSzjJix=A0bHHRfENwC4%vhFx6!$So3qFz54oEL5He&(Y8szvg`vL4cT=2 z=waQy(AUOEQ>PK=Z}~bStGXjIC}TtdAF_@QQmy)+gT1RoCAh zO#b`*gi!fzf}gl-X)$1UK{_L@@}D19=8hlA6Aq!5dDh*0>|sT$1ZZpiD6NEgeNGd zNQ8U;|I7_Tvn*7B!~Puko2N6R3K>t>kw%3cujtxM#3yrxH)&X-YenRb%58K7zaCOg;jT< z_2LEAGoIY-8(4!fRwQ}K=_sW0Q#J0m{E-noDSWf+Wgj+_vc|(g&c5iP$MN}HQIfx0 zW=BrT4dHI8Q6NCC#)W}q9T z(Ev$nbKt!N?|S#;J0;^4XMe3urI3;%8P`Eq;`47DJRCA7VoLuRn+jjtozy)f!|0%D zhy;)#VJHFCw35os8!NZJ*80Xg~{@p$l>Og$sHJt7kt@XK(8(gm6jzL%eV;#GEi#Mc~^{$=b$y(p_hK_ zV-B`SOYYbwx!b$ZVubApU{zHb*;n`gp8xEk@Qtn7G>c4;W~S)Vb2){4{|p9Zn}nkq zbc~)dD?;TyZ=~zK6Do^5agvK>P;JWl9N&3tELW(^;S`ro`nyi_BAU-l2zzoM4)QRD zW4Qnl8JNnMpfnd9gq6cVrpA;m*i~wgawLhc*}9vtY|_Y?;6OGkS!OpS#XVrmduey) zn@mDxJrS;4Tw~nXtG|m)gg*)mBR*H#kT|V;L_1+}K$_KLxB}?MNcFwTP~Lc#$`a78XAhv$9PzypQw-`U*P}OqQ*ye4FgV4Mr$i5 zq4W8AP8`%Kxn#K-^O+rCb z3QamE`7geQ2e@2M9E2GJ-hf*XUO`+QL!>0!-VPZO5ubrxt~r zIoYKALqprk>+OAu>ZEfAPVU=k*TumJQoOW0q$w172tb2pyiU&*-G3}2zu21n^!3=# zvHe-3tHY9N;@s_FIqxBD5Jlo1d3VCY5r7uu_&vDDq)KTi@G?mGoZQWReRrX4(R+WL z+1`fQ7ei$Gl0M%1#snM_s#o>*NWjqnan{)y7h4LrL%Sa%(6!ys^-df3o~2*!fx9>b z3u`e1r{5Ymzg(EVJy?VFI+TtVgg3fW3(TaXW;t_TS4A)Xp73LoQP%2%hPm{X8U4uL zQ1VFNvm@vh10Ll!R@VROt&0s)?fGF(TFDTAWwZM}cgjpx>0tXB8VL!P5~oM3;4N;p zDAieSMd2RK{n^O6tgkd@;3@IV$WcokHfFwt?8~g>0pEejIO|;rHxYed(w@7cOuei8UH)N_t*Eg zP$NC*Umnc?9U+F$0$g6}1$lq~-J<-I;CoO9jma7Y*15a2u|u8ur}4^*t@j77x7$3j z3lkyJr;RTy_s93menk@VHxYw=>AmmC$}lirfPs14df^E{O8uv8&ems)2N*T;WYx)S zXWd~V;GRkUd&=X^=Jm}E#$(wtV?bek3+UvO3R)PzJN?~gV5NC{^<70m4v&qTL-Z{PC5X?7BNVe2nUc>=0k$a2QMCxH7@n*RigbQFbGj@Re#W z?`P>OY4O3H@O~7L*T0l`8-W8RSaq#l#IKgowy>*}W2I&~HwWf@x67~2F-Tf1HX(dz zv`nn}*wY;@MC^I#<&?nf=z1%c*vd^!AVeqlB$H9d=w96k7Eg2`C#sJHvC-6i+lyavrvyvf|3*#Gs9_{Vq`iE-Y?x^^|N72jB!}7FaMhw|ON~oY14*MnuH{IL z^&kH=RO?T*eNCHc*{rU!LvA4tPlXK*-k_gQfM*}L^;@lG84L$!3t%J;`kjbx*wfil zv_F_ls^hH{t944Ws+1^KqEMoe55O(ZE8AGh-zZmSVUjHjswKk2Q1-t1_hFy@S;&3W zU>Tafx-4IfV`Ip`BHuDpTq?*1V;#pId{K{DXBQmDF0`bgcS}uXU7vM(nq{hHhDUCo z`vHvur0DV?Bn3{GVVRbo?^dIq7Dh9drGE>CDMSghgt}TP05s4SGa{na6LwPHh%>y~ z>7>ib5Mf3u#PXXhZnvV9qa~)gsp2P=kt-{n4={ z^IrSgm)!H~RuUUS*=h!k+QPyEyiA9}XrxMh)Ox(vVKhD3tV|2DR=V$I-;(Ui^*+>| zsxfF+%pGf>(BT6sbotEr`Ts8W4xZ#dW5$r%ls=3$vUB6=vZy-S%V~uLa+tvQAepR4 z$3%FW`7$v1FmljU0Kym4xubGcRlY1>VJOaR3$Xh@stjV*=S%$tT}`*mP^%D|USRJk zCdX!_Q<#Y7BO3!ZYVwR|LK~1hI4L8dny-R)=2QBqXxsc^V?BT94flK613Q8ZzNpr6 z#)wH0Sgc8e$hF8-)2OTqSZMbEI7_1iZlwkr1N+l9nLVTRr7OOVPEHI~fuqj*rqYwz|9rVlAhdPYLpheP-uyXQVb zXYpX|6~627l=P>jLR1EJ?;5@k2OdsvD`jM~xZ6(Im-*ryz-6|)1Zk@k zud`O+TKMI$+{c(&K99U)HuCm}C0RY3BdD)If+VS`qJgr?Lb+I}VTayWvU{4qf;^8V zuu95pSiyqo*(1Z8Lr*p57nm*wK4-YhLR6vMkN|{)5{7&9HjD9 zI&la$9^I~lm~}XKPSI2JO;NXj0x% zbBs%Ha?M#tU;}kf5!eC-c0!P%pXhRYqqWvcAeD9_MrgCH4B8_AWOO&f=T3PfMx3D@ zbN&pDbWpkHK%r)lVIu>8CRD3%V~PQv#a{A5(qd=3ZJP6uzP$r8PyvP6u$JI9(IeiQ z5Q|=3i#c)_GU85#EycJQt|Nd#|Imvs^wqO(x>mfNF*!2AncJ$CH4W)IEGFDqO%CrF zhF{H$bTS zi_fZhAQ>vlx=fFMv>5G~r*#L>rlO%ric`^j){;_{%`By`$!`YOvaD$1g=TzbdGy}- z5F+-iL^Q;?c0Sc`%Tk_}qY6~R8UQp9w!)F*VdMQdyU{-R z<0|j*Vi_fFRi9*Y*{m&nN?7FYaIf&hBPn;8bdf=RKC_(z9&Qz0gKeY|JLIZN_}?}{ z&T*Ul0uWf7jioYjtXKS{Nl`5kmrzq%tnx3OygeYM-62Y;Tt}xgD!V^)BZ+SW<=vP# zBQ*OvO?S{)bXl>kSS?YVDo};hvRv;+Y?xfhzrO^?qSsfLFpa?n?cd9OqNs&`?ciH? zL@y|DV)O0%<*Gyf#d5T7;T>742j*i?53i!&_lT-iT*)HVxR1LCvmznO;dGiGDnzPt zOxqF?|H)JC)ws-Xu#~3UGD%siX?Wq6(fs(}O;Dxj{A_8Dq6?UPP2FYws((adbXBa4z)5D%t3^=IJD*3dN z{^R3j$vLe)o^OLfiKWS%aA9}QrAg%G${*YHz3MJTRdNM_xU?z+KN2ta0#Sih+1nWB8iNsr2e=#*7XNTu6Xi^brX^^itpZJ2&@)Xbz#InU zZ9{fwrQCwfZ=6I2iYvT<-*s0YR$LaH*_`}DGx!{r2SMG->6gGll7T*ngxUocUvm{P zCN-eOQaK;NM#3)S&!c;f8Bf{fx$BA{wj;q%=J!&YUsC9Y&DQs7xsE1YTVYb4 zDmm!xK@_ZVS0#W-Yov)veR=45;!%uYN^=3Zi-1?Co{%X zb%)l~cbEnoq2~IeqX}AcWqrsC40>*(1YBVrX?Gv}gc~5`7}wBfa+O|Q~uv!HfosWF*1{_TBRn+aeaUThQ8s5?FR@n(u8d*`Kk?!!|KJ4 zNZ$j3=;{_KbdISZn|~=LIHa-@5)!4bOffN^uvDoEQse==di9M>%e8+JbYVxDdhZw?j#g+PcqR*{C-jKkpOuw z!jN-+*}#pGXEU+)n}q$z#^$Su&8tx_C$l9450IoEDOFG&8_f9T)Tf8Ud8HfcccZM# zMak6*h@K`vn#Iz zd%`x*3@Q$eYQI|MjH;i;IAp1l=Ck|Fx`*Tw-SOLW3XN*n=gyxAjO&ymQ82vDA|9Z! z8^+YdYYZt@H%N!k|6c77ej3Q0NL-t+boJraadL2c3clIhGVqUg?ylTSML{d=+eokQ z8Y+r^8!B=fkXqe7Q_701Ts2^n8tb*nzS$%B`6-G9lWJJE*ZDUxOXjJAUJ<9z9#C55 zMj^+W&k9>NrBQ(Em+|g`XHMqx2cg9J4kym)w zzCO-QrQ*85-W}EipPjZn;VY7qpA-_q!R9khwX#4*1-s??ethvPrOL{5Hsvs}bAMe@ScA zFJ7~)SwEx-j&bKP^L9+MfSV~$R%@24`x=r1Q>$RFc}}9=A?<>Vv@!9P!LN9yhZE)w z1?r?nLaRxUtsM-}o$f-3*FA*$GlTu3287*2id!O57EYKj9mWGfWo6;Sk3|{8Y#K z|D)+GquT1aaP6nKySr8-CY9&Ee@qPe0k6L&K~*2 z$jAsQd#yd?p4T0=fUn-E^0Hjt;R8i;g8+1RXcF`RhwNW_K*qJ+j?t!jc#?3s6aAG- z4gztj3ibeV1hF%hqV6U+`+GElKLQb4X$m%QR@iQSqicN<)YOmBH(0e>CNGDHiQqqw zOR0kLXomhzbtqOby2}kJpE*JQR@`C&(f2n^>NeV8qkj*hWwKhTc?Za0aURp*G-}!< zvQj^oa-6M2+18ygEHW6Pe~;W-;VH>@m;wwK^YXp?o>-~HgzSxe$((L?z3g2O8IWPw zku>hmkZSBfo3+4)oNTwThBAlQV&t;DJg) z)>kk1R1%xew6v`LjkXS-Baut9dTo9JyZHzwLB+x7Mf(m@3tLjKqWjPh+chz=J+1;m z4{wH6zqI;KUCK3}hZ-raEJAhkZ(^Io7iFXH(Jx*l(W-DpKo1yjD@hYaR_Vs`1%jfT zv|2bvj%wARbUsXEu>D5)uF`BHeBt@;Oh)3Nc>=mk3Ty6m<`T9#bC#b~R{(KG9_%Xs zvcvs9SyuFrkg@$==0?OwK$Vc5zI@;9gA1R8&L#$wW$T=S>3)DYo*%lM*Q{!;(CZBc z4~-o#n@60Qw#zm)`y)G%yDOp`1Hwe|Zw;kX1GNLwGR`YF9wm9$ZZdn$IChl9<0AcH z&(J@(7MS@7^1#@u3imRUyt@nk_A;Un*t%jJ=rg_sTScD_rzWU^ys%D==bcEOEKZrk z1hfJ$I$DO5+q-J%RXyO-B|o&hZTe@cjV3`X1DX2fVL>7AVR0n*{c^P@Ah*rUMbnpW z-!XC&!C6~cHfLwb4xpq-fj-fw`92V-h-9RSgE;w`tk}f5ie)=83;?;CWtLPHN0X$; zM)MuSf&Jtum>;y1>BvdIN@L3nx~K~qVByf6vKfH8|(0Hlk_yl|HjG81fa&(1`nEJ*(s1xRs zBl*dlh}iKAR7pfo=03)Qa@`F~8%u=-;|_T{yxI#s!^F5;|0(g$=D`gq<8B<&RnS^G zS&1U9lOvkyn8hvjJjw7lFf{_`E2#SR^U7ID_;|Fhi8X0rlLx7Jg+#!TnJ9~BqHgEf zTrawqDQ7A$=ht7ZO2d2*UEIvxHALwCs^Zt$jKcGoqCsy-WyGe6a9?Y z(|2qpchS||%tWN?nD?g`f|=Ik*cBZ}l5-sakYwbWvIc)>Z#&Gpu#Co$mcp>~rbSEW zASd!gbfUV9l&23$1pD$@7)G5|Efl=R=-z9Q5gN%qe(2|atqeEgux5ahRw){Q8JPxo5{wSCXLUW+=H9)40Gy`UDBRyLPJWPF+vk-+DUAKi*+R$53A81AoUE1hQ1MTJ&)7q(ZOf>xt47v}70MP_`9&55*@Wct z<$I)SK|7C0D51crXj~=fcu;lvgmT?Wft`(G-3{gA2PrlbTgBI`N57BtlC~+X^PG!6 zma7Q>lxlbn9*QJG;W4rRMw_>9L%PM8wyTWz;!~%21WM)#96F5vCX66`c5J;Ck2oy5 zQn@a(LzgU`{KPCZ;u--L?Um8&>iOhRlUZ@fG&UstpR%>agR>wv#mcyt0oK=nATf%X zLnebi2SDFfUnGd6?7s~hR!`BU~%ox61UCw!oi1N zSmg!<*2fI6o7g4 z3S7|Z=k8Xiz2h}Ugz4>OkVxUORhQ>f@nOb$iv$etBRrMqe7^)HlvAaeG{3-`rD*CD z0wxq0;2(33g?d{^oe#FxqUSXG7YNBba(D+`Y?2SQ-}z`0toIn0l)S!+rPQS#LBkoQ zyasyH*M%lX+hkLdhf$SMlfkHtcxi(`54JQk;Thn_AgAl>=KAisU11mlT^=Usv;l~N z&VIV!$ zc-`XmNx%e?k|UZ_78ex_TxIR#On5KEfJOB1U4sNY6=B|Q%t_exhiz8Q$9n^YUrE$s z?ea0&L2*?~rR+ShH6;!-Fny~3%WgI%1c(^@2c)5|;=1rUg`c!Xqf|{#=ES3)( zs4=0WrKmVnJF70R+``(-A#b?MQgJ8BK}#BBN8{`;gmyROT4yS3eHo)5LJd4l$`Z7} zFjAnGN5CH*_)sB^UAtIjskgeiePA3gs+EH?IUH|C#cwje!&nCByET|R^3rEd`iLG~ z8qKY&i1%Hy*IGO}d6j%YQp}puA7qvPb>Jgx{CKIPVGexv-gFNZ&!8~KIfTYN`n+DK zoZ)t)DJhp!b()wt{8iNuoPD*;fapp(e9P8IkitYFnf%LFRmG@m3S#hz3F^W1y$=HB zVpAz;6ZmRbF&$vzpvsyjo!T89Uih5l-4@g$cCCoSI77+On}PkW&AnRLT1>1Sc~bhx zI;2?gxb#gRK)nE^Ds7c%SR=!Xb}9|iwDP=m>Z!0lw`EI%X1jNOY9eQY8TQPglC4q- zLz$yufxQhQ3CZzi;+d_3=~s^Fn{b+LJD;Edms+XSd3M$%Zzb;D!?QD_gXR-b&f3KN z>Yxfl+g2-|))^r;t9_=6qA*K72XykTt|15K+@5PtztH1{&H;2?Lk1 za%FKWMfPxbiu$gPM<={IJo$_O_uq}!4P&Y7^8G{C=)_@HDupj@8Ma^QiEQt-ACvJOO_eMg_Rsk%--$Sn-;dt;b8lOz1VOp%nX z#LMQ$$`9&i?tSEX8F;@7s8dF+ea^dPhErLY1<4W$Ba(gf%J1U}>C4qOn{5Ce&cwkP zX)@qmTPYDR5y(ZR3ik!}i(wdzDk~i)5o_V;%BKzjGEqJ3cKM9|M!Blq1_-raVpq3} zEpNDft&CiB>Ewu#94CC8`{BtH3!ue3lwA>2t?(j}l1+68uV%d+%Q~(6cky4PPx@7ILq){i|R=Y4G4CKCSf2 z8J!eA|EPg!zL}?YKAmX5nS|dUx!XnKTEi8dAqy%S6Dk_hpU^m{iU6ftQ?-l;bngLl zbj032%z1hb*-I!C-}^knXmV$W@r03Mus;;~xF1>_lZb}D{}QXG4O0bY5=ni;D<5>l zUvaXq7fgoD!SdO?|A9L_j>nuCY(eO6^f0Ba-vY0FUO3^q7ROg>cDPgc+eKT;LT8?s zt(s%XkAHTSGvp)(V7H~uCS<54{0S-HM(Bh}H6=kVxz9E>8B|Kfvf|J)X~ww$m z;oQ8AE)OG{)aBn}%;&#>*fV_GIYGu@Sk67Xq25yNUPA}vzZ1MLRt9i66Yb|u?np6m z9-6*c3EPSMvT^EMJ;{62lZ`~ph?F1qOrLei^b@Bvb7-$+vJ$c?6}JP>hmH|uX0jSr zr8o(w?OGaf1g;!SeR@-|d*t0CMz=ePqG%V|WJ z%xD}qVAW}r9l(by-V7-JOECJ)ALFNR*~Tf*A;&L#5GI9tjD2LYa|C2@5KU%$&>9(; zQv(&JnO}HOQF%2&4xAQCb`4Q21$=Z8g4s82Pi_!I7P5;#=k}fT^|tK?EnD?p?N(odrmqhe zO$Qod#i@F3y|x3bGZX5PZ2R4xX_MXs_FYrItx+; zS*u}B32PCP#tUPRG3?Q5*&2%imoS1W8g0w1P})+{%{S03A+7+O8FQ+?m~dwJS>y<(y4k=OSj@35D( z;NFr{@p!yg_wLKd<-G&pOel8!>R-6jP_0&&dIVu2s<^dP6IvkmO&KKev} z$VO|v>FyOg*tbw277#qRI~0F9D%)#sI4^`zR594MQjTZnVtu)rM0L)MgtCrz)>02y_#k={bcSgt`Qwi)YBvA_i)9D z-TLfJ3D290JHzSsc8z=VT^$g(ERef8Sa!>rHi2FTrd3%g>v?8M+V&gF^<5!(5@Ak*boobGSSaD=FR0HdjVkJ&n#Kfyd{3nFVxfcmXwB-%QSiZQ9shYrOb1Wvo8 zq~@x$)*G_M@mmR zgbod6kYkepMjk=aiH9Y90;#OYvxh+z0t<2mQVLTdAwuAmL z+OQGhRO{X5uino=PaM?fI63mHQdwl$b|9nQY^pIlloJATnCLR!>jM1pKlI$;mKJDq z6G(<$+e^D%R|hC|9F&lWy^<)a|q6+)qPM=bKRp~6RE*Ka~?@*id6ZP=iX z9FQn2NU}fCGhE9|O{u_5izD@@q{oD}l)|k?Ia;y`B2rYg|LtHOmCzdVNu88h9C|Xs z<>$d;tGymAk6yoKHQU(G0-`h4{bO0dOhHNQ;S)SQH-{UA{Cw8yHysy7kEJnUTFVe& zXJsPdzsA*(MKz)!* zf;x6_dGipPAm7~c1S(epn!hV14CVi#Uq0x8%0P^Am8GbKa~GWIPeXoj$}#WYd4}(8s`qK8EVyq|o66Q};r5 zf^*0FLRc4T6&R9Y1_+z{m8-s7tx(@I*wW;1s&`oZH2sO9^YpmFKCDZXlI1{{2DP|f zHo8Sfq}S>T*PEqR^@`0b-tUY!`A4$l)j)2xUaNyObA(_y$$)S}F?Bvm=Gy3c$!QW) z7!19gnPpoU^ij?E6=!`wVDuYCOXkvp_&t=dW4h>T{yjH5B|ZN93ZBHf21Uie&*GgFw!G0cT3Sz41aVa|cOo{`*~F^w1E%XLRt z=o07Ie0NU|Gk0moWR@?(fC(`=G3m%LqTM4W|cIcx2(N9H|Rw+C^lBJV?Q<)+z88cg?XU_WHX*oASX&wJk78b7oq z?6S?FjjUOma^>Rttp9C3!R=1!tA{F)VmDZ>X`^_}(Lxk%N_X|OYZGWDvL!HMp2uU( zDBF~$ot34I+$L^e?V4~Goc0;Y?kOW7XJJg)8IY7R#rWF&(FxTb#GSc>6nXg1(aq&& zQ;R&ru%w=@#8%p|)zM|sGL4BtK^y$Rk*slCr%|(*oGF8r7Tbsks9ibJUk}3aA%Ewg zW#bEPA0T4SuvF6g+AQGv4Jnd7#X}a)VUW#Acp|w(CE%3PK`ke-EE+D=Pyx)|&s_`) zND@3%m-^>C8~JGUL+6G~#JI`%OlBVU#hAG0LOZ?_2-NP1oH~ov@Ka3J9hwd^1-Hpm zZ-ICHvmgSJ;mY6*r!NkEoS5l4k?3&gX|}@bK?!|5W~~>SmcEN+2U&(()W3a*-4=IT zXDYt<_4i#9rup@;0p@g-Qakxpd^);(qq=g<)(d_E==7BoNz%h%4{~4f4VT>54+dG!5L z5$jzG+DJ$cOALTFm74|&zF#%ScC*b6MRj7xx#ijg|0vxkVsY_B_lJ4ATqlF^rn|@2 zK0Y2+*|c-B%&RN2g7+ut$EXlv8md>(?YH~)nD$t)#XU#-xVac9D@6@ywSSi+x>UP5Sf}8sxY|u+j)@B!UI>D=ck1Z_Tu?KFr z_6eE(SNiFy-bXxVy81@>$8asc^M;R6NxM<3dT*vY5}dnKSA1>(W85(|#7ouzuTI*= z;EZf+lvMNV7#!7$`MhN;w!ccaZ1m$X4Obv-9<9UL+5YK7eqOahqndi5%py6o671a$4qW81Y}JT5IhlGF zk>&@#NjkL%z0&liRWnq$IlR#p_fcmg){aU`5v8D$lC7V{a=e9^cPP&5fq|2e*8f zW?gqXKT-h`qsnrX7~#-8A*{Nfu8Ai-b~inmi9Cj$DH#0CX=Eaa&>=F$V*^=cMZz@= z;5jZvtM2JpsoD10QuD`9r?*F5PC2K{##ZlCPVnzW4knUx<`VxT8k!zqPBSIC%I2Zs zXewQT(n4NyG7Coh22NMzk>47X9ua}Ra?attZ8-qk+Z_qBtVB3;#Z0WPz%v+4tr^GF z{KMO0`bCtbGv+fIfR?)jZ#qyzz|I2X1|U!HIAo!#OTHvmP@7Hem88~qj#raS?N>%g;ACK_Fa+Ps0 zMy2ZRB0T6nveowK+9>+2pw9%cc<{6Umz5z8fQya{p;3BMnx2>WO7&OONJp6d%|@ww znduA0#84~X%%uK$CCLUgTm+q^8UIT2?}@{bN}EpPUyw0jnLD;E?Avlp17N6tEIr2mJD7R{!EKQJ@NFDW4 z!M020=h&C*e3S!?xc#yukmQNG98EW92(FrfAZ2%J*b3F``_By>om+zm*HCXN+(~BD zdge)K%APq}A+q^XBfnjy-E}hO?X1%S#0mxGcSPKD5iC#O- zpwD1TCNrs~j-jj1h0EZwhLzPbLB~L)f|yC3SQaJ~cGh)i_820a8@Z3X9cF&rJi09s z7?u_&$RqFgy=sC$0RGC2d+*~Fm)pR-$mKcYtJ;fQ?mxjL^F?pIg<*knw``nhmJ-s1 zA^wTSMl`7ougob?QL#;DJ*8#P4?6m|m17cAA5tFSj8O(!6fXu&u(h=aW_P_v!p6fN zCK96l790p)L)#_O$V;oWQ9`d{M^?r&W!*;GqZ9rX-}SFsG-(+@4)0s?C+92}XU$RY z!PsP3{{LwK##6i=|IB#f?+V~@2EHz?u!Sw-L`w=!=_m*S@`l^euUGmA_|A|LmWd_U ztWh!$;uwz>@~nbBx_Ko9VEd5z%M*UBQies#7%n-9dw;IzrL$89Njokq_{EJsbqTM( zJpFY1O`Lm&Ov2Rv@7LF9(F=o+e`d27gRT*eb`v9Qy$6Z);9^pJ!tKAVWF;pgKJYW2 zcUpR%xHnwqUpg-xf3LgW6vr{5?4;M%U z7or!>cquRpAtXEGXkGj^&8>a<@AP)n&UH!m!nrQ<%~JS9Ag%NMbm2MAAtwoI;X<4f zHKqk5;w^z`sNh<_4)2XBh!3a#0ZM`YF&)k5+voLFOze^S+4?j#%>_R_G1_|G^zqD> zJZ&|j?JBeb#)CF3uO|un^i;7am@i=GZy(ce$D)bQy@fwVNSzCVmlz~ik$;bb4Vi`u z*}_b9Zf#jm<&^b7gY$#UfN)!jKdFtn4qWK{$5=j1DsIig4(`K~tvDhMh1DvzUp=}W zbq@>KV$ut%0ti9nvTT&E>}Fs1>*-r)wPAO&6CL_EpM^iK<*&);JEESg|G~V~O3?}% zUIezLTrVJ77B75zJ2&56k9-@Nl1msr-kZ{m&FX89`4VD$64cVk`&MKkT%|y#U!uy&;{Yaej_j!; zKxnd_Ls}itWQ9tGYi5Dgf#i$(aC9W6OU?kMh#+e)3I3--Zbt%B5)KNT-gFrbO}XDw z2jL5jF`iFZF~g0>i}@wFJHHJ_2VaJ6O=BMIhM%;LWmly6GyR(ou3$Jh3(Z|{ zCNd_k7PWGnEr*f>nvC?ZM*x!jWeHS`I5S|<5*7?Y&O=pul?)kVl}$9s#hJB2jQ_hn z%G!EroLV^%TTZh-*W)`SIF1Bbsbti)<*QVIhcjIBp>7{s(HWgt*v?709RrA!vdL^Pk_ z&v+iRkTm&$VtX5c2$?!(!#kb30L>vU=4$fc%p;0?b5F{Oa7V=s3NMeq>71ik+)zuM zYOC208t;W+%58hmran?HNWsc#&9CCHI@ki!p{b-Ea{BtT8bP)#D%cy$ea|Oz z46vsV=B(Sjl1AnSdt#JI*{AO_CtdL^b%k-OYEoaJtEIjnX?@E?q9$g>t=C_bJBfgD z?o$sB!Z4zB9X)0`at)I~9z}kmggZA!Sn$HftEZKjAC*5oW%Kj%*E1>0EFkEYs#HKr z{awFeg^&o?evSUeM4nXC-1)HORksJ%R8#haW2A3UX53+nEn4v}=k!yw@0(rJ&0ccT zfkdIH88?-`sq1Ppnw-kQH6=MmoMK593x}2uIi$(GCDo;a#<0eaiSel+#@f+vEL9Od ztJ9pE4uW6KmZS*U4=;}pU$@8-p2cxck|rxJ>v%E#Qhym{XBa&#K;B=v<}xQHa_C6~ zEQ~nLXy=z@kTWj|2+DEJJ-hh)bJ@eOs~+0wHN~C;4%=N=>yBG-f>Ker3lwflWY_DUS9kZ{=@BJfVWdk`7djou+mUt#$gQ<=+DsM444F>^4c zvfZ4uoLNs%YxVLtJ2{yv@mX4vg=R2o8JBB4jA(Hir_-!&ShWEyUMkjDY!^qv>Hw$<5>OF2Q|6V~F-?;U(|UJ^2zF zwV@V-IC8AzAU;4uyn*V7h}EL}>K=Kjwev3u%q{OL1z-PJWBa4?kO_z_V)?vg=a0o; zii)bB8~Cp>5=pzQ4s~6duz@s_QDu&6uUP(&qOUeag{)te7GFAMDZ?eLpjuIHTcIVo zEVbhwDhJ!ymVj!4ZiGc_8l%plytPC=@3h!&K2f!8Z=!F{e9Q*vDBl_=#b)|iRaMXL zGHYrdypqVaQlVXqLcq=IHS#NitHu>l_|@b01kPj7mkyZEC_Z zgO9<%Ji%Z*G1BaUVU#M14u%2tDW{{C#lzheTmu}`@$1*hwsaXpSf*sjIDeHw7c~|y z6Tl}V{e6U3pYcUPPHsc0F#f@_t1c}De&XxV4))}z>5WvX%s%cPB;>qUQPx>{0sZ)t z3%h3}UA@T%PG-#@@YdmLHH#Jv1 z=w_tYA}R~cs-n|YC6iOeOiF`^GffL2-0TSFTO7+iD~{=;Y}IA_=xP=@C2V5MRiWnf zu7Wv$cy@3dYx6xcsZ>L%<=uv}mLq<^ODcnto2MUkf-CvUgAAy809kAb}P z6pZ-f^nWjj(&_vEeWOP@<&s#CHW5K&;^CuVYuK#_b13XP!me(sMXHn>*u_;uFiN4i zHSC5)7EBCjnXAP7KYz~2p^p7Ozh31dTuxo731=cFH{p&UicEb%GBtX+rZQc*ta5~O zbzMrGfxob13;ONKG6eQ@2;w8e>* ze}{opo;18ID>QEotp5E|*dl^kXr2i+r>g$13i$YU4crSicCY*$Fxmv-Q;SZes6@q> z=(`hhDK?Pflr(G41S!j`Bp6g+Ln1VubCVfh;XM5p^aW23apaA~-m(JqsnfA@apMe- zc3*{8tGU7A%bjL`>@PG%twtIRx;+MZWpn~GRu#~qW@OmW^TV&Wave!N*fxa+0a)U~ zg_OtA|63S#dm-qdMAMZ@8Dh|q#R-QgFj9|f=6~Z5wc;4=Eu-k5=_xblZNXLSLj5@l z=(+Exg(=jObjk3h>N=>Bgu9GWb2!enkv0NMFmeT?6_Z&V8|YBzLi-0jb05^GAUuf9HL;?=obb}ZMp@LLNzUj#9e`11~ZXMbW(jehefYk_Q(WXbGhZNs*gDO)eMEq!@?fpHA)LZ-LT=%n0u;fUzeXqhMUQrWO$$e_-5q0D_ilVT_Txn67Y+aF~vxhPyFC!hd%gz8^~)7 z?|V=DQpG>`#l_g}!&rE37_->xesU7A+LQ10e!@tSpY>Gjeon71yv-7loZgV}!rXiO zaCRyqtZ}KX(e8H*y!_=mIlor!Z&1?m)Sei@^`^>PPv*Yy>AWeqf!erCO0VEs6_4K+ ztn&({pjrau43>|MUzZf#+$r=@lFcL!9;0R+uH2Pc-@Gm)yJt-9mr2{}f6;2N4&83`V_LJJp8V0>GR*onnBo9O;qyLj(S2WNe5){l!(%C#0HmHnvoyH=k zj2afy`&I|rLbyMO5O~m0?G56S?)|UN;2g5|<6v1AUTHb;D1G@yO&W(QT_5iJF4?Nx4iy5SG|TKw9{NZ?B@ z>R%&e1280BxL|^Xt?IJs-xk#SIo%HB&1*l{2H_S=E@vT1~Af!FI^(A$aRyW7iCn_!@y)=tu! z0$`>1+V&0wc6tSy!n(e=V`rh&O)&K2A;1%TN)edKoA{5?yWBDk*HvL;v1OxoY!n7u zh6!L&wSzbn&L(F0ycgtGISY<<4ebtGAAqyov$@Sk*sv0Hs{r!f91&^O&;gjm+q-k{ z9SjWg289xt&9rYJY8aVGK+jH|Uozh>eP7;gQj=!j8sGoAJsjkJFgJN&`Ffc{%bi0n zk4;s&fhc(7^%p&<+TC445O@96qW?xt&w5S>D< zui>rdco=VDsl8ZlY)2Q<+MW5yc^vHQR@YU}RzRr!#@#lXE4sPmym!p{l?oVV-N)(oJ5Lqoz@W6n1c3DU+WSACauvLVM%~MI``1U6zh>#Vw>Tj`PE>Uqr_;_uPUp5Vx)B|Q3x7zI z5h$mZRSU;W=uFqUF8+vHj=ZU6?#G^-sJ-s}EvAiDj+S}=dVEAZy5&4H#-2Oah++!9 zRnoMTC*o=smOSX@jzO2Qt}Z)$(L8$i>AyB23|+vV=Fil;r9A7Cx$wF0 zssOo*+VevRvE8)svXKWTRMgculWS?^DrSmwKlK{HA{@rW$WdZgoVdI5PmuJYrw^*6 z?z~!J?MySRdCxz=zq{UITE8^jIE`36S!W``^9j1zTd+;KmiQ+hg^|B?z4v zPecfYb?`*88tP>}=&ru_$e_Xxo2QRSgPhLhh{{agc+J$$9`hY9b zIMpp`kG4U&joQ^|h~=r8ImZqpZLvo6`?X+(s!2t=Bh^I7-N!Ku=dFPWf}09YQs=jl z|9@5HenY-aiZ>0sH|x+LiN;4V)zPvxMsphi%@vgce!KfciPGnO&ZpLf<@F^e4v~qr zC^eD~MQDEoe*q3<7iKZOb0hSBAN~X`my}S}N5^E))?qQL|5Nh=FI{fXNIL7lhVi&x z8l?%%c7hiTQJEJvF^pr9jX_yyT#R|f>qa{GkCwJ_@d;Og!1qVtN^LzNkeqskErB-e zQY}ym2|-IbClhpY+eeLOL}a7&vB9vxST20N|KCQlsO#5X5s!}1d1aHlv0}_qu}-^X zTgzl~n6RXWPt7}>Hcfb9;z%syhN?H<(z;;0%Y~mA!w0Myp?+e7qGDmh6bUY7jYvh5 zD@Z#)jHsD5xHC`?LU-r8tK#ZuAp7|Xyp+T z45?sm*{^hT*Oprw6M^+h8WAVrD#Tu2pI`p6v2 z04)6GW7E;j5I#81%DC|vF;fEB6_GM!*wU(&j-NkaS(n=QR}&a$gY;Hy_4LmL2sBXu zmR85#09C>n#Gsp2BJA`Z-%?{!owiYAifvWE%+$9pufG2G_cMlfDv_^d7wX`L#*a-1 zt+uq@G5Sp56O3^~sWj6m+u!uNWGW7Jvk_s)>ol0^k(GNcJi(ciBJxDeKO)34>&WI_)QD51k zO7;*q7C3pr+w5~N;6&Bv~g zql+M92tN=LUe~Bns`e0YgnlR`U5vq}quU`C`5T8S!4BOZPOC5LdhXKyZ47_={UI5D zLh7G7Y3;qE98s8gu6~7D1$3806 zJ#zZ@Dj$xwWAEllrXc7h{9aOGw{c765>}sa+C}tPf|%zf?pl(g#e)1gXrl2-nm@wX z7U&QmMjY<8t~YOR7-N37Rn*PK;i@C0mNMuZ zC|*PE!?{4dk6u(HjCYqg83yBk#F!^orzG2xO6~3m=6VO>^LFn!!G?b%A1E~n%u*w< z#?}!loH>nWnVp(R{)#rseovXoDxmgscke$@3#aIr$`82rci0eO7@QzyGO*^XXF@QB z@0K8cMJo8u>|kF`nZnj4BGLg9W^fUxLZ3uG51?1lNrj2>$+8ltN-Z-p?01dzqU{b4 z;|wSD!yVQ2Gm4aNYKmC+ykYIfg^~@Y9b=Kman=RK+iPGHb;x8??{o5zf`s$u%(=Db z6hizvBtDZMBr{mz#*GmJz$-ZjU818=tj0u*D4FB|UEw4Myne3!iuF=vv*`Q_6Sf6f zbmbLO5ws$JnmD+M1iCup-|r&OTA5cdQy z|LH$Ox}uP!X^U(yL3xQTS&sX)81hOJZoQMkU}1z)R7*5mNiJ&ISnS}<_5Hv0fRM~u zaE!RBx-%l1KnLV(L(vSvVxD$yioqL8@A-j0=A znJV8zv85x5IE|6HXK;@VV-Usz)^N0R2I<;M>S>coVm%Q+8Q(HT2rOIfRaZv`W)Is9 z6I`Xt{u@s|yg=H-LaVG(GRB(8Wm<4dd+U>%|3BF#H%>uoLeoW5i*FXZ&o_z&Y%`W#)&&mI6v3%5qWu}7v z%S;bF3mQkI44G{4k{MZl0&QF`seCUl8wHy!fOf&blYM$08Pq_IP?VVX;Tj^|f5bro zzP|qL8|9?tJlU#7NI*GKe08pNzkdM*+y{2;L+9Hke3z6Rab@1 zKK&SE4lH;)Z##B#BRmuQ%=!M3)O*NHos7M`Z{P;8tajebB~@zNKfK8~5sSEMTiv2) zSZHAxK-8jWM9Y|*(a5T%GQOm}d^z6`+q`JBTs!`zdWawh%l(h@a(~ds5Ab-xdSF5< ziaq};OF;WxDO;a7sZjmJpifTyQ+zbhyf-$}XE({O*lNv6ac_t4ksD-gxdIu*w7SYX zq6d3dAZVI1Q#Ka(dtJIs9P7{ReuvAeVJPyMt2b#22QOE# z6TgSdAiK49g}2jCSD$6^9Prq1KBd4+y^uIrQ;28G2GuO}7t&Vp_Udp)61+%MOCfvy zDWQ-XT4Z8c=wfkK*Fe$1tN_pa36Qx$XBs;bL7Qf6Xx&HCp8ERbgjPf2F#JNK^p4iV znUahNr;wM6nPN1&agw#&EX$cGa;Z#w-PYQ)Mg8Dhj#Op5E@mV|TdF(IUU*zS1cU0qUNyo?PLyT#(qNMbOcQ`|TIf zq_0>5Qkm*ABfL_PD*kH=v_({O2n7e8CX%b>9F!LgSIR%XEwib;Cqg%3!p=b=k; zmyi2t)&&K%qq({9%SbMX#(qpcu0TdU5w!TRJQcc-A)LxsI`t%Mp)N!Bbd>HX*RLFz zzw}CYqIi1f60K|s!W?!neOC3*nV_tKP>{B33sWxdn@Ts9z!I{0_f(NTB%6aZeb`i>63eot!()qk1+wU zy=iazj=b}3(${!-@jxA^qO6$kg^${YvDzIE17`nXS#A9W76wAeL(=|j!&7y`&LK=$IO!U7T$|5#E{9Lb4>bT&z;YU{1 zr1H6-XC~lME&BCKr|&<*Pq*$1z}*8@>cE%qFa}0Bni`JfAoPh--pzopfCaCTHDPLn z)Zs%cQEbTmb-qN{+m9Op0aXOx2~5O&|3+SD3WoV4N1EhfY*2BqR~R0j^|tTrr=e@I#W;aURJQT_>HhhZ%NLA3eu-wDvnS+Rk?zSjVi?XK@X|5jvUr z^{~DG%kBScO`Ou8o%1j&D+xM!UOF>>KO8o5JrV{|g`EKZ#L--lR)G5u<(lxqn+maLEa=9WG+T>p3$jTD=^EkumC&4zTP zlWYDrmbRc5zjwKlDF3jOx3m^M27}Jq@2e;6mYa3{Nz#Z`G}0l?Wr~W6!&mR&jH#u` zjqQv!Qd1W$EVEg*#j4-hJBBH4-iNWe%A~!?SyO zF`5F2-M7NG-$(YLm0uD*nS~Vkem?gY;22G`E=jA{G*Qjk;Qi-jDi7%xJP?nt^6A@K z%b{r>PdA~yx(#{Y=-vEY_aPVSAL8y)_}GBP!@~k^|ApG{rRm|H+G>gi5&2dcoFjyV zsLhZ@1~2TZE^eBG{eKFZznb zNoMRGhprLKMt8_OlBa=Yclbf@MSS=mIiSbqdsJz4JBb1wJVZ$Y6goSx^Hb zd7B13%WS{jL2mm{M7R#L`K4rki9z=tveFJwmhO(vKOOxs+>;f!OG^?C>E8F7+qp0+ zfqYr@==uxujk-f=E4V(Xa1Q^1c)$GI{eJq%-FcrUu;58Yf#DXl!dGJNUk?a*i0aa` zxBo2xetR2M-9o81PAv@V%OAl^IEP+RHf$_4G`n$9vFFAz6>$6eMa{hV<#r8km_i^2 zSIYt2OM(r#==#i<#4vA)t%Xn{>jqJ(w8A`~KOf@;^^UK?nVGOv5&Lmve-*QkhDx(K z^2Q&am`MLgdHVq(^((Ods-7qCUPj{Oe5M_EJR7psmqBFkl5?=207$IR?Tjt{Pa1J+ zK+>ICHUDO;mlu_aH#^G4kmMB}%Z&o)gP79UpA|fQ`5AH`w)jKD!0#D`Of~<*J8wny z42rWaycx?^5EJg`dpiIcu6Ej`}cEf3I#@$ zpwaEV=z@iEs0hX8=74(P9DwSo%U|vCkIClK5ahP{9*abDIL@@2sh}}WZ0FylPlLi=_E;wX>Z8FONvMYwtAcm z!-9Mu(56G_0cNrPf2x=+GQM}*<#AAmsM#&bLmD@cl61`CXL&a>BGb=v)Hf8 zg&EQILnf(i0Gg93!9CGsPf+$isW_JJ^F!-TkHr6U3FYAR>a}1ahSyg}2JN2bBA4A} zX~cMz>!7q5p{}4LE~>&NcM%LOVIdwlrUoX3l424v%9cnAIrrdxUNg(<6JoJ!qq3gU zvriH>V#k(fnwqouSow3&yAII?LW?gjJCAG6#2Iu+aIv9TgWn6H?`1wvkIULzcyB&s zrpUf%zDOAUDQcx%|87kF`3ze`h>Znu_&9--^KEDdh<&+zFc&fCNr1&c$rv{Zm);tmaK*x&5Q5uxhDv|xL9Y4#BSLK7SV`s7L@j`XC7?K0{BKsB}s4y1X}d9hMeIB ziYEV)OC|nryPtOwC=!K4wMq=>!y)uDtYH~Ki3FO0xK?4dOnKu_$ji5WO#A|j2f#}saVD^E3vwo7ZR-b-<)SF4FErX>`l97F#TyRH>f1Hp!JYJ(v?AtTZ{8(%+R>T@Kb<=r8C0T(2&o&nXJ^5 z2a>+|`XEtQ$p06cYpzArr~dBOt?b79{LM;f9iuJnN8rf=)uBT)#6WQwPYx#AgU<=u zfE?|N%HN40i8|LgKcAUX0cS(vXQVnRY3#h+pSsSd%#Mal!~;#%^v4~Ot0L^~t`uaR z#G~qJOMgYL5akvSNf)t^fnA~hA5C8!7R49uEg}d=hjdEE0@B^xvA`nTCEclX=SnQy z-Q6JFB`qM`Al>rL@80*GXaC*j%$YND<{O`IZF6nY&xjS9THy?oEXokk=MWLu_N}A1 z97^4U4JNutQiiu^d)VvRmbT^ z`~eml?$GLnf@D!S?1?mGWl!!n*+G8zsr-!@Cs%}-gM)R-Fb9vCI~No=~E1lHJDNwGhqBVCp#z<*B`lu*9E8 z$jLZG-obkIO$>pFdUqG^QL^@D*}=h72JJSQDKy7X9JEQumQh^N1enZ#L6Ig393!4N zwgyaCdBbAo-j$!MY+tnn0VCUQ+_G0AOK9EHfz7OAdyd>Q)grrVf6HA7dM@PT+xoKT zp|OF4>xyISap=n5QWRTiFR%GQD#wOMyq=voJ=WIv3lWSFQ@y82KADjiX7dHhHi;$n z@RYslf-->4GB^hPA>;4@)`*?JQZ&9mc|86}1*OhJ1AP1x{|+ersqm#$1FFy-okm{v zxnYP3l-~n$X4w&aP#eh%hI&+YHbk`_l3x{pqZXW%V#NG8GLLGgA0SC-NMJFx%@^_z zI6WL;?yHbS6?Gg*P;GSX1+hA5UN4>UGBnHLxM;>{9~V=qU6i z9t($n?3tFR0M`(O<{U8q&GYDP0lggioaTHS{y|Di>{&^eIV3Mn2h^EauGe)VO#W=r zGyKveRF4;&XRM3fWNHf8qy4V)4HJ!%0n%mBXi%q12enYvw^it2GCyM<#r}jfh>@8RZpa86{ zncw|*g)>2xSJ|-UM(A0H})n_(W`2Fd;?$av9i|%_IJJy;0s|mv<%J6fBD_=fWBb# z-tYhk0wllory)w_auZ_bvCBe?2`i}PWLTA-)xo(8@IR?(MwlYYifo9EzM8i!Hr+#4 z@xO`wpf($$83T*!xLO?rGDpd60SXoNu_5c-KhcH;SJx~znr94GkyOL5YsBFKpw+(K#M7eq_ZxH5}V@cmbeE{8<^?XyZ-`z2*q|+OGCa<$@ z_FYe8?hZY%Rg{K2?88cM8Tc+E$FW1&n4#Z~?3@*t!9HMKMic_>HuG&A{?J?X*)Gqn zv&${Ej{BISYsVoOy-9@q`fpMVCZr4{HsV-=1rRZVh4k6gi7Whu4eC_xC#Z8h%iBbH z3-;_6|a`ULIhC{epjUr#nz&8 zs**9fp=O(rH;gp4f`grK0s{K3`Z6=`LQyX9zSoutYVHD@EOmK2&JSZwH4RD;^VziN zpcC;KHBB@rzt-P-(q^1>E4(>nN|rTKg~aEVy{za2ZZW4#t91wJR3XZbCn|#a+N&19 zt2H`O&vfI3*gH+Eau796qnsT3C*tR!+YQklYTSu+!&ugGYMQ^WaV>lP{Nd+We~HIn zC3el;FSX08mqx*zpz!*#AnV`__ z;ZE?}+!Kk2=TFN!P^vjf_ro6|k#@U_M)1Mz!n&?HCu5{NMIGM7fS>*AakukRfze8I z%kw{0&*K%c_wGLf>6mA6KDwCCNtiM15x?6aHYno(%YpHs;<@zlm-4f}j9h(B@{jdi zm)}3zb&pj&?6#QAsmkq2i4aL>8@izGHdQN0fykp1?yKxQ?{&W*8tZm+EWxFRhmJLK1^fVI7jOH2VCuh+gW zddmqq5pkD);v_YaN~w5+Bw-V7%v~28)Zp4f{JaB3FEv#tTBEDu(|f(P8?y7xfc`F9 zlg<{dBPCFki4g(fUQ@N|m`a#dc*oBx?`xHor>BjJunm!&(kD2P*Wv(Ca=;%wtPX%_^HwdG&y7&nyR$s>mWjKr^@y$xOpRDxx6S zmyfLVaMXay4z>%oqTmq6L%Q^>EzngOs?9uyC{?x-*%&c`vDE)`OzS?>+c?ikjIWhm zcA?${LozTZ*+8e=(17c&4|zXVdHI-FtnKDl=pY z`e~UV#J6YW(9>HLQhKpZX0I>iE2hKAEKl5bO1Y;3`Tc~`{d&US;zoXVgq2c#;$j`} zjTJ0E)c;EpcZPzV9$>*KvVr02?Yj0Pa!}#(jCysOb1F)hKg_LgwkE|y=JDw?DKuYg zg;SYJKr{urCk)TK>|t5}QM2-xfKyfzaF9B2JuI234vFz(DGx2HP%R6ufbJZnUfdXN zMpwC9S#o@g;@h9f`g^hy7&gXH1W1DHj0*d}e{gy7GAu;l{`zJiIcn3(Re#%uOJS`d z$G5L+>Vwl?(hN_CM5l?nZ`f+UJ$$wx&XSCTy+PaPZjk=%6T`&ML3U18DGIBc=#jZp zwzqwpB{mm$GxbePpgpF7sZ4Ogm2zH5aj2K`+QIk3 zED+ckjug$ggOhRH;LBpE6eMe?bV8Z8VWXs*w?fh&KoVuxIkBQB`6KC&Z@zE73-cSCxwEZ1L0=zv_2OV-S)E^~#1UQAV@ew4 zP;13_30;(e?QJjp6ZzapmpZ#o(pf2>q)RWCf@nb=A5ISVV4E2$$Y zNZ#c(dd|n={)D&qY9XF@(cuzsCv4Y`vCyYHj`a4aGD}JXlzT%WP229xgD^*<`cIVZ z^9!QIk4E@7%A<_m8jx=^*W|%Cqa*S&I;`R|D_fGd+|qEWsBCic(m#?eF7HVD_BEE4 z@KO^HYTEIv;qXC(jB8oSYj%+mNc~y` z4wtn*jRvmGB3bYhCvtd5{(NDo`}_%sW2>X6f@Ufy%PdoEk3Fg}uoB#6rD*f^p9qwMYMm*3#T0~AK>oH$WoQNt zp|9@Xn#4{+$^y?iiE4h&;jeTG>kIT*3KZw-MQ*qj2k7CSp4JAqrj-j=3euW$r8|@D zptf_zR#KQL5l%o4-eytDa@_O^qGS)D~){k;mjm! z;8693nZJ|0{e4Pnhs$6et))=93)arbHA!1jWIUQ%9hHGHUz{dv5}kCT@5qWC7FrY} z-stqV9A=Sz&s6w!;Z4APyh6(Dl2GQSB*OZ`Xt#y@W2>deU|PB~LpFgh_Y>hdao^wmTt}>Kfa$OZ;qz)op$4!Tl`LqSu zULTNl4D6=-fGt(#05(MQbir(6&DNbSI4 zNeB?a1akmupbq7#Lq}TRP%cN=z#}MnH?f3E0(6q+fBh(6B$ixOJ;olmV4L^^G9+`l zE!jLg3f#4ms@Ye6Bz1+Wlb7q`8;YaVEDI7Kaj{C{J>t2$nRSJK{eu!Fqr&S= znRxs0IPk*p3uzUIzRyxoSwndrPr`O!hsw0>*98b!(+{J1QEHLI`zfVGkEY{AYGlRP zF<6o!Au@Ct)m3SECli`(f(gD6H1_>;iFCM_R%FiX{C!)!-E;*iH)B~sN zxCPCB+m2iAcF#Qap%b*nPTv3Uu{_#u@#h>Em*~h&nO9)3nS~h1_6w)Zoqs zOloay{lG*)TtXE%;z#zob&Q-GFZF40sk>v$zQrgl*^GdoO|;Y{(n#s!ID|z!Pg9JP zsAE`DhT;f2GP7Shn9^^C#qJYu~;bPN6(&a=?eKyZSDE+M34syPHI(5Dz_fU3X-4} z=B7@iDuYr%ADQ7p#v!%9!l|NuakFzF>~hsU)-ja)WQbyr%+0A6kuGH_Ko|~GPc6yB z@~e#7Xgo|siCpPDyhlaU=f@{>Yct|YXU8Kf{iTYEH#cj|Ps+arszR_yikD{6`W~8C z2rVa6n^DcplcnE^=RL!+)&CtU3M0L?&)%FiPS(WT1TKA&FJ(0Al9E@pFyIPq*x7R+Pi1JUoF~ zs=U9ii?U>(H<$DkHYcRtnSH0PO3S2G%npZcAyYU9rw!jY%0T@6@a~WgXz;(60XF}A zC65trgASMmTw}(UE|#35`4$%~6R}ZNw*DKNBGPt-P83ppIEDOh8<9LDG1xYcjV4wd zFqlJq8^}v5?*=WRilhnzGEmbaUJ8_jU^V#)&Ty&%y)XbL1ufE4>*0?^GKuRl$yr8U z%L-xme8fqi#|j}vgnX>aD%30s{Uy4Id1WeparqbKIe!wl(wr?((Z>EEz?51DcM@*P-hrjMuphvqiY99 zUqg(?)m1|VC&!uyW^F`|=LSxoVZh_hE6q`s`-yiYHU4>>))PqJS1&Gs;ig6o7 z3&p}CsbZ1#iWODjyc}PVEpw>{b9q*B&yQSVV2lQAUcM_e6MM?EAR#+*f*l*--oEwz~(jwC*eFN)IaNz_8YVB%9 zeqUII@{_r;2(F4UsF#(|0zB0sKpa`=BX$)?CzwyobQ9H`5G@Q<2!CiP7%LefPlJbR z^Nz-gq%JFyjnD6A(347Pf1u{!pP0dWec~y0HaEAV_cx7n%*C?sMHu9tA=J$3)4$Qn zD&nOi37FHSOn>SPk&)H})by>FD9GS&Ucf%1>kQ%@4AO2ePL;ZT=-g)~c+^n}92QSD z{%!)XDvJ0jTjr`%mxU7yccq#LMM*Z@;uX?!kn9G+DC<;diH;TuM#@TrqC#~%8a&3L z#i4Ty!fQd_FH*?>T0e>FZLVxikt|i-K=jRLYArpIfN{s^q58%}I({aUpRUt*5v2=~ zPSQa@Jq*ZtIjIe*Q&qIge)eAbN&72trn@+Ori1dAmF68M@<&80asC0cYGGk{~kx90JzUxoPe?e zE}%Zea1cvTk7>(4cYp0d7*U3|Q*%Dokm3xf&zLK>8Q_e=|FjZQCEiK(Opcf*{(~-q z`huRNmNN!jeu$K3FX6&dFxv?c&%Xs2n)iMf&HGy==|^AGpj4W8luTwn5<;1h@fEa= zQ8v$K$nOa6Nh=m7q*z4wfubE=FeZ|cOtT`hf=tw;j(*0)!9Db9&N3rIF|`6^w3o&H z`NiShq5CD?!-LfK>S@8t0eA(cWCG)%Qc5gb!3(*^H;w}6nfByBanj*rbC^V}Skg;O z%a&jr6x8_%{gJ!s;@Kd1r`#pka_F~6T9S@W%hRH#PeI=9OcAOTWqHVN;Hg5e+T8xz7-o!&Hqgteqf{5jf-9MLD z?LlN&=0>f;q(g%)?><8kB;l^4dc0eyMme0{p%MLh3&G`tg;=97SLW#mZr*Rgp9#Sn zvF3l31z9Y4`u}%py@b3Cva9N`av*GUdX+5z6OcK%KPL7lW?87Mf3l~Khf6cpxP-CE zToj_ZhkQ&y@sZZsVc4pp&tRjskr}mIA>hv@Kam9vPNnvL4&uA8hq3~8zvoT~5NXW8 zogMR9kLwe$4@*fBm)!mDbuP7pgbzQ8wBj2@KhiW>n7Wa88(;u$p+Tw6?Po4G2$mEc z7k?Y=bVH(`K`o3W)ldth9Kl8-c;3BlbGY7G+QLe93zJG%6$O7gmis>ZfWJb1jb#V#8M52)z;Iu@Z)C_v#7D2co5Z$1@0TzkCAPT_=wp2W_=( zxa}gD51OJ@$=O}OsLqM=f%DD-fT|^Ff59G-!+v<*3#EXv7+4(Srl>EL!e`!L(V5DT zj#xnj)FJ!-?M~cg73P)lN7`(q5);pPDq)A>5?K8sYZn0etZ!*}H!s!%es>1^OtKbd z25XiFSqnr9a6Mc?N49-_`~QX3yNRtJX-@Q<5F8{^qzms}Z~Bo5^KA=OSZSgu&9kq; z>5{2~vM%rc36W)tx5&y9f&175Qk$lF$mh;mPf+Ez_zRp4W?y~*9swO)D`Bwh+` z(|f?A%Zx7*M}gSfF)cse@Ai>YP{FU%Lv2h2j(2y`;S{2lM*d++u4LtlzTaKVUKZA?c2dGa9`F4ky+N2)Q zW>hG?-MZnvX#OT|bpZQW!(sn%5xaDG)sf@BaAFg0QBe#mKqVC~d*$_TXNC zM1RH7@>l)_*9Q>VsYJPl+rt1HIH-&SO_1Zp~-xf9|~4!seS>xyQ`!UaHY>TZD;=izmO(uCPV+X*01* zMCKwKi(_ccn}G&4SDZ1bxFq36scb;}P( zvtxP8e%&2*5~xW02rbwQj5>^DE2l3AEMlZ@>%WOV0Kx*Q zah_Z=@ti|`?_!ne#lCYGZv~`M+#(8^XNM`CQ<`eCH z+uE?bT}EieG&yDYuC)M{D7iF04HRm;Nesl%115w?TeHM*1m|dn9*U@7aV#7q zJvD@~h;59&q3NL|u~m6Y>5OL9Y;-!~tvZD}jiM+BN^onpHSKXKHOik&a&s+_=TD*|Z01hg2+5)e2yz%0#lfp2wf{TS zx!nI=YgeG1O&L9P4E7d^WB~pmcFREEeA;N*Mt(a--kb&|?5%np!$vYa(BS=VTz;;^ z1X5CKuMj1=O=_fw#K;vAr|V4-r#WO^dh*Mepkih~Q1NEyzA^IaEoR$bEUoIwLB;={ zQSpCgG|0^@{g6jbt87EG$+jY5WJh>^j6>2$rTFRRLttT*#yz4%v&>ad*xLWj$RquK ze=AC$vDQ-OCW0NZop}6>MlC;?J?6*F%Z(M!81|lDfT}|37>YXP+;+y8f^RCMuTyhKQY+gvR18uo7fZHkU#ZO@B@m?_&FS z^YZ69&}A{Qt-dvFYz8iYPJv0Xi>|KJx-5}utOSgMN-UG_$M)Ye-{M6j^glwql#_RN z%;g|lztnT=GIf>k!cPS}mN{i{gY$CJKZfR-5)qB2Pxhst)yc}`bM<;p`2J8WLvIr> zYT(GRJm!T3TX3*iLX@@2t%^d-Av$fB&0Hd5h!E<6P1ue1gvk$8Yml@EEzE81wZ1X%qP5WZbE^Kh4zo6MKD6W)JHNiSeo9tl9!h*&Q7NNMX`s#4b?EhbVZZJuQ~Gp^ z7>7})#da!Pl*VLS_TPcN4^&@+J3W#-DnYQS?Gi3cteKPOk%#E3Uqu`%rVarqomt;= zUug1Ern;M+fArP(%2My&ZZAGdY zcTjD;fLU|3aTBoTyD@XhmK$lO#La&Km-7LsJwsty!F#TC)>s1F|9RXW;3#Q0`5=zH z0~h*T_xCu$-7aCPamro1T} zxGLdoqnU3jEKlPy96mx1F8~s2yFf-1(-M#7Nq#x1H~Oc}K-Zr;QLh8t&u6CoJfu$d zy$%mIA~%0Y(IlQe&{{16n7lfyZ;`5+oFUyXg5{<3_zL9~&u6-Se?_{DEY=I|s-*7z zd=9Fb=y^W&y^V_tA@4(wcJ{In*g zlq_%S)SN)~e!d9VC)k&c8?s+t+X58Eh>hmpI;&9rBS52E*5#EA&}JDd&dl#ST<+4I zb-_i5&M2bJ0gd#_Z61ov?@DVPij1uBxpu!@>h|q1ctt)2OJP~! z78ckTx%l%eNQu$VzLfAMw0E3}vBZUZqH)z@b1~h)1=7EH{S>9f=+|^dk$n zU}z=>qq5@tj-Q^iVqtlmw{xK=Q!3f9;Wy?tWcwmh!GX}ZJ#*~k*%Vn6Xh&TKVrUkZ zss;2`!+UGu&aDncU1XZ1<>js_@2+VDW#}0r^Kv>yrVFd3;06XS>`0oY{w+z$S-!(} zAxrT?uj=X(Ape(a_}Vd4lV8i1MRT!(J|)bmBY2-GLN;~(T=A1E_Hc<7en@P)TNo-u z&ses-O|B;$o|>L5ViGf{*`fCtf-v7pNKzNTwVixk>%wL>J@aqtAE+*zegVhgySOzn zNp+Cz^UdQRl9a?L>H)F#xA@}#Z&_X^B*`ySk58Wf*TOjwv%AQhBAUZ948k^AZ{pb8 z?jKhYyP^JjF#+zt7~*offHmJJ?SJ}1w=&UHdV7O-*-ulnf{)jx!tMV)hHZniJxKN7 z96%^wxZ0P0M+sW4j_6APi+$~vOu`jlKpEk1Nhd%}F|9!UZQ?SrrN)o4bG91yrIf#m zak1DNb`E16l4A8jgXhmUub!oUg2Z$9K%_(cYGPk8Y=H-%7+7&+0f^($O39J^69Y}m zaX!-xu`fk)L&LW~i#AtpQ+M~!`=&^P0<#}e_OJ2zU(TIu7klP;obKuvW%s61g?#$) z?}T^#ab3t1T=((yPPuuP5rDoQ`v>(vz1fbvq>$<9YxK1lGJ*F3C#ke67%R0{)z7%T znYK)-t{?K}22S}?m6W+eEWL$|KlV#vXYepea+^Nu7V9CYx}vs6*|GL!`GAp8`bT^)Qy_Sp>Z{fLUWtMf z!GT3cgJ2twqz6!A!NkSrABzk_DkxP(w!%55hRa}yD9f@o$Xi~rFwAs$73>04RZX|m zWAPfN17cXwa%j6BX|&tzYZLOlL>_o+F*i0CAjrxcGGDe-R(HEc}Vbta*Io z!}nIw?l#ibtJ?0R=64al31|mCe8Ic0nP*{0KTV~^j)1Z*e_7<*AfvlyvFk%OBJS3 zS9xSCR2~HvoHI=0gqgI12Y$J<%?T|Um0fVz+uzq4*J3`Nu$f=~M-~Q8d=(P3q`Hd? z!N#HC`++N)n^%ewX^}$&P&aeOg85-=UVnXrpXR!+SjmO{)S@qTB5(I`OfvqcI5q;% zHze@-U{$jqW|uln8YP!H@9i2C%F@C}d;3`PA?|6-+KIcRm2?_Oxh5s)4c^X3JuC!d zYXglJ8p0!Im$)4#$qb7EuMk|K$g-R=qDXra7%;1m6|obgxr7F-nYA=*7x%{HfsP3?tmXrJ}o|sDLINp4a9(pGeo@A%B`=F%iuCv zmsep!1W}ux&N1c(#eOyU@@RpO&tM%1Wz)e4W>?b+I^9gAjYWsDLy!>=m8)fBDpkh- z3@xGMTq-zki$u@j+-Q8gCMy3Mqb;nALaAPA@EjPbm!>!S*Kw z?I*yXGsWrC7inq}MBo!hcupv25J%3upW zQB&iJ*2gxj1SmMI=de2@#v~b7vM+lN*!)mEK)>Bg%~yCj;bru8oIJT8J=+l3y`Yxz zeu~EMSUy~3^BWgrj?j!-YZl%)W%^Ww=62*b>C3+w9)yaS6B+t>qGTS3fB`%imOv1C z7fX(O#7BH)5N*b!c%ry?I=-}l&$(o)+*7ZA+rO#J-^AC`loa&pvNUFZ7MiEOR`PKUtP#BE;umw!_$ck3yH z<3@CFpgi=cE#gfVQseHwcl_jI#@$Z5lZ{iIZF#bh@50@_Ef@QE8`?}=M-jzi(x`9I z(2JYA5WJyd6B0@TugyPbS_osLQcnCsXQAthWo;$N=71>@OeBx@6YjHSUv?OakD2nG z%&ijE*>cTDM#wi;6yxhfTSV^@V;6psjF1+?PB}1$%Hc43)y>vA_(O=2_7wv3xuQY5 z>2|UO1~-duB$$^bCkdw(?9}gkEDyS_G7L`hS3n>>0scLcCgU_l)S0U zhiS{D+nPq~v?_=}7JJrsS{3$ZV@;1|HE2kW%VmoM<2}3jvp4T_?$o^g`%J6A~d%2 zj5tG4-4RbvR~iK2>lNv_O$WnNJfH9R-qX1x9(;W1{kB#V)9E$xz`6YygK+)nTe^N` zY}?Mx$oc(qZ@48+(4@%o)bmOWGK?~oR&AB=_%J*v3gK8Wk?DJp^VV1S#1G>O=r5VV z?Lpj1i#<>VDM54RYiMy?*5Bv*#8Q{c&B^%mzK;puJTvKzm^4EWeJ9A^l^@`m%*N?a zwYSla*eTRyeHQi}S>8=N)C$}+PA4itw+56K+Zx`(ySGtxQDQBJ?jAs|E&?w;7f!o! zs!@zaPkcO)j@xrgc`;58wcL8vB*e36Y>6D-?&IdG`qiHA(z=Ru`@@ zWMN{UkBk-^8yPRBtQrsB*C^UI9lRnTygkG?yEqegI%(AV?K?iOmAVZO+~-(9sRE0w z|2F;3*3ULGgmw;02BemEifSc3)h%DV8%u&WAj@*$)lJf&tTNrQ;RAT_Cgn-66o64$ zidKV$^Kn0;+jp|JmwiY9+5H9m>q^0h3M_0 zV9bl8Z`7LT>OT4q1t=^y{XEpo;e+!(z)5|pKdGZq44__`$|5c#=%k?HBhb^6=qr2` zufGT3Gtvn}WR+U*aV(4mPW(8YeF7(Vv{eq+wX}d%%l!!--5kpms+~v=Hy5h>XM7-;vp8h`%uZn%0at_|{9O!NAXR1@i1lsve-aklm`F2q( z2v$%~)qU7nhCcXC%))BhClZQcxR8(~x!_YOiZeuB1K(#0{=sTq_SyGaIN#WGU;McM zl*}{g>Ea0H#85e0S$k>~->yn(&>S8mj$CMTJ#H}+M@2U}BY$Ce%ONwin345$roEYf z8nI{_VAGj6jgA5MZ4!sH0wU#uZ2~^sCKG3FN;gE$D-vTJtDq9truSS*yzVJlIedbM z9OW2PunLh^0WXo~mhh2i8C5ypY;WF%>y2hYyaVm{5I%DgLfTsX{P`@BAam7QK+;D_ zzNz)k<#RYbT}t#Q*@W#~%fA`FGsCNc`|jwtW1A5r@j8Q=)L6neoXf^obp*x@HUY2R zi~0|fN!$~}&8;ryULk;>-R4~;aOx!`ocSR*}_{_LxvYmza$B0vJN$b|FIbQd-bPS zV&9#K0PG?A%gstak&fO%rPZ@;>(@B1+-G&*;*Cwcg+e{_MsHB+(CXh4lia1RN--KH zDaLu;w!e-RzqgIOL~nk55V_dQglo=EeBSYRKI1WTytf;KoSAY7o83+NbcobUUuO6g z8o33%#J&Cqc$j(}ml4VgwKM^AD`&rY{{-0zFFdnv4`n;v4`>*GJ|t`P|And4 z@)CpUD4~ z6Qi9Bn1Zr=M_(VvF+7v^`a@-YIoA9{YIaF)e4UmPcNyHL@2L+13Ry4zG=znktk)jGG3@<^t8XPLmbEiP z{*k@{O6EOt4HUJ$dBeRZz8QON_I@N{ZQ`r35Wy_UdgzaZLbn%M9&dDa{yoX8zpuVr zdz;%~*Bo0TC}cvr;VM~-MMC*a)A|K%*cigmi_6G-Ht`#z2?%=ZQoNG7QhE7iww%sJ55 zY(N_RjD=8EAlqbz&jg~w#`3%lRr2+Ts@RwTJ{(T_Sc`2?c^7|GCa$+E1uoqOvd2UMp^9SB#lY*>`TRJ3t~VP zurAoM)3_XM>E$n}ZaYtl`xPQjn{e(|Bcu@H1}jcKqTKJ+R;gN|)4#VLbH>glVXNiX z`Rxi4`fNTAP#G0;KGXL+*U0)GHfCo+zT>@XX$l2bEJY9LWj$uBd@O&D;pq=`D!qMh zw2bSWjQ1bw!;DmKVDSFBGJz@5Oz+9nGm8le*_D2$79_p1Er1OBr__BlAN(+bLl)rH zb5SJMHD~GR7nYfcPRc|R(eCOk^vIE^G)H%>uQ&B6M-21+zA7lm$5Sk*WIlH-bowp5 zSXG(! zgRa4LUBCyivzx)sjRDmKZ)i(aWDVkJCEVLl|CrB z4hsl*2O+erQe3-MnEc$iCwz~Qed)ZA%V9M`b~bAp!l_SM=}Lbs#2+T(IYKy<#lPeq z1jy^2pRMgap5oYND@MrCZ>4_K%cH`{#SJamzNt1&CC%%N?~ENWF=4Mmb(N44D3gW=YSPH}|Yp2yhHLzC!J+A2M3X z+x+m`B8mPI*$(HS5+))(*TXjBhNCoBZoVjPw1k-aNwxgL9;0~1L~2*P%&N;@#rHgR zI9x=W68K6{>?|ocgfmCn)=hdR1r)YkEnA76?3QhM_3|!tp9l0hcCH^xyF5MnWqq>S zD@j9rd{EoSjLA&x`2pGDCi4$(KgfKk=N0<%+?ygOa2GC^>9^R&g~qHek%}Hu6j!-d zkYWmA-5=)>!p6&cJxM#WX*|D+y1#!BgNoxZ99oPxcbSp-G$2y8!@t)U6!AE=XjnerUr;G|>}m)rKJy;UELKTfnPe>C=IM2-&o*Lv5N&7Cm98Hy8~`K|m;cU~Dk%J?ybnH$JVu9W^@Kuom2VZISmqp`D9+=k56?6*l8iGb!$1dc z<=ajZ&)g4BudTQQ%L**t_PIOeBgRNe)-=5K_jHsstC@fEe%Vk++)W*s;mGPH;fV5f zZHIUFhEv**Ov2_km}$QN-DR*qOtaU@W5!pq(*sp$a258paSVh5dN-G7ZE)$qi69GR zb+kx=f)ESd7HP4pV(Kxhlx4y=a&qTneTns>8FF{4P!MhP}NMpRn!DLgx zcr!D=^7r)|9dn8e$d_ne1Uz=wxiFQ3H`+%|4IfY^xRvP&)S|tdy@!+b_Z2(z5yg^} z1%7fh+OU3Xg`za_vB`+w?b0J#QmIiGWLe0XuXZT{i1uY!uzuxss5U!TB6i-jG3~jtpJSzdG|y`MfAHqj`H4dl!jI?c{Jet^Xe!7*R5!cxr0p@rjQF;<+r;-dLA5Su5wI)sL_) z*lg0B+guRFkro1-> zGXD^1YT(w_cWm$@c$yXgtZV#EHbfKb{U?upDHgd&$?^ZN0F!Be!7z8=a5J(v{34tZ zd?|2ys8S7C8SczZ{ znE#poFPngK=(|=L1C>-|x@hi?x(!n?9wIw^PaaFQ{4Ld=n;60K%{7A0HDb63!Bs#z z?Q-@D3Z*CyyB!8kcsNW6_Wc1qTMFJdhnPFm+BjAErsEste6%d2fEpsNeng-w+0J9; z;2^rnQyuFiS6i==rBFcFd%{;=tTHl}G5%(3x*R$z;(Z+Z*7=gkf_TWzIf9Z?v9AX^ zuWgK#GuYUa_?BEtL3_YMqte4 z{9@1NUU8k+VWyNrLBVj97-H)uJ~-$3nqn?b;;?LiQ0mMUZ9^F6#3hX17Ll9&PCFB@ z4NWXIbCSK#zsev%_uZo2Cw;LEL4TmYhCges7k=nxKM$nUGR4cBF{ZAVz)1X6W}x2pC$>x z^0)0V@`$q~g~?^BTDbx*ItD{CJJ7+VA|BRbhCcpw2AG zEWAMXGqo$)1Uk|RJmOPxi(k2J)vc08HR4>4I9ZK93#R|o09$#6N!`&bIJ&By++fBzj-@8&#Dz-lKiA=xS6+>q}2)hv9=JisMwJyQZJFReA ze$PC~f)9IiDxQzabkBP;iFHrt?dKQ=8yypF4vK{Ko-61&{fG!Cml>a@Mo^|vZ*B(t za*yZ9FW}GLmc9KknMNwId12YT%M;gJ@~{2Gk1Z$Qn0ql3(W_=hZOk%LyFPTIK`e)G zs|;O_%{Y$YlL)9$1_G>49(T0DHIv8$Jd&tm=zYPb=&10$4KV3jTi|hFI zrW87Fdp}>-;GOS%>L5xQ-l5Duk0MzoR;0jP&NbDomv{I!mm1eL*;0ki-)YpUb)eI; zcQc>WGZjrOG-APO>(Grtz5HdzEaG?7k}~Z$2;c4ovCkbaR12~sx(PY8%>Q0fYnM&& z_hOu|E*j#{Y^NYq)#LBx2POQh65%pjAi4zS|Hs6dNJ=Z-LKXUV`!Ws%^JDU^_L#>w za_P9-EL4&a1;H?G+w41Y`S&VZS{PzLjr!62w+?0_mr3VLr>>dluTkSjNWSz?ZRu(j41|H|Ryty$e*_e{)C$!m@j{+)US7x})PuhlwZHQhHA?5j1*+$X z_-5625IK5{Nbv*`u9T8a2zx2J02eCJ52PYm(}hg)6-;0l$w=}bhe zC!(h(C4-9O48x9{1AyqZR=B#+8!nDIBn?G&ehADTGQ4b`%62j78WLDMzt{{rckJB9 z+Qr$c)-Fj&bgnmP$7be&A6umNH@hwxMQs)S^Y;SZ_j38e+yd_pUF0Tg4FF1wn~0|;W6v5 zzFqdsuJ;!tmv!p?7Z0+}lU}BMKsuMod39Agk> zJT=7K@ECL#SK{FJVk+ab;XkR(i3u{8E)-eX)b$zH8DuWf0P!$X_6#v}w0!RE$`q8U2MtZ>FYR0Qh(&;vt5Voe=~$Xk&c~!EZW5_gJ!y zWrkhYX^<@?j0`tlQ4RPszBn~k+*%&`6 zb=<~hW`a)DLRThJm5M7gQhH`;IYsxVqmau-G72s7^G&Zk2+x`zgG7fGeKu(coC=zM z%eoP~5)%s<0Me}N!-Qggwz>$LEGN7`RHb z$*C!h&wn}jp80NK7x@MG_BYZaopl@T?fusKni}bSS6s$kTzdN1sk=xv8zFAXAF8O) zY;g|EQqvXTj;vvON-AEZ+|~{`*R*QR*zEl}V;heEWW>MuRQy#pQzy!c-y3|#G zB!{f^M#=UNr3l|We^1D+g?{s@vAVJ#T~v@grexki?GZOf%Qe>d?DXR9*SWy&~!9%{5CM8x0%U|a#%MZ%@Q6ih?c!K_T^ z-XaO9JE5_pZilC>r>^CLhs3oK0W7ybi*ZBa6a)u(u*gOaaEIN7 zr1=;!tga69`G{o8q47dy3pxJuwtHv27T{Jy0WmGlwgl!RhIm+rX|FA>rJK)ikImEx zkJtC(zwQ1%c5Ao5okvcy|q&J2w=%s|BB;`S8Yqlq1D0LEf5) za>Tu?EDFd9SjnMOOEmVJ@H#5WBOlXg?JY5JJY-B{#jVlzVZBvUakQ#?`Kc#~5#+=$ z^L6)1sLH`~^)dXDppoGGAyCwjyDBUJY>Ur4T#%%Qigc7ikB`55yF@GNDQD0+OMtg+5s#M| zPLRwBMn3kAtP0KX8{)PF;Fl zwqQTUkz5@NBa*~nNzN6mp0nDkk8*`r8Xv4H`aUn$|Kzb~H5Cxr+bxjd_r6I?Rh!Bn z&R5JxsbmI@H<_nCX&C%FDxAck1F2svr0eY$HZ2eF5-{V3ut18be54E3Etu`6+1W-Y zC?m~Wz+eNDqeQS_Jsz>k+ZMW!-yJnmF|4a7FP|81kc>GF)@9=5s1y;uci;B{*s`T= zyHn?m^X+hyru|$fvQ0{z;UHG)_t-vV{7cJWH@D$kuW?Bp?jLaD9^agVJJV_m6Ed)M7?%pETaWcE#&qk`b66nYU-H7J&u+X1t>b7$ zazj^{UWAnHgnC+OJ~9N=+A)UCPcL5p+a_`;#C}<)DSQ;`&nUnV+Z6P}y(cA=>DO1sq?dwX}^`1Mg6v~r!fJWmiiHW2ZviIsj-0jI^# z%3Ins`FsalYxNQ9wd*rue{r{MoIHeZ;1pqR@G&|XZ^Occ4W)HGL~R2xA*%{rfcTvK z)D44tuW*|WaXFY=&wy1Za7@ccaQm`5q-d7n$o%{K0>H_JGp#eLW4xRZk0(Ir;=ghgqm zf~$&2iqN2Kaqav*9QbRA7*R5gpt8~O>`9m5orj1+$wUbHxMHfN`RoPK%wvo`!a`A) z15gMmMI*;KOF2cJ6kdvW9^Ltcbist=K-9noELpdq|m9!&i?v805YkwbHMN+ zK}C(oM%x3V=ZYxv_h41M`kbxMhe)tm;(YS(A^PCwNp5bhiSEP9QSreuB>WqQ8wKg$ zowGdg;7e?c2nayaF)wo)xKhPH%s}AS!hs>Fszn)Al^Q+56%s!JM zclvI!CCs4H)N#l|P&g@^mm`NVNB_LRmHDV;hhMvdDJ+jr7va$3$62_4MZgng>| zzTJLQ9jx`bs`+YAiCeM75Z#|r$gGU_$3%RiO*}9B{3U(NNt7&x9-4lPA4GXSVGl*i>YOuWZSpQwP+av*sAGLhPk)X{OH{);a=# z8bt@*pxbf7Pak@wWENRiwGK{?^#NgO2A9X-XSftbw0}dYD5>#U;Y0`LV9UoqTi7e| zs>a*8AA9S%vb}BD1$cvms|GSj`S&lJ`@FsYjHc)E>1FO%8p*V}#vmd=&JX@moDUR$2Mtql+p z>LicecgN4%*>ZCYpd@POB`AE7V+ELNVeF9Pe>)43R~a&(fCp0at5u6 zg=DJ^GmvS;|B>#S>A#0Z}Qk`jGsgNLLx1Z-<-_K4Ko8&u*fq0Hg8+uJat-o5ly7GCGkeX{hc~Z{Nko z_S~TTr-!CcOipV_lDrbiM4s!V#3jjKVhm0`_6&vA4xAs7(v%3m@Fkq9&+p8JCbgZ}#}KXq&t8Z_)Oz50$F|caA5l z2b}N>D*l4D1U)Fu{Be>yrU;>B@UkE%{fQ$?m%z?)uEfETc33P4@_{Ge4JAw?VD9Lo zUBnwkh#o2!biO6w(8Ek|1#L>b3_kT6d+ZOf$)~IMr)xTQ{&2?L{qQ#2O^^JwDV!WQ zh|zEmHsw|boyKDdx-Z(s2i_#ZCC{4C1uN_a|8EN1)q3X%4xL=Plg1bh+fgD+5jT_M?3-okcoVw!O{-Nrm__n#v>e0@XIU+7t7x zX#=DSD$0p}>+y6ti6!#^5fv4xt{OiF{^JxfE6Dej+J*^p*l8QyQg+!c z&MS-Lhq$gW+gHc$Vnul_h3R!=rXPp6bjP*_fFe#zin!XS^mn(MiaXExCwAM(A zwm-41w*fFg6|7|z_%?=`Itzvx-xi@uZRJc_=L$v2S4RYCyE|HhchI?hU3U@%%Bo3X`B)30y0nh8L}D-nNUVTzKzGN&zLKB;j7hM<(#Ev*iegL`Girq z;^R+cMDl!nmkvnC>>bP7WJPdAVU@j})cfT?V{|L;UXO$eHKDJ;$;tgGw>!zRxT%?n zh&`(jr^QsWV6a@?3c&kmdPR6qBwH!c`|VkQ*y>kM^ghq}oO$ts?delfEMu;`THSo2c|8r2fASFEY@ow`C?-f7oHU){$*mW6h8YDcNkwxG9y5 znftG^G@k?hOHR()uFHLZl_984V@mrmIHvIVFFE483G)ftUpBg*Qf-Hu|CZiY18*$g zANJ?}n}JY&CU{nInPxB-{>q$qLLMz!F=o>573!l~n?r&iCo|=9RA3+*bx)a8)_?ui z!1DsCWWpJClPm<6`nYp1w;SY3w?4P@8nA=>N?*C_psl1ic#e#=aJPai9? zyx8E>aplo}JqmrL{@?HdKQ_VuCDe(_%78?y|Hp495RKqH)&n{nT9#_*kNZDZr6_qh z;_afARcInYQ8@w(#L%eS4tO>t^Qz!7EkFrZ8OQjdx$r6m&7bCP&*tOckrigA-H>1B z@9hGGlErcGb?T^NF`Lpw>xqaad#~-~JKn(0ZFy96U^+R8GU3@DNB))b`w#nh<<~07 z$>j)d?gmoNp*eB9Xpc!)s(U*+vhA@6t)Y%>zfyu2sghxBAo18_p+UGlX<>#|!@w9i z!NbziDmB@2ebJ1@&T#1A9F-}G1z?{|p=L+cqCu+37LlS-c$|)C=$}Y}?96QEx`)=$ z0o>9t{%kZR;{+pjc1qeQ`ReiW-@oS=hXf0gt3%6#x$zc~P3`7Q^4diop-bcl0-}pO zXzm>aU5v2wlsbw!V>n~3xLgP}O`;!1A0$49yOUi>VUdAmsG*~5hWuU=qAf$Ear(u=E$wBBeCZf*2BN!@>SWfmsK zxg&`ba>ED`An@P4__s3-56{mx8H`nBCNHW&)Pbh5Ber`{wvowG4LQum5Ye*#>gn6P zx~H{JAIG=x{LclsLY3y6wzO#$*85tjG#QeMK7JClp3mBCt~r$jnXBY~(mI{nphf*e zWzl3BaG@s{=ryq&DYLKj-q+z-bv;oPS}oF%by{8asd4M7f1m$lRV<*3!1;7dAmA3& zvt{Y>lKmCAodl~cc}SJQjW|z(ZQZHuzX6kta+}!N0vWvyzK=&&_S640nYy?@no8&k z{q4AF>`ZCyrH20YSD^}+dO~EN=w!DxV-B93i)p9FooK6jtplY5^Y*9DMZjCaH=L<0;xEcE7Q zhH`H1Wk>9Lk9Nr8g!~8IJ?(4HjVKRp|ByCa91(2?8psCgvI+T)Z3AB1SLaD9?Ioc| zXD9WuH_qdvuZaK1WK$K&#GV1%_n@+_$ba@rG(J-ViUVA;YvjwVnAyRctHV*ANmfEJ zu3CH2uIU2zR~W%3rSq@8++^%AKJ;yx&<=qRI9=gCEuq`)e~6o`xiJ`+w22!2w7e_5 zY`)Bq?Pyr>_1Tl@KeV`eNlYk(U2mJ;It)HjtOFsA8?HdRWMK7o8*ktwz}*J* zuEpct|7^9Ze>I@dKCiPy89Kj4@-ZaVvGss}yIg`TDuN$((c|JJzI3{HHP-qWuKKK4 zLNm%RrsZyf4TXg0t5@0O?wh+$LT}B|!0zdr@bii)@imau_wX5MIoq)1q_9Q*H=quN zAtcO^_g8>07Tl+*{uif>s>5a=ZO}yUH2@N{RQz48z~r*P3EXAFO0Bf7pP7|}&nO7z zNcr&PZ~GkcNyNfw;MU><-;EaU^ey3u8w@}4TC3OTdDfH&`@!1FXTdk4&o{FXdlM+n z3b;~>0WZ%=GVx#blF-AMa2pIzSKTlEHh0x&5J&joj*ENph4_+QZwjP3cg2M%%$-c1 zo!8Yj%W*YC9F@fbtHOdWM{1tI>+9*!`Nyf+V7T$_c)Q+z->B}n zzZPJPxUOS%0LOj)flJK5f_=FT@`Fc+XRpt8Cbm^vYY8vV_G1-miA~_^fhuSYD(`^c z^)pN1-%lEnBU*7SPm+y0vdaEOvQgu}J~U)I2}6LLC77}31%CO_$G3BWU5f##D%)|F zrnPinc>Dc`XdjS6!O{+vm^)@vt(z*3boKBoOjUjx7>|1}COwl2s?uVUblOAlI}M)} zi9R?96nLl`$_VkoLT%FVZqIIjPPrF{)>)>fd}*t{wz zW9al1LNOT?jV^9B(qu+||NRnhmhyU2r7DXnp{OEV_|YT{FD%H!+FA=_6`lW75E3+{ zAU`X<2n(T4SW4OL$1hRJzS`=e{I!q=(SxOg@6kND@`#C{6x)rzCD;YBdm zys`cGW-wAJ{IQ@C<3BcO&~!vG1_3cfrUQ~XK>3@yZCg9Yla>%uK?ZhvtnNs!l_u0&ND@2%pb(c@ zv=03|Nm^r&87x2AH#hH8QX(CMMePlV--XptarCJCIUd^)74;8@E+ncvBP}J=!G^9* ze1``(;zNi;!yuQXqK~pPUB)S{GO@AsXQMk0nHNyK-+dv$g6jPzk2NTFC z9tmXY*eRJt#`)HSr>BrGdzqP$ku^Rf&;rOt?hNMiYHf3R%K|wd5pUpH(;vm1$&#ax zE-%K~5v6iEecDjQhoJ`6j+yX!J%Km!dkZN^V$_pOI`fFj%Sm`d39~TCpsyREOT>n9 zQ-9G2u{G9v@)_6M;acWZ6`8Lbe`cT3fGrxMOQgPDiaBH_i(!>*mMT~+Ub!iS;M-uK zP3*}Ju%#6JXdtwAYP5NTtIEclbONZ*$+TV1nY2tU^kt!K_2bsoqT{_R_Vz1%FL{qg zzT0YKqxP#p*WRRsD$U^qa)3lo+&G1X@@is;h^XWv`l#vk^7nH?Y zvP%qlUMD~-mF-cteo$3Hm)02c0O|~8$_4rPPjvDN=yl3ae9Ft7G#5e;FJR$8%lKz zevHvUs~xg$w*;`iBJ&*6Bgqs7=#>~Ve*XT0o-FLj{l(QO8IKb6wP4J_ndzUw_AHh@ zm%*uBZ^&^u;_d%7AD~Lvb1?W(_p%xQc?izMTRPTBx~rIm`14Fp*ho5rkYwqCV2c3P zm&p$OHC_s#h}(Y{W+SWxP5d0pWa2Zj66ATkDsd`3zPDCZ(pGidF|2RlypJ1GE~J+1 z97bti)sB!Q@unPaYuM}inkn0VdJdsW__zSucGM;6k<|rQcMX9O)2L*IHDDT#l&cp@ z2@rJIsqqY12`2EF5U{#rDh&&c2qKK7lVw#aMg8sKPMhM&2#5H|4MV^^u$%M+@d&CK zDxv?(i`VP7>mqlVZXN~uaaaYgZS46B8S7G35iuWsYT z8CIT4h6Ydo;lL?h^0`aYu}1jy&h^bUAKc4-@G7hi`0U3>7Y+?=Q+Jz>_~F;f%VGWW z>}kXxHegT&=~%#N7AaOv=PuSM&tP9tP{pXSl7os0<;@Vvz8mH(+p1N!sv8h1EKTjB zFtt29eK8Dp;Qki2Ye?@G9;G}O)JF;7I*v@faN?=FulcQLE+Dz=Hr3GGf2gOUO{I@2HY-JVGVQVNG*8Fbxyw0>lokPu8>WMoz+|$B ztREod75)JLo-pcvgnGNu2rvzNSd3E6_0@PSm&$wQFBI2;|!|AkKOcex6b%bL?}P9LU28k7&J?INMd`neMdKC z-YD5+`4Jyg%(1*hDCGa@CP_kNphtis5SL<{HYQqMG`t8NdXXRd%$YOVC z7U|a3y1`5I*z#^XjejxBS#@r*uk(KwjI##{ho_QYp_kOD-w7Rysi8A@uFXpG9L{LT z5;7!G<~Ad;m9y53haP^mlJe|rdrv#qN?l$((W%r{bvsvEnN4c>)X0CAIZq{jdW=gJ zkr{-7zkg%?nViueEs=r+1@@asPoCCX$2UhPv6t7!(yP1_fmno-O=BQUwcUMndra(QRN>5cYno9V7>3Fq-8>^NGEv3ejz z3!_EGP9-`sf9`jw^6Ii#^LnusSA2K;=JERVj;GOul9FY`U&i_Ge1J6rr@NY%l3JZt zHwC?PkwRl&PTM_7OQ2PBik>d+Lo`f`^^6H>A{buoKD2qFl>NbZH2-}& z3~&`PRk@~-u<;eNtEfPNSb=fSb+XAvL*^e6yX}(pb$f=+ zzt%7*BZWuVlAifzGzi%ErzvdJ69N}wL2tkG+`K{>lRC{-Hes)>}b)Iw66 zW^ckJ|Q589U!H~bH~fMe?Ki=*J}(c$G9l^+W16eVEl z9^09}%O<{783E8>L-U>KnEqQ=L!p52b0xXIq2a2>H65$JnJ{K{;}17@lmf5y80Vk0 z@1b+ROgZB5V6nmh!*9nljGEnO>xBg@ipJ&1}%FR_!PMwmAos?c%G zF1g9Ep`>rdE&~~Z@1aaq95~}?N18c?3R9)vGzGC>2|xim#BagUvi0&aJQXF~o^)ny zdWr#eWv(`meZMw$NOUjNiJKJeFIX09w0{cQt%U;MKBC%xZ0ThZV&lG{%-p43WC|EP z4{#mU;==K@z%E)ghOQLmf3%Ti=iS}iuI9<18bd%XF{PLZ0Y^n5z>ad%ApP8(M{sIZ zI-bC}weP!KG`cu}roIRs)VSU=cD?L;%W9335$QxqH_T)m^JfhVk2`O+fnW$I0eMsC z<2Pg8J@$)(wbzI^!RHVuUj^IpD48I6TKS1MZ&$zmni^#{WHAQ1U=|V6_zVXW5`it} zu2IL8-UUHmeIR#bWQ0yT$84QN>Pt=-rac9#o zg5EWQ9tEQFhHP1p3gXu<57=5suu0naX`Ep+)8aCT|GHI+H8ziCeJ9B(kJT9nskdXy ze$O7v5!!txKD#7iWq#&sIL5Bnjd^@jGxU2S40xs5VZUg3?|LB)=Tm4Rf@!21+SB@! zgzkhx>_HOHW7WmK72q#{77{an{*?xF6#~X*;r5m(N<)uZd1&J;vfXMSutaAj%>3%( zGF~yKA`jE6J}o|BdjWZL8>o2}y1odC+~!UrC>3(W557ZvzW_ehhFj}oSRx4neNgOf z?xLB~=}y;hN2pA1{nz;z`xnUQbYeY_Y+KAX&ERg%^lJXqKZ&Aai6tZLd>zJRB(yoo z)VUE|!sLCq7gIlK2bUCII`#Xi^ocV}m#hw`2@bJ|uam|mS~uJ;cyA=#WBQ;Y%xUKJ z1ex7tGmKR~(ac#>j601I#(}@I9kyjLb8#Q(&rmbW45eE8&=KCXbN+sZ?%51wCqg!m z(;lOdhogimz!hGiQy%op#@fOoC3yB92>tu~_wUVT56>eM? zwmxRal1qPmOeck)=kAgiMofHYKDql4wpW^b4$uU344&QLJa^z!hJ{m8%p7v;<6`2Z z%i3s^d2>n%QsNU|pF|5?ys&QZUfZ0W&K^HB=nv7Pjun&l)(As6zdA&hSALUEGwR&f zIZS;yJ0{$lb8bdyXXPLHjAm~)8pUywyYls1H4NiJL&D$A<)96-? zE;#0#hJ~hl0*9v}6~nh!nrR%*fsqw7rmVVAD~+%=>)Ni(-OZQe0px3B@FqDeVtOjuLAFS zkwupgm*I;Cgq zGo`$M9If6Jj>~L9>Pzw-W7ZpE_~*8pWrk&q=%^G7{cIKpV@o8K{Q6)mGJR8+sRVk__CUx|C>b&F0)lJQZpzFQamsu8hI6W!WjQ~m&04*;*D`hodI3`q|=X$Jz45ntJ^Hlg#~8SJVFfQjb4}_XiES4YrH{UwaQM$40rt zEJ1Xdp+0R21xtmS@L+W3yOU(HS(z-(O3j~94#p#REdJe#aXD9y+pb}{8M4s936F3^ z1E~;7%l#50448hmG7SMDvDb|`P6_N%pT3=|;Op%#lKBdiEBhB`g1&kVtyysHlRYtv zc&LM!hN1tKMD6~0sESmSbbF10;u>9L?6XMywU;3j#*aiQnXmXTem6``n_u#gB zx%Vd}eS$6(tvc4u1CgM{*K1H8o8t|i`msV&1|xP-PS)QI56t&CQ86}puXz-{aQeGD z#w_1(H~FbL{82k%{}&#nfcKaZCN+;UVrA$r_OX?tTfM(q`=R1HEHd1tUU!LFOh%U{ z4^f*Gv|n68^y?y23(riw6nqRw)%Ff9Gnatf>UHkc6guGoNlO(ETE;T0#JsY`?m9zb zQ8Kj!PA$Tqydz`FjaW)7LVoTTMR3N4UKL4A9`owJ9H5YPceVhpf>=mz8IVSqLzs89Qfh*T$y`jFl3f3|b+P0`b zPj~QfAeA#p2saB$O-0Jbu~{sdS+erfE5T`F_8Kr|-g&SLt@RJLtn5*o7e|*1-UQJy zWnaFGmKZ+XNVa04?fc14KJR}cvq4=5k^j*h|zouX4# z^4bDZVQ32>KOz;owhq4v+s;5|Q|h^oXgG2_)7= z8N`nCvr#ebY!jdp(!rxN^Tbl@9fsj()w9qGcJ!iX`T+#by)Hwh+B?*i=fmoU^MDqq z$@&0-&}!|3O3BO|q_k3pOo&wDtXbRH))y9bEpUIZI!9R=L6cU=@g2PyIdaAZ{`LZtA;uyL4AiE-J=$`435T@SS)1w8qP#<;*1fKYSK!TTJvCnVx4SHD0dk`jE zKdz9~NAm26^7SmW@R3&{56^%6qF=645TE6ipg~XXCWF&m%7B&#${5h0*u1|jD7ZJi z3m-JU>D(pKud2*}Y;b=8RhX+pSvAD2uG1`#ye(~P;^F>db$$u2RE*p16EJoh{;a-2 zOT0>r1MAW%cG9d;fs4|?2;D0QrLHQWtb@v2MQM$nv6C(vtvtWs9^s*PmhoKI0B)Q)DQ%p?uF<6 z(^{3wN1|CN>I9W2(a1Zh@|@PFk6rn@|JETmxX8pK=s$71?Q4H~baKaQ=OKUFG1+{! z+rboYChkKX?=9L1VU9I*G1+LPm#G$6oOP}wa9lM}vUMw`iET;mRX;W03vhk@sEy9B zA2aBRv6)9mlWk)P8fleYY5baq-wig#ke!S3DD(8!jSVY?76QCueCza};|KPpO zFgB^Y9z&71YpR|irp4XobZH~Ma@QI8?f(d6~sq%ylr#;?EwyHukYJ06_~C~5x^do(qd zo)Wv1==E~J+TzSWc`}hd!pViYaav?!Nh55{6m4-g*ufPyS)#}Qb;P)XNP9d%H#X<1 zR$Y1)ZFjRsY@o#$C7YB4Y>ctyF_m`+5dnNulxgd)Tawi*%Cj}7itA#Gx&=tMahfCaZc9S zPGSmCQI0ylunDDpNLx{+q;ery@w6ddaDg?J!!$;jIU1TDKSYIXK6+)*oI+w*^q4zI zmZQv>j`>J-JPf594a_7nEJR;>}*0|Zd2^_ou|7XJc?fGUa+WZzg( z(8%p)Wh`RgP`Z-C?gt3FaIvVvGbene*T}Y%!Z;uu(=PGAXN+4PO%j$0^q&|HHBNA- zF8ANTu`sbJ$71;g#zu=F(|}%P7&(}P{=%Xkhs_6vC=5y>eQJ(yTKW?hQBnPh?grmp z6^Mg_ix2Gxd<>osZFeNZJKHy(t`axr$m;CDCBY7m^(nqDypT=hTLW-HykZJc)nH5y zasEut@=XybRjpd*{PCNP@|q-{JGN_Y&mAMSEXx!_oJX}n{S^Xb7Bh(=-nc0aXfD%} z_OZLZt9~Is5k}Z`>XdgicKq=KQeRySZ#CEs6yi4#G_<Zz32Q1Qz@fGPp;bf*jMQn@cY+82a`F;Nii4>m7A3aDYH`$_=@NE%cC^{?@lc39 z+ZhNFRF&}y8+Xuv?XOKnZDlEaD~$>r2th=rs$ee4GJoOjPYdnCPeCf>-`YR$vd7a8 znMsw>CDAuoEwM`qC0ZsxgaGC40_!zG>#B|otR1EHsJg$;}Zl2-j4a5N0S*5ZhMenztG}v(J-axRI z#|acy^Y;$_>={WuTrHqKq7;Hbv#|A0%&N~~j>*JLs82*KI8{BZY}N!(fVMT5H8M@H z7+mmBf*b+_>^OmN3;J(Sv-vHvMV+g8&FhA73jYlDxMN}M!`-@!cyXGef05RrrID`o&x%fiWF5mWRiPnU3IO$=_BZ?sQqH?F&fuYCh(X-@FrpZeH-T^}c!x-NYeg zi6p=(XVo|7V%SPyc};0PUsFY$c+{hY`14AW@>-M&=%cx4;-|4aHp^(F=D8XLL^baW zoI0N9s)7vO6bQvue81ZS7#wL3`EKTEtc%wfu4S;Fyx*PK??U?Vzkm=N=QTL@N5)JkN?%1+Xs>-r0Ei~4FJznvmWLS|yh;__V z2sodjLw;%{V&i+`V16N+b6-z#OubV?HF7_+*FyUq0$qyHQQa!1sWRK{Y}*g~fb}KH zy2qZER(oMs9&?--o`d4_|7!uJJE^ORa_IoJwFz1L=(i=XF%Gpj^;`fB!;c?^VLMqD z8*ySH^GNiK^Z^pRDd+`c6#C}kpokoaG@st5W_0_PT;F+p`RdWNRbs{g$~FDY&GCy6 zuCQ<|huM=;SLb*1d(wr2Qo#28Ekq&zBTkcE(OT&yG8GnRl$%1<-W;nwh81CSuyWpd zUY|Z?=4lGyce1OU8Uwwc|gnK z(qP&+@-GH)?}GLKyo_NyE_J9EUva02B0KkoDmbniQeltb$3_ZX&CEZ6TewbIi2wi@nt745Jr8(IElQLzjx zE_&LCXhoaflGfiTyB+cZ5St8x43@F8mVn zOQmJeo=@0;V+ub-l`X%hf`(^8+R=8X>7s&G52ia@b9{3GMphBH3C2u{^RF5u`{H{QrXe63Y>PQFGr0NyB6bq7D?{DTCQg0#Nu+`lA z%lF@bHEj(|U3-t0@cZAUVLO*{HvJL!)jKgC z(xC0kM&!I%lD5sVE%Tv+vMCP5+j%PAV7li0&+uE{#oNNJ;10Ji7HD`UWP7k{KbmRX zncVYF>wQEx>FRFHaV_g$TD@5S;b9uVd47v%MB~C>mo{UH7l z_V?wgc2duZn}9^{m}^u%8RojUV*n97!ZL5xneYBPNSjTvINFQ&6_8C-O1y8bU+2&h zAAL5uKH3SM9R-X;?6Of6y&qpVa1$h7NCoq@>}Orp7pb4TosT2@5M7ATL8e<4(s-Y! z#uJ0@X(&Mn7LjABvLAXHzCy9>S6-&RdPD;+^2wgo068wO`gjixeR;8;Ri1`$BeOa& zqDTvZj?7Pe-II9-`ZKQR4vJ{^D&NGUUAU+tm1_o~=aLM&sB$xP2zwhs9fdMPP-B1n z_~wZdTf#q8_xkkQ&26=>7HlsdnXs!{{Xu4!D=Y!aPUEOTIUW+^xT2jBcK1Oqtd0&1 z&=KGyN5$@O|B01t`n7qq1qysP3bC8+|GQ#xo;zvSB_XC0Z06V?_K6N(2d7@YiW&Qd z>g8AH%87mNOya>(#4#dTt++bsua$LE-@u&LN`%M9Y1n>#IjO5>h1@-Y#QL zyYRNp0zL|<=6kHHi$0um)S^@s`4Q3|Jw{w>x<``G$tLLLQZv~gU4E9NRR{I6Bd^DD$SXctX$Q9zF_LH-l4WD0CRE51v`{1k;ax4w7pQa zNc0z#LJh+l=nOd*3kG4E6@uc<$cpxy<(o=Ebm^RDL#HThJNKHECs zYrhvC?DeVl24oeQWSu^WdS-|x&r`+d!gR^lKIT9HAzVo{H_2{@6|Fwf-O`zln*hxH z=Nw&$Sp#~*=nj}4EyV?eY?8Q$bA@E?D8KGU9h&a%c>b1e=@A4b|B-tP3Vhe08%o0G znhYGAEg9tR#9$X%&TpRG&s{Ip<4Et!DHm7NsnQPN40Cp7z?}Unjue2=$%az+2|cL< zB*Ulz#+}v8S;t{)vM{!V&qqscd5G<84d{|cPfEdpYmi>4-^V3hX z`Vy9^RoWD-b$@ZqQ^ub6`t3Pz#q4=4b8=6uc>4qHU^RCa$}fP8WZyPg&_Say`nKeL z_1009{ElRgqq;I^=drYOK4q(3^GBXMU)&tDWGZ85TWXl(SS>N{`M#3-v7?{it^5yG z&D(~t9^V&&+|f*aIh}L@YwRQJA5ph!Zn`wdGQUmJRw)T|tFO{mI+9+@X&&`%K(|En8luE*F;{00;TMt5-FkVRI23oa7>X!sGr#<}@>` z#3%~pewuT=4;D#gAP_IncxpEvJ3<4ds8p^0} zdZV3tOXQ2EIL)8QMO|gE=QWoE>Y?V@`=Nng6Em&Rfz6Ux!~dh{tb^L>zOUbw(&FwE zid%sK4ekzw;823QyF-x{CwTDS?q1y8HE4lS+)8n$@ZRV9&X36-%)kV4lXK3#d$09b z^kt^%X92-~io%D#(6YZ}DO)R8TiM#jM^~5_CI&LIpNXHQ0(=J?4aXtld%?~UEbdQ< zT7|6K8Uwi8}T?FZzR9?jSiTpHK zxNNk&QhjBW1G-0q#8VFHj$WWuocIDWXQeFkf~)H$`Z_&W0du)tUl~v7LYam=zWP7X zhH?UP#MB&E)LdA0hdI9o6K*JZi0A4(%5>2(D3 zAw-)o38_#UZM~|uyk8ZdSr3Hf>7**9R0b*EN?F%5JmY#kfXmRV_L}vEwZO>(H4T`F=;fHEVjk~w8K$qAc0tq^ zTvZ(!F!oqEqEzrG^YZ2+4Kml%@GPNoy9sWJ+(3Vge%ZBQsQq>y_4>m@Lg7)TYuU}z z+1f=(PP5lM`-6q);HFlfFtMtDdV=`$O4L3iVbjEYhN6NJ(D>638 z%L#9gXv86H8J1W0Zcr837U0&(^u;XFb}~CGe3U%`RHBu>Ulp;zyTA6edj>LT$I}aH zXmGjr>8?Bb*6BGaG@{LBf=8zD)2}s?U0_ka}UYb!uq z$SPrR@lDerXGv3NXkgym?Q%X8@z~dQ!QRclIY#2I<&R6hd+Pata)vle+qkC$Fy{DZ<>P`;bFn$Q8A__ zRxHqA=HxH0djcUkxeZ^#GLP+Bvmz_Y)*~_=YX|R&#Qm+3lLEFy38i~#SQRxTKPpHu zGfB%(yTID}S-#U0r)Ilwx_RrckTeFF+Gq$Nb;ZV^;CHVL<-TyBEimr4}_?~wdf*7ZTJ~e zV^YW6Fb4X#z>5FEuG9;daJ;2j;rMS}_L%gznAe~bjWgo!#zY@N$hF=PmM`S`ImOCi zTUx0{51fbg>|iRTsc8`~(G)GxvNMtvc8z&Fvp?K;E?+CIzM^RvxrvqRJqVwf2zN&I zH4HK7xpnD2xC$KpnYY$9^jB8)53lg{EN#jC9E&RfX#y*QqU9SKnCctTWJqn%k!EhV zgjOUAdU2rE3}+%9J$fp(B!he}-RJ!!mgK7Z1BRkwqc(Pj!oa;2zQ#Ze`*+o$Cv2x$ z$kOj{-lz{E-sPv_veV+_=32ioBb6t?`H2<791s8QW~)J_se>5_X#tin$uEuYEsR{7 zlGey$(DKg?g*(-5b1sGnhA4I=zUn;!ZgSZX=44*QVqD|0-(M&yY_eO`&(Hdp?=|SP zFQ6>sv)?v zz2t+ugp(fv;i#Vlj5&q&OjzQ6@jL)fl3&Xf<$q1ear0fq;t9aH!uS?D)a+Zr>`bLk9VarmA!4E!)pbB28v$Y{>Y~ z_y?@CR9vN3$$$e@rhhp+{pjUlg22CI>3PnXci3IaMMq(*{ZK0&6ObZv3O_SLr$c`E z{aca;dYV{B^hZ=AaSOpY+qeg!Mwl4v`_6B7f!iyx&Nmejy~|Nl7?45SI}@d5Z5(!d zGEMwBywd*hDw8A)YC#Hw9MvrR*nF_jud z;rrQ)C~o3a?*NP`0%s$G3L`BHw?Qo~$u)2}g9-|fQqbDSSQawFg=lN@H3)R3Y=x(q z@tcZxrjfky0s2>#X7I?|&r)?JoY*zNk}P7rW7E%P{A!7$&KxEpoyI~3vvYQM!i1dxDsVFlzFf`8x z{V08Xv%h-&1nJ|*4|8FpzERlJjA={-Vsweh1qjikxERwEQTyVUV&sBI>%E6rD>hmJ zf1so)@4YS$mToLSu^6{_8CewLXv;UjrgIg(z(kK#q$q>On^eJ3>-JW1etI-`z^!LM z(YSnT^MF*wIF}YTLaKxi-oa35fjPzHfBl2C*+BAO`g!JYlI% z?e&1mXFfo$bvTDDvbjG~eOqFfdqo{l0*H#({4FXFpx|IU{ISxlg>pACqR^*f(>gi} zPHdDuk? zzp^awPBjmkTpYhQ9-fi|Nw%T0aKP#O#nVAK*g$WG( z%eYV@0EA29UQVM2g`qSAa7+sDKQ!tgA!=;m@#?oxviO5zgh$%uBBV}!9)n5qGMa~T z?wAVSb{9}Ruv(sfp&4NCXR!kkHrFh6dEu7_foJoHM@#)H%a(h;^#88^ooRF*C#-nM z#5^1B#c%H7H_$!8@#WPfYS0*G$_Gr-hnN4pVtacz#&%Z2c-ksFv6|gAxe$`QXQY-X z^tDO(gZ~LmP|1EQqS_F^WSCI};P$43ub7Eh-%J4}AKJTZWH#BpIgs0$Sd;LoPozwn zY=C1}WlT`@o4F>er8W7q?GGq#qpHD5mt-C-MwxQKh=MgWc@6naJ$zpA!#AyadCm4V zYm|a*i&0^m2ba)D^=SC`S&)GHhi)D+?UgWX$fVm9_0U+VmDl)zwR~O8*?gc0zlA0V zN_hzR+-W+C2m>}Hm^mxfiyy)v*!4RPg_-;f8EW}V;tUsc5~+1Nu6cVq$xMTNV7eyR zu|l;W<^+lrMf+HXN?{^nMxpC&A9~D>;39h5jkuj#sPpcY{jsyt1NDuE;16MZ&5<5E zJh!IhwfCR06Pad$M|O}M3UUe*il`G?BN<$_5257q*oITIn4}3mU-zc+tm&cfn1RhMEDkqNL3#-UGk->*we7so1qkceu?}OjP>%G zHWjSl40-YHahKMa063-%QA`=5s!nc^}wW-K2+3YcwLJxsp?gGpb{T-NTA(P4)%KEKHVo z45o8_{jKY0n$qIUIY60R=FXoFX|a$rG@ezG12K@kYdS13FtriL|;Eqe=UDGrYgnPwQ2K0#=*D%U#l=? z=1)B^Ou9&%2T3>{G9^b?Sgq4Q^c{lrw)l^h!#93Ib82c5?!kW`@=8llRpb*QHfq& z6Ha`)Hgz;$uDpTZk*m0~_Mn8Mf+Om!v5Dpo?GLCv zQ^#Cj;cvCq>64`YjZtJ{zUd>1fvL3gz+!Ehydj%~qU8sz2&E2$art7mA3cqG{lw;d zVkGg@?QMeTASYdGkonzQqX&QUP2AV8uy)snZ$XuBF!x+PNpcl3N$ehlb9^3wMVSaQ zPO`al^z^KWV0x<092Jv>g0cF2JSI;6gcE1CZ{OODJJFBKrNf_E#bz)-hyiCmA$2=g zS(laP2+Yf4U}r`>>%G2Hteh8&?g>pP?pImJR)g%cKpb zF;^NFWejA8Nax~PACRH&>)8GpzFL+_yyKd3brF7sW*bS4!23g%rHW z>zvy7+O@f{Cj8gU&rW}64pVPx=#wT08OBE^kGJ3~t_5G3pp1q~4r#_&N9=H)wXR(1 zVl`&qe|(#fY3StaJ#n|pzZith&aT8SEWEihwkISiu(fY8S_hi8i`D56AGi5Hhh1k2}T+MR0kYR6f}bNUvpi3Ihr*LkMh(TlZ)8o_q-jF?}7 zkLWMv;X5>RQ(Oe#!a2fe(5RZxPi~>9;=f>C#r_$nl!WyX6Mgz+EGz9m z@3l~%Of=llRF^E-JeQc1fd9ySoaK{h$D2xnbcdCJdW}R@x=!D5L_M=CdPokUP#tk9 zHEbhb#;3!9su@-Juh*vP5SNpa5$pBlKT|N|WNMFP9%lWr7XfW}IsyBd38v`A-s310- zjG1a~ZQnfK4D9(0jU02GoQmQ1zl$RN7{ez(&c)73pgzQjme+%8Df`je*=K?&5v5Ox z7tGofkyXvSx0eAxpSV&#DTt>M6>S;sGq~@vRx9(1ifnBAOz6Ow08gg(>+j0-n#C*D zo4O2D!*b_=pa>Me9bjiP4|jXeC;J?lTe97o+v3{2pcSdq*K-d|TEiqA<}7|MytAM1 zQuPAsN-L<9o@t>zeLkLFy-@aHvQ6lIqHT4>cE-g~3-#svWlbPfCLGG{vT*Sq-(&d} zK4Lb?afWgqwi<95_w|87pfeEuG3}k`*8YHkK}KxaU=9SUXh+qyk+Tl@?lzSe2pb|} zO*78{Uc!zs84;M@LWFPUc0aM+SgJs~1hAY5-g2kN)Q9Rj8kPNq25V*{RH)A?4jmuQ z9yeI|2v~4gvazDA^nIbDi4NCtB|@Mkn2+dK&x*DW^e82G82Md|?%zl?(40%7AWM64 z{KGmH?$*U+RYT*c^@iFQ&9(l}<<{vu3!-z@)X;dO7{-GV%D0-N(N&CnYveea;|)%8 zXpHEkuQ%^!;f(tnnv6wiP);uVJw~}L*VyKeK~MeeQMd|7M~?YIt2+@fXF?lexvV`w z)LCTom^jcL^1|4t6%6;2FGZfap>%Sjs2?Q&TGnT_ARYUkmEYiODqS>@YF0d<>xB(~ zv!;SVz;jWmrIq;*7i8_Z0`fbGRvSf=sORY5sqBo|;3=7+h2<5zU_uYJ$QR^>S2BFJ z?WAtJK|`K!b50lbX=_@tZ3Qs_Xh<~@6h!_n8`T?Dy)Bv2)v^tD&A&|SJr2V{>^Pwz z#;Mw&5nKDyC-q%jzm4LlSKla26l>{mk{LSlB!&N~_Np;GT}e-Mlm>!}CGgnOVu!|) z7crEx&H&|-maUrO)&3d}hwaLx7HLafJ{d!(#paSgGW+s@Lw#2`WQWD$Yq|x3v4)2x z+9Q7|*@Pxgn8;b2L9rr7zGEThZ#qd?U>*sHQo=$^;33G`u3CGiJ9HbJ&CPgbb9P}pO-wtzg=$aB5k0=aTUp6j3!q-mU{!`sCsDb~< z3NZ@~*355ELaE1-Ue$=h8!Y;G^{v&>xRVDUkLG~86fD^Re!#_j;a4Y%1fojg3WH5M1PYON*mnwK)qJ^kAdG z=fB9?b;q0(es3MML^SwffkE|52|wR``T+CmGX0?w3YRaXGnndmuRv>JpX@=>(nsEI zf7^#Tq@}cdUT3nkQe<}n=3m13lbNm?^2n56fuaL+sY8y;T#e=cV&Weq#x_}Q+0FKBr_&)SA%rhvC4#mJKK|t4_yMkS1>mc8;n1H1>aS;e4gkj z~k3ft}_5v;bTX zn2f8Ib3dG|z{J7gV11QAA1_RSNLAkC^3*T0D4{0Hz{z`A4BO|@4jcT9iB1i%tU(4F zCeP)`{ppn@QG_li+IPRiePXT5=%S{wb=uP08$hL#UUW)Kbh2~O+3O;-LBMPV=GpjMNc zcLAIot=n!is@VQh`C(07&r0~pUsTMM(xm$@Y?Yqx9fh98-aZ<07@8F&GOL|C3e(1%W0}H(OlTET# zM4^tgJD#0@&J)qcDU79K$mR0Zkeh*_8E63?SGPAB$XfgtoZhyaUmp-Ac+=#3%as{D zl?&N7TpsGEe(L;-dwGI;X{hfR@D?7n@%2wY=Fhzk;{vztHf=X8H!ZPdt#nXI=NvQ2IAJ~llP7poa4iY^Ncy=G&wi&%VrNHuZtam*Ux#>E* z_5Ag3bocmWZ0DsqIid=&A8>cm)^XCqg3pqQ88}G^RFJD>->)z$O>z%YuS8aWhhbYo zpvj!o-vz6`zaG*r&X`v&9lC~6Vpor=+h#d*zBX41ce?HWY+81>!2J2RrOHo3NJ!X4 z0#LZwQ?|$Gyl0yk%0-5$P5A*iRe-VrdJPn9TYYP1s$)6g15Y0Gkc zFrK;g^Ih!abm%|oXRt${{QU9o^&P8>T_)>{rn$P(L%PwwV7nMh_pgQ?w1N8dtRtd=y@wQPZmXqZLhGc~h4qpN>W+Dpe`h4LP|K zF)TT|6FlS8Yi0kt@vEB;H@rfwmwSwZwx_31Y{FuEcR{ATvh46*bbMXGI38?1aM^Cs zx5J{LPA=KiqMm*X4(>y6{`ffKb|;8i7J9Jg+`+9x7k|WDUOGAK!fUK*g5OAW5x&f2 z9G|9bfLW|sOqyz#DXV&hU&|~P&xpF=G70#TTlDZl(8iXd?tBM)Gjrf?idZ_eOHPQR zR6wBWkdqM5I0orQ?QuqoA^K#Wd|a4sP`kF3-;=<#F94hS#< zDUG;9aA4RR3;2V7lh_94gz^$s)Ds>xL_5sQ*dar?H!d^EQ)GRGeps(+#m9s>7Nq+e zmjIEyEb3-Is0akCpBAP_pTgzL(h{W6cM+V6`M3xU6T-^jWObP!)P(NB!neHh9i1P? zRCBBt94uoe^USiq+QCS>LBR>DeY4ykX&N)7_^Q-sttd6(>iUTVk1+qSo@ti+9m|Mu z$5BzkPb3p*Y?3fJV{TGTQe~2fpW2w16B?=kJwNjegQqbrcVBiKXRMUlCLaVZ9mC$@mpy` z{#z%2?9!E^Zf%5LY`_|9@={;r>j8r(i@B1S3*Mx-PURKD8O5jt>IZ17VcYM^NBGDl zEFn#d+YN+F095&;Y8TTFg6(Z>Qy#@Kj4IR5GewAXw9j$OK-UVe5HHiwCzDm>=Tr=_ zhSIW!`Pno^R+f`E=4<}bSHU>FUTU-5n1^R%=yU2AIE%E&%wxI{5`2cz<*HEpxNd9j zY8vw>R%&xF?ko)TNvjAiMq)R_N|m8H!hGirZYAMrZnya94#-tkO0rf&8Iow#R8`L+ z#Z}!iEW%=r)n$zY-(2rSVdSQ1R|?oRzJqE>vZB-~wo=hYah z^Tz8~-vir~$O6?JTR~Oz@>`B)x}Z$8;Pi?t zS|F>^)IY&SmQeI1z!2JL*nhXWmkY_i;4n!;0}U1bTFzTLD}|(w>O4E4AZwt1utF?= z3Cd+YDMoNbsAv#`fOjg|U#y9HzS4<)F~wQ)qX~ifQbm!tyhZkz0;$kr_;`KLtSpS; zhjn9{n=MxI)AjXI&$V_JwFSH=MSSpf}IG;P$%G68P;Ra-v?_&=X z@c(UH!jH6*$p3u}->q-{E=C+_`o_u?ye=@i zpyd&ju$z79f4J*+;@j9&oqX%x@~;wjO4-6u+|vI&H=Q{|E&0VO>E%bQM-sU>dT9d{ zVEAQVM{ooP_or2p4B=S8!F2^pXy-JHQ|JXMz}8pwjQ5}md=O$4f!h}MVHhyItq%tJ z8ii75$kI$qWq?RVJNbJVlx3qRZ_{2nIni8+GAvkCB4eANEW&!3FD9h$0~7DO*)J@* z;Xok;`Gi!ysBlCS=;QFt?sB0mS!)qhTzZ-(b39Xy6-jcmIXpEqwCu6})2SK_0_dWe z@}zUZE95nag{@|e8%hNQVpwt&rx(I7Mz!Dif+{MlR?74ijQWh`(Ul!?I_B!F!oq%h=b8r>m`wHP@) z!iJ`*AT|_#j@#NT=ch3#WZ9?;Yss=)ot-D7&9*%6?M^Na7BR+8E{hVXpVp{ussE7y z83|_6d?I^?xAd{u2KYKF&0lZ4&F)CoJQ~CEE?H|SMOz;zlo_J_!Job7; zQd){~@hZu+l5q)%Y;Nx-=3C3;+U$oy;j;ZL(VO;Xr`gZESgm9f;}tV6ldnx~`1Qovzj0H#`?Vt60!)>yF+ z;AFo$?HlsF+|1ZR&%U3eK3Nsserk-)4`OwxqoaXx&8kUa-(Q}z_Z_!|tu9xo*8j-1 z%ab03aVg7bNfr^mzt~oO?@WDDi-r044=`9`Q3!|K!jF`nGM^utx=zE4(=%_LLjvxy zF##7uso&dy);h6dWC*I76^e9+YSz=!{Vl1Pd>TF7*vo_q;NQqrZsx%{BW928(EVXM zeg7TnpWlC3o)f%pI`eW4Sw^R3hEwRx;c71m^YX07%1ZLyv9S1Ku*hzs$0vGA)xG2N zJ)>66!sMq+;rrTju!wm$3cVT_65?@5R*}~~K1zgJVTii1?lfEt! z^E-rJfFn^;{IA>o+F_mwO(bgmR=5?X>B5Rd+hVS!tJ6FD3mNwZOYcSWm%aTiD?b{! z%vvpkJANPj3651)Ip(PZ>`(zi#TLxNT*c$~3kZe5FF+^l=^M7C`XmGAfvD)_Uk|aV zd4IA#MO9p_Z|euO4eP~=UL$TgaaE?XdaxAUm9+|;)orh?r>+x4%J`uV7PUDl!fs>v z4t>}~<|S54O3^thre6cn9Zq4=i3y=VKD}ByHzX5TI=(K0eYjApmbJZGdQrpQL1Ne3 zAa1g#g1!KtCOj;aLGS9@TRyP(Lo{NB*K6dX#aNBn2zH}LmEKmw~ zro5s2mlfbcFzv?8L-bXK?=iT32zARcVB>C!Gj{6JA1&f_PU{vj0nyGadIG}vQq@n_ z-v~XgvpCt@LpL$0S#!VbZZ>)xytimyL9;q(wDu`-b#~c$eHoMtg*ZDs~1Ch zT;uz1-~jTuhX=Wq-wS^~?IMMRc#Q>j0UGuY#p>#a!cc?q+!mh0sY%>rMa7Ehw~7T+ z7>6LXw_r`qfWsn9jYlLEewu9A|6u`&d} za1*fpwaTl2Gc`2YkrNZmCFP9dCG=n!a9=iDa1?S)oB!_kJ%xJyQVq z2r)(#anxJccg6Ij95bxM>VzetAIlFFaO}pHz|9f8dlYCd_qBnDtzRNd*N48oz5`=J z0Xt_Ke%C%Po0{}}dz7uDpy^3jUG~CItVtr>8>GOF^>hE+JYAlcBcsFh0pFDEjliq@ zjImsqnNzEu!uO)1?Fg`8S4o#6lDQ(0GKrpkT{2c9sO0MNpX^rs07>!qP{of^Ei9V7 ziak~yXW(C>#?>WWD?o)hMQtulTCHtB>HKuboULaI!qWY-X07fDas#U@fde}XFNVFs z46LSCZw>_J@yqizE5(>l`g-i`>I)n9e^MHBD0Qgj@9tZTl5_q^jz02fj)~MYoYpBU z@cDLhXvJ$on&p4uvfvM z7A;<_(QM)+hehy>b$2L_G{z{anMnKQpB>KP`WFhzJ?s9omq%~+7;!M;T@q4U)g_u) z>6uudd3j|l(B`{#CZA~Mh4h4rQ6DQ!A4rh8jaoXKxo+Fux#4$8w{bLY zv6fX$PP8jqu|5Qcw56L6NJCVTsc?ZKvy6oa4Fv)l`UGU<#>B+5s3CFa*b&pO+p2$H zVd+d9#l6G81L&7J9Bq6Xe+F>(M)ZFgbbIK&OiS4Pc4*}G*L6v~rMMG0q8zy0<3$P1 z%NGR01?}O2WHI@}XN3QK;o1XWLLdYqRLoJW74br) zfI<&DZ2XPlF|XeRThPi_EcgXA z59vN2YBq}*2d4S-#6ur%Z%5D#===npUzzUD_iyQ3)7g#xG-1%hSGjhL znugKKd-uADI~Eu%%U?QYaG0Nqy4I7wym?4J_VMdAyaB*)zs&2zcA4b~a6@sO;p$fG zjYk^-M2&ED0RK*aTSW^~lPn|ZJlWJC3)NAfQ`r5&m>~=hMzWRT>@jCn7^Cp;^p}IP zOVI*dwwT&Qs$cEQUr{wXLmgVFUPH_BSkRy}ICcL4Y~SIA;2LMd8=3H9b=q#FqH!sY zY=#5DAZqe4F~?u|Vj}FB;$$iqi7{f{U)&y`GyKBx_lxC-l2^=>Qg_H8I`c^SR#oB^ z`QI|2VjctJYfi!>E$|BTY(3U1VyifyV5Cu1AwcSz zyz1}9taVOEG`DPR+bmdN8UBQz(sloEq{E7K)ujNB8{ZuLoUrDnbe zW<`TkEl5G+4bVWEIUJ_K`ZZ9ly2lCkv_P&{6idla;uH+vp6hc;PMc&v@sz>XV7oIE z5T>;==&(Vm@MrM~%5uwD$}Dooh+^#X$Kp)9M}9BAzuO18AtwR;J@M=FR))yKQTTD#%#g+%|=w{#pEHonu zXf4j01Vt4VwhPWmPx@SQ=JJpNfPiA0fm2AYh7y-9CTzU46ccT#n+g{j!9TxB9GOS9 zv_z^ZqAqQky8gxHaO|a?rK z*`S?>DIWwjhrhX#dbiAZR1wTtDEBE(W5D6Y8W2vMv^Iy{_i3sE<^FBf5=j9Xz&Z!A z(B$Fja&gd5AVVe8BjF1bb6qN{d^qeKh#zmRa1&@FMjh1b4*WjXxgC zE9*sj)+FWB2?;|&em;|9<#Aj~MfLU4)jQo+xLfAEYNa!6H{_JR4xQQx6F$mBg-O22 z=f9BpMl&rXPb9tFD|7MF?)YTJ)(7+sd6s+Z>>FTnj68!kYlwdWsF6v?Gj`oht!7Cj z1Wyw_L99#{aaVs}^_K5XXSPy=ly&UZo+-L`$lPohim>YB-$TW}vg?3Y%`WMiNMX-S?K1Hfv3 z8MKkO!Ad7CsftFxmFFH~!t11~`{&qx<{YeNpMWCz9+L#?jUHG6uaw#iNrAXz9EI^q zRMCfph>KR5r6$2*WJt4-@OxKxZj(kORP<>OMPWN60++}kUmAchBAjZ?WwI)?rzZLR zuD^%?q9HBAiyS9sa)RKs}9lKF8kSSMIy-rbo z{s(qtgY#a!`ajp!KN^=c-P=u+czi}i7-PN9T_*4J==qikoAis->s2qJhpotpgIi({ zt9kVueSnUBVqEni+=_qqexFl0>)n}r<5;FFnpUNFlLK{q+|?z#9Jr_{`EeKR6G-zz zr(l~HaiMH3a-ccFz`B60m4JJ=j5>rFVz*#!a8lFMhI++y)kH&D0i3}3E>gdwJ{KsC z)FYQ)!Ip*S+_i$s=`YS+DX8Kcz|A_0gt8K_i1k>-cmZ#H&Dqr`erd_=GOfZWD~$oW z_9XE*k!_wL%$7*2eo6~boPUJkGJBPHXEi*}_a-1Rr>#%vpXSoc$}reBAS(ellVC6_ zWEF{cT<}m-btr}<@@wHnPfDlfUzBa&w{0YxdWN6)e8$59T8vEo)ZP4&{N-I7>3W4) z{004ucc!0fip84AO6c9PYm8DAKZWeJ2gT5Wb7GX4&x9L2Y7%b!Y7T*swSbFH&-@vB zR#*FPm&zOg5&wze@z*xBM%TaiD>`CMH9v|53-yaa za%+Dq-fVkL9E?UkUil+`z*AIy57d~BBk08t>r5nfefi7sS=qV8ZForD9OoL$%Vlz4 zj95st)ePrgze-ufmD%mP+BgJU46qq#mcZ95X;H-4;@{GgVfNTx!b6I{L7jPomFMqe2)JiddNz}%5bQ8$C=qdP+=kbyCwFOqxHB1j-LHTnsqG z0-7wo^z`QOajde6>{ZR}%_e+g&cdd>ld$q%rOLrvwcmu{wSehBddo8p*gb>Xi+6`j(=e+0Zsr9dJYL zaP{h^jg){-ui^6%>U-Zu)b|VwP=nuO>~{!JAXs$I7xd!f*NOM@nyygme76?e-6j9x z)NTej|DLnbcr+~yhFhEDP2)u0P8638$Guaub%0OIsGBrMWaBRTnfU#?una=`zfVs$ zLam4`kGKT=$28IBAwzxS2snQ}8;Y&E-A~{zg$&K1KYEN_ zB|HxpineZ^4d-0_6?MMp5y8GW(uUHJ2aG2P>=ddxrEM43{Zd)K)gvaoJBM8qzdv6O z5Z+W=Hh%bPPbt*g=bvMYi$C=?@lD@Yj%>z^E%j`ch( zUME5%1x(bh+!fCP=4YF5Y|1X>;$7!9gXh4yRG^j@B{!3auS}cTQ~bhzwAz0G8cd+C z--xOe+*$CC)oW#1hRvIG&oA>c5~D>cDV4G$O3RR$7eHjR%9wa%l1iCHFM_oqSY6NQ zEchunn)!B@PE&PEE}jo8&go~Hmi;cj$pir7PrqwjfWVoH7NK5_Kc{Dt6GXiBNs1jwtc1rw?x6Ch92a$-zJ5^i`6-_CB#&Ov-H zQ;9A4O>30{Y*QSn725vhP%~S_HKl_NMI6c!E)F5(R0I@#*JqF4x;>pMNTmP$SYNj3 zzx+d*?d#j`Jx6uox%_j*#I{WuAs3#{Q|S=2iLFI;EsFTuE7VU{v}Fj6xvY=V6Zl%)Is#W$*`0N95SO?q~1~ z3{ZA=1>ZRwPanHm&mV&W%o8fsa&ViQ(KEvxFC3Ve>*96>&|?gpOEGJ*G| zL<|M9Z$U*kw%fA?j6dd5)A225roh0n^vjGk@X_H*qCNKx7DI7Yzmxtn9W5X(oHO63 z!i}?Ek{qe-xKYBX7;|^KrB1nekg!^A`oB@3sIHkznrua1a0v*vN?zCSQ!8wH22M93 z7YWuZXZbarn9tOZV$nJ5SpmwnXa^exGEj=AWSRU0Ekljl6XSDO3#2HBc0ppOK3b$p0OtQ->zzp@uXGwbPvN;fUc7Se>5tBL(NNMyN1=zV|C7IFP zsugZ>w!haiV0tV&d~HT!GHiNHjXu0L9%}gxKs35p;m&s3vL_$H~dOKBwWah zhi`L#06l90V>R>bYU>fMHrf4@y2U?r0?hd{U^Kn;_u*Oa`P_f2p{_OYn~Dm-e*vXe z;FmF7$MJzQZgwj@XYcHWBvdtnUqM;LLi^7WN6h-o>Zr7cq<|*rhY*uo>NqOXg~FhY zhM~?{g^4Jfdep5MXwve)sh*x;OR3$pejJs0?|jsT)v!^L+MK)I`T&9eV`p%>@}zF- za=%@jh7f6Onj`Vu&XF3@=&L;b4ZB_|KFhin{Dz#_Q6yGm3R^`|+Grt&BG2+5fKySW zhmS3T5k_sROnpl6?&M+rtAE45Sam~Z98VZD`gD-?e{Fu?>2KK-1Ze#17##X9xV3MF+ndTUb@sjKL z+>eOan`NY)1hBj*$<+nwxz_~p99L4@`%z3aGn4CCxOoEcL*m%*@Uy@f07SdJ&5i<= zRv)~I< z39Ry4aaI)6-1uV+&U20=(o{P~XIm2-<%`CqhN}w`IC7&d7dMV~nd_8z&SH?;&`wBB2;nb*LWQ%T_^4`yDt3Nf3lSq?Vh{_cLLLM(%I|+ zvunzpYxb2|X}evGk*EW&VK-H^;c$m0g->WT4HAi;>ULnu66zyZ#v};)N{=75bSQ6! zP{RYib(5(jDOg0(M}Ah_Z;1RLmXr^TGS8J)m{yV^@mZ2kvp|MaF|$04hn2lB-dcL8 zih~D1nl00V$g+TIJ&KXV2+Ml|Lc|ovnS1Uw6FXVIR(;mKOl7Ongc>gv)|lpX_qC2N zBk1K}YS!e@z70;A-b(R>+bC$%wRz!8PNeeU@k!e)MUQ1qPx5F35~JUkqEP-Jd#J?| zBYSJAz9KsMlD1F+#57X%4PZ$=PWQO(luKkAqG5Z_6E!sYYHAcp_!VAB`9577y3*H= zq>k)hzQ#SCVE16XlSvOPQyJqw;4+8EjdS!yOA4)vqmAsHv3w-IyUVezWP-x-SWC;Q z@xj%|JyuK%rbUY>mw_ZrZSpHuHj77ac-M<7;VUu;xVD4bSKF|TAYp-V=Dklo2u*k0 z%Fh~Eu!$kM!tYp(%c4Kc%PF>0Pm<^69y?TkyhkqMG~3`Ud|q7;D^lC%;XU3}44H8} zq*Y8FUYgBmnG&>y3>fR~xC?lv=}ah0j!ljM=}pH6_G%x!SfX*nx!`tHq2a^7snq}g zihDti7aaNCzNV#P%pb67q9QiFJ+T7fqDuVMJZ+^^%*htMF0(kaQLprgOm_QqF$UM7 ztth(E1=Er*4a&2LAn*t@P@=s0*T&PVC~Eg$q=22>aor;7>2PYa42A`Bq+TWV7mb4` zvpLi0qfaCsQ;7o6@U2r*i^Nm{Syasc6l5vas|_z-;jU#tY$FwKH&L_%uU0SPStJ9cV=3}l9(fR zTr`hG#+Vn~#SN4&XT?Z}im2ms@)bhL2)wo8*i+1`l^~jiKg#Fl=6oaPh~gJ<)J$4M zCNhz*{_44&KB6U?vR4(aa_eKH#f>vWh0!Lz*49lg4>Vjuxk*>UHfoO!R7Ga(AH~HX&N{nh=$3 ze(891t$|i16Bz@N#3HHB5&b=mcC~&^>0iSv2@ruhr||NpV9a%zaBwiYwo)iYbyc(8 zlD2Aiy>s_QCKAJxI@EX6jKgBpL;fAHy4C1F;GNm1oq%aP3J|dd{&e1+!-}k;LWJyX zphiSb^O5NsmIp%V#pJ9-b5&#PMM#HoEnI~LsQ%;6J3OKy z3dC~P#Ku!_`2qJBP*VwQSS<9MW7xTz-v$4=O0{+{1>NwsHw^V?DURW%_VzS>DRo|B zM(JqW--cIc$Bi?N6QdK2z~~@V{>qNJD2}cR z7kv|gI|PEe2WNu21$TGX!CeBu3GVLB;DfunL$KfuA-MbP@76hWf8Hso=EqR5yQh2i zTI;bknL^znWZc~kL6MgHKOTHY1O>O16-~wMbO`O*;sFA?RDWL*i>-w3;0h#)J)5=N zYwFT6_wr(!zLX0IzZpSSo&YVaB)~XB>O%=VD;PT{ih@NN7k|t#4k8Xo8g!NF<|^T0 zrkj9^o@8FtmCtYwfFMCZ`7<;rYH0;jx>NY~xh`H$;hX+9z#pVGC7xOPQ-G5u?k-)2 z=kntUf12dS5N#>8N`1)Enu$MUPpn>6Pd^3uS7#veytoziyyKeA;ZLc#xH z5v0M_!A2yJ0|tHSndYG3JEH$qZ|=ZdzLfcaP^?>>&sq&w@g4$3APDcC)wg zMIbs$%B#V&Hx*OQ4^4*{8L*GO6D=O2gY}AD?%#Ht4NTyecDRdX5$c$*Wm#q)liv1G z%bVy>6MLAXQgI}#u?L7VqT`m8!&mTWftatOV`@$FaMJG}LS}{JIE9+lR{s5M%V9kW z@}WBzzo+`#i!t1zcJ{xLb`Sf6+5O3pt`f7cc|)7|`emFVJ+VagU_4NU z7f*BxpMJLjP~-eB<4<~_wSS6FXy?!aP)P<%SwtD|AFRwDW*Nk2EwfecZndJ>uaSY> zk6bxd);5gWiDz%By5-|lt3=GH>dE_0T&7|axqtYL4myrD++6Ic%LSeDYBh!JdObAt zJP=S9T*E%P3cv59?e2cbGEhkS43|Q><;~n>yVJs4eOUc+g!&6)r?=GKWJe@c2ti7w zr5a6GaUEj+V#Qa|*eLH&DDw5{Qvb_1)KOle4$oX6qlD_3XM8_O0-&p!?Iol34LN|q zVIq4VbfrsrIXR9`I}s<^unO2hHgzk%5Giw6Q7-i@8>Mh@AdGZNr|Hurj4B~e(Sj+O zZ1*6IEhE`ql`=&$pCw>LmDH#SV2-)M0eAG%@MSkgV)W_8Iy-D>>0+5HGZAPSM>>sJ z3%66)*&@xUq|{L>cXgz>4mUt06R&x0&zja^v}A-PtuPkOaEku%bV}sDvKIdkU~AIV z%Rqr4H9yqAz6{2Y5UggZLkWV6%!sNa;iwUWL=rY0x$=Q1 z(WmK*+=oUJIdTMZYcKdf?U+@|;#3?Kg@ls*h=pr|n{AU-&*+}#Q_QPO=$i>A;wdz=UpxGces|;z z=T2+~Ji$Ez7IDmZO$G5e04~)Sz(DkcmrG{_?$f_J5!WG#yGH_NuSefstcGc!NMmLr z3-!bNKHgK26^QAlCdFa0XMEu7X z6Rn!1*H+A23MDGGv4h!+KVyfG=TmNyiDN|oWNo7!M~&KnK|7E&h!FHKwhR+{@PqNu zwp3i77S4rj1A~95>5ujdc>?d#{_A-hWlct%cm(EPN)Rj5Q6^b>r~OK+lNU~Qp8a7wTR%gh*t+N zJ16PD4tydN_$2o1==O6%|^L?*f%U!&1A%E6>);jcI1H#*Rj+a*Q zK_;(J45RrNYzM8ICA(o{%&rO^ng5!TO{$r##$U$ya4z7zRWpyV!`%d?wGop-( zS6<_`8z)+sW>(pUS!`{kyV*|w{lzEIlV;=}&)anoW~%BU@%wvTBKd{~V}=4-cEdwX zj8T6)8vfVeNhGtR8wzZX_FM7`5Y~g&c8{i*@9%so2VqM|-(wU3@9InE%>LZ>?|yHw zLWkc8;qvk7@v<&v{onl`ZqKK@eA6*V8yo|1MNCt5g&xs6JeIfJ$KjY*%v~GtvX)CtwKIAx=JnP=q1XFP?$hWNy;ojI0a$O;bX_AW04B_me02htCi? z`iKPRM`ND<1rHNSsVkY`TWcuMq0S975a~@1*2y!@3sV_j&S}A0>e7^u z3wfxjR*?N=93P2{kU2 z$5$bXMAUofe#w1bt$8?nKMy=!_umV8e{p%c7Fsi3{k_Z*v{xKrt_>i0)cdwef5*nO zE$|<`E90E?`Cw5ruAyT@KoGr2J4ueIDL$4MomzT=IS}Yr&>#%xD_fy?>7g%oHXXl# zmg5(%)~l^{tJP>~NOfShn~x3fSo8%!#-vJM;4}}jI@6RQ^xM1?)McQT!4ek24a2ju z?Q89wwH|7e8b% z%orapC35#Yy)+SS?#|H;o$JLkgPe`=KGrHom;iUKw)XAlA1QM+DQ2g+&&JcuoUjbc zwDaYL=ax;-m@^~eVKltoF~?kOeCR9f&AnZ>Nh4YFnvk(v$je`o*qVn>X&jmoLX)-& z&KjivVLZ;1-CcOh_*WgIeXbuWI$Ak{OUZ}6*K5*6`@7nku6pwFlg;u>;=sZB30Fog zsxR>Rs7aQUlSFfRT`E&(MK@V2jZ9 z-v@f2X%;!pFaWb7F{t5?p(bv{YBwzXe(9N!$sZ4dXu+O-QJ2uJTpPOTC}5|0l22*N z0Pap78*&w3&xh&jVHG0)ByI25@ZEeyMFLUIQx`I-M>LncxXsNT%jZMlIh_hD5PE3T zzH2Z0SB!YsW&7=Ro}7~%UK&X@>U6KQD0w+9vbjc<@A8vNh2>Y&$9tipZm}DaakJow zmy+o`t~{aT{67`u zC=)E79KNEk3iK_)NtTMaRQy^hvvNQDr|@lIVgTnOHB-k(ulvcc?f?EIeLc_h<>PPWyYXb0)6ZtY5S;3OMnJjrVVM;jz6Wtx0B92w5_7CyZqsNfQr zUHISnADWG*OHt_xl{FO-ccI}3onU3T_S5aw+nw@~1NkyYK_!C<=8nfb56D@jRAQAY zULpXZ0SjwuW7F0BTe}|k_G~sjHr|;}k0Z&!_d_+4(<)MNI)JA)Ta~&ym6-33fF9tC zF9@gulhc%h18Rx#*}k3zeXwOR@dSHUSC>4n!cCz@jPn2Q^;n_$U3C$-G5*i%WuZJo z3i!SM^O`iw)(QW=p8@ax{~w=(zkDEQC>R6!{5~^-0!%4Yib2g{jL!(xMm!`dA~*X&}RuCQNHezllwfmSrhaa%Q?~HpLQZ+eLje0;3){#x678c4+2vPH{$yL zEsfv=)*+omTW(lxSas++N>920#9A!+HDvCib=d!~H4C|at6C)k50Pb<(Tf$s)fi-5 z;}PF&Zw^sm-_{1-z2_@NM&^0uFXLt%$E@0@DnL>&{UBCU!r@rNf;0;=6&l$DiBNaZ z9gUz8I}?Ax*Jp*i4-#E?tZkmXiS_vEEz%7xJ=^w~pEIguRa3 zyuMj_kAA=P7cx~rS{v!-j9Ll~4={dySl8`%j`ZKNe4~*!G+of;1de+X$e>VV9FFp_ z%*r)%b`mhjLTWfRTH%aQ&X0)V|2pD`xXR}WTx)+ei?DryV=kG_+rBnb(;y#&7+>TpLREO9z@ z2@zM7m*?YB_=hhZLCJFE)6kz#ELDfnhsIO!RH_XIbP9njMcs;H0DJWxjuFpJ`y*CW z`6F}Q!r!h@jyWoFX%#4cq0&ccc>w!irwTRee6CcI$!`z`T(nNMeNIgOuKqinMN(5> z=e2b7o3P9k*fl{yF6_PAKqH)t3w1D+2^l*msweM^M20)W_SO^#t-o*eY3Q#yg$sCP zis_sx9}6C(Dx|ZMn=f2bQa$~e{anh}~K^YGzkEO983}tip^BZi_BtqMx z^)Ac@G#bD2-F_PvZezFLHqpm_gz(emD&h%vjrAvDP7mYi3fa%|Feq=@D0U+w2nVtX z;~|ij|A4Xm-(4=c_YFj#&j1mnFzXpQ4R1*hPkC5Ft6_lnj+$_qYV+VlGdoch5KB$) zzI2xy*eaDVQ0qsvwzidcxXHg;^c1nuRi-I;1T8mTMBUbzizt6K3mLi~_*BKrx2m5J zAZ9dv9;=*hhr}1(4n%io{bFmq8$51FYyoO>y`$7PB3 zP7Gy!;589Wv@im8^dYeRJL%PIx6p3l7g^W)9~+(ivG;CY3%*Vvj zUN?JLZ`!$uPEj4|aY>u*hTX_gm3i`}ha~qK4yp~Y%gf;iOoaxuz%v}Z{QP8THc%zq z$~JMRm*v6mZJcGro|F4(PbXZhjDk8_&&khwXi#3p>qO{s7eI$sjTS_UN)9S!aoXgh zEn&QAbFYrW-iN}vpTl>Hr=d=n=zf>j_HJUFS#H8^O;p+w_|X=7k}%CKBSE>ZQSi;2 zJbxd2ogDHGPL#?_dZG8>mZbh84t}p`mVY^$N%^;e{5^AhGRfudT@1e%KebHiqiw$9 zkDHJAUhuu$7W(Ix2|u8U)&NPB{~V0B+`6c8?~V;)(#n}dzFHVsuL-^X-eiw}NTuD> zwB#Jh1<`=dFkhun7lb7QJIx$l$N`nbdq^xCbK(Q>+hyweuiVb|>7Z=9C0}c=1Twpq zJKWU*QF%q~cI6xP+TsTigZGcD2%P7RU)M@r4I0rj?tl4K_;oM-@3e)C*jka#%t^u# z_c0~38FAZc{6!9n6#{WiP|oc=Ml3DmP}wy8 zI;Zxu`tOAS$$<vS??X9Wn-DE%MyAr~pcF>(3vpfvENY)=#2e$H0BQu2a|Z*i%@E zl_zt|3%Lha#b3)xqN-!Ou8z+i?@PsoE@3!h&z#Pu(0ta@di(@%zni2n+pk%iEZU*5 zAXm@x#F*~*D%SX0FKcy)^uu*_HBIpP=*mytC+LKCgkoSB^Kn-(qtXr_XHTy~7p;FJ zu7tlW{IuQ>Z9?N-MzDf+`=l>FNr*`^hlH@oxt`5b!bdpZ6xrm2eBKNH(l6xO^UR0J zTVr3G;48TGC!Jm3F-b8u=c4it`Nqor1|R%@B$Id-qCO)KIG82y2n3tibIY!Fbi4Fy zxQAtr^gKb(5wVTAtXvMRnNZ?c63rUrCYJ-J zu99M#pC=-d7%S5Af4Km^SU;&CG|Y8ObijVJ#``KlrAZ;GNo}4I$C%2PkR_+RY#@yH z6rA$`XwYb=B4MR9;!SrxVTx?+w8IrhX~(b}cY2N#4#)CnGNG(&TcyW6a;8(q&-G|E z9}+6#@U|K|zD0%Q3LMO$Hh6IIw73jxTZqqdbq|dJC3URlVcfbde)AWYh@L)ATt@=Ony=~UzoaR9JBBe^|d&75_i2yzAZ=Mg1VwW z907aYxsDodFmUiFbk=N?J76rIdGrZYZ5%&x1OH3u^zkIwEvJ-12Pe+l5*U)IB?E&wQ z6^XO!Iq_X)LMR@4m*+&`rvFII+pU;jhpTlF)5{cY>2{I?-w-Or4tI|V{ettv!$Ig} zhnY43cYN%*E_X`am}ca@jCF(SMPC|S1i}yGNG$aU?KM4TC-XOo*$tkZBdgri zRWyoB_EUYQ#}}S2T=>}g^E_?Cv&yLg^CF5qdP0v$Vcl;y0L>i}=KSXf5Hsl<(fKdV zThNIJ6BaG!+Kpnz#Wh)VEz9Y8CwTr^&~%rCugcDylNZEzJ<06Q_o+ty_lkw(a2|rM z$&%-{FvtWw6!!WtkV^CO-(rk-sea%9fH_2+FtzFdATPTN-)5v%rRhVowg=DI|8Klf zk;YDlinoS>KZVnR`XU)wRT4&t)5b7zl>mj5K_WV^(iDDv2_49fG?hX5oFtoYoOWq7 z;mBXg3WL%u(qGT29yo?w()tT$AlO(K%$T;RH{0EIFz6Oz1)g0K+FJBWO<}nVhSOIn zqL)rc*c+75Q^S#{?zyUa4d=eQWP%yjYVT*FofxLH4>h$2k+yzt)%lRa#8wXAvlJ|4 z45;>UcoGBo@9>SiKy%D;7)8sG(poU{aU9B8^vha@Tjb{w!^)VNL8(dfXz$k-90YncyJzH}!r8VW8JdYFK(FC5(fQ+URsW6v zs4s>1fj$LET||&F9R+V41^)|)drR+uMd}E9H+Xx78X_l!t7tjK%l=mbSw>I6LCE9E&+ z%7PVf8b!Lw7HyxYwfA|Pe0PH*$M1&C(i*-E7UCskM)=8j$d}y&l*67ik*0`y)XSsE z660k7N@HrW0)LE&G-RR+JJjQUNei2X<0oa9IAi96C;SHvO_PvLrZ&?aV#nsbq^UY} z8#6XEO~uz{-#&PuR}}IZE3HpE^#FY$zT-rhprB4i#n1BXE1j0)Hw^uEAZP&?i6M5^LV3E@&jJcS24nYmcM#q%}q8=J$?!MMUnJ+lvWY13=V|O^Jlf7JnU!% zC)Q^R2o$@YV%o4arvk97_kXHy`@3v5Cm(!5WM}Mm+HtFy%TsmV z=FLvrrhG+pN4sCy2tN*{DPbHvR+xh@bgS0=C;r@oONkyWE+)olmcJ3!~7f0;?L z|8<#fKX{=bSO16-K+g^>B4c6dI1}XK)BR`9iFmrCM{R54_aCsMRw)5a+?kt>Ez0*2o}MlHz5mBT_|#NIUMOcHq-BvcbpTU{5&Vvo0R)1s}$ zIEj{hO5DVU$&|_)a?Vvi4+S8#J}Z85CPJy{;Y)qFlT6arK2UshJFkIaS&3=MF6MQE z1UX2QNgIWwg}ckR;b^Yo`lpAih&f_#*^JFpga24$Z?M@Pi}RqUc0y)u0y{0dn8;lo zZi~<|b|}cWwLv-og^PvWaLC;Zd2ZWfO3-J-0Z5l|}BeeanW`2BL?;=!K_EC=fLx_w$ol_6i1-`l%Zxf)I!q8!-odY&tWC+4wN(N4+J95r?GE zpWkPedq84IpxPhs^#JKmQ?HwQe{T@yRoui=(C=uMAcFy*;j3Eg|J=U$S+&m8RGDPP zW3ec-y>jk1Stu=D7jFy}GVJQ)nJCyHEA1F67OT0()Y;}dDFeNv4A0kv2-a*-~~07mgL&1XOEWD@d%}sX8Pf^|I@Qn z{S5)wo2H0kZkDGMJvUL#E@860j#Ojf z_qW78VMLf|I}Dw#T%Eo=#?E*2=%g`^;KePQoU6oVpN@J$Q^G%cv&`@f{pY33HK z47?mg3?5H*a~WA9UDmbW0w+ge6vV$(qq)|B>ptZVOEsh z1|S)3>=L>K+uFPlSg9)mG1t#xpV(Hg~&mBPEA_Yl$Lxp@f(AF%GWJc7CmUoS4JZ(R*wM$a!(&4JO`p)k7F`d`>s{zg@nz{g)0JQYl9p>n?)K$W%D2^sM-g9<^b!%xqIP`oH1{%5K6XZG6sT6; zR{eLmx`p;ld>LAv1XXIb8=IGdcEZq_5O=YQwmDn|USknOWsfhWXsYGx-K%*{WRg}ZU@ ztEIj-CIj_FqpzL0b=OmZ_kSXG2D>j^Iygbix4^{r-KY)gsDN{>a<8{~$-chtp^2|^xP_$Aazl44Yh&^9k-j{8r2mts<`@3+M##_59^ct=9 zzd&&*19cREtYj#9M4H>)=qlKleZ9qI!+ggP03mMsszMd{c^z<|nD&guaV*k$>7pE#BYK`7? z(KM}?U-+NIm4BY|wj{%gh_8WX!9$?;U?OVK4ivLRmePaRwv-SpZLk064$Klc6aXqk zeSL&r7`U<7%A@V82)tEA3b}p8`wW%G!E~Q^n-L6!F=Hz!n8QJ3z`|wk*ar1sB!M4MC`_?SV=3HI};HX zRk#kQ5MwFlC&;Pe=i(GiGatNo)pL?U)aptRVc39nc#J8<=HTFi^MWTiW=Z7f(UVN?opDB)1aG|^vM?IuEc1J!?qT)0p7g5B!~z;7Ud-_Z-wft!CD;G9Y1l1 zM4{0Ll*yjKsJ$0akOriX6Zzlyb$OGM+nztb(3Y#dw>sC1eqP&r1 zP?OE8rpzm=NJXpX?yB{r4Gj4Z$uXUi<^NW^y`Q#2by{StjkP~Gtrg8ig`2>u24dir zVAt2RPfra|>RhEIexc3E-aK%2P8IN9m`)AoFgpU~pGF@&XXMLr3BEq6T zsg$jG5yb9ZQ57E-Bb#jN z5esaXgKey}T&2%>|JAM;h8cFw zn%iRt9BD+{OvI%rdqhvqPSPt&em;`rw=` zS+7Dc!8yt2(bC*1T}nJ3!LPSkW-7Kp5MbW^Nm=eQd>Z{;BHV>!Sa zi;uHL^b^PU{wd}f6~FoI2|TJAcs(O9l%d)tQ-sskm` zXKTS{)wa)X63}UX2HR!L^9ow}0`=-v+#BOiS`7UhQ5MEmG&X(Garb3z@7(7*Y9Oxo z(s`hP%b12ie4~&ngI$K&Ren5!BzcWF08lZJ}t#5(BMrV5T$$n|gj1QEYfwG$ox z$M<(O*Mh45>y#wYe45iYJPrdh#t9p0iliqo zKWnFC*v)^cVOiXht@_Y7{e(IR#rkYx_tr|kg!{jvoRmk4L`Tq4Xyd_8*~_p=7Odfo9VombwgGBp8$ zNHDW%#9-WL-Y_>#()Neuv-dQ3boOTi##Lgq?uh(4DT1?V;_UhGCV37JF!yy4V$=O&4tMZWX+t z+sVDSPi=rY&*c+joma%j5TOD?bFlg}jvTF>erK^I*H>D2iAXymLQQt9n2RZXr z&p{J?he9%rZ!t*~1@ZoIa6abIp6Z&^lOtnD=F5PI87Jo|m}}}-vAVUj>!9Ncc?!NY zHJg4IE7XxOdJLBl?odzAe`-FGK7BQR;k0(aDZCYO|TqLLsTy8&pfX$3+VD2~80r$Y_>uqKXu4>wu$qDCDI)#XYum9{yx z8ida3wBiv$crKUDErv0^%1Xtu35=yb)twYf%`bJ0jsB37oL0T@Vl!4mF;3GXu)c6s zouRF^Gu;u`mghGsnfER-MdJ^As-i(1E?bA%_&Ea2mb?`#L!lm88ahi$$LL72oZhr< zdK!RaZV)6>? zL`9XtrU!kLP*@mH2(AiLi2d3Cm9ZqVLgKbf^H9FchwU$)#nUx7j=h? zJBk&T$4%S~89488PJM6nYoQiJE-45_q(<=MU0cz7f960=I;*Z8=-kVK`@7#=pia2} zTCI(X;RX1qQDe;@=`(3Fm!N#dZlJ}0iq^beK+ro%AR3nr6)cZ`z;G1Jv!a+Q)^uY6a0SeFi5d!|1pwX5^D z%33aHHOFgAqxJGt?)78@hB?t@11Ol(s{;K-Ta*6QZtiHN=SMwS1_NJPSm&(d&YyHGolVY~89C|Nk(x`mo6 zJ{rziGm^N>n4LJ*AUF}pxHavqTI}g8KYlB-Y;TqF7Q!%kl?9p}z52Kh9~AF!Udq3W z0fd}TDnE<)+G>h#e^-Uyx8K?n@a`!b{^INRnql-~a_|vW6TKZUQ#5AS^dV6PO!cP1 zcjL-bSl!UY9LUz!&*O45)TCuHlJ*8kyP$c%t^%S2+*kLv+c=x5^ATam2|%l2Xz1-A zgLMpf1D89QzBfUim`Dds$D%-j>9p9ct;9{gzVYJeru(GlbAkPB>D-*eLc3+up7X$7 z_LYPx+{$3dgL1>^s26nlj|sQbhJG)$g8qpv{Q`cEM?Xk5gbs?T3deB@80g3JFLcc@ zy+D?&jC3xfRUNX;PaKH-;=h&52#4$0QgJHm zq&lL3GlO)RiG^h@(zFuyU#o>t8ciF;Nr3h#smzbA_cTZ#KP@^JSW|XUTSE2UnD%0T zRMlORJ3aNNd%uaGB}h>kC)L8gr`B#uTj;J`O(Z=*;_Koy;(Vs;Pz6(@+;?lit=Ue& z`zM0ghp6#!wnEgS`*-9p0~wC?om*N5yi!!NlVC$mFi3y@1f_ zSw!0Ud=@~+6=VOD^#%{_6B_8-(ed72+{d=mY&t(5WN99L{dk=Ouc%n7%ZViP26~|- zM+LR_U)M>`#a5P)dYP4>g)}wrsbCo0*Qg>=YK-J zvAF_#`(@@k#~&F!LdDAGM36pYNy>9v|qGN{ZW%Ag(I)N zqHf1b7ZJrUJqnm9GMAa%W`A&#RyQy5*bkpC%KPnJuOZP!oe`rw@o}*{fMdC|dntd3 zT?r>dZ-wcPCQj>W7qq3~Q;O;V;;Nk#p8d)Yy+xPqgrOf!jTCJD-*)IQPm-5Ne5#p5 z=ohlN5m?)|rV^oK|Jk!$slryW=p1J}C24^IX#x|&MeXS8+51M`lP zHXuvvJ+-!=1;@GxW(FT3B3Jxa*z41bNd}5PZJ%R8&A9Ls`+3IY<*HjAI$`dfiFIN^ zVubUIxp;5x(3h{Py?97nRBg1P$+Kaw=j%P{gPf$GS*-XqD>LGk8K70b11;}Y6u*Mh zZZHU7NhUBNg^CjK6hG z&y|V8Ul7%m|1sCDGC5Jx;p|VBJsMQJQdYP>u1H8Kf2z~~N**?@$gGBacB^Kq^pC13 zNy#s73dib*5~6MT_1bc2G1V4Lo3*O8ZU6yO+RJ*=YA`0bldTPGTpQ zyFjj0a_5>!pG{)M6nt}B=sKg8!uK_UtZN%0jCT6$j^2K3WOKLihg%mx|1QxD7apsB zPHEHH8#$K;`$_4$JEy3gFI;~L{k!yqq82wONjjS;ewh|bFAfwU8wj4yH>)M(i1n-e zj9}PIupg4!@Ev{J4^}qY-gu7te%?JjO>)NO2$Dlg`ltpo39Tg}=3pXI{MC$D4oeXe zz6faPFo$vKurNaio17x4xMl(KvHDsjLS4i7RKT+fBZOKzK{*90zamd+tHP=%j}dE! zl}rmB%!yeC$sb8#)MD))@{&3jaW${om1f}lwj;|gZ)7`jFE4jm(T76qMTEh85aj?v0lo5-EG?5 zg(hHG@@VJ8TOwMwQA?}N>3xsCVzzTmg{T#^|D+gKVUHJ0NifIvN+GXL>R2w80b=Nr zaLnTq2j~ZBC^mq=SqVvzluzI#)q|tY8Surz^3ZjkeI7ukW`S>=k~kj0FnPvczF)*H zHtNnHoxWqz7{mR;H8%1z>lPTbdyj*+Yp5 zp5$1GO^t@e`M)|uf%zmY09(qwOf{{vkE@H36N3^eV5y)OW#Eg)Z-z z`;_FhlX<;CSlq=TRWl0fSIU(36a^2LTtjO4YNBvb(g zW7k8AvuZ(d58Pb=Hjo~Df@S^3L%J+>LVcGXYYpE4f=Rih2E<=wif;H&vR{flIgOYZD zrDa1aJ%@cDX5lqgQs}^MtXKR0%LQPOEi%rp;BE4Kb`d@j)VL>)eaEjA?0x%(>TqD_ z{KlUju1Rz!z;D~!U0gX*h`LH<6mO$7$=Rup+Er*`&5-QTGwRcAq~2M;jV?t~)7pf6 z(-A@`3mv4suF$nG|MGqj437?|p7KP-AA?rA&kDKjdH9cJGC!|X6UnXja=7}wGLtmu zRZhjd2BB5BNi+Zsmo0tMdMa+Rtn$BPa8_qoE52R2PrB|JHOOB%O5{x8E8@zP5~j3H zoi5;W5eHQ>S$R&`eQvnw{()Q=`*Kk()@LuI5q2?Q94Q!@P78WnTz7it|iE3 zgHqfmDKRd6suOq9t7N2Jmz==W{oG784bzkvZpLrSo>{N6ueM7#wEIJH98U<>o!>f{(x%c_rdqsWCQxxqQw2~PQ--6 zoUBO^1ya(@W07TfbsMo*MdV#EC$(U2vihFS{)IH zW@11VCrLDGhsXiQx!J$AHeJD-!<}c6E=%Jw9LP_K=`y9Wt5bD`h2AS&S0DL|>QH)i zgztKtty`0iS=RgWL=8vo@=4reI?P(ki;N~Xg#i5|sFdHwb3|mgcitl!H-s)eq6orJ zR6q_vl1M3Xk|8Kf^6IDvS4%My?Z5LSs*&iwcalR@O%7*Yzg4BbZVws5TDZDcebrCo zKN$w(tM_SA!3BV)Wy=1R7jsj7K|*{eVc=xwq|Kyvy>aIT#t>}C&KBs|)yK}8>C2Lu zQjxe6>|_Jr4L2Sqg#_WJ2E-)`S^FlFyvjr_XBV!4B=2Q^oJSU^h47H*satXx&l~4<1`b>%pYeAdPHz6HmtStsmV2+~lsn z-Q7Jmp1aj5(jU^Qo)j{0#~o&v3jA)uC4+Gy&FA#I->6ZGf?ocxjVSv9^KR6MSiVYDz zgjG57hXQ)c3aL9@1JTX-lpqq$!o@L>z7lF#lLp=xS`^Ch0FSAxl*q8fd>m|UJS~RB+&fqDd(w0P*6WiMwM(y zzNk&ZaRa|Eb%~seOoi;T@P3^k`H$F8=JL6$tfYpy@=8IUSWw59=&c=Cn<64m#-{A- z13WtFOK9x---uBf$_W#!a+SX%DeEO%N3(W54>2(VMgEZOZ<*XR)2;f0l|aTeJ)Iiz zI>22#ojnIxc^&X+UleFO$7;Y+2uVr>pY5Cp?D`!F_M?liF`^Jgd2pf^YWTn-AVx&5 z^9p-ByT)wnz5)_>WT*-m4h~=hMW*4R>@yk%&Cc>6sc;;9Q!ff1O$aBOkcQ9* zEEO(&{#^epQ@)3$0;3bH$#ORiiq=%Q#HJiqX!)Vnd33>bXdn9D;m@fqk!EuftMjdS zBytfKNAF?0Nda&4$eN&@nx%`)ZyWQjsPgMf8E@osj!tcG_b&o5fcpeidl!mxb4)cu zPTVVaX|nS(L58tW8XRCWg8-W)_!=fSxf^IHAwi9!c6(O;Z9f+G9a%!crOg$ML&xWT{PM>0l@93mL+t?yY)n2q-2%z8Lh4y3`2Jm#tT-?UDdLm# z=*1qQ7dc&Vp#5LEq+0*J%YMU)@k+9<9*2n#!lSkrW|^_)d#{(sV1H?3q%(^uSLFE_ zwwrY@tUI#*=C<~sAbK~${MR$y;jc&;CHasseM2hYdsaT0`wjuLYiAF=;N@tRJuab| zMG>h}QZ=AuEz^GrFj>|LjoyF#y{cOAN{oqBPH+V2)%?-**2mTMY|E90715--oKdY6 zMhQL99jb_en$G`gs7;QdK-8+{nmGJW4i$G_{8Sx%mVWbtn8<}o`04Kf3zg`sk{XWk zfLSJD;fbweBI=3SpmpOV7_|xku^)AOKXjkJ-(V8)+m~q||4aj6ez3lQl(^%);jG#^ zBd{R7L*9Ii^aodYo)oMs$2-(cnX0Y$75^|ySPFHawib*&{oi$!$$tTH43PYSHwi-> z3UzGNZ;!HF$FU9>!r=~0r!1#1EJYEJicQeM^Y!L`<*R8zTJq1;9I|es^@mjt~_oQ%88pdOGp_D~vLa$!#6;8mxclw68;~W?`V7nq42;o~yEt z=|nzMYx0+GYR7_Qw`l<(bEtj3KR_TqWl>S5R?kshQKgrC>6 zXjClNGC~S&eJ%sy92WRGfQ7!1EC7Q&4WHrUy_M=VWoE{;UQF6kB5j3Mois+&FYWb;&8ucx zfot}F4qCRjZj=x4WQ}xNP>~Nz> zZ8fZ=t?|=rBuT2ZqrOyvku^2h-q(_M8g+mr(*FK`R~n`+EZwwTn;xA$LBUWHId46) zW-;Iwv}z%}DP-)hTwtjl?k1_uV5N}xc7Y!zBgMi?xe@hi$z`aXB&BqR5AZ3i)tA$n zSY$K}VB;?Ne~9`Dpf=kk+OM=gaSd9aP`p5KD^lE@;O_43P~5F}aSagMt+-2&;_hCc zxZSt^ojZ4i83;2ZA&>0t*|X<>50mF2t-C}{>Gh2e~=giw~XjJE*`O5S*6=&p#E(f$|8E9`Shv>SF0`&f^e3y*t zN9FRlHA7H5PSqfQ-Hepv#7Jt>a3e~fCRv+hCiajyT>d4M=;iE8-ieGkY&cY&S~;Fd z#f$l9_GM&IgE}(bpamULrf4F=xjo;0{}jYE^WjQKS{;e`JC*g}%m>oi*Sq-aB10Qj z*4~mu#;Fcctu{FtbWBrus6=5#q%A$rMtyC+2?tr{a(5k#a#|aRH*~pdvY6_S`(X1NPOt{GdZ^FWSV->tnGpRF_ z$)Dbk^!E?Z(@zc#3|Jh!Z<5K+c;6<~J5%F|84_yd*%orN96+yE4WcTtm=>^{5#-ym znCyjtaD7hJkR)ybRxEM>o`hfc?!(=3^opHP8xxv#*-Y(=bYcFfG*Tw|y87F)f9J-3 zT@*aW^A0%Lx(zbp(ws7!SAZfN<1x3f_IqiUlbiS(gSY}{Own`84~TRmA9;pCn%uyc znM_YUMU_k88EoOJQPuH`J;ChciuJ!;^LSkTzke{cyfiW>f8mE6<5@;HSQ1xE1jg@PrtU53U0I4;(t(X1? zYI%Ikxj~tI=>@Br3MK6C06`cR7kvNVr%v_?tirr9kfW3q(gQl826aeCL1`6RP}M@w zQtH_A?R(NjX_9E*M(KJBQib=#u0`WyNVV?a{zM0qSwN;DHpgO%G2c*)8e&A8up5xS z&Hlj!oTnG{nxhTIONM3j`waVlk_Z@|%#!41`hUN3Z8QQt9qY2U3FlztJ(feaUMHVX zmm0$wsiDubqei#yut-Yy3;7rJbI&&pkga?jp>tN}rI0b&I>zPetVNTtQ;z`?Qp_TF z9&EXJMGiFGI_6bCdGpt_^zS4dDbqZTR=#S~4A+mBIeI^63ZvL2{BG&G9-T&N?@2MT z`L}y%&>tg9%X|KvmkeIa`%j=`c+YlnjTI+X$6lw*q>ost$)4f~MU;*`PCu*P)1%&! zMnX1z5S)qcpMDZ1WvW`4qq_ER9vy@x@HK;?|N>#;Zg`XZhD%S(oyu zpeop8ClhOX9vF&}*k3`n5j_srRw0;mO}1`W(gy%$A9b)Yh~?rT<#3#5(w@C_@Ydt} z@J%P2bb7okKEs#Jjk+(;mezFRQ;aE8ocWhBu1+;?e6ZrKiK8fPh30r_1s8D-H#yYB zWwg7NQ5Hlw2TcTLC*dnf0s5XWiwAaH6y4vJ@&1jFU_OeBY{&auny1Gu|DHu@8aH&$ zO8~TR;oYe|Hll|U!%epAGh^L)7>)D1IHd7;GLqxCi=R0&uDvXIVQuJwCkGWCZoA)d z^Cc_*^;c+vj0o^cC?8o3fvzJ+Fwc_xfSq^&8`sH6M#K)ker<(0 zqC{s><-wL43Y?(RI4~%g$Fr6^ZPnrWiKj}hV`qFkIpP4u&$oH!5eG%epe-8-;){6S zn`VpLbIQgiu)Fg&{Ci47(J(K^K_xgDK-b&1w))TS?+W7X@AxEu6y@pf+id>M!HZm> zWe!F7a7Zr02OC{w1g;8k^b`$j5WFXnYec_4sxZgY@-6rMlsFke-%b2PuE;#zY|P2O zwNL@pLIMm{)dWmis!8>oGx>HXD>21{s3?D^CPYTqH8?Ove0oc*B$f6wtF2ewF$$@A z8*Kn|iD|m_)N?vEW&KCCd-@I=Yu*4|05NgAunKeI;u-jvQyJ(UmNf%|wWR*saeu9S z`3T(%+A$18&+oxo;NcDpe*n?P;cqZ7BqyM7W6P&|UyPin7!L_qC1vL3AxESBkYk%p zfY4f+6Z%?!85#SVd+Qg!!MP!lFa>U)>QSU6aJyBNqlr6gYMH{<23D7MD2WT z+-DEXt>4sm#ITZfkde?+=veA=yb7!v+>_%!%2f;mbSi#qH}$y>y&6ubzhx76sse^z zPyJuxMMzNJC@O=HqUzQ!j+$NvfQi`G4E)UG}!mnAqxQ3~t zkoJzy5Pg*w)AO@wJ9)OAYO z!NZ>5d?p1#4Y)to>-x+OD1SCd$Aq`$G?Y!oRfWWyE^x=jQcI8c zs6XXZNCU<<72mA(&f180Gu{DJSF|NAW+)bn^Aq40nrD1WPfus57QX{G=TeOt!Q`}c z9n|mB4dl8fq~r3b@@*0J0rc+HEs^ZxqfUSpK7&kTelC5Us*6kSFLpFkS9KGkCc#hn z%pW6-@>O$JNJMl&;Z9AQ6|_#sxQfxMJcZ>4{%II$K%^2UvX9sfruUl zv*K-q=F}(0Qx#X4X7OwF*4rz06>_U6up1 zLry*-*<{>`!_3jQcMh&_rth5nun~7!?w1*1f@IF`HFEFAw+K*Cy2ifE z3?MpEOE2zGjm%%`Q%$>E5XljBhFR0nQk2Mk>e&qfW8w_J3#%j~#~0bmV}+RIaccd& z@zyYf+l=hzrJ#c^N-j;tb^Ml5X!8TX&Rep?c-r|}XFps4pl>o0?jT?&pkK3KBNY+| zfmmb+hlCz_G{+!RhQ^d3C)0mgw$or#XHb7*sC9NmqpS!5DL27La@5Kr$_s}~Cbn)8 zqeih(n?9?Rh0gJtICzZo7QEpv5uQw8sOsFg-c2s|6yH5%Svhx_x@CqWGYm^k!-)!| z6q;y?nX+5fe|1?xBWjGKMj7Fw(1~ttX$COqVO+8nK4t_{E{D(gOqlS}NF!QwAVALz2_CfD^(5wq>JdS1Y&2g`l3j)`FP-(CZ$7=8 zMxoVoC>-Ah{6WIfHi_I>$_AXgbQ&bWR2Sx;YHvm{7(t_BUHREX;- zudLa;>id8gmW7(h{SG%%TYO(V8jtW;w)+~*B|$~>&CL9~C?t%PZzrO1qtN;ihBki{ ztULp=c^ebt;@EE{U_2JT7ct`7A=CTrQ~`kkB-T!zrF*q^kDs;9Ko~}qvE0M?u60PW z3a5}Ox5huNBrcAy*}x2NW7^NsS7^=-F^LQ;E+;@vwv^R6G+;j@`B{A)s6U>*-o6nP z=Qr;EI-c6Dp;1rvibD1>i5DXt6{?nJv(KRS9I7DTH7tQoc=DQcO9pUMqI~KoWU1(Q zvp>@opk45q{CH%?ICFFXOe-)l*(=~8bw4`Y-&ftA4(k8O%oVaePadQZA#HWGo3Qur z{7E7I5|Y#5--9SYbn%omum2RO@9QKt^(8!-wBtKYDD+zuMdEdM)c#~kRzCwPXt^%l z@*5sB9TB_Sdu-#cfWjHtfd_(kdQu3=9)8Znt_0cD>x-KR>}&q(2_QglV|hq#^&x@j zOLMj<16$7XtzWmdLM%%KXCsiUB}$+an}6}Rf5@nVg;v%x>k<#DeoVswbN*-={7w_c zO~UOG6MVfZGr>foBm2pyzi;ZD)(`A)a~spQMUH*Fx1>&dHmrZpl3TrfDsQ+{)~CDT z6k#XmN;|8jb~V^GcE=OF7aU^#|e6R&-Pp5(-Sj z79fzPaeE1oRw$-^9*Foj(Nws}xO^YI3kc24nO3hGzUD?SNwa=3)wD(81SL~Rz2Jen zAlM^m<9E?f`#F~|^G}@8D0TilFvqwQB1I_l{^=vx}>%@um+oqsntJ0IYAlud6{^PMfrrt z(uXsDmQin&0mx?0FburDb; zeRiuu0=FA|^&Bss6xek=h-X*uIJd~@OwWDyX=L4h;#6#mkABLQ7_3CVO%%Fb($zG1 zc$cW)C%EM#uzTe73-*k2qh*UA9;iV>nfaxKKj)9MwecfbYX@E^8kpVO^Eqh!^}$&0 z%RAzZ-ir?78(ws1w1%(e#Ew(XI5=R-)nV>GvGl9^!5oJMweT?}M8roI{;@BrzL!J$^1e{RVfA1Dof9<$roHMgg;c-B!T zGip5|o}Awj+zncw;WXJ*0`!=GL_Tz+eP`+>l%V>EY5S>54%CK^Qpo>7D9BOp8LB3m zTe6vvKx5k&+|L_1cl~w7H~b`R(A7sgx6_ZKfbW3HB|`z6s+bU%^0E?p6JD79Am#r0 zKfU*462SzEL3OG7(O;;NbR=9c7T2wf8#52M4A69R2(e=Hoo=?^bJ|g9(POy@R<&fpN9u^c!u~3`ZKP}qKC1l7{pD@fzPma7%XXO0 zpN$-kbIUM!R~Z*VmKVNFt4^~9jk;JPwc+sV-IAx585z#Ax4a6m+Yg8Gr1=yB_diIA28MBS>pLOdIW| z$l8@TdagajsU5MT;g^w)El0+!xMmrr!#((SZ=OPx3_iA< zUrpY=MwBR=U#!){m3($ZT5O{D4-gjsD=DeMCx~bQHpvazqR*UwoB_l6p0E4);A)RS z5uEN!%?g6sW57#ZZ(g?37x=ss+~MfV{V$%r0((}cj!&EMZgoQ1UBo+O=#XX8g)2w> zb<9{ipNlQ>0lg6xmg7aLq#}cC$&9%Gp_0JzatpW2Vok#lWEE{@8P4E3nTe8*a|B|c zfBEqB%cfRHN&0hZeLf@!F1{_GXT6-`X)>?!xUlLI?o{YvGw`qaUQk|I6tZ`FDCiM4 z=$l!|Z?Zl*1jI0aEv2VGX;&xI#+7Sp*_NwWYT#zssD+vlv^B~GU9X?=4$JzBZprC= zLUPJ-XEFkA-q`aRqg@zmg4av0mgH~(_qs2kW>BXrQ68K*JLqf?F{Olu?->thNj64G z)uI{3*BDH=v`|H&{Bei1B^xybw9PWR;&iR{Eeq~Wc?Kky;tESN$;ztaB1K@jqg?EA zUBmyUXzNln`R7kK!^QA;kQ2YL5*<*8aVxxUvNpR2J~R@mK24gIE$9ce3xUDPKf4-RIKFmHc3an>7iT2YJY`2ME1IJR8I#MJOs zf!lLM*ar3HmjCZKr~p6b>d7nQ!yY>wZ4VDIR&^ydL?>KaW+R)R0ySS*i%xIK zJaOk`KS_;->R(u~Q#YSY+qqkCExQm2{M1Wzo9}0%`WY&*JmGo$;N1D%uDQcUzGSg* z-frr!-olNKw>Z@P`LJZgG#l#+^_U$^bP4%=V9Y5GdwW}?-n6*&2Zy`a;`FkeNcrW6 z=7kkjqL}nB5m`$^9`sgI7Ty*E3uO*@fp5{8=xelV3)v) zU7VJxNJdOCqKyDHnNOWgGp&{8b`LU}6fNuAGlLTbB)8 zRdR2P>&-DOg{)Ddl(-u1dSO3O&9RJ=`nW7FdaP}3xzlaD5JVE3PYW^uG#r)j;K7|n zb{<3Y_hoEvAiQ%pKv}$O~iULy}_g zBIznb0;j#$1*`eHL(TUw{~5CE|$%BN?Yc9{5k8Fa<<>9>U7K49vb&2NYIM^k0RKIi5bm{3v zqb=&pGIx?A#b=(5I1;PiutsNV7y^rt;@cuc@+E1vsWNx7Tt6<*69M%&y}!pO)_Zc8 z%Ue0sa7vR79c8|C_TqiNs^+yC*?A zkIc2?DmV80F$;0FM}r*m8hu-V`Ll9(yr`e%gF^`vi%`gD3D@R$jBmmmrFOn0G7+Rd zf-L?30aDvzD&802ea4en`mXnv3%d~g{X zS*#49=hD(uJ9shCgfJAm#c!zgOota_p0C)3}v?* z6!LcsPB|vDpJ_S!mO)WqQED`H-=>#V3e5LYHY+bkc4QwBdB~r*4Lg=FsffI&l&m5c zq@_W)lm?qOaom>}xvoPN8=J>+T51IsB35t-T#|*dQd{szQbR7#sn>JgRuM81crn=2 z&o@6szUx0>yanjJFVD^|ru^o0i?x;RXp0%&3SoE1n&jJz7e)h4HRPP)e@UN$^j~KD z_j3gP9zG8jV!(^dO|hfN0nn@Ulc&qzAn{3!yN9HE>lSquTh6#f*xSpcmsq<)DllQ4 z9@By-2#|d0in{KfoYRd=f#j8qoQXek(B(1E0hY`VRY3u74`y;GcOHCClMaMUL zgM{&_H%Rt@#qUqh{(jSn-2NC%&eh>HRo!lem{!5_5ewq#VEgT7{7UDcizxN1j@CW9 zP7}v_L^E}KoiECbJQlHW{LHXu`?amsPzZ$fvy{?&8!S*zUgjZ*D|x84u#_G`L^*Qi z_87N*Wh#bX0#-@^nZhe`ADjhr^kO|9r?$6tntD0+$82sO!vA1rCc!B&C7(@naRUfA z>sM8;S1M2yj78sH68^X0h>!Gku%70JV6a|7#6xG8j2KuNm%Q`9I*4BJY#-V8wMtzM z>x+i2-@y6nuD&NPSmV%}@8upxUS1qECS2@=u<7{onHjS1BD^@54lDA`sSrLeXyN+I zD>GpN0tiZ*BDr=vGW&YpQ6{*GiOCi5H2-9gz#zTqMtr*j^?RLI<%4L!K>~}933$hO zN?>ihOQ{s`;#znr%QJnSMFs3x6Q%L1$n)9|3a`bL~G?w{Z?Ld2(bJSW)OMeL|#(rROEr*uPWGP=; z0D^J~K!yFVnK<_pdw5EA4mM1cKHs$*lqj{UA{T3Fq>ojuOF9U_1 zdw|whI$E|b&%$Tq@s}~zJ+3Ngky}j-wE*%9rW(8$;PIh|()m6kH=lvZRP9?)-bx(m zp%i>A0FEAgS^w_@4$vwdR>Eoxv`yE@2%=_ZpDAeTnymJgaNsa?y$VWQdN0>lO_CXF zxuMNr)nMv%6||q@Ge%QoL_q4`^e15Z8Oyr^&h+abrz*Qrfh3ZcD4zXdXqy1F>HWa( z7g*`|^1}EnvU#eG&x^O;^CF}5aroJ`NNnuDN!-#qu$ zL9Rbel`kQW&B|+W;qATa$Ku@9~0gv~g@w!MD zhh}mzj{4N$3m3o)@WXfdGC^01p@)#*Tm|n1!v!{2*D$@>-+d{ot8kyoVb>LF$I2bjr8jFgZOf|DtJE+<*3fOg z2}t6{;8?{Tr&(b%qPGv8VdHt9YnJM*|Ct_AoNu}H^Xcq!>vyc^MgO}u3QX#<`1>pJ zlP#Sq`%fmpY%cE^PRD=6WN1l8a#QG4g${D!Utvd?v%_)mu5Smq zB`45ec`7N+>2sDOfrSzaDT{Jh`GVYt73fM+-N%q4xYkM@9da;G6{kVVZK-_EfdBN% zDZ^gB+sMf!a>;wz$2TJzSdU>$-cZp!?Y%EAKh3*dxn3q;7Zk;a@vh?AZ9d)aDSga? zX!u2`4VIi92YX6m7Y8dz6_w2z%?ov;&{<~T^wZ_DDxKo}ln-dDRE!K}kfQtivlT(C zEDw<8$f9K&0uzs-9Junq$rwQ30z&}$0kenHWc$YADx01qa*yRz=ebcPb*EZhaoe}c z-MZAQs#_kv`pNF^VIQtZv<4ziA?;+A3CXTvKP#n#GeeXLTByD5(THDuQ^sR6L7Tl^ zk|(QVo^D&){hda>KXZyG6lj6k&JMt0U@5C~%t2y2XV5$<=27P73%R&IM^!J1NjtXLm?^!uyGlnP*+qBKEM zln9!>%L&=tZY9!E;V6gQb+ZGv*E`{~G_@!-nO=7aYJ4`c%78w!YWVkJ%A<)Ca^c&F z6|4t8PhjUwe=_PT#JA&;Rl#F!{Kl=(ntjw07iorq1{;3rpaLQ~nM;peD^62R{pw*H zwJ4s^`_Oyo{wtTDZ&cCJM;pOsdGcM>c`Axx+Iw{zQl|MDZwfl_V#|Czr<34Wm$4bo z({!?&T|N8D!Qz_&x$cw)uI%-@Xzr5&dt8&LL(lrm54jTBeX|!S*VF}5TJ>IUR-sWB z^74iAQ)74?1sL}mCDw`T+y0&HhA&%mUDw*&f`XeK2Q!V=x(?quzIIWOA1?+iu4YgI z!U;^3*-;OTNv^7htHi8)yr!==JV{Y$COpPHx8@To2uadqyuvdt+v2gSXOKI!&TlG~?Q(BHM-Lln|(ou$FPMz6j3B4lTqP(qQ!YLgtxHrvxT&rZgJrR3 zochi33V4jYev*>d%9ySzc!8~sd}P`^`WI=;WiL7Ny@Tc)Sx`?$O@|X(WxK{stE@*H z#5C-&9L1HycQ%2|6ujJqTB6OY{25|0ax%v=Ims3Ln=Vd(ulx86BGuu|^<{*~lySlQ z95zW?lsl#8lnK?ydJdc%&vKbDoo!@cukl9KNyUYQUbC7c9Uch9$#1|K0x76hDl{1O z80M|j5~Mq`SX$EArrtGL8>TP$wkk!vz`Xgg)cfYLY*|em@g06c4l|IgYA7=F9UF#9 zPq4Nn9)0c(0vugqnl)>)nKU48rVnSzKfsCPNgMYFOEhS?v<5Z4g?WwpG*EyM>MJ5U zVLhr=3&oTnu_P{-c42yh{j;4sj41!*eQIanFgtjP1FvT0EQSea}ZIFwF5lt*1cTqzx%B@L^`7^n0P4+5l6T_BOzgxC4 zEdoR-FNJW^Yjoh2nIwl-lVTo4?Fw`}9=eiMmnPSoiI7(BR`AgJErF_b0b9a3C5j`; zwU1Y;PJ=Q13zv;HN8~2#$nC(3N(+R|R3dA}QIwzz-4j(7Q*xCpqF%2+(#@&dGbTn_ zwvyw?tXrwj1ff^#$?ktvlaI+MQC*DgH|jUSsU22lNCoViIF5hySduyX?Us0Qxn!9K zkKEjV%=htJKTOrZ=SOPDsxveaX26Q)*0#TWxm%pe*tZU`a2&rbXL2J{Lf{oHwxRyK zH=5W3y36>*+-WMWSOB|=vIYu<6JDfDyRhy}EX!=xXCHBoPo6@OgVR%Da*QaKl++`P z^=eTCGo%G)?%-TY_LrzqpbH&uhtFU(ucP0-aWY5co|!DF;UXF%i<55}UO;3aoa=i^ z@&t`?4vDlv@Mu-=Pb;vq*DU35wKZ@Rk0uqM3{Sy@#Qm|6mCNm8xxa~Bjxx`pG8SFh zEy(w}Dznxt_zz;3yNq6Jnx}L+-GmB)gj4F&=!Ds@A?kCz&mu}-)Kp;N_UAD^d#JyW zIKM$<5ffw4s=vw3)ke=SyF47F+pp6;)0@LJ%yeDu0nsRM4v1&5F7l~vXu zO(|glMIDE6isnKua4#s_ZMcMYXw+r|C{s}$^IR=k+ksN20(fN>Z1UKF9Er*JtC5zS zW+hi&Inq_chE`lna3T6U55?{y7{AY0Qmv7;z%Dh?q8|Ug zY|O$PUTi5{4`b0$E&^xcF^m%f_8}xk?2l6-OBBtDPMHbuTm5l5F87s6Csyyc?Pm?C_UhI6QgD~SPwUQ1#5nxKp| z(qjDREcV`KoMJ2@k+FO(=+LGcvOaJjev%`wv3V3K8S@^TxA6TQ*%nD!pYx4<<@JFS{d6rdnf%{#JmOeZCcDcuOml| zMAjOoOr&vBD1XRo+yi<8>o(K1L@{KE50kG?z}LK9gnMLdW;|4rDV7+MfX9`zE~_#; zKYpB(BHDR+iJXAU>1l^tLKkt}Lzk@+cK1a-We8}4%ctq+11Z6%2_g0zr`D7?^U2Kl zod-1P)KjB1^a4!;37}mZ;-zeF@$#y*82EYi_g|-^bMG8H5BmIt(G|$Y`8A1fIaH&e zDcO{5f$B^ptzxPl2A@uZ!hTJ6wqt?&pm)J#$~GkxXG|^4GB9zBMgPnA!JEkIYk2c2 zJlP|x$2fVQ=MM915 znOf=MHHEQ5MWv)EZBNbwwmbM^mx)r!$YqIvX|rHasZU$nl+iNNO9R9os{NU_3KA| zK((7Y!zz(nbn_rig=53kX#F-YKp@ovy%VZz{if0{PH(**s%BHtBuiu6SQKiwm{uHN z*uvcyb>7;X5~(G+vrN~Nim$WAkRFO{$=zJZ zbgz#yTIuP4p=DLt(P&n^x>fODv6$(zZ7)*B2Js;xO_XFWeArNap`=q`1x%J?m4&u| zBU4&Y8kDEKP~1oi|Ba$NnsP$2NMiDe&;?bJOEi;lSx2}$Y}@%}O`rf(8bawg%dr+C9Ln zceA)rB~uZF&gZ%R63S)6BqHsn0axi`Bc7S;Eykq?zd~ob$gQYb>52}R(ost@W ztF)+2P5s0Z`kD*k*2oZ^JIc>$k6Zfsu@b&$3X|jZ3OTpumx~YIJcXhSYSni(*@zL{ z_%b>US`OFB-1j6iXn%b0*L{|+>Vu{jWV;6cX!QR<1Ox`kRIwo6=3Rp~w;lun_YH{Q zz_cHAR?gCD_6(X3qZ1R4I^R_@2-We~bjg*RZl@j1PsCxX5xd`|-8P6I8ya)J>C9Uz z!J*H!NP7u*NeFZZ{Xj`ohD%T!Xs1EY8c{A2TJRQK{!?R7#LVS|HmBF&46ChI0U}?x z4839gS5m(cg|3;NuGg`A?Sq&2mxLaP-=qaJED^KJ?W98XLwfVQ&c9GUkd_IoI;fLs z0_;LFBO(N7IXR+nEIL<(QN*6BgSM>?2hA;e7C@5j4HvaCc(_}|dj3^toBS?21}m%j zRY+Eg_`ohKcgB3>_74NjDkedP2)ZhMN!=uGS^Nkzx*n4#W&b=j#@fgV4ird)N=Qnm z;g{o=rjncc&vQ8~Hf$U5U3N$jmyjfYO9E+zJ@ETgbc@9|l^tC-OYB7cBEg}|d@Inf zW&Vwg$>*=NqGseUqX|~1)FpO_R`r6oXpyJ~X=`zApLI`jp(0;!nK7ZF3C{&5b%gVg zS`0)ce=fL`9!Z8|m6-YHQKL9AH<#XNx}vymkR6Th)29pu4X7|@NYL8h<^z+PZlXAg zRB{472w=*aY2&%mMKz1FEPI?Xg@s1ZuXPZ9(nmn#N3D`De?48NQzaQaH@^1`#n|X= z(#^NZZ=>dK5;?a`*+w|9`}Rl8f3@ER?Vx?PwVfY6FGHgeYx{Tjg?5KnE&-|EdhfY^ z9LXcNH7w8jgWu=?N^dvk2XtQV^~=?V(A{&vyE9izbn#Kcl_le+Kg)iwqWzn-qclL= zc5t)lrH4*p{hA9k$KU`5b=@owP8FquZQw9^{Y--s2xPK2;p{{)?kYc&McJqU-^#5< zgB1E`Z|yxpX+3F|^h8^HSvzuBkONp}T;w-MGo@yc(&jf|3zo5o%$~cus9_Hu8_*?h zHDt9}RxB^gh%nSl;~jDt_j2mKIRUA=6Zfp-t)F3XS2>U1G%hD|Gq6N5Zh8%m8+Gs2 z=HH+n?BacojVbDi3Y08>0TzqrvDBEBz&8dlB}JgFj|Zu0Xmkg3Qj|p}^Ui35Qb%HK zXi^8hr3cgzOgk29HEf0(sHE*h4weZz`9hcvVKaywCi_a4Op4aY) zB0ft2r7z{rTwQ#KHx(tY)nw#i*oQy!5-NPWQwy`}LRcPjN3A#O(fHq+ST92oC5jnn zlR5x~kz5Gz8pO+73U^m?SgrP7e|3QigQ^tZv1m4$;)GQcd}u+cX|xtT z5BQ#~&}FI;70_6o_h0QAc;q;a&8dc(>C@I}&>RIN16=TW!Mf{(ZGFm#LdOkkFfgw<;*&zqLcGzNm4`;yyq)jM644w}5{S`z)N8K7T{<`9oexgV>95{F zf|kZSY=LbezWtTs-%5FK(ZPvvFsr`p^=fOH4JnMoiL4MkBJKVz(kkBnEhgROTw|QX zuJz3UXG*a_c(jAt@O3#77jcB^lYp)8tem)Ey`?+G0Uw{i0ilMeJT}!%(XW$Jwhu1c zuz3?tN!GSKH<)+=eXH#@Z!V__uol3Fai=EtaoU32kMAgh{&QJT=$RW~tl-W!G(ypR z%1op~vu+cXUl*=g(9lYJ6IkNzPR4QDJCe+pl+7KgAA)8cK7GUAv2VUB-i=cc zkjRm!5=oZ_~02wAN*BTOrqvz;~NEz;5tf}G9^)i`>%`dpU`g*KcKojzo$2(sKEOv z6my8d+{*u88U0N;oh8I@V}ZJOKbO5l^M6b1LsJCJlyC<=*}*)h^oWNTLBFV&+$ox4 zGTf*2YCZd5Rg`{99FI5IRLseVd~4XYB7j3ys^T1dq?r+-u2y!4{W*1mx}_wkt%d|$ z5n=9trw@vDl3CQV5+ho^HS@`wDb__sf+L&6z^zfXB$LQ;DN@c8epa_EcPBvR~@DbB2PZ|Un{3lR=Yj^l+XYt3~-fI^Kv;? z5Bv>o2U}@r%QGNqimoI;Q1+j=__x&rMR3A>lC+f7dBkcB8853 z!+IN+kiEiHV4cXZP2@?#f{#I?{gJK&SjB{zW%-17jmMi!y!A`AT7hBa?^TOL_pp}x zgNIk64~=A0%igp7LgPh6^li0G{l$Ul6L+P@C}d``8G35fZ$y$X%bWJ*r(GP>9&2HI z_aF>R9+ft}lXA~%u6=a(OupJEbNooU{%=FFahSgdDv2-xIHe1lv6JJ#F1r!ld>Zt- zG(1?0Ntf3fF**)|+agm#i;Wf7xocRiXtlYLoHjs#+u<`Y3V^A)3eD(@?Q3rkOE5g1 z{v>}wWuNJWfmEd-HZmTMgp+<(bY0$Fy@ht$7_r=Zev)*usH49+x|E(tKi8u~=fjU? z0^<5FLFF1W4YwYDH^1B+xJ zK&(YCE8Arvu}Ia^R04C1bXSgEvESvq{WuS(Qc z2nSCh(0?ik=}AKbo2HC(&&AWXK~YhYcTdGT@|h|g648&0r0AzzJH=d`GP;U;)_CeU zS0_ny{u-`y5*UkLKPc8b@;#yX^byAltT$5wGd-@lG(G!I7KvxUql5e|1c`JV6&PzzemUntNTcUbkS^D+l%s%Y|FNS%*m{`eHC( z^;!VP5A9>Ud*g>Wb!o#VBk{&0Au&V-&wXAt6|1~iyvCeyzto z@4X_)${LG=e3ap2PqKCGb>!Eg-j^i(KXv|3>v#J80tO3iQ?4LgT16z>{vPBTZjW=a zyRfq_O1A<#n}_6aabEQ{ILouJ`)sbV$p2Oc$+DfoKW1mM#Z+lja25i7j>E5oB(OU( zxV%LV!0jRKL#^E}y~$p-hT=#$V2}O}1*dEn8_oy#Jqq_Hw>ejQK4X*5Z)n1N9|C_R z!X=@7PxyXg)bsRXXXZH00-kAgqRq#A+TsacWnR@&y1mob>mph~(0`)t3goUG=>8`y zX-0%J`-Dw=klAJB@mt}DaQ;2~KG`dAj-E~P(ve56?|{VMhtIsN+lEK&%Yj43K}4;Q z5RWv|s9(1ZwkW;TH7EZ~+T+|YL5o&PoJ>t%q2pfT3@or#3{P%57Vec8jlVuPr<2(j z?p*?*-*=lVoA`XR`xjJaukDf{7jIQ$QLTs8ykCa||FV+qQvdwUAIgXlW5y1I$tUKF zZ#!rlwIjnlbWQkG9xqQBp0_#G+P3IR^sR8h2M4j=1rLmz<^Ae5uGBxv-#qvLrv(V} zMbNUSG#BUI@jCx~uCDY;7dz)a<(z75lNa4kR#irK=Ux*=y6JEW4r3?Z;W=<0n26b} zt^O)8KT)-6ChbLy_7?U%|3sX+GcDBTb>&fjq(QpLMxD*9j;C%`)ES@#s6g<7{vfo{ISebI)xE{ zdSun%olF4d;l|5{TE=f2ifF`gJ3}rb{rx0Sw*#{!YFD^rFb@e@VX@oRzc;Z;kyJou zVY5GGWO{MG0N7;r_Q0g(>kTbXR=9u{<%;EvwkT;-;I!gi@cr(Gw$;1CXA0i@{MBD4 ziz*`V$inX&4>T=mf9gAPX*xHRDQSy@di&ml3N$ih5YLbm02eZqsi%IYIz3Q5LCb07 zG#`Lk@vS9XLKVdNoANxosiqRHA_{ySt-dEwY3@f%VUfJT5zdNYHqPbnECGb^c(;NJ zc|}}Y*VJ<;F1%Q>QaSp~M!@%(w*%XxjOqm`RHmdjROHL!Da<31b9g_uSst_F$nIR= z5LIwW1tDMD(ZE7@(8Y=K=GOFDdQ{x1NsE<|^$Uk{3E>x)I_r2Uz_ntZ$CJFwBqTXe zIcN&iWoDoT&E?wmW|@hRQ^9!4RuZ>_Qdxw{)@HeH+70J?G{2Dkb76ko0Ya>C9vw(p zGk%xKR8v_>s{gDb#rRy@x${6t`O|0+>*VlNkgzm;%W;EpLB0ibimfpreP|;}mq~(h zA&X%%l{CE*9kUMp=qxikyk@fM?dXq4zpe?+M)FQ~`(&+@Ay%3goay{R+T+zuJUB5d zTH)Lwr=~A@UjX-P)cDSFsb`V~UIXHBINs71@E3=`vPm-7UR!-{~rvQZZTZq{J_X%n&gUpbcv z_rkbRys3P8zbFtE-A1XUX{!}~a(2AL$C__t3PKLH*L-=^8Vx(zH!e@I%-!La{sdoi zhr@Ek3@q0j0!!WJnrq`7I?OuIk?OqWD-=^GEs;W_K!8}LcfHPAiB~Ai32;u&WQx1C zF0Fdxj0~C{{)X|32S!q$)KXGKQ7Bt}M9X<8jVh7(%en|3FD08%BpMRBN;*XnyKwH! z-5ROrMipG=A=0c>vs7$STMVIMl^H5R&yXn>ES$fv@TSfPpjQZ2Z(7l9-`V0c!?JGP zX6fiuSe_>zrkhS{R9f6 za8XSc0%M|JbbU3NI?iu{*Q_^fSgDr#Jkna2LgktG35+;?%1Ur^c!!rwhbb+VV7DOu zrTOjzCwm=l48l1`M%P|NywHdYq@&lLp-{V)tly=lq^BJM&nXeqRIGBtN%75!W$Za? zYXSw?3iDh_nQK}=cE$LQckwQgnPrUg^keQiYcn0nWj#c{5g$O+?wtm%S*hkpmU;!eNdiA%PmhNJXtY%(HXd@1-8sFn>)Q_^ z%SATN1anlZ>)7(oUkx{^wt}9)uqI?+Cx~-;XT>iUqQdoS9eVcFAQ#i-cX{zFFXkf&Z8vZ*ZRw_LmNB5g7h3rX_%_Kn^54_uS%}?!0IURu^L{*yWe7n2${=KhPWY(7x0=uH?)8U+P}I=dYwO z2p?QOHaO{JD{u>D*8M<;gksm*Xu;Lnukgd=X>p(Oi*I8Meu@)p_Zl|Yb>#TE(MuC{ zat)_tC2uE6nVG87-n!-W151#n-@`wrdqL<6BL$7Iqv!DHkB=2^2L`>l8$$|GXJN_r zyFgy+Hlf)vc()nQ?IBB+)4zzK_f!ARQC+e!)`4CC8#{|Eeihr^!9hS&9nu%QiI$G+ z>815;QTrJZZtf5vmsHlTuhEAg!WHkLF%Y>^BCa@3l}x05PNeJdZO^Pf2P&kZuXVqT zRY2!)FjCvkNt9=54rkSRCY87UHFSAU|G}n+GDjDfF(%CETu_b`+;Cww;NygSrLW4? zyS%g-*)RGJ+<&1f9vit?Z;6J^BS3I@!n@DFBzcu+ld2ttg-Q^8%e~mOv%S9h$BJYB z!EESa8}X!}Et)anV9zA8WThkHkMijjz?u%_XF#0Yi_if|Y81JTmk0nKD$OnjcJXQL z(P8+0kkGY#%L}iTYpSd~-l5KnN4F+M1-YmgVtv%rAk7;y5U0yncEvbsHUOyMrV}5e zC@gcqdXTP;Cp~Y5*#ug!?i6&^*6nA`-qmN>pA{(1C(wu{!K6qgpa;!+0p;!@n*-QC@byHniVp*RduiZi&oySo%S&-*1OIp+tN0GSEQ z+`8A=*NP_cehl)B{p?!QY3A%bJ~NDUVEI$v(D~Zn^TcDbpopjis@}xbp$lxL^xNev z)=Cl8FK#XCxSp*vaz;kSj z#k^acb(ZGXMY=JIHG4FD#T&VrVXYG*_KZQ!XK>$U{9+u(#0}2&bGFIl~mrmx9&syN+OeG2B({*#M zZf~6R(uuFO#NodBKB8SbX;bwRuB3v9?P2CGKbgM-4?<`D`8)|qn4vsbiaz2UTyFTy zZ45|@jnf&Y_gOb{(t0+?x8pyju1NWm`yIVq9?g zmZIe}Hcf_%#wxu=4&UC=f&ZqvI+gEE_@<+bl2_wqW~Im+x+aB9DGmUyADAhQb-pAm zwTg-b_?9=>_dNM2SgP3QcFk2}2&Hizm#lznE;8``cj*)__r+{zc=*Et2fWNllu@@n zI>2r_I%noBTRf($(NnTJkg>~O7PBb`=3PeLXH}~VSN-U1zjUbzA5datG5v={N2F4? zbmOn1tV;1mYRq9zCO{v+%h0+Y3$1Qf?IdO0W3jfG;WK~K#)&Ip7f@h1Hgai)UN?4o+Pux zO6(-o`#|1y>jN!>>zC`7F?Wrj4Uf`NA{FRega;>S6CGmVS&fb+36Kw;uy>gy-DUg* zwu&PEz$8?qZIlF?_OV1tG_ar83>dW;cG8zEg9|G@{D2~L`<4A}BC8ruP-&6TS4W?f zCk{E;1_*&#B*;i>m}y$EGRD^w-zKbzd|JBUfUSIO>Jyp246t|;R>lSosCOaaKuLS`y?A@deAODXPgk!VQlNVX?J z+M}(lCI1v@WPr=jw6nPgTf*>Vl^97iuY%oGPf;~dYF+)GRZZxBCojM=maFgqP`s|- zus?TVSFdQBCBd8^T8Z}7=`IIh=NuT7Ve3`KTr6^qwD3v-r)+_|HJwa05{6mKWB=KtF_7+1OM?B|^B9;4xjK z#h-GDwcfcu!9znXCJE0PTD}`i*eY{j3A`>L*iOt!=m&R1vjlDKGt=pfaq_M&9)e!S8=SY1^a@@%kMJ*|PI;Ht9rhs{MsRtQVb z^_^981%{>~!q5sg^jgfgZ{fYR`}zmkY(~tH$75F%SQo>LIiaeDeW)U`A_cr~Qs4EU zyCM4euUShJjjF`ZF#Vrh+cqSG#^`~qLhaG-s68^$2(I<)r`(Fk4>7F4;LLatJGZ@P zX~LDyhc4WW&;+_z)U)8tMJGpIoQ*Yf2IcFrA5w%1bkvoIAZr@Ui{>Lg@Veh?vhI!W znurE$3P?dewOhJh57x};?CP5GlwtXhwe|L%~RRz9Gd1NwaU4X6H7KNO_@fz((!Sgu1FIP`zkr9|t`hP-vF^(; z98-jl^DZ3q;R_475)+K-@Oe#6Tl&&c!}G_7h>N}SwX?DF@mrZx1B40+WpfjY4^Su% z-e|)W$H&JE^DZE}EpsvQ7(BeKFHny=9xqpN;2?90G_xq~#hvjL;>-29=;2)qe(u-k z!Q9VyXXlg7p@35NWOXAV^lLP|>m?Y7w;U+_hStAnOVrUYsQno>x)JI0F8b1Im`r)9 z=%*Hmm1OnW0QyGd)W%hVzy#s5S^>jQ>OmIYTex^!&K2G5;n$9_*N64(t!&hK?M-ua zA3t`nk%IPp3J>~vyL(_(Y_Cl{m>P~PpDa-Q%0G2xLV<_ft8{h zn$B=)BCDlKmP_>x1DF6U2tV*+^dq?o$5VnEtoId%wFv554~W9NSH9lr_$UjhfY=dcR~rqLk%wyEkoWdwU7vV)I{~cC8f26XRV7F;WBD=lXx6XsL?uN^AVWYEzi9 z`CPlV$uq!s(hflT)@qW9j#`dn@H37uY&H%Kw_uX4l5YfJHM4m4ljPkOiCfdWG6M<$ zK_`4@zqI4!1x;QrIO~A#{EVpH**tEoOITsdksexjZB!`URH!Ldg8+Ssr5t7>d*HsE zZ*Acm%^o{9I~RysOgiwncM|&TJ2Z9A;Qr9Ec)VPM1V~nsSY>5pC&{i~F-U(?J9ej- z-vzn%{TdTNsh%sI+b}MzV2Z&vlSQw!!(6j6PmJv zbjp%jHVvKrf7aDfbE<8)O;f_wfE3b0sAu_FPe(x7yHb|BxNv-R`22lxvKuX8sJ$dw z4d9fh%))O7&j?0P(d{dz7)ogz;R5wacNLw%$I7DzfzMAd-B_4oeKr^Mz7K@!Ict}v zkKI=u{{p||BDcCXN)I+!XwxHOnGhw6O>lVwN3U{uUfg=;3x;Pf^gp>sjkTI~-336e zFbDNp^++Ki7RMC$()%8iO6??2s-m#~1=KnCUF*P0*q;re+8|bFdf?cZfFplXtC_{ z;#Dn8zCytnl;`RUOz-LiyPy9C7Vh0j>R*EM?4p#^AtK2jRTlHMs`8M~^1$bBwy({h zknVpo{|N`$|Be2&lo#X)qN|sUx0v^nr}*dhupn;_33=N88ilXe8OJe3HUU(2_s$t# z9Q^|h`}vZ^OGN}7rT%ETzI+4{OjAR@16Z8Lq08$>e%hg0*xNapc$mDWr`K?|Uao_a z&+tqOQT^HDV*7p5H+*!(1qwr%4n)mT1XnPX^g@*#+4eBZ!cCf{ozXAb4!1w&6ZLl+ zB;E5oDf+qWS50=s1%b!gpYMTL&FAO-68$vDn#21V9w*Qa`Qwh~s?%Qb(Nw4{Hex6G zN8^+YPD` zH&9?nreKr^DWYCTK0#ourYa3Nz}486cbm=qt|Qf@X}Ou1d4EiK&DbFdNPaJrzy-{< zt17U7szhwZoU$SiAgfHXPtAdF z0O+<4i!t`oEHp|;bit5@Ibv*iKFvo_fUxt|#gfcPySuXu)KYm1ts49j8p z(=#oRp#RVc8&^z3;y zS~VN8YCMCP3>9mNp+p%Y=zx`~fs#-5XLR{DWwRTYC?*P)eLA37e+H&dt2o*D?@{m( zugUK!jbWIEqvR*2KY7*0|8$qL!{x}zlJKII(r5*Gt5WC|5Za84w6F_Chf|Q$=;5Tt zexuQqD(^RNMLG13WH4t=w52oP&eKpjtIZ(Hhz|L{(Ati>aGQ43A#`HbxMspW;KZeV zj117i8M;H6c}k{kGi*QJI!0`_%Ok*Uo+;P^oKJ$AEe=zPwz+P#^4^*l7)f*kqg08G z^k|9_Sx_ZGrn4$b8GB@Zn|T|_#IO>VY{q?llOQ`sJ_Q4gShCXsOZHLoQ9G(pbz1DU z5RFk>c^n%sy1+#F4S`t$Oal{{ObXpTYsm~3upX)zVxq0r9)geEFcp(%O* zZ-2gyCZ6A?HXoeI$eCnaKNoFEG1a`WcbMJsG^Q=w?$$s~5R;oKq5>n@VZhwE|L>M^ zLcWGG_n=7ir=i5LjbyzY22~5!jZ{n((ukIVHBb%CPh~B*lGfvY3OoQtwqYKM46>|{ zX;KY_C@Ewv!{L{Lw=p(SnB$j8{?@_lSm}k?_=<)a+gTk+Kz1tZZ+pfXIP^jgqPeCAQ4X<8x` z{?%#dk;|Vuo!%Lwf}`Y<;XtNgiMuatSq`i@Gpe){XipxaE@6Cj=#sVCw4O-N>gg_L=mtX5*bW)TIqZ1PF{Nw;_KsU=e6#A)QcF@sB#oAJ9^a zSCr8MWx`ljvN!Ajt=_{lvXUp1QT@qRbHTd#Nps)nYV6W#>c_~Um-n5&HDE{O#M)Ub zZlHxrSQgA-S#cYBaTt2qk!lms>-PLlEO7E&ekE*nJ9lt#3Cpetm{~S^KIDg63U*3J zn3zb{F-=PkNi^H__@uoO9V}8v6^mFw7;hx|t1r6L8M`u^jvfsHf-GeXcf?ulCMSV* zuA)sd>c`3ZtVSNaMrLc^U!uu6%s7xVDJV6u(dbKM?CjD|RK7|Je{a+`urdNR2TIF- z6B|Vq)FojpH}Ssxd%1T=DWanM;O&x%FBMV0UH@DV^P2e2nyx?<;$2&^`I%)pb&BGn zjSb4Al0ruMh}MkdZ42$W(ty6NTFn+{uP%hy@OBDmBpNM^HQ)1YLWM>8k7R05Sdh1$ zegq$*RuC>p4U^FqIHr#q_U6l$g0I>lm+-casn)t+3qIxt+&lAOEPWzV#m1=pkBw?{ zv=e=Pm1nx;#@1*vVzb`!dAae0(okE5%gZL&boZ1 zFO?!Msl@&(qgm~|JyO7q`@7f+S4MK)J!Brl3fqspVTX8q>9Qw z+ga^ZLeR5;bW-8HSotGVrW&&; zBM_zR?VNS?g0;zCW~9v`giKp3o&dyb;U29WBFfwu(^o_`=>lvn01|IYS)@2Xqs;tF z?o}M+0&~Z0(itd$Su_)_!^s)M=SK5+f`)pVOL3aCQYSF?GTI&xd#FT57WB=I7lajX z@I3JwvKTZEU^MCDe*~HVp1{tnpMRJgG8Ag29%15VMWu2?f+1WGCKIe0U%Src3 z!o&c#^zzG^uTV#1s~+eu4EWE_FD^6rh!sy7wXky@Sh0S`10b+w)Ce_cGhorACX;ij zmlAIHsx$HJ@cz)H-DR0SpqLEkPhvOr^6fDpVu^D`EHBg~s?HPk=QNu9eAtLQYa`mI zQ?FAk85~#^YHSI0(ZNus2lX=Fm=2NAP-7uMF3?=SHlDCvgvwPot1{{$=|u`Q zHvWSClje&LN3Drgon%@yX@iu%D(tc0XJx-?53=O}?S2K(uH{A#p#buozCm_m2G}(i zs4=~7+Oiph^~Gz+uI~afEhUnrY5E6HVQ=C1nqdjKb3)3?{Yk%oKuK6P0FLN%2{gDs zYsC7;$wn*XH{M|d&_QWPIM&*xRTurI>)E~I9bm)+J;W}~kzYIXIN_nG(^S+Lr(w4r zZQ>dX1$s15jAKg8<+IxC9I~6BRb~?G8~#WRGJ0x+6aM$gU|XFReGnW4`VI+hod0us z=_L%?B|2CEO5(bCiu6oNM8H_H-EoJD4%KZB00e?sZQVBD=p*$%SC>UcsFmO7DFB~= zbo=#y;4HL1KMD{twE10Sea@9hZ}jhdesF)MvDKL z>0rx`sY}Gc0)J0GTf}j<2IMs~nK3G%C4`tCQnyDCXr#G0d)juuii*!^H^T8POAfV< zN*;V49s9`hTR{~jWTi>Ao(rO)kioaS9`CnMXiRG%JGuhAzQR~`Jz%8L3$kje^X54n z`LMLqL;R!>D<%F1js8?KVyguqkfRg$JK5Pg32J*qT9%RTKQCdWCMN}3`SlkemirJ0 zD=XSXF{>N}deVV9`NV+xotQ2xJxu5Se24@U>EwWa2)|ZnmeN&INsaxGs>05w;-jW| zvZ<)1B&MwJcNc*BsEj#lmSVTVE}^K1gRtc?YU0yBXCkU36_;xHt1fbI$P)&1vF71-5?cqn+36jS*p^9Z@&?KjJQg0<}ziDw;@=&bc=g? z_l=hYnIGc{3>?g3nbwo(nO8Xn9K$whG0+c+*h|5@_faS$45FPdQPHp=w}?XQr|NI1 zaBVxTG6X*fA{LbmEztg5%BsA9`Dc+jo)DHF_*BX$7KyJ&MG*yxT8ciAAW?lQWiNmlHzcGt0dNGzLN=APE5p3wz<|jVx0AYyQ zPzq_=q=HS{RE^Nd!q@N)sf557n2A-ayM-9eA+53k)4~vz^fDzjC5Ldth znxa5TvXqgFFWZ5?mdTyCzNLFCz;wG}a&_8I>Z6GmFW=tFWAaXMOt*8`EBJZ!2+Ub= z->8|&p zg-++mn4dIW;<&v)LtaytZ|_PRsUqD3>(uFXo+ul;Rp7A{@tDla^&eW?Tld6M%g)D# zi!EZ5)bqTc>cIOTf3qFN#E&93sJ9dX9|ve? z>qmwPK}k5dmyb_@J8k`M7oQgiJZ_^Cjo8h6yhi5s(&A`|H7i{@pqiJHsjb=k@F+;i zAc+;!Ls5zK=(FfW@n!hbG_zRL6@YEOH76#&+FV+}G{YcD?db_kKue1sjkhX;hx~532cK z2PB|3sH2KP*F9*!xjily7u#vXKvUmQ;B{xRKbS{Noe^Tkoz@&`iGP?8c} zqsQAR*Tnwk!*6#jI=e8gZB&|ij`xokIXRxuXB*cOKt(dU^Jh(>VkqkVzpVaY(EFPq z&fpDKJCA`$;F1X7%$kswDxwC>gu7z?j#NslB7sOp7W`mUbx|%H`E*GCwR>>92Rop! zD}cNQ9YibAZs2$o4WJN)i21qA%VR9gHugGO{2)ByMxjE*%{ZyBfceUhg*sMh$OA-pSMFg z^p_G6g;cUe+GUl;gIY3;oW}vYS<8YVQUPU7(-y-{9L7Wo@cnYqA6=zwZ zG-MgM{9Y2%@1d4E!KWVB0X2CNguN*6|8%(tqmBzFT00uXZsvGgyrlkHKf6CDAs(|) z>B*#znT;l9cyN8olEa%IW83Jpe5Q7coP2K8ro68UvL(>4*I|?)8413-<(eRVP4Iti znRp~yGJOwvc--uMgC<@*VZE%9{qix-qRcGHz$2{FMT$t)!%vf?#g)x(EL#Dgo&@1Q z1|Wd-^|&uD3V#vk0ni|rDx#vQer2%-`h^AQ{MlgQOEA#J3v{UH*bMer?uWe~vni|~ zqYC_4@ycwW!5Rb19Rw?nr2Ezg@i13LBX>u5NlK+wO_uI$^f<3A_CkeM3olmCXrgmd zvT^qg#O2(drV@v5XN65JNq`$TcmiMVp zwq-j=7r0DWOkcL0i3IqzZXjPhftz2i@H+Qu!9lvlzXfGpOaRr-s{8U5o?Ym@$~RmW z5?B2y#gnf@a*{>XwzYp9e84Ez=IGwqpj&^V+`LmdvXGjWSAdTy2l@NOMhe#2iq(Ac zfDDsu?XTU@;YVOOnZZ(d8@Q#@B(F&3ZQs5=g^`bC9I7H6mkW8!UtYKH3DdVE0Yo?M zcC5)YghNz!w5zm+J7$P6hVXOBPa&x%atuKs=`e&$kM&k z=D{~yI6Lh938-@ajSqkD$}z(al3{u0NU~S*uUSPg23u}(a_Kl;#rYTs z1`BKLY-Y*(4;gN1zn3JZOWo%M6Gz*Cak0t_46j#`+Z%@~ADsqwwUIbNWbLcAuCQ`9uwJYWj5*f4 z?}DKnRybsZl{uaj5Cf={>e)yoS*MlyU9?*DkOny>iv;HZPbMCgnFt zVQdJN>)F)lx!4XIiIqrtQnB^4j*eiNyI{M zBrBWcUpo))eARW!B2D?IG{r>!ijqbAkqkl7ZoJLsDbP_Pq22u`t{LwWQS}8)UOxD6 z9lKL8+(9K6JS?fcH2NEqn8pc&&4NM{zGtJ0!p!}(^YqX|+F+kF70Mp0GQ$AslQ-0* z%{(4@f}6Ow{eiA(NfH=f);!xFdJMHBYivbXrA&`b4nOHZ6__iQl4PoknUe2cCoR)k zfn&~(ZE7;TQj?}Y%uMDrttN+#4+8KOVA#--I?unlN))75R{dmB)K)O%cxmmSX3K{u zQ495xkyuN&l!HJCR{re~M9ijy_IpdPwvasC(VC#n~34%2j= z2Znl$4FXAvq|}c~UGo-F(@M?tSi2v(EH~;x>vr;$z*mqh*_dZ2s{pf685`zD)09oF z-1k53vNk(+GpiyA@qOel(o+}55CANXTH@gP(q**BPjFlAI))_zmAZfeunJY7(*6Isv_pxLyF6 z2@-F^zO`>QLWXYgx1fP1Zx2@^G7pHw;w`14m0BCLZ#i=H;nh~^W8E*6_q+~!9~LL( z-`PpUdaV}jh!xH=q00h5nX)ZsQ}wR1+=VjaDTZQtLNS3AQYOC?)v(Gfww`Y~=C9c$ z8;zJVeuT&;Lm_wVTOh*&wkX(tz-N2SJf2@0RB=8@0yR-`$`%<4`U0?GV+BBtBFc zqL3dhSpYM0Voe2MuWS@!mtg}CZl<8AQ;ur6+_N(%-AXY=p6ot4Q6hDswt11#lWt`19y4`gUs9W(vNpDD)#8^aRO8% zdM1C&8JDOZ$m}ymxrP{NmDP)=!8p=PzCvYh5s5zwbJxTcWA1JRU-eU}tACf7|Ac(ugNwLB!!jLV}YKo3X7vhR97 z@g$QniK$dcmaSSW2}UxDyc*TcJ}ju0uzC5vhGh{9Ds|(UK~^(RUS?WzNHI;>Rq&ok z583!objDBn^npj5VcDboIh2{Qb9C9OaP)e#L^drqrMP@1# zvhx}|oa+*uKET^RE0-q#!uh|*69~eLjF1(6233OP5O&d&ICH~u72YStS$K4qom@^8g0K=nRQxOxlL zt^|^iX6v)~y@7HCv>m%xmb~6c!90AS0WoT-vsYQJjl0}Vho?l24)5`WwipQ|RlV^P zu|xIjmRe}zr82cX41^lqlzBUx9I=`S^xx{T8zZ;|3%7>;ASM*r5MXIJF zr)>-~5Szm_2N4QbCXsO<9EuyQ;$(?r6XAa;qxK>@u9gS3EA6DxK&QnnovS9ph!e%)~){c+yXq3iMYD zj}-bQ{~jT}6a?=d-$w3~|EX%%7-v{Bl*Efm&-!}v6ou*7wx8`22j>k70YD^-GV^vJ z4eq%)M23;lvAG>4Uxh2YZlCd+waDt@`}@;GGM$^K6$wAPLW+ckPESFD@)I6@ZDb8z zjbIvIlt`D+M=B%qN)N^1p5}>WQ==BG$F86Q3Kjj5g$^m%Ws1F@dE?}XPh6$)xsKdp znkuk<-C^d^(KMv#dUZqg)Pu~$TX`U&&}={mAGx}sWUN`hl*`S-nEdW)MIj0x0IauN zrM6TzSox$CQbALX(I-(LbHkWvqA52lWGjW~bt|q4Sijn%hyNnU@#`1J zu&8-7f}v6@4QQ}f(wX?YM{sg;9c78TH;gOIjej9bnT)$=vc_6Dl^b!PYSW|KxKi=2 zm6%02ji0_Cbv^EIHMos-K5U3HBcFewDOp5L?Avk1-ov`~5-mA|Hw`xR(5P5EZK+J< z^>rGcQ>8{ubrbIu5{=9v%lbW1va2qgh=}^YZPO%3O+ywpTypSLz&ZRyH}s;ULtWYi zl;9d04v^071LJa1A2s`Vx;x`KcnT`Z%S0vGd3X8`K>HmgwjPf?*fo<1t^@*?@Vsz? zGLx;cwv{KcBWt!+lw_vtZM(Ne2n&CEkhwnv#6}8Yk{%sLCPf8Gq2Qu~MSI;pa7z<( z>-{%(hHCe63&`GhpKh#cJAD;=GQYi$tNGZo`4R5!M@Z0rDpmlJ{%Y9CK@40^79+!K zhBdIr+;C|np~VtkU_|RFvSiyjB0(+$WAn_3NCT;)NuCicXXxXs+vtnCsukb%`K#epkcqWAGJ`R3K3r%hl_3zqN8oRhL0YR_`R}7 zTGq`T);6xzgHUzB1zItlnq!ZL{VHHM9=a-wCsLyT^^)hKyG6RL~9tRh10q@rn_6_F8jmXfwKnIUd zd;8}8qcQ)#-N0Y2VVmdB>u+mNg@S{l2UV-=?{9~R;uGr0Zp7LMOdT-t?>qXQE|jy!9s~RC!O77wZ;P-$xTVPNKrxzE*Z#@u-P z!^MU3&B!Q<^*xl2z~DlRL|macdZ|j1|g7?;)^|C}%bcpZ=FUSUKxI zhljfB0+&Y`=)VEx6WyNw%QG{vpOa+OVjkY7oUuPL2(P^a z<&cwG3omJdce_`Bea<;l5IdgNI zUT!JP?d_+WTwuLK0S#?zU#67V+H%{A{-b_rjXkYld7>0E(<>45(PlXnHl<;5p%q7t z@ys>-?Ds~U*~*9oeYvll*;Vh$u3Yy1#4sY7ivNYn`wq_l;h=MHtG2GV=eI{LGFsdc z+Wic0E^>MW1F2cO_YOfE+F)(o!$*%C`OP*UAeN0TD-Yrz@Mmp(XH)No*~8K2XBS

YUC6K^PN`V)#lb*94sgC*xg3 zRS{|OjWW0+sfXr~u%oz~OaIp7-0U8K)cdiG04;uvw9qiFIU(traI@QeYf>vkFA%mJ zcF_K)7nNeXqk)}rw(Z3)R4OcPt~{@)Mq>1L7_W39=kkRv;LMhHP7njDKCmJMV8M#T zXnd=}cBWFNwb_ZBAkudr6)zJP4&{Lk)h7I?E-aMi&W-G4>oZ{pe2F_Nk%$N-gwmPQ z)>M3~Zi%5s9L)(a)k^aNYU8L~@|#>5DKR_G9y!tw4h?^J@C+Kts|8J^Ybh?Qcf@$F&t#+L`fpEWGZG| zBdAkl>{M=tp&FR-ziLTzdDje;ga=AXTVp&D1)QL3@GY;=w|7FVHOm@6H3z!Bho7b5 zaLVgD{ku)G^N->w{Q0NT(C1$kV;AREh2K#AN^wh*XzkgyHjR|+W`*}{hjG?z*1?4D z*X}U~PLf3@hYoB29g_*VwuVLkC;^;AVx=($+O61!&0#xkmVmO=6(di8=jq`UD5F-D zVm%)rh)id*(0i||PFcR;9_ELZTRoJMSjnDwO_?c&DOGOGnC6YxYW z3)=A-p;Zv16v-=Bo?t430lw4Gqs#I=frs)M<~YE)pJ}XQ^-~!iI50Ysebd*=j5*V za`+ZLr3-^rl>CO;8xZ%bi}4Iqmap|YL(l2{I`}3+c9Nm2GRuQmR8pmkrOaiLP^(!) zA)ZcMhlWegQIRi&v~ms4ZTs@4zusk53##|eq>7AckCQehJ@KHWp(T(j zU6@8y0#X1XgRn3|@@jxsw!&6uFCMs6S-Sm-Slv*%!N4ClRe#wf6Y3*VS`9_AOjKIt zy7W%&t3G6e7Fgo8hb$bUeg`$KGU9wm4)}Gsw8wRTv+(G`j_`5|<+0&{W z;m2en{QP82cR(+-@j1eB#jC^};Lw&t;NIUET_t-Gp=) zxUON>N4wrOl1MKEL$a1tIOJs!2^!qPptX(c+@}f=DwmQql?=m1zQt^u2%T zmTk_6fBOQe%nP%;K*#p3a^~kCjH z0zmkcO>G|l>jZIf0T1pvwlhi@*W2T8*6C!L zIDvkv%@eY$t`%}gx9Q2J%Tm#C5VGv}$TPUdG8m=YfGTC>604Yj=t`x zfy9>1)R;D6F$cNWQcOw()+&7+R$E{Fl;+jD@7@p7QYNFX&r{59)EXZ-2`8C@bQE$I8)Rg;& zsAzv&l#3#O!1d1+I>5UtUC82n4gMzgV`Zrj``*I!85tIcuhM6xobBhZe*>yl?FPaU zmED7Rgm0IEeYnx%ph%}uEXY9puDWTkKP+9h+~SJ)#UWL1gRvarH<=m++=j|HLt-$3e zMO#=ns`iuw$uf@C1Q2L7>KR8`!PRbm&VRv_Q0G;vV}whNPM{l4kJBeAM8={6)wYpA-!8Xag!SA z$Y{SE*DhNNA^%h>eR27{)i7>r3uJzPla-_I;OIE=v>R-G^A)^QI%P9y-{hd@iSn`T zDiAw+9TkoT??5c6N-Qgv(qk%1b{Fkyhw#BAYKz_dQ3%JmKKE-U4a$-BvPKa>3Qio* zSp@fT)k7Kek7sqsa)zg4tlCf_nU9peM)?NOM)Q7wO;XYpA?0tge(}#IVdgz>p{yl7 zs2jc{Ivy7)+_rmaMX8$6KV{mc-Xs0`wO;I`X~`@7>dvKo;q^4NhH7HC1VafzcExK& z^yS`i4f*NW;m>(L=-{9=W9|qU{Qn*SY&HB>PIk?s7-sauD>%?K?cOSfSqbq0sxpl4a_iQC$ zylXwFuB_%agmN1rZGN;(`g`ZXbDTXmgjum_2qv$jh-lha^C<$&VWnt8cO*}VDj|T8YZkUdZf>=i&5b;x8avb z3r>w%U1YN^4)T({tTuomYBBak58E@TT^-oFQgwRt7F3Rty@Wx*22Mt81MT7jNKb zIxQCNw|H?NrSARdoq?KaK}Qa|>OON;2TbQyTlRcMk!A(SQqh_P9GPgFns+CH*gL7 znf@vbd8O`;qk_TT*yI+9ZV(EmvRq3e>}fIav*|TuN~5W)8wocxP}%`O{SW17- z6@mh2EQQQBoD{coyqZ!{_WR^!3(6@Yq^VFbYtX1(NF^-B4QZ^}r7qAo8)yb>n%E6X zRS^Z@vm=u$GZ_o$0<2u3?Iv#b(UQ9)8DP#JsLpoj(zSxMYsmxYY12{GK?B8je?O7i zCS8DORQE$mx2=+H7zw^FcA%(O`8#P;=uS{t1ahfWQ_a&uDyJ>S`d&8SU-SzgEL z)i<=4wATzpUo-b%!hSV+!hQs2V&w9e$V~4Jj#RKsV}wRN(y7z81u0Tirix87-e4MU zCJJS+G_q%mr`0gkZ$bPB)m5NB1wo$wIeIiluPgd{pTP!(TkUWUx-sS?%yr`1C?$knW+Ba-NS9Zmn@7L6 zB)pHkZ(VA3*x2ULRlG_vWD~=|6icz<&}M`q#nk#29Q!ig_3c-mlS-R>Hi3*;oo>jT z@SbA6j5v+cH7}(sl1Z2B*yGagx>Nj^Eke8Q7K#a$g3o}BqI+{{u=oMWGt;kESTf)X zzOu=leTnIX};X zt~6M4^&I`U@(*aO=;5NWJUEQG+Kn)u7uP-D z_QY(Q#=f1Yb*&Y83K?0w&Bt(RV&vrv;pgLZX- zq?qEDzF*5S-0u)~=UQvrAJLM`W}Y5H`-LGj2=wBl^^mutY-(z(i@srE1)`T%m~L^^ z?rs0bZkY>a6RRs=EK#M0EL-)tGaA&ZmPXio8x7FN$067e!-tmzK)WeW(Ode^A0|WGC2l^MEBDU@*Lrb7njl&hkTRiRACZ zV&kSBR7nkvgoAxEu+3dof^|ehwo4{VajXv&O3Ap;K_o#YA|Fw~lnRcjKFyugC{Yq$ zC{XazzrUDel5u%LgVC%qMT&j$i-y&w|0@fs8HwMeUr;mPgnb{`%I& zGTZKHxFMGTZ+0yVUU*;M*dkey62)y=kvVINLq-93ftx|tG&(Yu%qcnA@I7m2pLKMM zyOLLm8VtGjdG0Vw1kk?%StL*s$tXr06X|F>Lw14zs4rZj(w8336=^zY~%2g!_VlG{biK<%CwqbB0M=JN&oa?%@^ z4q$HM^~}*_=JT669)&0Ld;6N>{Sq#aW3eV1rCJi2R5|i@K%F5wQ9Y%n{(BREEF;;t zPVkk`12>_DLOUntYR7qk%GILdar*6HUHAgoJCn#utu#OXTN35oY~b=y;@qy1?3B3n zgkdRi>EmOI-+b;tg<1(4I_ z-wf3w{ZG_4@n8{k!dNVMt9jT;{G>rTGgfwoKGROaPB7g}CVldEP0aN@Tat<_ozTg< zPUt$tduY&kiv(;Fi?KyCdwd}z3pfE3oD`qqbaMx3#wxsX>2SB&z1yk9hh&8_dX~8> zC$KXIjr_dlE=C7&mMg|e73D?0udfwKqSKJB>-hfm6`B7fIxa`sKE1W&9`~=ta^`00sQIM=4aiSUsC z3ONqC12i#^5=BGsJQA!H{fbRa4?{Sn(qa@&g9K@ENN>C~J9<-`mfhTGV`)25fDvg! zc*l(O4mv%g26%NfofgN?l5L~D$F6H7(Y=|sS-qQqtz(`@C2Ew{5Dfmdz_?a^pNZ=v zaqp{R>fH$vCn4^2B(`Z%XM#*Sbbi0|U}x6dlUY)RYPD!pNR}&R59uxqrkt3TwoKMl ziL(pBAls~_P6}?Ho?#-NvEevI9B@ZuwUOHfSRIoUE162^{c;2=myLgWH0#6=`=12^ z>}U0vy4_Wpsws}fLMfAnk;*sz1uDV<;)~+p$>yEa&e+jeW=VqvW2qHa8AORi?<0OWnKxR!D4WJz$JTR=up_8Pk9Y zl!8cQv6{5FnlvUJgBkAl@|fl;0d5u2x@wT;q?nJH-(>Fu=jWMHw$EEMmK0veM()Oq zL&OrDSTv)Y`^yz;ELLQtONQI$_NDvf6hqkhkLiax`hZi3M44~q^(4dS%o&5x%lD9n za)eI24C?LeYcK1U9*-ADuQpMJ%sVfmVZ5GC{(i641DYvQ2k*9M;*@F60CGyGVE6iRT8nr&~Xt95bUd1;!kc^&%9iR;o2mQAS?HIpn_?MJN`F#i*GId zryZ0Mh1YZh;NI`!bFMA=;@!7F?4@q}z?>QttpesmMJ`DoYV>i#UqK6BG`e!O{TP$4=?2w!|9K~G1skzG!0*% zEc`B>NSgt3R$U{RE3X-|%#3YD?s2Y zAdHK8C(u4otFel@MBY`uf9}ODD3eHEQ!{(WqbsZ)!K2ZXKQ>}1-Zo|8_#dw|>luOl z;RXL|)(<_&@2K6K(^ER5L<6i02e9LYy@ttXT2LB=B6!dxUP0~6Zk%mCJ-UoNsnk&m z$FyNKGEP-*sKsS38 zF2vdLdnc(aRhZ{#U`Z-U8MTivUGuN@b<(qQ``23GekGM3iVD{Sip65+*NF?>6YeY~ zxU`vz4B{yio&4Jc&zZ;1)Fro@b#v9=(FZGzB2E^CGwvcnq80wLM^0l2X;^?OX_W2pSfq8+ozJ%-oYpdgbXtKd~$>z|Zj^x@C%T5QblH3}sPr_A_w zW$EOm%%Yt1nqJMV=jVwlh$~s~{`mj6D(->Tng!?Ff7^sSq4LN~x~WEz(#%;5n7j5I zNk@u8b_wf+zv?FGyJvVU5|)*3H=PFmPI02g9I~0?Z|UdhyhvC6XNi_tL8aqSjv zCioG00zL8w7rg%ipc(uZs_WD+AqcZbVIRCX?nUZfC+=6h`lIv}!`YmZ`0?F;aS-DW z1i#qYgB^ncx3E^Sx@u6%V_br^!-MA*FoMkZr#f-E|to$M7Z5{TVvI$dc_&(!eAMRm#9Gku%bHOrlXm~ z9y8OA!S@0k>18RAf>9*WJX1u%#^1DQ+}$nSyqXWXa;UO|Xxh2|G4w`)n(hbnJ7SbX zYUH2dBOjw`Da^&$n( z^uj=7q#h}Ek%Vfcm|3PCJvKdC{om=@Y?MOAr>)NyfhR_yVcsdbE5^^;&%V#6SBQ_= zU2mPt#L4C1Ouw7UH-XP{;=>at%gg3By)%tNACcp4V{J`V@pgNioOAQZ_h;VjE&K6f8~JVgodFR~8kmTQ8x$fBH+)}9 zA7BC(Sy`zw0vCgVsmQey8)OwQV?v;sm@=&n4?pheKmZL=So)WHdy`!vx;*tSb=L$j z@s}C3hV6_5-SA-3xKfXuXS#P5%$?H5yWjifbN6TS=a$i7PV4LRXZq)dz-Or23Y6ZT zf9+84;|!ZBCY^nxgV@dqi6&ecx?OI1ywn=iJZGtwQ2KC@0CJhcdQ}Pz?6TTq9o(Sb z@f4JDNz<=V&u-AGb=P!)sh28=#(QGPzv9l5FXI|yB*Gc)4p^S`!&vr@N?S+W7ljp#l!z z`oCV>SEcwtDfU~~)B?z;d7*i31So>Gzu$Odu`e!X`FzK&m$^#7?wK`24Hq6x^WZu` z3F|+o!?Xu;I1Sgyt!TM{RH6qv3m{Ax|DoP z*C&NWybPwuDS1PTm`qe&dDM05K56_ksScOnVJAV z{LyKB?e@So{!4R{je>KjI_Q13D-#35&grM3g2J_!0Yb5a#3KAb12rh>TOel4N4xaBl-bN`22m?Vw!MtDeF&YaW}4y@kyj2K)^j z@uK1Bg3*@{F}u^i1#$(}^_2E#7uaFraUEAtlG#R4N)E0;6RxQFaGdO$dS^vep|*igL?P$on} zyN-$kQz5_>aCCM)<4DJQrzU+yL$l!=yszJkjDw&Qo02-QLrY;6I(-)iG%^@xiJ3r$ z&6p)mIz^~pD{ScQ|B#IWR&9)khRKrtTL{0thcz=x&6J~vK4S%fC(dl7Riy@fnaF;=|MW8*Hv!BkdDQ2sEQD@M#itB8@yk70=%iNbpughjw zhKb5WN-1K_07pOeb2lsWzv7?K#I{k(<;bYZR&(;7IyEc`wKFJkHfkmxlWY8{9%PSO z?MwMT{DpSI6tA^F;j%N;PVmGZ^{&@{QSJFVlf(5W+wmWH+d8ychV{hMsuR_U?6IBq zu}rJDM87c4902$;n>h6#`0M!$oU{yH;?2smIMsobUw^$Ci~876GWIiFlu4^vpBPm9 zz?Jj>hTBy$_NKS(~UidN0Qn106=ve~05UxO2AJn7hFm`>GU8YMPP zNyk2rLEhjoAokiwkTEl*UW1TVVc!J)^ME5VIyVeDM{Ywt5KWvqX z1XB*zYl;Td+=ykRPuu^y^BDnD@ZjYIjP}oNm9Inc=-&!>-^9Xv6@EUhIJcw9?IS#< zipWmo*VfTPgPdSa*%d2ik0agrc0A7#=H1NCdURL&t(=dL)XvlsnVheaWAu<6I!*wE zJ8F^f663wsSX@l9d%-+!a;X$jW~DFL^Z%K<{Hkjp1vN>AcpDjtbf zT&`2kJ3)lizLpb9P&}q0b+S!CmvOL~!v7uDGUaFqk&%(jaKvOO=LXB(lk(Dr?GF`* z?ZF}v$WjY1!g!$D>l4frnyh$wyblt)9`MQkouBr9^G@lL>~HbM4kqJPq2EzGZe<|4 zN}9*={Qr&}#$q@T@DQfy!h#t46^bY%juOnz7FLzyEc$=Ppq`KlDR{Qo_1E~DGA&;KLt{QFlR#|^E zk6M!lZwt`GGOrqq38^O=E61b;p9Q6-d1fJ~DKXxc*sUt}C1@71jcNo;7|39pSPB+| ziAYw}C}e~b!@`Dui7=5A`TO*qVGu1=f^zLSY1(OuV^xT^1v&+se2q=~!?IcfX~e`$ z%fSm5l=J4~#$4Frc^ej6G!;P34+?DQgaii4XxVHBPwz1>qPM+ydTWZ{ zV$;>U;y1|)C~y{M@FcQgoH=zaIG?|8?wrXS1Y@mG6rlQMS$2SC#6%%pVpW`4lG)9< zKfBA-%X8_tbb>Nshb#it1JsARyG}hvm2|YEIh6YjUtXN6{Wo^^QD29-E5gbH(a5`I28 z0m{Hn_h06=TnUcK;#BRN&aJ@)R@u~VUPa4WJFV>X7`fWdp|1hSMyiC2>T-;nK5sa3 zaWz~xb`tbNpj#Mkta0pU>ambZ$KTv~3AV*xjWo%<+woc>&c<>PO2_Zbr*lCwY7cxA zynrk3WV7w}WDC}B!A0^U;$*BtC0N$Zc;LmxAFG?36Sw9g0C5zlp#d=;k(OqQfTLH; zB6mlbpP(_%cCi&^0WHO$nYK>W)zQ1aO)qrZ z^W4#o)(L8VyE{Lf+=g&t=AE0D$hkQ*2Exw>f%oAOUQUiuCh|oA;Uw@3;QIwC%QpOg zv^qAf6)0MH&RrFN$W08U5~Uv+M)2F#gi?AqVTp+eHyOIzCxZ*`d)*(el$q5KHwP%) z&;6GzUI6{>_H~z{+!2z+T`5@szJobRFrQ!>pRci%3$SPRyp&R-RyjmUp%5c81Q`^^)-a-n5#2 zMi1>#FME!8v+P&`3ony6lN`5j@elpYS)4?O=SE(q(LQy zX$Fb&c%XCHU$zSn34NaS+J=tpyARsu&wTT<+4E*|k3hYS2N{$E8;Z;vUHKg&@)fdv}AdSoZ{>VAp4VT=T3cLR+}xA{v9N94Dh9ba ze59V}fL5^x=5^rYUG#1eYklr??uN}=s-snzI*5D8sCqwlB-CgUon z86V&N;5AOM3Df#lo*Hu_(ZLFE84)EQ9;s>5z`jAu$~~yP!b!rb%&>|Q(2;0 zvgMWG(UW7TozKvBF%9EtSVmSy|aTR`40oQZ^hki=7w$+dwMB^3J}God8jY zdLAzU_nLkW51esQ634%@JAB9sgAjrfUoc1vhKx`8%v06+j$>e>Fjw8yc1l6tA&(bDKnYTwu3YN^PMKS@1KL33c__!6&DuK_Nx33msj;Fp<*`&1?@UI$mAqrx|PU zc(_dQ=x4r0yY^Fwq!4~dVJpKS%NL#aePEx&T8}V_5?u{gq$J1tbS1p;X&gCA@MaL_ zJ5K7RgWDyC{p2ot+Nf zK<595)*vk=K;m4oD_FEKoF+wp@CFV2CD#Xc&3R*&2BaD2HPkBQggP4x>3zh)(2acQXXi&K{Fw!?u~j3tFqQhQ}mOmlgY!SCe5 ztCg>NQJ?m$$|;eGV$!j`Log$d1Y}NM_lDbbiQ0nnJCF%Sw9U}NXRINN=(@N26Pie% z-W=^8?-BErQod z!vBd_{##z78u4@dT+lS)m#d*JVuOSVcwRe_gNbNFPeHd^8%PtES_B z1efYn`QCh&)%NoOk+Qb=Speo7RC4mpvf0+^lS9%a@TR9}2q8b9B653rE7;5%SDdwo zyQGPAYg>G$Zowi$ZHDkn!m0~@T~;z_hO}x!({w4Oj$T=<*%aC#MnVTq4Aw{jU_bGC ztkfiZT2|aLI$=Kh*3|>OD;WFrr#3w%O&W6|1%(qv-=E`LCQrzC!^*x$nY!~wx7wrpvKReT@GDvp0MUMXq1+y z`|*2QB0^J-HHSfC0H^G>zZn?AFmoNaVBKrnWtgRii7Ex*G2!?J#UybkS9ns^z;|r4 zK+fag305waqf|fjAomwXu*;I+(kbf^t+f`(q^gfCuVGWPx+qSFKd;QlT(t6hsY{#l ztBxlk^7NvKK6m%Q%MSHH@MHt@$V;&`A7pWZQoYg9=m4GI>453c}*t9Smn{@fu@! z?#?kPK9DA-kh~y7$0HL?nG5E?1j=orY@JHx*Utf-OD=ZqijAN6ETRn zwfzU#s8C9I3UWzO)$wpD$dU%R8iIc}KXq!t6Vs?7m+3GIRUz8B_O|rHbo&b~G+=tr z!A#hxBXC}cY(&&I1IK?<#FO9i7fV(znUB~l+%d-r(XTU?7pRBha;}ys!QT$E78ZD? z*J#n8zr0zrylmnp4|RkI$*ohD8J!+&Hen<~{9S*f0LBL7fUDyg#<$`U*HgE#Hg^;W z`rjUMgGBejmqCLbRLQ}tkw+a333i@AE|CZyFjsJrgHR1#zgIDwx5@Q;B}IxMSm4*C z$zsQph%Eo$sYIK%;+*1e9@Ps7s?Tr^{m}>~&z?t546MV?x!pO2XE240lHLyEkNuX% zn(q==ciJ*Z9M&AWR3)q~GB6HK=joV!y%abAoc`l~LFBMIYseAUxw`|JDFygl3f#WB zwXNBSgA3LJl*m&a_SFuL8`~G13}Jlz_d#Kq^gcT)HXlhRxs5>uL%e=(!3_=rbP4W% zzi1U68Be;`hw4i>J+eQ0H80t4%@2g`gTYLEzC%fesnRUa9F{?>(xG$P?JVOzAUD$YEr|X-Qf8Q$Q5j9!XyUqOaYIH+bFKoaRi+CEBqK5 z63hbXx`lybdHBh>cLOYY!uf8)O6m9Lm|YclIpq{j?2vT^M71;o#0`tY1=?firhI?ESF$0iRPXlrq`=w%vT`Xr*3& z<j>hJH| zf(d$rAknC_O#E|JMpG~OnI2-|3-fc!-evmUYbqj5PnRWwVcD6mjw9Qi_pXjQzMf33 z*_uJm9*t|@0m7G>Et?PDD4o6Sn+m|p={-_TAfvw8rB>$~v~eSet~gyJVLx=7$J@3M z;knDz0{I0*5Z@`7b&E3zB4>DgJkYoSf>GaKx9m*z_}G&MW_YDcz0r`j%1kojf1+3H!^m zus9+|w}u_hGA1JY+RrOkIlqTwzVWD>Z8&+0%0 z+oci2nrgdN&0>j)pxC&BU~TUgt!zE()(LAUWFnT8Q>PiW*#u(_tCRFl3air7%e3#> z3Ro!P~<4ANr@)T!}D84_l&3H&fz=4Ggepl#&g7l9kl8iMa+nSJ8cAd{b`pg zC}@0scR`Geo8@sB16g}yqN}5VICrKqR%f3V9cZo8`D0)^$Zu=^l*=v!?xL3z>G9?4 z(RrT6_~ixC%#MM}i@H<=V*IgA9JBnX4ZqZ@KA$>ef>HPSrU9#CiF*m0#fpr~d30pH zA9!?;Icc}S!c!Gdfm;$^X-3OXquBWI_4UI)s4h%axH@?0KE(u<3M!4S4H|CpAn<&h z%TJyB$O{^u*Lw__NEZ7Z`pGx7y21zsFApJ&m($Si2J$@>w3ZC1qM;!9tAM-Z-G^eB z7U}h~@7Z(m{tVa-Eyu+TcO=WrsTrYV9q(4-@l0d*H&Sve?&-PUYkzEng5Br|?P3m{ zyVIXt=?553!v5?Snp~Jm^=zNs!<;HA&*5kR-o0L5=$giGJK5IPW-RR#^45bbZVFBP zttB6*us~?H5^J-PH&@c@2P81OF&UW<5$7Sy-8Zafab_>Y+Gpx?^F20ID$UA>@QkP) zHG{}IU2OMmcDXzMBK5y<_x)_FMpZ+kL$@|<5>_hY8)U&+ zeU^@cL+4HtHVZ$tJ>VZzi5b{?H!)5q`H13GKnQ@UmxxefO&KST>KlL)y9*;lnCyA# zU1N50I#66xR{5op3h*y3Z_f;Vv;-9A!a(-3xIyS?{M^N<7zcIy7c!|vFx2fnv@1?@ zLkP4zBM_Rd0Q1@$%XJhSnH>6fAbW1zhIS}qZbds$rl<&5&bG0x*NYl zQmwzrjJbM@PM*p=-8~29f3hOQ zK5%jJ8~&S}y~S|wojS7|yRBgJI84jNF>H17zJ8T+M`;u3kMnT62_8lk=S6T%E+$hv zoaZ3SW{?foQY?;4XAC z2woNoaeY@j+KUi6AWFdbN+WkT6(7M=`GNl$#l9Ny!7zZ zbn1oheLnNw-VTN~f{>xWUd3xNBku0zF1QXwK#t?Oz*&0XfF_BdE9S@{*3N-emo?5TolMSeS%w$z^m_G8~z^~glGow;gC5Wer9XdIyLILJO<6WpOZOuzU&_> z`L_CvY`65!&=Ch+z0sFsaAanm?;;N46UD+JK)ype>Dau}HwH*lEWE&)3z`~BO0;bJ zD5h96@7vZDZ078rDxTO_b8uSKmqv2;e)1RQ5HFRQj}e`ot#dX}BNxLQsIaQm>)sg@ z8svIO3-gQ%Fw=k2uP$vrz!WMq2gVkcg`oz0z__yqlx%-(;Xyc zdA8k;b|W8;!e-{>ZPce3IDPJc4P}8g`_ko^?)*k56;vwGbQfrgr;#kM8Zw8O99Z5D zroAhda|9O+95=AqKB;dtN9s-D&7dMQ_h7#b{~g9l5!YpO$m^4o)B8v;w<3x!zw=A? z?$5tSK@bF!w?}OhE3X6uJfUIBd|OA?P~=W!Yq+iHEH&RP>xm~&`;5nVo6~EAcC1BW zqF%E7giWOqpYe1%IQOlO8_tOoFu;b8-pZA%q*dua+nITAu5UaAY|&kUx6`PF#$F*u zO)GEb*7H8_U-`&w8aS$71_Oa5(IzH8C_j16LOStiZ#!|%cC;ftc`%fW+YsCN$nqO0 zr{Oe?z6V3VwN3@NBrb?zs8+AG{Kw{lG$8+|6!^P9L!wi7=JwddhSy9DAUNktw=PKg zJ=Ao|*$01fhzSs^{G&J`FMt8;-k=<(jl{*p0My7GZc)n#Ae4Q>szK7&TvR>*8vltm zvFe*3J!ffRkV*}Ujht1PD5@a-)rp8^RerOrA=+UO z&(OgyI9%alfgG=R39fB{dS8piJk-S0sW6*Nc3UuG&5U^3vngciiaKIO7NtzxtW;HU zY!j3Yh_`X!Fn~0aAnqsO5F_yt5QlsP-hrEvts3=m_RzrN@d|EJaV`MY(=2Y36w6Cn zQH$U$HjH$vyMwo|j2JlrxjF#b>&MPb-z!g`U{NOv?v9KHtU#$VIa!5!BBYJF<>2WfVAKEO+0X~JZH#{kdIxV z5nhF3Uyy*dxe8s6GjgrSBC$k8;i6M*(h}ecuM17Ig8^GQ#wBhuE2*fhp0l!#MgSx_ z(&3dN__RY+e=5$kDS4p}b_;4j!=T@~bw zVZj(nv9EuCG!O-DJtL0xld$h~5gJ2Z>E^GUW;! z?OLl~N{XNl8EZs{yu#n6qiUp*ZHJQ4j@HK;b{b&VE|YPYKX$5haXVE|<>HpMg_bYw z9fwjO!1gD%xnBB-=HgL=niyqJv@QK9eSb-)3H?D)Y+;~!Q<0J~`x7o?3c%EX~@UVSbrIc&K?&8{7y!0RV>MNuenurZlcVP%t zS?W{*9@Ka;m6g{E+@8YwmjhRqqrvfwGbM>?gg#2KU(%hw^M~q`&@h^77`}gkp6gg=D}=wQhj ze6w{kPFXTlxuAj@ZOX=M$Jc<1>+6{Tyl9+90_l6L8)1LV#dags$cQMos8_{Ny^l~q zHr}>jBBSk@rLW?`LE4Nn|HvB_@TP1pTloEgESH?2p#O`mzpiQL?3z}0Fz>oXSmm>* z-1ouRf7MQTMEU>_EY#OILnxK{y?mE~nUPTjlL!FLD$l$6A0OH(`j6{=&+k&frn$=u z)kUbLT(heAxw%W1--b<_iL4|^$tTqU)9hA;#1@t7e<}QoFj_oiGf>U_Est?eOONcD zgmkeLENmwP0x}Uk9<4lrLKovS@xmK5tB3?d{q5Zrvd%(_6%Tp%GZu5Eu!sd+NUTaPBC+5D3)gW#>{r;`8dLpXaBZt&@t{rW0Cd}k(A-Ry)J zg>&jIvayu5xkBHWUv0#GieaFwgibA{L2?SzT-@Xh|1OVPOzkL!OTw-&9O<T!m3!{pjpT+@tD-kc#k^0Vh)P-5T6*}84jn5Rq zXgmM>$vgk^DS-@PWO2bGq5Vx=Daw>uc61}Jr?Yog-D({Ra>l^^}pw~ z=EOv9MCy!C#W`mD3<@Axw%^p{=l-U9!@uw|QvR0(W@zN0=(}*yH`vs1+Uf&1p@jC1 zqIxlyd%Pr_6FSmqG!~VD33x|XnS$I^{>7{K_b{THryjHE7f1246y)C~AP5Q2Om~yU zp;~v!D@CB9sDjSh_DA)X-UbM6xOTzXWyE6gZ|IQ1n8rKNb6gD-1(o~i>y7s0q~d_Kd z-_}BN4)&GF&#q}sNsngrkM)+5aTEP-lTCFx@WYEg>Wj-DVbI1gIbYg2QjiJ1)|D{^EhSY`1}uYiaR4bn zyXr@H5hQrHqJxdr*5dEGt5{qr2@32#ozdnT9HPHtNNT7m*FQf>y#p^*8z19nPPj=C zlp==)bG&<|DJglwo2*lu4(3>OyW93H>-5<=4ceBB_*fkF+HF+2-Wux5N3h@(sU@xP z)a**Zfm7X2$(!AoDDB8N+4v6L08>BoEfuziygYcw01;wRDWkrah$4-pkiE?;0z~Cm zR}j`vEs9H!GatSg$XHnwF($tNk3IHw*oV$UCS^}TLjjaqKGb|*4x=*oz^lF5gGpY$ z!Pc!T1FdD0N)`KEBYvMvR8w9I{$F`0z>EmqEZgyUtAziOyFG|3B zEQ%-RVi!d&PL?wh0mp@;d~9I;!pjqYk&Kr(VpRWeYP}mWVn$#aLj+m`omC-;yl4jLjS&cnWb=Tp=6RCits7jW z69k}YV4-Ws>dwzc29#lqc=vm@>Z7S7f4_U>`vwxLqK!0{O2jaZ5xhKY5z-$A(!fO& zgqM~kbVbqNCQlMnJV%SB)s{I&_d>`biMKokj690Y+C)zgLdWG?_wGkNpU|henQ7}0 zI=<)!wjZAVwu-FzPWsr;BZ``2y-4OEY2)mm9oK`;bOv>|jyOkBA_1SMO;YuG;SeKo zaDCy$0NDmAnL9=Kj&zb^?BzF1yAO&MMpqHN{nqg-RTtC;qZDZ)f^C|tlOd*dku!!~ zc%8x&U4{{&SqJ0k19g$CqVz)?#XvV<0r9~WH?w$xYA&1!4bT==9T3^3B~(DwE@=!~ zUp~rV)ubV7jspmYLP5a3<8hx0dNwQ%b4vC(|`TiAxkxa?* z20+R{US!SWM%uluR9fD4soIsn_VHlCtoL3{TW&aha{z2%nh7Kxj(hYluP8N@| z`h1XkyV%sV|6>!rn_MfuBzy++pc#8-{#su-vPj$ayZ&A(xmv8F)h=xsG8^M(p@@QV@~g(X7(1XoPa5^)Iq>hU5f^Sg zhdz^itEN<+y%f5su||lqOYpZzpQOnJL*XiO>}qkfxgSFBp~RJe@-A;5{=Yy)R&-#; zFxBq}7RhOpBbuL9#&xFc)ao@X6Zeo&nr1e!N9Q^A?mJA4kKU>eKW0LFhqtYGNzecq^J#e@-Kh@8Yg@4-mPlTJIiO7kV(*>(UoFqTWfZ9h zc+n28J=w>O-&VjZ?Dk8!IQTS;s*I{5R7^$Q+`K%PcbO>z-g&MF@2Nc><1>AQ<8N03 z`wx#2i!Sfz&p)c;m!FPLUnwe@H0i%+q=FMrS1a&rO|?+1az-VJNHHf$+$u>W%Uq6~ zb@1Vh2~no(G=d@PYH{58q=khSF-A?L8et<6)5?_+ikMG5q}$RQnj_UQp+d1|iIfHW ztpY<$osS6kc9$82Z}JO0eTGlY;e9VXmp-q8!;+97K!Q|fP!RQn(n5=F@E66z7Ux?J zd@ltIz78WF+h37uI7Bog>cPp$CTB5p(nhKH*~cHxo(UyJADEMvyf=Yr0cBLF>_Z2S) z^TJPK&Lr=7Oi--Vu8SGx_xzcxPT%sv5U41PqR%)5Y1<*5*hcW56`T<2^!E}FHn=%Y zzSs&!L>OI+u@`8WhsJ`pmnx5|S_LYJ$9&(>3p z)BB}Z`jI+HgU)=rH--@a?(d`oAg9@Gli-3Aij7{QSVHZqE6?$Y*Wv`XisU*2qf)`F z1p1nmj05fUKi{t*)e`z*P#fanOw8{H&&8c7UW6vcYqU&@g}=!6Zr%q`YuJtxZiEso86R zp1JY;_8QvT*>UQY#=wDZ-_~Iw+irG&EtrHlA9DK~vV;}PC zz_0F0L{_w{n_&ykl9RB59Mra?_AqjW5|76Mdln$u@i}(+h2%*zCTAVM+HIeRU)mbwD)VQ zXLW`3vs~}`OMS0~Tn*XDewN4%rnNV`BdU|OMvnP_y}O5O(`-?P8p--~;DQuWxK$1b zJb1Ro;AoiZ>fS&*|z-~3tf7?Tv!JI0&8x%`M#f{##_WgHU&Jk6CE zBf5;sah#UZy=jtBoA@H6w0mQI5{W7nB-{MyZVSV(+q36j>bq4DkR9 zly|EltrnLA2=$yT-X|ZV%}+?sdNabMW{#{SM`5osLd=$`Piy_D73eX@YP{!)S`f)RwS2{i#1_a1kotmA(fTN`KN7hJ4j1)-Sk>xiuN#fmiD4K~7TjI!@&LB>uz_CuqOIgqLuuN`5(Vels9o(?FJRss$1TE>1f+f@bq7NIgEb z$bMDK&wvS|XuZ+cV2GWZcl&tlcfeRW$lzs2ql}^PI$x7O;fK2$!lllPD#+&8aPkuK z!cjrzBLQxkB6MpI{+5*x)+agrN*LLzjlqypcUf7t7#&%-3$SE%{AN(1nen+?QMs7* z!<(e(tV4_8%8Q+t>-iPxhS?^reJu0()je;Ss)e%VSVtmyH7V_#8>!sy<6K{p5BGvU z2Hb>h8)Z4`zDir7c{EN9(wf}R=WkF_33wj$^`>(9Hoc3(bkWY=MaR6BFx|hM)p?T@ z;P;J|SM;DKP@y|yJ{hzilvy!)`^e;Yb8#5;gM5PYg7g)3PDXvYitcY2>2Zb~_nlit z6qb35ejEPHt-WAfhlIae?#LONgSrwxz0cpgd8U?8CafM%s@j5JfX?b4-}pwe8iU921YrjcO!hM z9%$cq3-+yB#M@+OSDmx~^gPQ9GwKs@9$ zO>MMz-wJrrr?r$dLfZ0DlGujx6@iqq{Y}c27NzESaCm151dkkwY00Y+aVw=%hgeZp;ur`Pbsfe@#W(aD`fUt3+RFAgAjgdt6iakEp> zV8Wn?ddyHZcdwUTau7)3K+$;0rHhPu1#0{7CsAXd1AD_i!?7C30~!380Uu;JPqu1j z#MCH|&if`7>>qB3=$&$hto&p%$eoA%h?p=jl%VK}!<@m7UMjjll`g=fvFtFn2yIA%2(|0h*~5x<-(0+g zQ4j-ss0&A1bzRjheInwIYyv_HFF^~z!llYBp_vR7Tug}^*+Y2u_c8;1ul2)u=8sa! zHs8D&lvAHZZ(GQpJmf_cjS-e-aa}8t9CyQg37H~LkR=1RKcrK@(P7X&_qLlyv_7fa zw_MzA%*{#@>Pg9bQGZmmlH_=ueUQAD#G#{zmRM+xLVDsXpSm`Ixe8HuXa(OwSzdG7 ztH&21{(+A0_TR@V?uI-38H}|Msr18_=LO6Omq&huBVm`qrTi}!^ZF!L>f_#67>8+M zVX76*2o3R@H5eSGc(&oo-QQCjUG55zg#ma*l2uc_9f8Yy9zU{qalYP*N8oWyu(}PN zAJI4TJB|8S>anQBVNv>F41=USiPf;KLws|DIQPsVgKHG@kS9Op=0qt~2j!CR>6y56Oa+79sQ!HOg<5%G-5~1QgXoFRfL0QmJ$rWFLk!-RxrcmHZmVyWPFp<`rXxrdq zEc28D)^aT&^Bi19ZMzvXg=%B0Yf{Yi3t|4Pj}`t+{>lCYL8$F=P;9_lyA!n z|GaRz^9ozo{_TW~pF}bzz8|^qC+`>8Jqga;9|U&BsSmlS+(|tkp#1!o(tO+ zhFU`^D#|WXM6+C;?$|9Gg57qx(sgz;&8)%ZSSNPTIfdhcTmCao_rGv&HKO488C3p` zvH@e}W87*LF+9T&>oFZ{%uz`NHs254U|!8h%$e34|NZmlQSxIR+02p11*IJ{Pg}@b zHvursGE^&j(fKGZ>V217$|Qq=9YIT*HJUb}&DO#fd$j(#{rcnqJ8paZ8%Oi<+XnVi ziyk|7gedD^=x4%Lud=ao4ku0xd}n)`VwbumFkuT!sJ@~L-wCd73CyLm6cmluQRoJ~ zpuGnC&1S|mkrwvdT=GD{XVTPiWX{b_>f#13=m$Cb!j zbF3{~bru8xt9?u^mStuwSvT?IP$>;D6@j%Qd1nV2BKo+K9n<-i*_~O@gKXM7t7Erq zB1(#W@tlF=ZK&J)-boKCNgyCFyI}@7F}pH}3Dip(iSzLTsd!RwJ^@D$7@I$Jkyo?Tnv8 z?4Y09772|9G2mnbj>?Yph^I28l`=I<@{!9^=xcdowM{^vt<5^+o!Zlb7k-a4Aof}V zA9X}B4ZFEIZ%;T@Q<6-_F!#yqm*-snGp4F;7u=2%UuM`uNM zNNrNN#w{Oe)_He4xcCScCRCGA@~7TU%Xx%T9N?fC;EaxOF9PPkepfhhF-RB)?r{jQ zJ`!X$QC-R!_AeXSvDb5~rvVFd>HEdKXP3;Znwl9>eF?K7T(p#1WG;jb`w9^w%%4MZ zlp53Q|0}t~>o~cE`fJHNGQqBQk9(&XDe(_y=?wFtuaZDO;%uKQ+e2PF^~H|ROGqL} zOC_;Vw@O-jKZ5N;WKtG=g@*vwZ2z?=MT<<$O8x>0ZPm;*Jduwlehyf??4=FL%i1EX z$=cy+ZgN^%MPI`T;3REb`$B7Tf^m^0lK9ZNZ~i^q57#Sax5`YK-Vcr+Sey3~GWjCD zJZBq;&94)Oi`UPb8eohHbRR>Wd9engXk*_OVhwA(&zdGsmzoA?YW<6}8}7S2daWNO z`Jf=$q(7rauV2WMv+@6P0h*0v2`mX*X5YP(M8{vaJQWeAoR$2@YKGSUt1M?(*z-?7G{D-b2ClP#3@K z&V_DnXEf%QT9df&$U{%hoapVHc5`LWTcvtW843rTFj8>UTP-XIDr|B9CMw(&ZhycU zEhUpJZ#JIM?;?{to4k|eK)iB&Dn>kuTNVrzn&+We4zm-`@3s5*;=P(y=opthkTiM% z#gHLHEuPo1jB1fxP2u7wBYOdlVtqwM81)OSg=V3V(GhcTIZdj2G;e>k^S<4vqJV?9 z*Zln(%MGm&4*Yv@$<#L>{OLve8dK}EYlV9)q9m~G)^LJgYWwf&DR2uZh!g=L+g!flXMnYl=^$W1G*1ya2&=PPPjIsIR&kfSk zajC7ta@Sf5=k}tT|8GP*&dp`W3&=VziDwMT)%9bYew8-Bkm$Kvtt7W<0+m61tLsuFfRNw2&&gKEqYYAwCZM9Bz4LC&|i7C;|gX4b2k z!BLi>v)#M5%}#zZ|6f#aaB#t*QJ-cIE_!U`JfYV|RX)Pv&XUI^P`wlpsqPy*dF};G zTDI5ilQbukn2>z?%-gP``1|^zN(MK&F&HI8Lk;Ys+@iOV%8z@iE(5hNQ~P1l9F`X@ zMmDY`b$|X&lg=6*Y}Za}z@Bc;Q(s?{!lzZZ4nu*3%P{)kET}G!gMo1nWR=IlGRZz} zF=En1tBhWc9?FOdkE_<7^G|*2bV?D+6UEGGrTHcA*mO_NXZ@z#%F0XuDEqoaH`gAL zS|-u$VZW9qnS3vPbs zKHZoP&r*IVm$S^c4&a5yS{lStVCjw=?#$n5zlna$vgjhm;_ifnm5}a)eI{hI6Cg{` zt83FwTsLt?`0j{Y`1c0A*O&!@2C(wrs9KK;*q_K1poAN%F_+UA;?JPqkl>~zOBc}} zEm)QA7Z3g!Sv=X!=MMoV3$xs*Ub*p4A7XR&QJ(z%jkTvIfA}^2a#d&5a4=8w`#zRb z&gbu?-S@%Iw;fx96su3@Dlrm1U)h)^u`=h81zKok_uouwN?GTr3<;zza*Rg&AdLPa z%^H7_O_gHx4yjQu0D8T@Z4QBc)zpHpGc;+c0_x`=)-E1JTQV}T3^^$^J`fOksug-u zHyX-6_8!hg4Wp@&&;J5Xp2^h4JtUv{+AVMT&iF18h4$JO933&T6w^OK*f7sf z^K?Qke!Icfok?8?CgdA?7}}@TO2l;}TFf%6R}Uj$l2|9kc`5AuS(%7!<>}q?h0$|* zz}=GTlkHkQ3DJ5d)oY?Od-@5R$FHD+--tB3b_>4TIvsl*d!W4(Y~dwX9qw3e^)jO* zzg+2Oy<9=Q7t&qdi$23ZOXf0(E!T!bRXN!Pfh>vV(12TjkLx_KAQ7K_*#S~w`HW{A=W9-5DdJ@jQK)MwA)E^FC}cmDAJTyU*Hc^;m47@Bcny*SH+m zy*mpGEsIZj{5ku7(}e%{O)V}%y6F0UI1NzvUIgSp6vfNz?_Se|bzN#up#oEWd+y0? z>4851VLmBI^M}9pn8HMV9`@zv+v!JHjp}p_&$e!n&G{uoe>0oQ6qc1`gy0`ENRT=$ zh94Y~b8tF(@p9g{t%UxYkDuTKbA<7O0+lsJr*~gQZ%14PdpLzX!{Y_5lkb0iz(W08 z5~DyYkoCdzcL}+JI^kr)IE-)|;pxxM=Z06`^=|szX5bG`^xw|t_9Jud(L;p>D_4!A&^w00T+UjRI zE`5|96~T=+*C)2m_jFOAzWzO%?E(hB)oB42&@ZoJUPIeb?p|YJAWvV^ir^3UaPx2{ z1Vt9JFkkbzL$p*kguuEQN}Esm=w-qHM`?jSt~`I@?Ow1QB|a0&euoqZNAn@@)OdeU zpJM+y#l46-`|3*)n_eBqtFL2qe#8qCV_H&)M2+h5O$HBKKN?`lT4UNm;6x1qzNWb; z05oT2EIIt!ie3HfH1OSZm^E}G*=s=fopn*LCLhf03wALnW3zqU42u@5e;Od>&NJnn zoDQ?}BN4muSb$)7DUcmu&*~7{-OP2RAS=ZvQKr#%aBbS+|G*Q9SbeZsz<`T;T+5v9 z&0Azhy2h4}wc0o;a=D$in)P@RIO)qY`$+EDOv=k~?c{kzFn5h!5j-Ex+E!AyLzH4} zqRUv)g~yptkk7#rRZvt$rdR%UKCME%p_Yvt!Ci-CHJoLVjVsT+-%(^mK+xBZAp&cA z(Pitf<=ScTEk-9bSg+1m#80>@))F4kR%ETWR|1YmkqeaUgNYi<_SRv7kjsvK6pxUbjVHSzVkWrf(;CcC@El8 z{MnXo{Yn}HVn+odT>K~yy>&-EF_9U~9PiiD1a-dZv1ogG1sT{W z`>X9lB~R1$j=ZCg=6?dx`h2j=xF)dpYC)72dYdJ>Ij(Ihe-AYT1J3#VTX(@lU_>L7 zVz#Hw-!Z=4d>AJtx0dG2PwhXXK1yEC6TI#x2@v)a+LnLr*q;mZMD;O#KCoeuIbYQ3 znm0$jZQdh2G!hu8#nyNbl{f5Z?7S)8g4{qQD;T7$=y%842Ja(r*$b+yGco|G5vu~7 ze^%K0FEt9Kvj(|FTp#Rh0wf&;3-*0hIPT#hRt~v6X4E68sKfo^TAFH;$)x+6S^Yc~ zO~1Ze5yzT>bcql^SN`UDRkX|ACtT)fayhd(TKGzYLd^e{;YvY8YSA!DwD}L#-z>%0 z^)JTN(eXt>nx+e z!_mtlXN*~Bn|8lJ9OYxG09#FKY?9?vl#$hj^*p{xF)@O%)Ik21Lv=d)tgKhG z$sZCRxyib*O@3^5eBWdDHBp=TWD3i;-A^7pd~-tS@fVRV8{x6Uu-z-+3lU*jDBhC6 z$RGt_m<-^$8LU4+0{m76S&QGNERLAWm@7@ATfIB0&nFVrb_^dc z8!e;$o6ee1X+0b`l*;u-^vt}P0t|WMc4T#ufx%0x=R~^WI|9_L1TPD62)*#Qa&Bi==RLt9 zOs|Tt{Fs%UUwe#v4rcZrdq;#^jm!M7Qtko>E|6z z?F?%i4Y>-fh!#;HM!%X2GxFzJ3-MQhT?Px}8l3JneP8tX`K43_JDkh!iS%O~WL0AA zc;rPJh`Uk9(s9{^Z&X){%;B#oD`9~FZ)Q#6?=+`typd6=x>?>+g-FL0XK$CE3)dP% zv7aelg?4?0%F8-KCUjtNRNT8ZFukCHU7eC3dujE}4F%;!1CuGTYVxt&W>l6$hzjY4 zZ~pfw4Ve)OZqY}`f+doUyan^Y23XwQug%s-MW59n)hhEfgjS^`Zp-|RbNOWz;Mg}^4w zGh&v5rDVIq%VWfDDamxri$9DtziMy>d17zv!b4D;YITMb%wu``q>=MHitq1Z_?G$s zDWC=!hJ8hX@xo29xoz#@7SWNRs2-48BGU5)&#irJ&mCMWL{c5^h!$lf)u9*}%PoS4 z_x#0;pd+rRI%X*U;B`G@>+kcXXBm)z32iu;O?KToW^oW~ZM_JH?+>T@Y*@$G<<+-9 z%u;iXcDa+#a} zPC&4mmDxglzUydoE+=Gie8WO5Cbm^;`N@XQoXFYrEbKFnB&kH9HYDfh(&;4BT%h=^J z+7In@n>XLy<@CI}d4UikbQPHd=KJ|XH>qq6oe>A!Vyt4JJOQ$CEK#=2cl`(U3SU*y z0R+&!^HYAzuDIvVokAwjoK{#i^}@S5!{yd;=CfqBQR~k?xY*eyC7)H|5=YK|W64yy zPlkYrNh=nv4RSix8m`gYYL!}j2A}5odHGHL+dX7Sot<4=ghVQR-W$h`M^N@=%eXTh z&jUit`xXz`aU|^#8LCT<9pd1|5o-w6I4QHD^i3x7Kxs6s|wig{{zm^%q}D zYSpzsiC;z>z9}xB?G6i-^YtzWee#f?=d%5CNx}XY+HmW${DV(#tPhtFF1&d#34|cS z`n_zpJz?L?9KRd>_sg|@7wddD>+_pW!mnc(0WziV+Lg`Fra=$MQJv341cF-J+@$@Y zFJVjoXkaw8nfpIQZI6zo&4|OUJv$`wkIP9equy5ve(Tt@$)P*IMj>rWb$Z%$^mNW~ z()GrqK5{TyX(vJnUb6wamKF}XYwVx+eGIX}olkC`OzpVYK+aXssvH;h374mc_xp7b zd}H!+=#ny8y4c<4AXaOlU&Ml`#?zTe&AT1*`fC1oK@gzk*sfK~X07D7x{EM5`VaKX zS%QQ&Zgv@FXI(i;1!Tj59CUS3LdtCb7-M#Sa$d+{r6sRr^ff|k@kVU;n$z>PYal~( z;}ghC)L9kj^EVwA*R!Zexd|Pr{O7>@)ioI6K+O01#v!sJ;LPRLkSF35D2hoMBVSo= zO@=Qs$=#Wt@>bB7Yi(MqZ=tfJj2y20Hc_(Q+qr*p$Wm0|>)aQ43V?YLZ=d|1g-K6$ z4p3^*_gcU_GGHcAEkfYrXMIf zB?JboA3d}jRdZa3C5BD{b(+-UAK}&& zc_}qQ%;7&B%zu*jp|u^JeM9G|9eST*o~wt~!$&nAqhE46F;yQyZ)Ztr7SGGaXn^{ zk?BtmJS#rU_ap)#HRPR++mFQ*7ri~F6Bb!+HJ1VzqvrK0nAGxl zwT||IN>?_wa~;fMN<|8jN3jqz1MRLNle%BUJwL51yM81|?%}|Rci+MEdk7lvPji0Q zN}l{M`b}2>G)+fAbz&u-&pVV}#9t^CE)^gX{|CcOF%>x01AF8~=H*;f9D zT}X-F&TH1O(1)d7dBOgCHd<5QWd5NQQ zN#;tP!+pG`^U2aM+o-<+HQpN68C@ye;>xX3Hp2(tozX+TDJl{Cw=omInla7Y9)?|on_=E@r}t(OBc zqeqo7*GE{jZSjk&Zd}BDK2LLM90q*A0F_wrcU1Q|uNypST{NxZgb=mBn$ttbD{~CU zkG-R;$u9y~ORR$KJ*__@OIw(235$Q@GJvGP`0S9J+P3U-!>;WH4-DC>F1`m_Xr;cGEeu|P=)}ho3Tq^}bFr=apS2 z4R*VBlL%g$dRhc8jjK(PdZeOx3t8rDY@8;!HON9MBVA56Nyb#QC?T`fu-xw$yVpp< zK|$v5vaezG`amPJQn9{(-jNJmBCGtN)zjzaa6{VOYM>LyVhX3$jgSzh!sGiXC#&eZ zJSpZ}-7H&)WrzQ1SjFaxFWE_qN)Zm^dP<*J^X;)hRk`7@pQN>?lV2Wm>zt1OlelMd z*kEpG$A=-kx>lj>hl8kn_y^C6WF~50u0Ql3^}3ruov+^<{hdnnYt!WS2pgSkJHS(} zDw<0FSup>Q(-DuVY4g5SplJIQ%!Ba&(+ATJ|6G27TBe7~UQ~h}Q#1yBLbP;H04}@o zbhAQmMQkm%1kwa6*8yb;|GLFjRTu=e@S|yplV2bTULeGgV*kmCaCa@`b}4I~r;wD? zw;EQW&))`Y^Qm$U|K6kQZ9DiQCzouvk{WB()!7rzHaUyEMl{tCCTK~!HI(SEw`NxB z@F97-fi)N^@vSryAOKk&Rh}%oOUm(6K?~aXF1tWQRxf|rs~41r?=u7h<%O?B4n!}U z2KaihPi3g(tGfM=nDm+HCN{Hnmx8@0COFA~o-nYdEDtQpcjE>+Sbxy%*Nlf5Di-t| z3SN??9o)ajuX2pqI%bm9(t<(dC;5_(JHOaj?#3=#j%iXZTsj%xEI8MRQO>sFP%p{<2X^c3I+~qNWe$uakDC{I?=_gD zIYls@Y;9jCaQaAsu2@yXrk^2qRy@$(X_HkFWNs|X(Pg^2!`fD_usQ?sNEaA+WgqetHK>Mz}fX>b|rCXvc&C+f}BwU>SYOqG($OPDjD+5$1bpr-z2z z^9m#J4XHen^5Etrkk-A*Jnp}JDmE%EgIBXjU79O7noXySBgldx%d2H}s4jW?#S#_J-u6_O^K|2)=|k(7M4 zUJwM7Q*f*9{hTLsVR&0&M3X(`!pqGkUDm`1(ZcuYGu8^$sCJ>y>@`sP|iZ>^|Z0(rGRpxY;!PCq@8WD3nYi} zhqH>d$4>2O(mQw*+@XNHRR-lXG#FZYM|ImTw5_0QfNG$HXlAE?fS+C2Rp!TjA3CxtA=Lr z6tWUZ_^L3`yy+P4@$aZdzeNL_$Q7P|HT4pPO+BeoJJE$79-5l;Z4M?2*v%Ze#K^ix z@alEA-Ge@Vw(_e4J}Fylh1Ms!n=_qC!0K)N&P7!E6LrYzKhgE%g9E1hF^^Hycdt86+qW214@&>CEgZ{r3Uzz8 z+HO9ai@}noz?{S~d>ibwX?iTaI?wq`_k2FX~bh@5SfPI1?SCE%^SCVwMDk$^pNG6l}cwU0869*WBxP^K!C$c$QK zg;yYjdMff6D>H6JIO@(G?E`CGemPlNNr6pwd(A_K-UkgVG1c+eZ6Y5O4s zYl9-Lp7aVog(0=IhaX%U;q`Mz4`VoRK%}+6Jp=s0f?=_xjb)HuduM>Y;tA{djJ0Hs zg2&tC*Q9*-!5@u1ho1RoUj^-@(&8re0&8oasS+rO43?k9)Vvh8x$t8=5wCLax=l)b zz9N6Rr7u3D=Jq;Evy8t=*J;r-{+THyNdp7XD^5=EvqLbVuD))^6cn(Kuixp{6edS# zkD*J2Jglt+tb1&1Kcf~Eqq|+f<#eNMg}6ARykDsc4-%;BWD}`JxKVDf4gEfgZW6G@oV1`Ij$BP{6!n5ON6^ zcay}_e<$IQCUcttVa1A1KSvRdn|bDws#PfjS`fHW*7sM4h4+hcFJ+@OHQ5#hoSQgtjJ|@*Wu}AS znL0V)wiZ^X8EyGQ*VYn7+0?g>U>^beVuz_w1Dsh9mv#BisCtKTdS7mcx}?5(OHzTI zq(`kXhCF-1NXa)Nx?7%?Zw20T*)NSXvW9J%2w|s~J9M18zi#hF^caRmi(2~o{GM0( znmwN2U>SJq1Bg)>ZDf6iF55qf20X=`yYy~2g?IKLF&0w!sm~}OX)MSJEi{8GP0wU$ zwDmB3csVw&t4FR2s;t&As#m(!CbvrsqFx`kdCZ9{TJr31C!p0eMHax{m@Q0Ho1VR* z?f(u_-n&;iHf|a@hW?U#e{9ByixjF4LMxpTfF;lWQwG(}qRr(y9j=_7VU>w9tZ;8sc(X*Wjx*+)s=cW}{K4FD^0l%w<=QmM^j+UBUlU}u9 zKBQ%~<*_PGD84=L5vV4J;3@v4^i!@66(zJ&d}-`aO#avPqH4fMp~g4})-5x3JaH^U zq9&JK^g~T*$t@wwh5Bpx;6$3BqBY-FZD)QK?sf_HL%C8vQ1O-AqZA$gAup)#dOM)ZQ#G*6*9T-(lWS1~0rxWCD1G zR{eTG=ol>mW`7X`AV6-Z-83a_Vtu`Ct^cQ_#GYRbo#j{~xC>u6;|T9c4pX=#v;}Y- zNi<{F*ZV}iSCXDiwuSuDOD)=0=lb8Y}ZP-WNMa;>YCPABUKz z_t2Ls%d*c{IJ_hc0bC|degi}87%E0Ad2_GU#SXp?G{UTS|J)?)_WLYnjYM7t415_v zio<5Yd`alT9$5i!o2)+P*^}>C4gIlK8$W4`mAZVqJyWW$vM$7M7+rC7;b-!CQ0g5* z!p1>h`V!i*;~9}6*~{RM=(b~(i3jBe7)SUnOg!xcRJ6q{kWcJ~Uo2+v3=btGRa#lQ z5tc7`s5;IR?Pr)lSINXvR!l)BbtNorWDP33@B!(xOxsAi@}!7MR$4ci1FpAYu~jxR zDb)1(G8?WNofYy?_qi)4wgve^rfd87%UzyBmd7PUA(lJ+8GBb)#};{0q!1v$?stR; z#{g2cyU#taZM8I6#~fTIjQ08=TCLVc^XMF(9Ta)WF2=*Z3u4*t&$>0~frnn&sPJ@d zdXp8R(5MK=8f`avQ~S`Lc)TXB*<4w)uPn@@>3mInc0i0~K0TJDtef5S*L1dTlN%vI ziPGiOt&j*{59WBoyIH&T${eB{K_3F9Xv(hA4{}|73G05F)^A3&gL};EOfw`kl154^ ziAbFf--vq-hV-G~gz=XcCi-)8+-G^W|Xlj<#RSolDN@&Ufz$NP}3I5`K;NIe8ve$7Bd5pSoEr-1x7eFx4` zS&InsFih-tuSS7&bxpHjp@vqo9g&-Abbw;3Ucmf^gikS&=?7!efyiwO3`CcA{TJ{4 zwZ>KHw(>el!+er;qx>8%_eJdKSCyLdDu!V>#J>2aR*&I6-2q*yL^hKxwfU7y;n)kB{8zKIZIPVRgbQ_2gNgW+sLfG0XE06&2c$1;mk{jub=iu zZJ)+WFU8Eeg8FAcZ@zHD*UYI^;=wGu1eTg)o|v%I_1H|+H8 zdv1H>Vfn*zqOVF_7NZJoT9(wTld#yexd}kG55vzl$pL;|{U+J9SwNQT6BZND9lku{ zW2)g4?EGonhC@O@?TlOYz?>-njP&E+Il&h{V?Y@Vz}EM1KmK+Ek$d_8lUk#$e|E~1 ze~t7~W`RI5AfzpUfE|*OXo+0>U+1Ju1^(V9-$wx@vX*$>WlOt?Ih8;{*!=wd>Vi?? z?PDgIlY`5QR-d#0%x*!F5Xde$E0Fye);0+E;n2rLu17E%)@6+9%98FYB6j|IEij@4D{xc1?e*uhVU#HWnI>YF2`)q z#1G7u!DBs>N;AlCiMkD zKP*ym9$`KcJXr|z+uRHqSqs0CHK}s3zlKZ=veE%GYlE)UwI#G}FXthHG}M~m->vbE zx~*YxSFih3`T1xvs>h}n3Rs57ks&JtFk6UJ4kP`z9EwP}rrvNN?}4%HOQrH5eXKsv zm?m=7$k6P&f_bcurN^yld_`Mnk2nE9jKZ}bnU~<5Uy#rn2zz9S##W1K%Fn>@RT(OA z@vYk9H8NJXRbHB_NBgJdpJiF%*(#Dddu8Um-a_W?0_$6A8BL8=$~Y@i+-!t>m3Sk; z6{Ch{N1Hy?HaNVfXd)arFW@B(;!$}l>NDrIN6Qak@kWMccZ?xUgLy0FQ+3=x($;R0 zSF%Psl5qY9E88-2>H1bvcOMCq{(NpfUzt7_gzcmJ7lsOtT$iUaUhysm)dQ*}!+0r# zWHa*aT3F`nb9B5B^z^Rz`wrIbwaA6Yi)L#njl!r5HyVIeqlFC7B+yj^Y+{#}>)$gJ zZ{fjwLgS)rr4u*u$Q$8t=B$lcQt1Qq!{kR6Xv5Myd&{}ew)Q_zp2Vmn^qYNO100?!A}gfSxVd67|nP-0h~4_*201yXW-= zS3?7E@^04c65%%Sc2;h#tG|EWG_)6fz~gxl$|NCSGK%7=&(dr@Og&U0;{DCAz70qw zeiT{m@){cUn9brOpXw3!!I3+_LNb`_;fGZ^CQv3xPb3q@YO1n_J6Q(m$|XezsQ>*Q;H}@rEMzi7 zUew7UL?3U%MVBv00iEnY@HJD7*ZG#%c0-n&2NyJT%$2KZ1Tn!-p!0>pu~p1(XkTEv z<6E4LvGFZc&iX1DW1RV?1;!{FlO2H3QxJ{L@(P?d`7?#*!w^8xVP$l51GOMN{Ue8< zBE4RCWu~NI1`wMx2sO=r3+v)B2w4~B-$UCTv6sdMCh}R-_e>y30`HN@Sa79#oMeKJ z0*z;xYS}4<2Q>AH2sFV`4D@d4YFlWhHVOucWW0GI6ucDfyB@vD@GKL3a0cjr`tt+6g+ign&QKJ)rdUgtUIv$>~d z2XVvZpVzK-F7GeyDW&C0s}%pV6(pmSR2Q;do4$9Q@ro`}*K=z)ovjMY+n>a8d!MSj z(z$kU=mVt2OkZB^AR(Rdbx>j3)^r7C#bZ@mrf$i+i&8e{@Q@RU6EHr z3=n7{5WL{rYx7lOUmVa8tPrGRSJt znc?cyRisK$>5yyKqQr!W7LveqFt&@igXNJ<;s1Tq|1=bbDt3qT;dXUI(1`ffzXX`mFzU!NC%LW+Fl|j+E z6-Iuwi-o{^jnq~hR8GEAqBMqfDn>rLxN%EIMn+Svk2FlpGndXazdL?Pp}f?4DnkLJ z2!aT{sma-d=GoJ?m8^PFx#RwIYrFB6tdS^M*&W03GmyC*K>hnT{Ths@g?8l0?2yg1 zwWZUc*-z4rbBQ3`iHO9=`?bY=UKbQJ4j*fA#w0ARvdT<>Gnd;$)`rJi0lfGjI;tc0 zU9YWU)(IB$GNO8|y2HTbCvJHhoVlgl@j6Y=*Vuf!*0g3B+#A7?I8)NHsNgW!hL?*+ zX+y0_BzJ--u}j%pdp?-Z1nXX5duD>yEt7?_7`vX>QUX7&DMS(9Rmpw=rLDMmTZC>4 zN(K;xO~ONkwTpuS^YMGRVmWqNt89udrYR}o%N@3)miqRhj-9-;1z3iMRS==De(xqm zfSuT_1l;lL{uuS$PCJ#>=3EkRj2nY3#H_qH(ejbb|=p5?PO&5`J@&9 zl*knXisXqb8apnQ9%s&#d^Wy^dDC>+8rueQdNZO)vDhshMPzrPtxH8XlJ6|2gz5X| zF{}GuC$&)Ht4Bd1gfkip*>x=ltuqpdk->!p^BjO2vYp?5jtNx+Mwy`X!&_)`ZHXb; zP2rFKNDm>FmTT=J&6g0gcAUGLJ&&DVK)Wu*QF3vXqo}elLNF?_fp5RE#EJlfU_zB? zTjDTo^*R+cvW-BMT~IAy0e@o==W8Og9Fws`g&cE{=WbS2KV{GUY|~(B`t ze8;?(N8J=ox8<6391|xgSp!m0H%;U;3&-{Fd=KB*q!%ej5H)2MvyLNHaX~2*q^hH9 zD!S!hIUa%UIIwna{*7+uqD8;50LuwAL z9}t8-zGHlYEViJCS7dQaiiPO~xW138^A#03L6axs>xjiFrD&j44NODBG;IvS#F8ml znv!HSmEIw6bbPbf)H6j1tE8aD#IQX)KcqYC(+NBR$HY(@sx)T3T(X$YSS1DP3RF9! z(;v_u4(NpzdY#gw5%X0>(Qej*X=oUhgJBq0?V2=AiSvfW=nw`D9Y>+bVxr}eWt5Os zpqL(R&|xs{U@HQOlz2HKUYDdbXtqbt8*Yrr(8VV;OMy9r|6a~TefW3@<*|Kg>Koh zMH&jM-6rI*Nm*N%E{g(;ZyL#tSS|O@*>TmN~U(5r&8ASm;GW zI!jsC5>>ZxJO|ga(AlcfY}vA9%a$$Q#?}zovSrIp2Sr8I9o*iSac!UnB?LYy3QE-? zng-P}(M=E63+Z+PI)R0zZn|OD>zF*xs1zS`g*u+GSTw}z7S-u7+8d#}*0yojmMvSh zY}xW1*cu{Rwru$cp`#f-ot!$)J7i$%poIjsxs~bOvSrJbEnB`LTSH{amMvTUAQEIr zQRGBPMjV$E)*3a7S*0GGZlCd>i=`L@p^XXK#$j8wY}vA9%XeV=zTC29%a%Wc6wqdr zRnGeVYwuo`+l0X|41XZ-F~%jC)RRRoBKLnGzJfN64`i^3AqYubw9S%crm34L@3V!4 zcFc=@jb0?1e%5?E)s3liK5SH!jY>aNIyOp@SV2GbPyhfxzup~@5Q4n-vet_0MgR6@-sj76eMj`v6n`Nxq%&91LIy_#n;z6h)EJG*ukOilY8` z<==)#+qQaodQ#iA@;`4=1%SbDjdcF1hs{p=Q>!Mu(|F>vFoky2M!PEL;V6Z>xvDzX z^*Pf-ga`m&n9?*=p68lOCQ6e2Qy{%hyROsmc+`5m)^@wq^Yin&E))PhJa46Dul>Hz zrg%}6oYfq>_UTcZ&7%%>uXeoE>DwpWUeC0gkBATez#ti8lx3Oj@9(u*t^O=TLI~=* zPIXS-{1Ucta z*R`y*a?ZW$VgUdE0Q?`KD3UQov)SzRz0001g1G82D0000kjt~I=003}t zga`lt0Dy}lL;wH)09+g)0ssI2;Nl1o000007xx{9!GAvdLM}f50000`e?EEo`ib zR4uGbz*Gz!i5QuPq@Df{F*7o=5HT@vGqQ0rvJ)xF5s8SYsAi)U5rBaafk}x9sk)}0 zt(&>%E~acfe-3XSgoNWs{nZ2{m}u|UuFs#Jq-yG_{BAWHFG}NJxixincalpgTWeeu zia}$6izWgi(F4Qe7<5ob$IJ#uC({wl^uS1-Q2#5rf`@D={O=9OZ78C@0{>MD!1Vq9gZ{HJ|L+&# zsWUV;kMQeF%(A^#VgC0c^ZHZ%W#oOS1NhOd+&~F&W?tG{VTuL#fiCZ`5b&UT!31U) zE@c5>b2z+K=@) zB@?)mXiC^CFG7LnkUPM!>|e(bVTdS)H>IOp9$oI&w6k+H%3rVbd9=pibz=p8?B7bZ z7)anDglz=77K;{Lu1VmeK!!_9%#A@WIy4LtS%gmny&utv>M>3bx@wB~usvXt4%gpc zl^Crc)MC20lYc;bvk6)KJ&g^0=Y_5No(r>c!~hf%n?@K*4$Pr0-W;L|mUtXEpSE^9 zs()>+jmj-GFO8rT6ZKO-enMFHl~j&q`yryD2#BIi=nN(lq_j8+MWE8As0>8#uzC^6 z%3&a;f;Qz1!f#^SyA;kQ{0U9adAfCnALJcENT91YUp;M=)=Zy=_qvKLgofgZSjm#T z>R<~IsyIDe!D%PcyFm7BvitZR8v!rKFCsq$t5A%@Fc<$Y{8gv{J!fE>JxphP}avk!z~0mT}*-4P$0T43lr`4S>_sAR9$c= zLK{wlsnhAxuZMei0s;MkO~!q+sH=+6@5CZzf<9YY&GdT6KXbD!xPvSVHP{nPj4a_( zzlri+WDjO97OWp{yZ+>-E;U3AU+(*ZsvQoi17pUR&4I=2sOu>Jh*w3E6H!q^doD%| zf(`lhZIj{(qFqp!%~&H8P_oCNx#2C3h5|)@5$8aNz(=wy$V6*Yvs85Wnt=`uevutK zdp?UTJ`@ybvf4*`UTkf*_8ve`$?^}I^A3i-GoQo)qb51hs`%*SvBohXDs$dCVc>)P zcNzYhYs^@_7%jd?FeczB91N*xHQTLPqNQENBzqSJ>fo>liv}=kKERZfaOjpy4B4A! zRxMz##fhMc#1I=Z1_*UccU%BB28K zn6uWyBmS7`#=paE=GQ|;h9nlE%sG9{hK0*M3#3j6+~WgUuu>GB~FeKbd40qj1!6=K--s1PBo%ArXbv z?5(vz&=peI%RBD@*Xt5?bAlM8kG%pM3_9c+LkHQf-CX~M@%d?Zv{OI2_P+l)e))M! z_?)!PDqT2qWS*E_kPWH(GEUtFYAiuwdvo3U91NWZuQOMlb*d1v#Sg-IbblI^v8kfU(KdUUaQ zco6K;?Cg-S{_kJ1dtl40&DCQS8Wo`Pg|agf7WO)wyrP$H;j)~m`g`)OgDfU006lBS zLYc~@ZqwH<-E@28+jD@}8O;M8V%r_kg6mtiz_kE@Q?nXJ^2k8-{UnSpO11&u1}I*n z>ABC$^2`afo5m@C>EkN7e;xdGAn+Na|9OMhR>KtA&r90E$<*I_s&27B&AVZ-i)~@_ zjPgBB(@0B{^=zghf$NV1!X2Ec_f^-;ZPK7y-Q3}{MAyzko(O@OTKyTX*`|BKsEv-n z0_3T-7f1rx4Pn*9lIJ(=X6xW?X>U%RAZ46x^VrxkO*@xa95d+IGD`TW&GC`2=KhNQ zvZHIvRKYMh8F=yrdfI+w(o2mtKd-3qe1~?i;WOwcGLA?$J-Cy3n@3V$Ol+*lx(xl! zkUKlJwuM=5JBmb7VVO1RC{ zNPnD8vb+(;qK1Cw%hBQKtT=Ffqcg9TuXR5k4qwIo|JgpPggc-P^JB& z|K=@2*GI@c1gJGWkMS1em!4N3hrZsPk%gp(M_{nah3)+Y=|a;8-W<=}Jzh!=C22oz zOY&cG8Brxc&a;`4U&Vy%C9HDrW_tT;s{#i$-p(ngft)ReiZY;YN!1_86)=y@9yTef zr)q0`tjo_y%{Mpb@{wfN3f@WnnP9mX2?=FuUG5p10tg}Fx_ftJ47UTvBrVAw`0{7-BT>`fXT8ij@+W@TDN z?o_f$s?FUTok?onYMEEtjCtHe*H5IbLv>Pl9+#M|*S4(d#GE*3tRcKAmhET!1LTv_ zKeTjq?+0EN3=DOx+J>9cN(%2k1iW75KHjy>xRmN^?id)5Nvb3iJ4YHe-xBrTUPvo1 zA&ZZ{6)Z!M%Xf8`VPd#F&tdiFM}6pMC3GqX|10RI8(WyczxbodWzK4G4_)uhJ$zg@ zmf6*ZL@&z}6aJGUv-KheW`dyYG0Cm^E}2h(Jj633`_v?b(=M#P?z`-vabH9c?v?Og z!|;bZq?RVF?e0v7R?#DF(U>51hm`(6>Dh~|(+$46uTV;*e(es(OvjIs~(Ip%Y|#SrHCH(RFb zl*tw~LeJCxy2K7c25v`7l(ATG-Cgi?!-*Y-%Kbn}kH;aVUpbbSemh&LqP=^S>qxM~rIo2|lLVPGm9E&D? zxwWOwIeCylhcj#?s|?I%Df??b&0Ky6Tr83z-t)HPhdu-BUC7eT=C}?fWbLJ6K~8zX zoBbAxOCFB?9)#A{tAjr^UyB)CUz8LCeEin-_2GbtNcmmDpg!XU5^SU#=VmsR%^s(9)d_g_HgZBsivjl-pbM+I zOY$R%!xm2KXvPHNhXE;~)1w-Mk~d1@e!3AP=cQ8TYllNlK5fCoU94-o7U9g8^nP(S ze?E>N)U1OU#%$N}%h;=T%dxcQq@_(CIqz1#q(d$^H|Q-e`lTmv%5Uy>@-ik z1mm6IgyMLIG*l(zTJ3_?H)!9zFsrnS+HQUQb3`ZQ9ZVl+Stu|#nPN!I%96tZgd;Re zV@m?bCu}A4*SBqx#Ye{-_Ro03XUW9vF~bz>7Esrwh`V8+$PISynB#ea;EVUgtmujC;zzfhrRvS1M+ z=9nCNo=qPb(!h}*HGU)RT>y{lz$e&PH6;3R#D-H3!!MF`I3q?X1s|J0u1U$rtVRBC zL_F`65~T_}>2oWD-+VLk&dY`EA@-jjPRJN6uYAg{M|tiC?`7OM=5RRTd=d%Hp(QVVHp{^`{r=kw1oAf`l{<5H9Ca^QiJAmiG^1Wx;w)A4goiN z={K9*VmCD44^u8HTkY+hYP29apTJWm-g$BH)%dOEHjw zErra27Jq5qHlZ&nx#f6l%}~>zZ9FO$lR6TYc?Xw)k#U2A`vrxsWqj@#O)Z|*QMW9b zC_xbQ|LAxm!FV9H38n6sXU10;1$eFO%OScXx^?X`wtL1N#{gQAz2~|Y*9vRi zeO;=orX!4&@>tO7$laGrmMZHSK7OA1vwMAhJ1ndP8sikA2+tYX+#~*WNowAV$}1X3 z8KaOY=I?zWh+M&GstT%K{T^UegcW*<6&99TBpH#Jud0_@(=_qoOd!Ql&6?3nZ

D zuFv!2?+c4GOhC%>xcGK1@OG(_PPi*84gD?s0fR>dJE%z@-#S7$%OjBEbG_>@a`_vo zJ#3Cl*GR2)IiS{u3dL?MWW&*MqBk<|22!>w>mR~nl_+NY?xiw|-rfS^wVB8dGM&A>Z z{4(j=oj~Vsk49Mej>uABZQ{PX(Z7>(448u1F`Z}Z&kLJLM(yet5srWPjvS;`iq~y(4e0;EIITwYIMQhoi|B*0O5zi>cKT zMY4amh;VtkYGHnPBjHAdCWVw17_o~v%jGrtWmEVFw!G15X|B#;DRK1fQ$>w+LS-D; zD+D`FKmA}o^uQ!cu5G9CbZurGgpFDdEKa!^-DPmXGD*~=nOq7%I}OVg9(aAAd5YU( z>pM)nN$Iq6@n&x1a_NEqMKC-^(mQpa3VW%(z^O1SLnR`DK~ zk4h}OuU-Ht`Pcb&Ch4Kqcy)Q?T1~PF_Azg$=|1m8Z(H+jdTBDAt)rAAv9#rVumvS` zI<9#`5qu&>C$v==bV?zoScJbyYj@EG54hB7B_a8O{6nTX{~iDG?g4#{r|Ho5m_bJ( z;NDT=u6@2=YLtqqMn+FTO$HmIpG-ka?FcM5bVYU-vLi5LX)v6jMH-Xk6Yjgh8Zu} zp}UCJe=qw3pUQ{&FFA^NwGON4w>4&EF(ifnyM21i(p?D35kNZv6;KYxh0+7f-0u|@ z*@~y{imZ|mO5AJ%LwnznWH9<8B7o}!PF>=!SH6+G7!(vNeR7cu>4jKsPu;$j41L#R zw4>xPoV_~VbkSuyq3HCALw0A zlU+N6J|1cMkH*ch^7Oc7+`kP1L zkSvc<0I4N$)vO4^MNM5j3+In+W?a2XEn*w3cPK>zD1bS{j*ehSq)&y5N>1K~S->tv zYoP%ay^>Gbpp47Y*1H-v!#jSGeCBR~3R!KTZ1pWY=(4@{^ZFF`t{s*%t9xb^D2J`d zL{#%{X^39WB+zG>J}=cyoS6whOhmoQ{pm34=UX6=*w8VYGO9|ujx;mI=UN<%ohr&G zb8LC8^h_LP9YSps4lacXLNntpvt)Iw7i7Lu^HGW{;$aC2hc{+LZuoBvSV0*iS;`^c z7cAayi{z(6&VEmOH0cU=$y0QHhsf2Efqx#*C>V6M=I&rw#QX!i)9c{j$U>*a497px zyE>Rh1je#}vJmfaMMOR4>=wTsmYP42ZC>D8M$NDkG(3$V40@2MA{5m!?w&Y}^C*&K zwE$Vx`-xd^k`e+pDv$E9=s+4NPhjedplRo2%#2r1tf=fP<1W)q38bASmtOYg+B2j# z$okZG#V}1>JI~f6DkYALKAxV%;ik&2fzy&#jyOl)6^~a_NSV%&MvBBbwlU{pSRN1! zR9)|j>L1SEUGj^%9nZ|Z%5Y|VG@1IXT!E+fTS#xdIy|Lo>~VLO)<4!>753AOXLq(| zo2Ip26@9tBMwx2I9IG#vsp-D2d+A-7K9CK@p z)DkbyEKlCaIsLB%a#QElRxgI1eh!WHlQfP>l;O~g62qp;vrgBK4PyTfc9{%b_tw6Y z5|n~^H`aTqu$;-xfw2_130|#TLc$FL6WY-Cn&k`}y{cySUOWZu^9-AHm7e7J*KgkGya$2d4JDpaw~C~EH~7MS`BPvQKCAG~NRQ7N*qOsur~ zyD1lh9yem~fGBUi_wo_S(ok#}#@Hq$)PzQ88Toid*Pc=H(V_;( zB*0@9iyV+^2QQM;&uXh_#lC^%; z`BHrzduLv(bOy+NWHORr5xE2n-+U|8I+#ol6x2KGcM*7CE#A)St>3+%_gaSe( z6T3_mA_4%zLt%fZWr}_7)?H6N%iwPw8%;?)>6F0q!u7tK%y+Mmb-;+^zbE}WB0%Rd zEyUnb62Omyw2V3|H+zVA1{1%R!soI7HKLuq*E++0U3Y{o%a5(6uMc2MdaMw1=eeCY z$fqkMG)))VPun6`Fk2H15&d?!M#nHL8D{Tj6@TP`b|pzDIO3aNJ@5IA_j(^lj-6Da53rjFrN@;9QDi!D8 z@$i6Oe}>}o**Z3gfS*nYz=grgQLC_QqrAM4qm@>e#S}vO4w@i3;&i>I&#BBAkVTLY zfdgeN?FP>LW~QyGc0Xjw==;`|6KZ`d`vuWKVSg}&_rfADW#_~5 zRoB%_G^Ux!gW@97mQo|A{Qwq}H7KFY;?k9N4!_fCYM5S7$y2&95^lhMx6w!R*PyZ| zR_01dTnCnF?@81yZ9~6Tur(r1urQ^P;XYVYR#mGw6qnutj2iPT4g1(8xnzON;AU-&Li zg~~o_Z9RnY>gv@=E7%0F%;{x$F@-9E8TC_q;-F+VI+_GZjJcZjJA)zruBR}Zq7vG7 z6@_Sd)oI6+Z5L;{RoIXaSlHeW##oTMFz{JwFkKc6TC_44Hz0uUalry741xKlAr|rz zxDXbK7)oqu4kdNz+mFSPE|FYH5_plGe-yC7JxAvBrMc9_rEh@WhJwh@kV2vX0RWof z)G%6~&fr5Rbf|y}u%^z@?FnuWN9oxp#qf_Vca?1^_94BDgKhe>eR4jsU|lRTcWQ-| znUC^X&M=amyx^Ck*US*ZdtswYajXDJp`q~Dr0WzhV#BBF$!WHDbSSCB7}(Ii;MP7# z?;UdL9L~ju2oWWRYY8tE+?H$S94B*)qhIOgP|;LTa{v4G+5z~XcHCY*<? zDMN9gX?;I_ForJM)k=M5DQ7-vEMdogneY`lk3L^#9xsM%71Ei{#F5MOjqhRq@yA%u zs!I00TD&Q)?~$VfpMA+{80d)KtE@DyP**t;_BTb^kV&+1p7PfUp7V>WBz|L4BiGRq zXHaCxaq^AQOktig!gn#LSoxr*du|Wyw)&Ot&7^iDnZQ|fWi0g=)Ik1mZ~yxWb_xjx zAnlLWXGk9u6zWnu(v-&Q1hkXIAws%Q=2VLq+5}1LVG1tFKr;%zd}FOI2tznVFn>|e z4T_Q2axrIfSzaQnogK125DqGtaTszY=ff^EKa?C{xBSa+RPi#BkzLB|Oe^0RO)9;V zRjByMA4)>9*?-<}+@Q^>cs;J)L zSsX06tadx~s_f|MgE^&tNnw%?+U$Ln^|8o-d55sv*JXD(am>Z*pSCkC49|~>DY;X) zTqSdaxr0WQB(J4LT{IqY_azS&?F>iZEsFRuaZ0e6{;QWWmyZ@mBxt<@@_>**x%#2* z-{*A>k4QQ`kL;J5HhH=P6t|dZRo7OqzK9j-asK}NIXXSkOMNQPwL@3e@1*_H6=*CD zEUGv>s)&ut{N>6QQH(#yrA8FQfAbA%E#HwK;-S-E$FKv9P99y4Zf*{+T*wBhyo=Uy7j;a@&`9tuyx(IV2N^x^YMc$P(>mMUG?}l zTTdjG4nc&>9>(#+sT3ku9yvOgLMS()5H~_DKZfA>?DA}uTNju-9Xcj(A?CfZ=rJh8 z9Q!91I}a@kCp03`uH4NciOHZ&*3? z`YefzIV9wb*#Cqc2Fb=Yk5BO4vxl+I0b=h7_Id~MJF3*qfE}iAB+=dVi_^-z2z#UD z-CKxaVvGoq0JG83bGWpC>*C24Sl@rJ}oJ#v8*hH zWC>oLlY(#}o1?DC=a`)+qzFurQc-J*9LGqu{3J_kWE^WIur-`F{el1f-74|o&kXxO zs9gHaem|bYE4KDO^dH00h8VywWrWQqckqbZV~r9tH!nH!OdDttvJm5B6raI?z2W}_i}mM5N681}DZhz4EVy+L5) zI)rl?1Rj@&vr*JB>TS9fWlV0c{;KKwhaACqBjux0>@G#JfL$1BU0l4;6$P{6?JzUu zJL0-}TyHOi*P;oQYqLKwKZYf(goR~TOug6&B=hoS8M3dD(Vz*dlcb4LTq`LHt3!nB1Y@di{Y=rc)6qS?4w5j7M2%{Gd^qtV zqD2GuoVHi`HW&x9VmU&=F_(B9lReXZ-04p!2|npa=|IZ{d1Fe{AaInQ{Ls$M0Xj89 zu6n`V8DGUC5MgEQ`jtfx(~U8z?4I0>vt%1z_9o$$J9uX-kxFVdE4%QpGxkCwRn_|8 z!?;NzL3vHfVXkfDZ%fotB&j}!J(=BjadApAbVn|tE4-IT_<89J%RCuVr^Z8 zSgI&xJSxQyD)X>A;BXB8`U`PGFZ_Nq2&w45TmVauVZLu+9yPVMm;cHH@sGj5*UpF) z*q3Iy;P-i$@+2O-X7UzPQee2|OyfgK;$v0!>GoskoF#EotO&@Akwr5W8&@hk1ehlJ zmTZ&#Z}5`CoGp!28^2ZlpDpLVTb-92AzGDuMr9*b!a?s^^%J}2ck&L?!1WIJ$cZcS zb4EdRbTm1!d9}9>ut__(T`~JS)QBhyN)2M6Ch<1!p>D&tO5Cj=W_aQl%e-Zao4{`^ z^>QQe(d*>%H{`2nY30`HM%j6c4mKa*MlR0*E*Y?(a%U%+` zj-j6CSsl(4u}l0Zjkd{|iZ)&y&Hd{Mu>R)I%DXG-)4g3yaS3rOTslQrZ7hXF+uS^H zilUmyja_0bh*p2%j?7?ON{weY={zy%Kr}n_w+H_5_a6jRRdr5``TNUg2St=X<9x@f zRtV^KdWgaP7!{y+7+Samicp$&kx1Ekj=<3j?ue^>`dc4b9;s#+HtxG-W(_4+mweND z!Abz7jbXo|QRADG^WZ;+qhC!_HWf8BHNykmY1Y6zGMTY-?!mP=N>ok!ysu=>3Oo&n zeYrSzC`Af>)*(G@G%lL2$2&=VvHKcNXVPTqUdf1SCy;4CM)Rv2T_E-^`k@;UCJm&i zyJ^~G!_0bO&%f-?yS<<&888mmOvQ8Mh*n7^lw7Rify+36~ z29y(1XC*1}uX7kOba?{mHcsjbU~V4I&|WHAIF>x}32Tzu^7SZ+k47;m(<+W=_4RTm zWPB}*&6R6Y6fSNry*yJ~yi%~!%R2eKclzBDqzVga#NlpV{q6#V0C^q`(@ouMd?VsA z^%p)=R_mt}vZxbTk4l^i#~@iJudq42w9ff^hx%%1XQbdnE@$u_j_QL0QX>LxfP9@r0*YelXlPsj zEJwR^eta{@w%MFj7h5lM&4g%yu7zBH-xmCjFE6tjE0m?l}%Uk+-G5 zCTs5_KftUh#7xWDAzE7p()aGm01+tKnLxJ&UNj!FX*=RUSr&PzGJ`rK`9zVMB@!T;{B{?kaQK3~Ui^uFQ1maQe0Nlh zt0POx|0stVi<=Dj)-IIh+|YBe3%&7#_T2BLjDdwBkY8@ zI|f}rXOoqHjW;TRSQQ|Jy}2^(p+Ukv(g$u=YvX8!d-^fQM^IA(Udjx>?Ud$k*O%Gm zsYfKJyMJOD#l;T_khC27^11}(;KotnyaMaK=OyPcIdTDDp*h#78_r>Po3DM-+W6BW z45K3LjA{Z7eqggclvuABAD_VEexSX;MaCpesEm+fO^XOu$-El)pU<0ItgRNFNO6|> z5xBWphv53+|LVTKf&mBrvR&kj^M}))PxwfWL3oyVV;wh(I+p4ng(|?>T zWW>njGk5ylAhC;N>oyF!R`O@dr;enX-9uB7=ql4wh_HDqv;Vo+dHk^Cp((GjuC7rj zK-ZLflI)I-A~i%er5eu=o|e||=Z;)QPuzSZyW}gcnUPcEeuuBhq_VfxDVjfVEUg@F z{VTFD@5{$4kc}1P79)8_;0g2m)+ATgJ~D7XpY|%}9wT)0a0P8ux(-{$Il7cC>g8^2_(RMTu>{U$6Ibb?lZ5i&&F}JcZ_wu31vgJOtnx8l z(nPue>k3(Ug`E}ZS&PG%KIeF#PVmZz)kV9Hzrde?p)Ry3xrF5O#%d3%)CTHE)1)sR z%B{QOBggU#-=2`as%hAU;y?(+Fd$;G(hcJUQa)+HFojvJT?FJ@HM;E`DLyMgATW3w zj_EpFpCVuS^p0_UBSN72{^N3u7g%7)bUjd(u7_vVX^z_9ad-O4iu2>4)$WGn`&ec& zu;*ykF?H^@Q)>piM=(UHd_;^xmHqV&Nsv{{JXuu7faj6FO3@;&;$@j+X{5Di3Uxr(=I2FUx-qw?Gm zuXy(Ds=^^1FFdY^C61kQN}+s39G)5FYZdtqNSDn{$e zpGbPJFjM4F1r;1!!@F(h-}?}VkEyJfyzqrlm6BgfvL$}NmB}|!zudOslPpP`M?jT` zhfiEagT$I%)$9$Cs$lqvV;f3kyy4B8i9AC-Rs+vj)#mO5&*g3RS8Osis-u;@9sHfW z@HP2$RE zRo_!W*7bn`O2i)8PVniU&1br%lZ^!lray6L#1jiBG@wV#^~;~f(C}Wu zRT2#*u~}T>?KF1QUy-=AftMOXh#G)NZA)VJSEjW112AnUxLT}Cvqn>q9!&m&S*1LjYW+Cn4n5i&%;l7{fhmwb`(o_Q1J`ik+V zE*_4W`MvuHO(eZnnz9Jl;X~KxJI;A{JFme%_cMIg`Z?UrD;Bx3aERD`Eo-(+UVc7z z+1A~%%iSKnrE$fbnGJYB1x$l2R;aj4%uMU;oD&vN_5lG^3SFK3{z#SfpZ?l!0u^0{ z5>=T8MTfUOFMA?c220ruUctCN&4cF&^r2lJJbI~w+m7%(-WfMH!Mx2rS^A%-^&8$P zz-xs5DxLffDSJpM@kCYxI&t?4fJ&7fum`f=VroO*c>n!#;-1Iq;<81<$0rcAA9C2N zB3YCek`H>F8D?Jhg57>hwtzEb*FlCS;48RwSt?k!nvQMLfPmo$i|V)=(3h9QLOgCd zeG10c;)`>r>KqR^&uM5{ZoY@vXuD5_>2jbNONyoqk84z5EmrdIObdQYe10z#J6_}R zemWsRHIaO5V>&5!Kj%1Ri+LeLOmr{>Dr+p3_#ahO5W*3|8>|JLA z-A#UQY_zftrq!{hT4y8PBACWXNP#Yz%U>k)r5$nCGY!smklZv?6o35qT%5Ntkj#TL z*BFL_54W2MWi7ZyK_y(c?xBm%#m8u(s(h2GQ?lVd$gyL!(NJd_yTh6_(C(z~%N(AbW=EAfD*vE^89l zd0BTN7(Q&VeP*>upEOqgrP<*FYAf^j(^kaAlyNu~5;}V)6@@9a=OkYsJFxNU3sQeL zVk@mLDq=D_bZsl%SyW&4a`ktq+Aw%_Pk3Erxc+r$%H?#zdbk;#a}&Lv=F;5IK9KPn zTUNV})$MOPq@hRF$^gouKx=;?kFcU^9APJ~5EFrLQO`oh>6*T-VTq1m@dq8ISy4(` zG{Eo(aC2$2=`|+ZHqmVm#Iju1Zci1-w^Yz!mxZ*^HoALnQW?Z@yen-d1!;MwtI!|^Mm)OA!$jypfUfFW0 z%-Z(y#A-p^=GL$v*s`mCm>1x&%G>@x(4>y@=K*!B{hCEy0W(=kE~#i~{Ee+9YyuY@SbuF`b{WSLzkWj;c@3BEK*8xyBN*iM()Reg?$b80 zat?o4nV{kNt|mXBzxUS9X;Cn8AaQATxWY%kuhGMb3Yc{>BIPdi9>a9U5^fqdIGTxZ zqU{|}W#jLp1`D%}OX=uKQ2jeyg3@>+lgJGfv|DvM5-27w52OO1?=6{N(7TH6rQ`}) zKCs3ayTR{o+P{9#H$9-$V(Ra%l}KU8;E2D|H&s>IpI-2Ivfg36m`z~}4jtRst0Xm> z?^E^(pOqm!ue(Q9jQGZcLQQ05nvt00;;k9_9Fu-*KK|19u8Ch#u1fd$a|OF z)xR>1^mKFr!9M0ju0VIQu!Ddq^@G%MdR>3}fMFxJGaR)gpnGszAJ(y?QulEC9@ldT zhnU4F^?T7l%J?x>uhoh6=-Ww>%kt6V@yoAhh6t7R_^qOXpGL90_k;92V0Jg&(wz8My+L_UGs)FQU+&2e@m_V7To4C>2F%Y0eh9Pbw-yFfrjZU4&`vvb%o=!2$ z8OwTYAG2!(n4Ds|w}U=0fi|>ET<@~~w=K9bGe$KJejX#HAXiX+-b&J#*AxDYamr}r?Um>&>c z1gdT`ch=#kmDu~vvG7yi0U!1wYN6wM5Fhk8b%H;#6EcdHrt&gaukAH1I`f+gLE8g3GNvhb;0z%7*YtT9?R(@kOo8mFsz086W=RY(7Q8KEtQH8Wp^8T-RN zHYvnpj(%CS+pEZh6?ZvP?2WMiu2{A z?VTMqPg$G~>3G|J>S=|MYLqH;n3Q|8<+6f}8hJVuN>%hdV0wuCbSl&b!>Oe8!)`)V z5sFT%1%j2T`8s1U^Uyxr#{6Iw3|Q;*xfRy6+?<7rJiF6NVsJX9D$%3a@Sz$?HQ&*3 zaAh>4{7=j1ECc75JdyxX!gx>3vrKtp(M~L1TMRr)SFkK60Bup83x@_edjle<}m&0_5Ej`wVFz;u!IO zbJ}IwAOS39W&9mssJ4ylLwrw8sfy^GQI!m4iPvX@f}4ZZmbo zRjL}T)uJ7RF$uD!mV$LR(Y+Vg6cTVe!Hd;+FlKkYJT3$^d^A7V)it!WjjUQE=fOzA z&8M=J=u}1?k~^xHUJs*}h;1i0`8cyt%I5Z&Wzt3w8iVoh*LS-glPnStPWIVGaH=kw z?rQ-*l^9K!-NznWus=doqQ<$r&C(`@sRn1LWeBU3G+tvmB;!Ij9qq`yp#7sODXXbW z812z56a5w_tGhP4kMV9CF9S^T{<)71#BS)xVZngcU4Rctyz*KhU2zEXQ2)}@DpmP$ zh~V7Bh<#n}BHpPaQK1hcEs9lw=ow~T-4rk_qroy=(A2h`)+tq{DTO6DD-LGm*}GoA zSf|4dM%Z6dTc8$$Pk?Ta1|K~_1qmKuOVgC;P*uj#>6%m~F{PfC|Dplzlh_vsZd{-W zcwkdGWF{~eC4{5hYSyM;D>Vw{DCcch&ctJeBrZy#NsGorSeXp}l2J`#8%g|!hk-<;#2u$ymh3MkBBF=X1> zdDtyFU7lInm3@XgC_z*a@|4WN&|KOBrTW{_l|oKVfm(W7S?(665t$JLl9Hy0o@5de zdIdMGFugo`SJ^^2N@gZ4@|{G+IPA_f(s_D?Mkl}>FvFGP0{8;)uRmI%NO-1(sU70w zokiZmctB5-3gUo=P=Mr4{EpD4w*yAo(*-5=Q_X*62IX|rX(UKcjv1IdTbe+L4`MtN zsO}**#MxW&sUL4bdPPX0pDvxZsGKWVfft9g%w58?c%<5)BjowDILCFp!WpCW;lT)A@~ z`fC1`nhqb@2i#LP#0JjD;iqZDNCKhMRBFPwZcaHU_kXi;{L-xWch`-f-PC3JTd{D1 zde*W*qZE@e86_ERKs+?K$m>O+ak;Hkz9F?Bes+2@`1l?DZ%D{L?CGvYd>$C%l@;hk zZ-+QgWyK6N4i>Yd)Q!AyH)JSQDDawsoLD~Aj4vJa*s0Zf8s85~Qh81zmUbiwW6^We z$vFSkhMr&FTOGVLvJf7@bZpJH1rt@gy#cBxYqL>bk!e(%piI%Mg`KQuu&?fCo_ENB z#Mn1$%gGek_s`>h=qhigp_D3ui#+_;;4yz5O zQi~T2mazC#G3oJf%uj8l=|ADZWq*fW?NuId^ zy#K~9x z&WuoOimP-eE1_mz9Zva3qVP=X2zs}ZuUSP$H8fg<#9^nL5ah%`UhVS1!+1I#p<39r zma>e5TcbF!<)p*pVKGIDL&{}Gl!CN0M`1yse-mL<#rjJz86C(=_k2rpEZ|#1LNnlQ zTSohSgzm8f6@5+qK7c|3`o1tMLk+eNm7Kp%54P5?aFjB3wAf_;xIz*Q5389iNv&lR zJ^kmV;9G$^fd~|tq9QB0Zd^1ek`KGdnW*cflx?yoxX@?7#09-VBZv!ak!tvxj6<>< zo-ozFM-!l~h?*x#m&9fH;BotC`)i2Ds;>AvdSVj0W(Ck&P?wTDNG(@`UWEz=Fu;)H zNdl+)W|1Y|HrQ+z8hKCN#gKNi!}3?#<80$Iv8@7r^!E?uc~<1>3o>NXV8n@|fLXo_ zi5cG@KYLkK6)x2Znm2W;t;2DBYT5&NS4s9^)Y!6 z6vYLEt5DBVpN#QY=u+*b#h{{Bqa4zWdYKLOaIOY zPomN3_*t||r%b}>6aT=1KBFLUhn^EdNgZe(BfU(XB_o5QD%Z>Ew8zzuQl4xK^a=D*dMiQYIxyArU+yybkW#IlY?PgZZ5fR2&!@ti;zl;y$*%0 zl`^qFSN%f$Q-Km(!H`a-!5! z<3&Xx9m|bkjK~z&&2mSw&8bUsj3xO)4;eFBN(^84flZ+xfy)}7M_hvQsO9hKPigM{ zrfdpSqzq%U-}}pzOVFq=zcGhCfy1A+xdtOGt$x+mIwh>dgw%~M&Z=VQxQ5m7&zRU+gW_@w+<|cH9hs0Z-Go&Z)!n@wk$wGOAt8 zy|z=^$H&nic3iZ3FuL@qa5UBN?CcYb+E-Hzci#RCyz8ThM_#@OrV)KXRFobUTXAB< zd^*)yx3TA+ALg<)Cyd{XX*IJ)m}`r&kIDPRp?ceN6{cXh}!5L zy6g2^jlWej&;0uyWxr)%>w(;c#>tr&03a;A*>%?of|MLiD-?mGB^sVV5|4EBmOH** zl$pqofr~DP=Y2`og@i?wgVMFLTSs05h3+)L;QN42WC_mvu}|wd6hFuLyuB4z2F zBhDcMSvBlC|L!(F&nkuE0OQWjrVq}2O0#TQc!>_TB)d%^OSK{O8He}bH!I=%$F$+> zkPz3EUE51vp)PRGkXuX?G1P-uuc)ZDGlHNaj=JOp+^k{iNxUYpp|`SDrs6tM5O&px;L^+5v&D{b{iNK3eo@oQKDu=)lYFLorv#K^Jj zN2NbW$&}z7$TjCe^Ot@|Ny8cFb#FryQ^%SZ?tNb>^pk7#oxA%-K(U5>VUjsG724ngt0lY=96+cvYUyV$u1*GgeQN#qkwy0m)=i8vyyBRM}PN#~i&4|8xn9@9BG=CC(lTx?Re3`|XWF-xlI zh>T6fk_f#qXU8X;oQ$|oRjDnu9!=ND=5my5o1CVhNfOd?1#qwJ*Z5P2VIXog8QaFv zR1D4$S^|Nb_W3<;F~Q5@s3K&WY}O`c>zKy# z{2r1dELs7jEpJpI&?M;%#+!_)Su|HyXg(QW9rWn5+nf%Y3>|~YutV$yL}m`Mc_iIH zHBE}w{#*Wbb;hqJ6DGqmx}AI6deCF;k2t)4kKO$~r+J@cKW$0$iYNxMsgloHrY@jmDOvxx+ff{;N~6m<0^W~JxuK7mD#Jr{p6V(x}GN|t(UmDbua>#fDh zO5&8EapNjpVj^2*Rtg5$|6ee%FEY)UEX7KV)mD*%-3iCLTkNzqkaHm!&tVW`$tfA? zmUw?60ss;uDI}ct86NHOXs5$CF_7#EwY4%iGeGmloE{I*q&H*RKTOgLg z26Tpf29pUr-$b8I7)@Qqk%HM=rB*M|w0PyYBq?nYu4)?E!m0UT_DE^gR8f&t4Mm6- z9I^9{^M6X>n9%icr!Mn(NMh#5)|<38*IBbj>o}8yBwS(Hi|`W_t=Obh&!VxgH5RoB zvZ^2}=gnnbyygqPzSkz0q|9lK!*uR3_XT>RN^NO{jm6Cc@x~yXADvEdyLXjUKl9XxNI-66B-6yMKtUgRY!3Yu=9>pF_OU}OFl=;I@VjI3&Cin=h?&X><3 z0-vyeVx7m_pBEV+sp)qWk+v^->6T?#M%5HlMMk_1${_Jhh}Y}oIf&SE4#(?HBOz1+ ztF=b8zDM;*m(zBKPJ2kFo+UYRaD9Plsbq2*nl2*|A|#*r*#Sp8`|J-RA}xbaT4u#8 zB9BjTyL|?Vgy0R(I3bW^30aYm<(KEgbGq_Fo;`GlyfNd+498cIaypu-rUV%8F=kN| zFr7@8I3a;-k*~IBt*o)JT3XagCM0n{u)K^TvS8I%Yi7xr5-B7IWK~5|O*Bj&>N0SNW+O&Z2Tv-Z7hBYq z*H~?3sbm)4inr;l%MR_+4#QCu!|`AUnTkTzR#HgoV9b0vW$Y$Us!*t}u(G~F z!xkyDHHjfyqOz9Y#RlcgCiT3LLOwra_+t;|N9^tFaOcScdF5j+UHOQQZmh9X%wVgF zWCt3GqN3>%F(FYL5x=rnlSS`Q38AGKeN$5~O$}WW2oVy5F=3PvvONDiqKGJxh$Ri( zG|)5?MKRC}8EKXf#$gH_eQA9pNkSCHAQWW7L{}A5k*=>--_63yd=L04{1TkMBq5Gm zrkx%3?tRJM|L5}hPPzQ%D{C@J1YnMkC&Z(0CD z90r7e|K_UBMbqvm4)G%iVHGJhFYwXL8*J39Kgsw>A|G#Z%HB7B&p-X&pYe~447B9^}M8t&AdDQO%Bn*gVW9BCZob_gOgC@T+1jdK7qxi*2S_Ug5@tQ^O zk|asWNE!IV2t=kpY2^wRuU+KRi+>7L?N2WY+v8^u)yR-7S6E(YP&{n2f3nTi)0-Gg zK{Ig}t5wQ+mWuizhHBcb#2=q>_~;w%+`7$|yAp+~zvaf&8{E8N5Fg7t4SMWvP4VS~ zB#B9)w0ZM;wWCX3_p6L7XUG8ge3D2lfp7$t! zw4~!41OY)5;msZVFd&Gew9P(|()2oO%{<950yQ-mFN3qLQiBX)M)QIU3>mBWB$W zM~52Bk2xF0c*YW~`~ zM@Rx8s|Z;^`e_QB)A5R9;?T!W5+WgxRgLG{;7O8%ED2Q7_5NY6WPvP^L~0bjW?q~F z2Hv?ReX#rxl$D5ylN5UPCgh}~XegCsD$O!W#V73b+nk-8a@?@-1~C{KW?m&{3k)qL z@~2Es9`NwiEx!DAkG6G%i@#puH`gz7r8cD&oDv)zaXc5OQo5f;QECLg5X}3jQQt{S z5(Wf8NSuHq1VTvfnHfIUfgw?(AhaTtl?z6QGNvWa4e9M@k2p#RM4}i;&tccr*|>U>k2VUl za&He}jm{UbEF;Nc(c<9EVwK9&R+m^-_c$5%*gxpg_WQ&}kxcUnZedI?5st` zR8U1g7(|3Yl7f()eKmm~AdUpF$Y9wS%#4ku*;rW}Wh@bdAz>U7zhLFZBuPXNCM2?f zrsuFU4MP^MS!xMMB9S1{Kq{((P?KjJTb`#b*2|8Skn zyou(y3|{y~L=ri;a}D1ITYHzaoJNt8ARuymyhH&#gKk+!Z)}h%5R!(f=$M%V5|`O* zh7&L90Dk<_rW;~7WIXB9?G12q9>L7NJ5V|jz|<0BWt4@8m|d9zWGXFh(DV$ zJUL}Jc9{ts#Skce_BZ}7EJA>$qSzLirlN)s&dkI2L*SR={3R@40SPJm=%*GngPg5V zSYD%6>XJR$WAFAuijzErB?BsTcS2kj;@r=8;nzw`6gc!w+Ds=d z&U}U%OUR0XPQt`-as3cCUO-%5v0^1qG!)H1*9>$KAmWHPe6d;XPboq((6TwQg)Esf z3E|DtK9NDhYqu%SgUJj$Kke9SW!{lR=A17sR)gkWta0(m1y<{M zN^0sfDT;=v8R)W{I#^Nsnroz0F;NtQB%^2sie@1G1vZ}8_n95C%#sukHA>|sE6aK0@6H%>9CU zBt#ezN6~xgAb}7HrfHzd60+~%dI4@2r@a7wG4Lh@P0zBjvBA=VA(`C+j*cE9$14Pd z3KucR35ATr+Y=p{hOjJ5T}8}de8(g3!v#e5Cx$TD6}09WD~*4oH}7z~eZ=EoMD1dU zaw|(!taAEgpZ)z^x^0!YUPYHHlth+{q@f89k;$N$2Bs_%x<0<^6GjmvKjFQGV`ja5 zKL4kEx}w7B@2_$5>Kd(*MFt-+IAjp%jMW?ktAJsZsF!WDc1#?F1m}S?SU@sogrSQc zO31k)SvyDBG|5+MlnNGQrH|yrM1GRi+nq1YI0k=45Xgj5fn32Lo6BKlLh985xq*Td z`Y$AT(&_1wBvU-kC(()+`4T1Fz0OyWr7z_MJM^R)H<-C^g&BOC&b_F7m*ui&> zI62s3YiEeRyg{|O%!P`DEhU6rxM)KV5{4mh?Bcm?PEO`{L!B#|@7VB@1j3MTGQ}Ov zn8_vVT9vhxJenp$@bVWVKtWOSWbG#Ftpa;ppFy`n+YM+$P(GiZkx%4JnGcRRi_18A zlg-lGpq~;*DzZ|fP`$*(n=$sKzu=?GO-f?X$UTZlJfCnl#`gt@Rb_dlNvW891~*NT z)Cdbh30anqU*p6^QH1BX40{76b3v%7$cprg0r$1zl*A-)Od<&qA^!{!%s+$3D#FN< zDJ@Yh98l6nOb1;ivn2woXNxF_BEtEM*>J$j^NE`)bMN(!=;qflO=ReemwIOOhw2N>}h`TPZHYZ_VmUA-?~lF%cX^%x#K z<)l5LXeMz&;3dSdj-IWvv9gLOWO8vxBB|)PGPzQfW<7_kDL<>@2O!BZvYo@K z6e(6LGW{w3c+6nv5|z&BBU2?kpH7*Mr_9|LtB@yai4Uk@e&x!Gi1fm3kIyqe0j@h| zI-TSB0kv$7QYB9{uhDbHOhahK*KQqOrP0{j5uG)MwP|GM?oL$v+qPN}(;z%xBPZnK?0XMIl?( zkUuzLEFsh^R%wk3H$LIU@sLh`hoeV#xZkX>Qm?^e7?XPYKrkGDMQZGsu^bcqBnU7)1oh zn*tL8B!hgp#`0>5`rU1YM|5CI20fc?JeV@TtCYQ^R%l=&6?CT_j5L&Bi)SFMJ z-`k`6=pJ%plDAj5q-9VQ6`A<$I!Mc*=36W^@;o^RI2oTYo6Yco95Lz-Es{Ks`O!WT zS;Nm2$lEr-hd!>7N4HnlSS_*jc)-@-J?{9c{Ax*N$;wjQ*rf4fO7Z?7rwFU^OXLs5#eS6DA4?Kj>Sx+h#WCGtO7YWV7T<<2~3uW58!{ za>U`*K7GAOwzxjqc@9qdgq~zG%p2$#i+r)l+De^rCj{SR5(M~3f(gh; z1o4pB+-2ez6l*QYl`@u{Ma^$gu03SAaK_Mg@LZoTj7b*U32_wR42H~OmAFu(Rn1b( zS!At<^|d8hr*n44b7r2;JWA`f6+nvTg#M8JNJ8i(8p})MvlhDg@_rOU=nw`F#0HkB zpz8uze!KntGdq9DGc4OVhW?c(VeAnGJx1d({ZWE`qfE}ul9duf5)*_oLU+V;9^v_^ zv*@`U+Czt7C(FiiK0TF`kPs630p2_yHkCAp5J$xRoM~^!urnhlZm_z(!qqhkLrYTU z?*+vnfux{lMRKJTE?-{fu@lfg+vn-ojHPm(QdUMHAr9uaqc-jBd+f=VaH>s~a&L3~ z1d^nq8Z{bg9}#I4*00}Wy;-FoflNx9A55o=kNeES3~Hmv)k{k>Dt0=Kk&iR&GZ~LK zo2ZzD5~XU9tokCfD2`)1&u224;l~t2EeUU%MosJlENBC+MIaj7uG|`pU zrI>#Ld1*3ySRHSAbizCA&IFJ&WGzp&y1`Owi`Bh8PrC>7&sOMrRZ5ybB_+kRUC5yTK+L|^=O5r1#ilRs;QVLm)Vp2ohckw3^=A$7_7%cGNA#oz7 zH6G{B^8Dv}jL(ZABg+PMp-!V-rcn_5^POGx^95Etlj~VQ{zLeL03x5*o#KxAOy?1< zWMk*^WK08*L?mHI=(;%blvPXwF5$e-xHl(q4FWw&-BeIi4NX;%{d54+h;~dA`Z)6$ zqw$29W8kY%s#F*CFM;RdI1yf~lWSdItx{y&Tr^9S!~&`)-i+3Hr_=I=8J4{Izlo5M z%p%!FllpRv+FqY%d`A1E$8@Pm*3eLhNuoKEL7U^lGkSBC=DLDuW#7HVUb9vJkkVQs zMUhd2fG8r4LZT!jjD5l=CXrO^VwL7{la-}o_D+XP`vXq8F6+96AxlU}K;-lov^yNM zU0ivYf?TG)v`nkk=ZqPn!5L$(Mj_V8h$QWW>btm(gX4w-X8La8_nV|Iik3w!F0*v; zD(j~K-PwrY=^mZ462ldnf|k}mCP_r>PZQnxSU5sQHOn+N zuXF9{E+>b3>^^zG_T478TWhT5*U%O7)jnQ7t9_Wh;lOp6j>e4KkT9>2$ysC#8C{Nv zy#U8`nL8ey8<50d>io51JRu`#Hn#Z#l>CJ`vvB@=$Hz-FjK(@E%{&(>+5*zJ&{xmb zxdKM6K)JQdMspWu7UPYE48|U_e1>91Mj~x3x3Zg)#o(Gl`QIA*t`!EZ(jP&KLZ<`3Bxv)BIyoWI`Y^Hio8= zVGep zG95E^JiOS(5Fo_?aWKbmJX|Lv2;v3peuB_+ip!fUuk5kB|CG*Pz~F4ca2iljl{6j~ zd4%JAP7hu7&N3{oswkTF5+nLg5Z!`BP%b14BLX=seMl0JG!3=3My*w5Iq$Q#x63Gh z5%0Q=teeQHiiG#}J5lrK`BgS9uJCX?p))z5Kj<@@74b?&nmJ8;g4ux1lP8=RIf9k6 zj!eAmyss0TAZK2nbVWzDG=wUH z(7xyEwxRo#B+#vW~9GsKgMtj86_Zd3wNLQ&3ej48wQ_+h=Mchx20& zwjOiu?mpwCUy;pPSU5OC2VY7ErxONG_UYvt1erQ@6!O&uYa5%a-t8iLQ@RtEX%Lao z6hsmbPuq+pK7+8#(#kT;Mj6Yt5yl49zTH7{5~`mpk(XjZcTB%?%!B)f47GKd zzyJ6A)zu;!C6SVnOxo;z@n8AspZIH4U;k(R_CNi1{F^2ep1XFEBt%h!>$-%Y z`a`hv<;jr55YL%*zGv(9XZ)}K%jcYCKc@1#|DONpKV4_NY`vrie*%eL{E1@-7k_s_m>_~+!R+)*WEIJ@&Hmnt&jPQkri8Xadeh6vKHp4N8$%KQA{kkc;1-aq))p)V?GX%wF$GSi|0j1YJw0R-n>nF@05c{j?qe; zxMiWq8k&(oGc#mu6J33Y#O8dbd#~|)PANQpip9JQlEvJW6cV*esd0tN*QOjEea_?g zG28d<^Yr5HF)|tz5#SHnj5{avhI6L&HPG@H#IFJnUX~=CQz2=*>U??&Auz2B1>2;k z3p&me&lxifEd0nPMnhKfWQtjqE{vHDM(m9an4do7!NWDKl-J4VDvIwiIquLu=`)@w z7#E8aY>j-`=T`?EzCWEZ+}~omyG|x!vYLs&?Jz#u3wcLy~o2+o_w{!Z@#D)}sT)*Gh@Uxs$#d`FT>}_B_p>-w zmLZ!XlQYSi5d(LQKXsTmX-3RLLP!Ebey(5RTh{uyDtIkSHd)M}BqC)3c*ALuR3AhO zz3^%>Y;i!cIKzj`o5k~LhCwEd@ZGd*!Hd(x=Nk>YOc}kl#@e#U5>Y{YQnGtetEycFh#q=C9jwYtLQN|mq91csuL%SmJ`P@hwz3;xG+D!p(^28Pw( z%J2Ubhl5-6zCK`Qd!K5xM7^A&o)Ktn8+Y)ON23rSbeclP7J@)}!`y$1sG3H7V}+&L zyVQdYQ8tH~&7+ukgl15!mRW8|eDOF$xG@yTuF4juqR24OHnLoZqyC2cdU**%w zO)f24#==llEG@yE&TvOvI^8zM2L~J+b!iVG z;@lF=)fOu?8%w-{jYwkA9|nY!5RAG^`X}t|?xy|09zJ1bx5H^rqY-CBP=+EbaH^&`zIo-O;pReFZuSXFZkov_xWzS$3)hM zWCg|d2>QE>cE96`&pzkNZ?<@RIAW@0QDo3Hl}s*+X&TrW11<3&cIlsW8J?YRba=qg zafj1!40e_3@-oXcn~W;IS{O$7f83ZQ8vvI=wS`gE6PO2MlKcLnlZflTMF$e}_At|B)YHvoY0-cn3j$t8>qUCq413OKoWw$bqU=7*M-WJ z8?1i(5mzfZnIBPTok$`@9r$T2h#Lfi^B$8?kJHY8!Netq6%;8T4q-Y?FtY`$a*bM} zNX1ICPH`OK&8NhP&v-mx(&=#4J*C$_abP9&Ye0a#w?nA!* z;yWIE_Z8oK^A%ry@dclM@daPpy2aOb9kN%OUf5kE2Jox&PJYeE#iyp0sBS+yv9qiCqtG*yZ%W7kqQ;7N38=#lzDHo=}lg z6GJvI4TD0?!qjCH5fje)OeX`*P7XOaK4kx}Lw_zorc86WN)gSrttMB;c z;XVhW2-LJzESgQ}J-y4$oiF&OFYa(>ugCG&Lozd{Lc!E@EK??lJVI~IWHiQ|Pw5Tj z%%%}irbNEppjxsq3=KVFqN^YXaYtv22WOld9&mDW#8G>~OtLY{ODwf&RB{HkX<+CI zvVhp1GM$VWc27C$oN{v9;ppIylj9SPPmUNl0b@5o)pUfSW0)DVcj?1tl4hF})j-vC ztc;05NbF5GJ2~Wd|0z3LTWoLdvVGKN6kC{;W!6@ge}M7;#4e%J=j`wakH7z#TVH&^ z7hm7u?rxuxp@&42mJvh=fn=b_GMeP$3{E(Bc$@#1z4vOekK^``dUrI<^>%&Y6vSl0pnk~l_J_Rp?mN8w{wLhs zJLPl~6GcA0Go;t;F?3^MLB-T0r0*q7_r&`k0ukcSBT7?TXF}kO={K8n+8w%Xgd4`l zLP!)kmkx*=WnF|xjmE*Jyz}Sx`DCxjQQN~44P;qFHxyJOWz??I+JC@I#<45eC_h@^M)$LStO+z=dY5g_=0%ydyTc>ex%JKdVd;8~{ z^+1@p!q&}Kc=hT6%chIdI^f{m2fX{Izwp7sQ}!?VxIsV^MTCMvD(lEnf*6nJo$s@E z_gy}C_g&t;d%$@=z=A8RIrjIK2B8 z-g)n1-hXh+=_tZOCKW_VHP zj1rT;Ug65ETU=SHuvE~dN2vt?kRS?(;*`Lh5JwJ^VT)d;MXl}O_yMvk;JYD&DPgQ) z&JGuT8Jj;Ns+j^Ro+T{glL>qdGUkqUGW?_t^d9UEcZA+kCv&;-o#9 z)@Y1VLeW5$Rb=Tqs$wT0Od4Dq-sA53f8vk-_HX?0qep!7=#*BghZDr087Qib9P|)l zhg!PC!sc~uTwP(kDwFgtsPBHtgHPV)oj&%;c7w*n2`8uLoVOi3eTM3Mk*b|AI^Aab{Xg^W`ycWCPKTlE;RQa9FOa4Z zhNhxOQ<0-Dd>J7@QheHVm+?Sh_SS1$ySl{sLJ>=mktQ_~ug5{M%;Ls1Ze3kvwPaxa zRb6u`$fOxLEIC1zQruCG$)H24cE-i|DMzO*dZB?ma=V3Ymt7_`<~Po9)HBY z|6l(n|N56tdH2B~r^kmJ?eDPrXq)Ya+iX94$oBpjy90~j$_6)XY_L=`u{0G$(J_?- zK@@R^BiwP9PW_aNlS6iP8+64v%3HU2@+w( z+~e@zjN_3-e*G4=Zr|kkVu7MDb*c%9fh)hI!qhcwjPYCj){+Q_WBkrCC97eO;xqXGz*#ad~`9=+gAJO>p8Q1ry?S8`h4-eSe zJLLGZPOTr4C>o|NkVGNwaLB|77>gCk`5cR76In5^ZHr3LA|2EjJ1!RkkHDSaB{?K} ziJPy?V@D2Yv&B%Iqq4HW)$7Yt^cc|}6QUB#{)(H+23uy6lZzJ3Mw4#4L!<2@%-mr4 zjoOK7TvRjE*3TA-9GQLU7it(YY3W4hfA zC#@l)!GNKY5~*d@UVW9-g)+0+ciHGnkCjTYj;5&CH0adNd9;1ZMZH0zIb;}USXX|{ z>u=uXx3A7q(k=^{UcP5{*k&^E>5I#(-+YCeH`ZCQzEC%tG!BS;7iZMRGgq({Z}8SH z)>+JJnBo_k0|}8o#+x{FyAk@rH5RVE!W&y93cCCQ(uJoX_+ZkZaj?z)y-&Emd&=J7 zIcJSN!$d*RWi-Jj2wjF_2PYH|^NSR6I;G2E(uwcjbnBcy{D23$M?Ab3GKvKx-9(mD z3{^v&To5#N_~^k2XB`(uP!LrO!!$7SW#$(vlu8vUe$%A4ib`3KoC{tuU}*3`Udm5!1pNc zH${*UB?H4MU}_Sk>@(_haGf!IFTf2&lw6ha+!Cw#l+;fcjKNyiWN~GVjYS(%)6i5E z)09!;0iNT~Y>x09k1&c6WCblJ;(Gz({unQLp~!+A;PmTUoE-A#?mZ5V4%s_8 z;rRG~gZ*9h_IB9WJLID4Ov^sxO_;P8U+i-C-VR6g0X-j(RCG&2(iLRJw2$^V-r3`* zJzx3YBt^xw#7EN(ozyki9nbT8mD% zLw`7;?+QrvJhRKITwgKKqYj<3eYWr3XZNHVmA92(iFbDuyMiC<--(}(hib>AS zQ?aL;+rJe_)zEDl+maEJ0C(7BIP#c`T>L;lE-g~2CB<~YVrrRjWR=g1dxScZVtxuA2p%ig00>>VDly?@N{(cyIL?C$Vr_lT2@OD|L~ z^F?gSplDl|7PWelcCAj=k%{d!uHJcrTh~{)GN+?QJvwLm9BglM zf9IT9&<8gfv1>bVRd6zEHw4Kurd8Pj}gWw9WR;G3R}c5EV%=u*)+P3k6CA8(lNe zRS`o^@Wwqx!vVd)1nfCVvr8<_RH!IphP6Wu9zEp#qf^d%E>0{UNGiImp%@}z?}GD# zeGU%KsE-1o%knRpJ&PLqFsyU3`+&XECKn^000~LYA#y zq?p(Sn3Bt|w#VWA5&Ne-2A%+-j;!e9suk>lO+IgYyL`O>h!TG10=IWTBeqZrvlPo! zD!PF3bqkdsA*2F&;vm?wSPNThZLYIi$x+fT%O!{!l44UT=Fr3h+&-hpgvn&c*b8vP z3gv2r)%h}-HzJA^JgLCq<{UX;K+xD{cYBZH=7^!6f+(Sy1!Ubqn_SR5*<=6Ugrm*` zHx&^i8PzOP%;%XY+T;ug`I{bIkU+^}7i=n3lXTo=JnYeIbr}u&^v5ZaK*5v)AS8)B zTvtFbikRg&s>K4ON|l-US!Rp~yy+a)?)K@nJB%hiVR4<=rByZ;3RJ`nos%85?>}Vw zph;^K6GRb08X#ykQf`J)K8K~rXy3&v9tSX~ak_VpyB~kR`}YsnJ8jeM^l`ly#j>%h zvy}1{wi;oY8h&Am)wK;a7s|}$5}ejC7mptB@WD2_M@?#jm>7_il!z2xDv-16X`ZHC zrCiN3Uo~LdW-{#2XtnA0I<$u|PFiI7$`&h2Ir8#^#`dS|Z11ph(q`bqq(VA9!6ez( zIh$%RhpB#r6H5d%8P8Esq!O#IUSVUkLbYh1iXvL#psEU!{8iRA*15V^p=v28pSzEs zSZKKl%Zqt*(Z}!9X!ZJZyKTC?A+52FJ-f{2wKW#1HaSiHcGcwZ8N>4j{Q12d_Rf3s zM($LhIPmfP$3Gz<8sgkdZr;Ah8`oEv%WG(|hN@Xq7prJ#NZhT{8uaOP8g#mS>TZ$h z#!X)P3v(Lk4;P$efNb_R^L-{xUg zrD1LH=8YAW%NDtB$yFE9A4|S1Nr(c6z@0GmW5OsT3PXH9Bu)hoWfV8%fdAD>4X)!1cA>e(ow|( zRSfaMlq9*#XG=j;bY#sSr%%1uQ~7@nXEI?tc5r>4D3#&yQ5)ODFg4W2XNUtIXX4<; z5DOx*C?E(jlB}SaCaNrcvDodmkzO8!^&MO<#Py@Urt}Jeh@_bqhK`}jpIPtev`%2) z45ztJo{XBa$>nWK`HMM!X%Z0!KJKW`B$S9GlVaIIm!+@p6eh%>N8mXO`wo$0AelC0 zd+PQ1L832dLK27gu7mHoQ?;!yAPhr-Fd-ErL|H-8R1`%#i!zJupZF8|+%FcuIL4NW&N4Fkh8(Uhq~cA7+lzK8F7 zxWQBnPm-s(HIR@*A^vEDpNPbgif)*gnusFCxT7(y7ZAiLsWgqMn5KrNiX^^^Kbhe8 zK4Bt)q@kM@re$FmI=b|DbCCcZ{Z@_I=>^9}9y42;Y`nTfUi=0R@;APQ%jfbOJa773 z>E#AWlH{qVfB-};o*&~!BAR7k7#g~+Adx~G5`{jVfo8O0WGR|HB&_{M}ZL zU^Kz=r|%Ol}=-lBqH=&T*t+6J^Uabj8hUM zWJN{O4K!mqzv_xK&A|;l-0_IXc+A8L2or(iQmxW3ElktER0Yz=C-htJ14|Vl z_6dE5@x;TAQW8N%)=W%OM2?5F?|;bdVVjeoguQ;1#n~dWwu(eN6)_t$s2|4>cUq}d-xjCAqpvnS55)ybWuH!JCIQT(A zlnR%ge-pzrF?1bO28o!^b8sgU9LL28ViG|{QVqrCe^Q9@F5^qh?$iztKy-Wb>Q zaf5_dlur^*ZHSqUUCqQaRZLYRjr?g&tn1-l8lI|VV%Zjkp`t7DcUx;n z81DWD$M@dh|2eg=R_<`))@^>VI?V(9`Ysfccq7~}#ZRZ>MpLBe=JRv?ED0ay?goVE z<9uleQBqN)6fuqPT$dmgNks+2){%)J@Np+&TtC8(Ku}aP!$LOC=eKCuf5gjm8$m#f9Q?q?3#L(b&CFq17M8A}NFXGi zt^0lulL+EpOZ|wdfu^cxs)S5{@47e>hl%4%#|{#Tdih+Yg{i41vhdx?x1k9G4(UiBhKXkT5-MryDw|A|eq@_YKYj$Mx_+riI5<4OO?M-$=Wx ztN2w%>Iw12KAsyQ7{+v+c^sJw9U|Xj5KeRY4gG7rb((xOM!bM9ovufMFb$HZnue}x zD6;q!bqBwK$RqT|bbCW4Zh#-gUoEC4N(ib=A#YPGnCOahdH)oWaJpA@1A_GNvqF+e zD4ITffAW(hF)r6ue}e0WctJ8X?$XP%*{XrAYZ#jR`qCfxr#Cm)oG~eWV@>ZL)A-BC$ascGiM%o1uurGe z#Zybj`3lQ9he>xD@i`gIu(meGwaxMq(!tL*$+*t2zRTSYKHz>Q&(OTa|M-Vj*_^j2 z>JpHWgdYC5L;vJc?tXHgPxgAWtY7l$zkiK?`0XZn;YSz1&d7N7@mq|V2fY8sk2vhB zc==U+@!Qwgm@hJ8%7`Q+kw@V4=r#S28( zen{i+Q~u@ME@5GfrE9l%^ObojmijFs7#SHEFC<}$-uVvy@BjMW>6Ncic;k1xb#;!p zoQm-+-u#!X>RU#}OTbi6Aslz;p6+t*<8Au(HLUeJ6qX#K@r1ySkjqt+oc-KMp(mkF zI2kY=4e*2tVqs>QpZ3>t&jO;NqvtEku5Pf}AJHAacsx}geYWa6Wn}z}L>`elq&p6n zq&8}S431y^t{Zh9o*z%q3xrab!Cu^8(HhYR z#|#G@dR_%npGH_SGBRE!QsQxwar=~$Xr7|I$kv=q(U8B>eDG73zsktS_}NJz_3n2sxXVmLbYq|`_U#;$(k&*GDGIj8e&d+J@ z93ZT$Qe0nUwvfa4j^){&znx!3M#i@wfS{o01?=)1OUq^A#KEf{u&3s*?IOnP46`{6 z`>U%2Khp@RjaFJ^?S@Zav^nWCIsW)hbao9)b(&Nzq!DrG;tczYqY|a7>s;AfV{0Lg zN@o0Jyrf7bT7HquS8u~fle2E0=7V=|j&=5Q1xb<+(u5@R@kU+xo=stEk-5z)tS=PF zeP{L7j2|6AMmF-yY;7?gUofim7&Ys3Es0{Tgemde^3XCeGM;PF*e4ksa@us*9nZ6L zb(yur5+y^P>XCehdt}C6M#c+=0I2Bp0&{B-ufG*xH+&kN!^knP=1P>7Rw!yB`t!J1 zkWJM5B1_kE=(&B0hkM-L-{UwGi4`4P5~oF3laxrxQ(3;k#+56)vXaNX6i~{@cqtKe zRBMLiS9J9JA@=?rJI6=VYAL6pjH)PzNlcP}Pmc1^2Af-(TwSYBG?XmY?J)~0N-=)!;~lykz@&3(@|9wRT7?KFaD+4YUmUAKCT}Tr@*C(n~ z+@mJ_R*grGy2M6_{L&Jut5x!v^4#TcXJll255gv+)+z7*<&4mprLeid=3pHTWWsE)V zWMA+lU^E)Bx3|YX|MNf7YPCp`&y?LV=&^E{#``hr9JX`!krnx>(uDx&!8$&wWc1q{PL zlCp!vF9O-I&zAt-_ZbWZ9336udEV1*PR5Hwnv%u=zB|En9VUKEoCpY_jI8PymW63* zsA5(ZIwRxhk}&G`X}8)mnr&R)Cr*>6IxaO$BbUoDH#bMISi~@lr`Vc|mxC0NfM&DJ zMXkkPI3$Xq>F=K+Gcz;H&(BjV7Eu)CJ2>hSk~qX4k8oTMH;AXAXOfDnn%K61p~@)I zk7G#cy3XqAD#cj-R%$g z%l?RgC!-i;s%x)u=dBgqxN)6T1N6*cn33_6hyj?{R$ZKBv7t<2XVQo?h*~ zwY4?w+_}S*D_2-tT*S8Rr_+#(mxsgy@0hoTH9j~!V|)J;#~T9?0#DCL`PN%+ar^dd zu3fu^Wm(@L`sd*EFL?CtciFkO$Nkd|!w6D)lgjEH{^37uvb8+@1yoyI*98hcMOwVL zYY6UA+%>qn6?b>1xD(u6i@Qs4cZcF$+#UYB-+%9AWH2%^a+2(G_St)_x#pTvpkHKE zY&T3Wl@zY5JVX3L9~E-ZDTGjAOthvFT-f|v5`_8);L8%C?bOnG-YGRE38TcLbWI}; zVoXz{xe;jj!tVFkSoM*N;sz`eLQ(Qfn7!{)EB93+DX`K@TXw2cY3Ugl>e}0-1#%_l z8%q}wqEkZ#q8v}<5}1e5R=4j%PFF&OguUBiuVZ46IXF3KQpd~6Ux)zywB<0TEq)=Y z+UEK5{fIhQ?3fb5fl1QT<-d~0`4?Gou5A*upds6$Kd+@U`fzwc1b@TecP?vW$nda7o( z)i#(M0)_Z+i#@BX6r-hnF;VaI4Md5`w=MYb9{gSKT4^_pJvR5oa4Fh6*_^3@o&5j) zAo&phiIQD@4e5m}A>Q20HN}TJ70(Zk2}g=#n%n%9-H1?gVmc|U=6FBahA!*cDPH{J zf9o)`@*FiOZu3bauZskkl4JI>bWVs-3F=cd~vhM`|t1>w8Ak2i_ z3wBu9t~{NMV_4YbLo^L4ATtdm5n>-AdF0}?WRY?e>zH`+fz{ENsjs^dLA%R{p89SH z#4pe*)~-@!#dM(|fQS61^y^f}b~ceXM3z5a>fb%SIfeG>8s`9Sr)NNJp2VUS&s4c( zDUvZH_ABl(48~B5HnPZ(HMtcBh}kd3DeH1_0KCe^2JPsd|rM@y!^w8CK$&w0SmT}N%ynp z_w-(G5)U_hxfc$o6pwyInF9Su>*$N&w7(fU|1k!|=k6x%^?WP3|B-+?^dsYSozKT1 zH;$OlLEC;7uZ^o9Mz2hfCYd@Np&l$xgntpScyrE-%lUX5-F!cRA zi3XMR?Cy6iyCVS2w@%E}6nyTj6=Ur7i*0{;*s?}aPV(7T8A_wox2xuLMPRWHw^pte{z1_-a*NM;SWJ!B5+bM zUfzE;L&WTUPyDsXu~HKMh?gcaG2v6_q}R#$UyuN1j{tR&1-ZpUnWZ*2ikXi8Tvd#x zWT3Rn?LA=(8^TH%!^R?qg`#|SUMmf=5#%b#J`ATLsKf>gm5NTC^8bs$G+rb}C-b%J z?1ltr%r;9F><~-CsIhxaEk$J$5wCuBan`(Fl-X8(6(h^#kb)ZRyFEGJj;P(-^{c#W8LsLQ_Q)y3xzHC?7-n&(oUx%1 z4eb@>dOPcIlpDvUo}=T>S+Yhe2f6VWxP(P&o7swJzRbX(=SMHeorSyPQ@mW@TYq#I z5T-|}XKSxB7u}L=0xOC>S&jWU!Xia*h{WA;=`<@l*IB7z{vVH6c}xbA63r1aCVU8H zLinFsxV|JYCKWwRBTLWtkot&x5D1c6A)PewHm>`I>WgGa3`mU>k>szLBHSX<*Qk$L zBdn>MFhguoi@d!g3io!bZs|AMhn(=iPhZGeWNHi**)UVgoFFdbxSj(+DzOhJEBrPy zGB!?wtm6{04leS>XEPD(U-hF&1nu{>hsD8|3vYyM6)YM?$u0{8-fP8+;iGERb)7!R z)&#dnm|xPIJ358USWJmyEPRx!jIii0CK)TxO3a#-S+sKk<-@4=*t%n$`i{Ty@CZn0i4 zSR9fC51h`~xmYwxdPE2%d=>jOU7MMZnQd(5n?7hotdg7~SPGG}m-)Y_jjy8!-jaFf zUY9Z=kljCVa*n>Uq3d#c}!ro@+`)jg;90(HaI$-zNl9r1rXAh#SP zl#nI*x@>5$mm_zRf0tQ%@824Bi@t$jcOn3JZDEbrcv1wc7EKiwC2%Vy_5nWZMWM3I ztqf)hhXXF8UQ=n>$!aWa7JuiOgO=nZJCEU>@FactccD6zt(76VsdJK3eQrx*vJAD z`IZ$EM1rHV#BA2AnY(Iacz_@?${pmDJ1-3Ky!~PKez^R0#L1zhD2(+59i+Rq?r-#X z@%nb!79Iap%ugs|?9X>@5dw^746m@^yJ0AO!|c8Z`oXMGjg!uS3x_p-65ok+f3G-q zffdu?3f3OakjxsJTJNNWj_FomQGh5&jXdxeDRR z{6JwG5-Sfyb#w4$Am)osYrDsXSjwpPij7D2MCZm&{2x$Zh9(9(nqzKPC~HYUiSEL# zCZQ&j(bJcFgKy0Oml0ADUKFpe@_Uw#$LO+5O0IqCbP=z5N~+8lXUpADC6866JI!4F zefN3@hX7Wbfwkirq4*$}3rh(JT6_TwIh$??>hw2UflqozD*89#jd^nU*eNc%S2&HO zv?^6CRSc-*eq>{G@j`Z${GtrZKjaF2MW(n5Rp#$0I#LND{as7RL`HsMyO_{7jq*N^U)f7NE9dy=q|J=RTq@A zNb{B8sKqaB?jPEJ{t@hMniA2M^vx#$uu4Z|& zlPkFEkhi;5@%N=8lYWqDpwu0Y!&jm_kja9&;0kj%C(>%7_Mv=I832xCEiVBeQZUnB zU~+(9@syNiRPkuCx4GopF3%l&;Z}ru`?IR>h3+?dQ17d3FGuIo$Z?&klB(8UiSDi*#G#n^?9J+!+Pe( ziuqL2(=#|Z_h0d2xZuYY$voIxY1!al>K@BXBA0cAsLmZ9ZIt#mDLG=FGnc&?-!vpQ zA5xIXNTB@kQ8aDBmB%lOdIzPRFIJpaFt)3q;AM#*C6WPD$w!eIGZ{6IfM{SSDf|uUV?kmOny4Pv zuv;)NN)n5vs_&4afk+1t1|?q{+0ABbXD>Ti>xRxIke&m7W%0O3hz`k%(H~<*deZBO zhXY_vB$X_lJf+g7xCOP9DyR8-NPXOzpJXn@g}`#`g=02#G1RagJi&nAtB~&Zu5byM z#IHwHXwU|tlasYv)=Kr=ht$8R$!TaysPjN9KvLWWOmm1}@VbeuVGf?oJN*Z`^}cGH z_Tu*D6n9l(_(ng0DprJI_x6rsW<;BCQ~kh=P4ZZ+R2+b3I> zF86)s)F3R}CWU!?T=iBChzukHl2Po~yVDN#Q_AmwZ-uC6Cu$XcEC0ZnsJZ3~j|`0r z;gbdzB!QUgj+WC6){RVElSA;ZZk_ehR|o;#-;#<2I&dTx4)`})1r!_|q8+YjzT*q5 zIpv%-Akt5&GK+>t5t6NONBiUi8s zk^oXTxP(x%LuNTd9UOlk#UGqF_H2nFK0%<^0IkM|4yDA|JkcE<(vWN?rt_)i9i)Y(ouiZDz{F5+X+^HK6q5c85Bg&&Ynl0f3H(-PS2rM_S18hosT+UWHFsbXm;=YM1#B1{RW@ zmthGyIwd`K6Q!DM>5xKPSHXhoV#ywN{T;<(K*wg^T$3J$+G?8% zrR!Ia36l{H0wxlX93-D++B2tM`(X9sNeJM=Wj-c!^x)V%1LTqB*1JF2HY=E7e~y1n z2)=D#eSDO^ul7h`zzuU{J7+X;cvnFoW=82Y#T?0s2vDMg-Z2q7K5l&uc>6ztzxBgW zeRMyfp_)KoozD@{-BR?7Ku|{T4<~1VRAr^F;@l!ZpqB8v4B7v5q_Q4)8b z8;(GKy~mehB4bF>%u-Y8IVm>h`xRP%t)-ojGcw~u843J|IrT#t4e&A^*fb31F;+<* zSD`%x-Eej!6fzg7RLq~XBh3@auyL1TC1k3!-Nv&5V|78LYdF(GAVi%==4 z?+#QbLGh4^=7@T-ZvIHUR!L{=NMPcwyF2%mC7{LlD{`t7CV2%*qEzOu!fhZ0Hq12* z4a$eEthKJ^-j_oCRC(_|E4SBsNt!dW6NI7F1;e707-9JYXi+@srlBIj!{v<3J*ceJ z9WLK5>gTa6i;3`Kg>b__cX;1lxJtxTN5~@QoUx1jU*HPDA(lFW@EO#kK06>2kzW5$m;s=$GPJP*b@v z9U{H`1jZwjS3kysV9ZI8Z9%mpwaC7A>p8KVVQec>JsE!-e60c=n$!}t>R3@=0C0R{ zch4_VXqS!no9tg0wdGl4SiN_A$LtxZlZ*ND?`0IQH-mU)H{6l!Pm`s5%DL3X^JSbC zF~&Z=p;o_zC`t{-a%)~OPg>hncQDOswtc+wl`rI|% zxq94ubFi`!$SBOOLSB+qkybk`G{-ePIyVFoDL$Q`Vgki`84v1Yz`?}A8pcj;LZ|xy z*+B~2eEK^M_2P`*l+U*1+8Y_I7CM-*$Nsjn4%_tlps3XX#a00t8~YNji3B}zEW;{wkzMPI#KWn$m>_KXT;CHg(~*5|9HX|GwF5xgKl)N#ws!^ zC84H-zt!wH5T=1JM<;>wsZgQX(MHE*ZprlkY&}DYh->bnR)6{7;)cL|e?ehqd$F*sX@U_RgR5M}Vk`IW`frIw}0NiQ8?I?hAr8+aU63lH*K zwh~3pSn8YxM~C+e*pvXnnL?VfGMJ}AM&HLQb#Ec>G;}O<5&r>;nF2Yq{sop>!PJ-} zuo$slkJRm5^j-sHc0}C#<*pnhmpUwYYX6cLW{=!yfp8%X8GZLCojt@2ssgc6Uq_Ow zCb4noZd&0A`HNZ=b4MBK6956B#1K4gt?8M5L{|1(Nfrr^n0nb|O0-PJcX#NWJqd_% z6ESp54+&v)#(JhBB!hQ6-p;z1CHWRzrKLX3rs{ov*n)E((eZ$iT{d1b%aw)etMJ_J9A z^`iRtv?x?$E06p>E{QetQMY3!-z$aS`K*2%Vp1Yawr1)_nj7WHJY4zyZoN}=!;1{4 zZzxr3+}^J!bA7bd%PnPxF5NV86nlf@F`|9?K^KEGN9SmXZJcdRGG^-M4vwGvo8I2J zufu3D2Jblpw^-Hm-z{wYg=~Q=b;~DI9?c(A3f8Pye@4 zu78BZ_XI_!GW1)zKh43=N{ zahF${!^4e;HIAn(pAlP@Se06^TJO6Zu|eQj%NSwzU^;?*oYYaQC|sYYU&-xahGA~6 zfe$OjfP-{8jj|O=*b~S2+hCxJLk6$S)_eG)AlIR6+vr*q#E|ZCb3awb)P~BaEasT6 zGtcpwCbtoVdpydc3zr>swQ48MIl9kOtRvb;Q*i5d>_D$O&)K>D%)LobTV`iBPtfL; zY3(iX=WvhzpSsS#I;S8(-At;BA7z(04%^d)40g4irVxrLXKNR>BZD*uwG^saL>iN_ z2p+B=*b28SBl0DLT50Gz+4V~_LC4?EasMNOErA_7IpcSdkBF`J!ylXV47C3e$65ut zIe)sl|CyOq%BWG!o;LQC8a<+e3w`@M+t5fP)JWNW?y*KgBi1gNfM!`sh!yF5W&PAK0 zqYf=$;us+mA-LlfQ zuB~g-Zk^1&jHwAEiY^hX4+0S2dJ>ICr{xG7p6nrOudmxATjRDrbYyze18*d=TyUaO z@$2;p7wHvgkGK4gV^V?R0(-)_*AR3WjpdTa(L-aGGpZD)A{0Ot108q}ZMhBZc}aZ> z8>1vx*EzFWw%m7RZwRR_`&+-XdW8;^Zss2M@)5G=sYG8~! zM?ni7>$l?2@20Y4!p41EgNW;(-~r}3IywAx(~J;6@{()yDS?YyrVAl5op~M|dYip} z`vjt+QX>VNF`q#nZ7R)Sj?ohppXXJYTgRY&heTaL;k*7FRf?#3KY30ozJ9exm3E;z zb8W710h6P-M;F`Furp=#*w}^B%Q1(+)9~F5?bTvrXBclpyw&pa=oa>GgSOrav&^bU zIr-GQdg0TIp|Gh0H6UtaWcg|M6v}87MLum|at3C(>pyV}mDg@>0=D!^M#K-+npj|v zkum0)Y6e8jTF~q`$I;;kMWLLclG(6{_4n3Fz8amPXW{fz<=W9>BA_ST2sY0Bd4g7gFP$%8-POOQ9&|oNOyEtDFoJLKwH*l^9uONLLLw*&hk+-~$sA+9 zLVm-6&JvEBpP459O{QkP_QwRN(OK113Y5#Y(xv>3liJk@r6Z#14_Q)c{0u)du5fnB z2$8-&RI;S;>@NKSGnjYwG&xs15kNrJ!!fbX6i%++khxy2>C@|0Z!qviE4HLEFj#YT z)HT=W#DBp@mnA;i_F*ezp?aqLs4j+N$?Ijk2);<9zuc~_NsvOfE$cIm{O<)?9EyUc z{W6)oRgavpOh0$UGk0lXfR=V2eUpWTT;xNGzW_iJUH%p68@btd0B8lc8GZfC5~s1& z;7m$}7N|<2XlZcpvV_8GttQQld|SaO!jQ-|u4~=h*mB^F;TVXCSm}htW-v^nF=9>Q z*V=cl?jcQFp<3FoRMOonVd|c1EhrUl0xPF7s|t$>R1(5`fe{u1SdL`;vOKo<*K$VT zeGXGZ);rd(Q?2=o=IAvmvGXi75*ccSQ_FxczA&?&+NGV0T1wkjHrsuTVHZOMp-O%_ z`3*eJ+fLQk&Cw(=tKP3lTT3&avkCGRDdc3$=jm4|a;Q$&zth4&6v&=e@ir{~u%g5l z!#2#aP+fz6yE*b%W&wcEi(1CF*$i%OJnYigB@f;-mu)=q)l&*f`kTCoqdo@qcUL^O zCGr2kZa7e)CLhw+j*5A0A72ii8`5uG zP^g=vp33Ouq}Q3vb{J%wBhWc~t!q@xv9i)JwAh3|kUXwKrM6^?pmTYh_(H7lx%WBv zi5DT55daVOmnAIs?~V=Ob~;6~|A)Z2QO*rX{CnlU6Bz-w#i@8US^9Wz zs(M-lTG(Uk)7bG3Cese(}^-3O)bo#^)8CU6io9 zFvk3ilDgN_xBIP69D%=8wdX$f|Lv~&o2pIci@F>UH^B%;|(z zW70Usv2KmUK~O_xudECP!oIfz%|)@7FIx4Q@EF!hgU3Odsm*%US> z5^H=m?4K$RVH0jye%JRkRaDwv)+)J`bsg5E1L>%5#Qph;=L(vehBq(trbxU9a|o}V zu6V2|65TdM0@)Snj%O?nYa5U7z$KNssn0iH6H2Rm zc2%?RApu3F=%fKDf#voZe7h$=R~4>)S=+r-lr=xfKP@h&Ead8tv3~Y*wfmi*WfTY z5fgThy>8qSp;=5`3UrQ4SUTplv;O%p308Z3BMU}_BNKuHY60N*4jbU#SJ4d&sJ1NT zYT0k*#J$W3sRk_IwE7o>)R9dZ0^P12I1G(Ky22eD zh6>{Y+sJQoRrl^;{KKRCMMz;ti$~@nlR1r9v+Ff!aI*n1Udf&11(YmOgcuYwWozR9 zN@2{Job@=%FM`o`vP)JDXI@AxPWhjmw(_~Atztv>Rb-tfYQ1cDz+r=(}R&So#Yq&(|D(oWfnR; zxfyg^$k9$o;H*dVk=Ip+=c=H>RfpHeD(rI=c`zwF`7Sjj7JLT7-mA)C16hN3_!_mM zee;Mlt=BPn2l>|^Jo4Yd2|C6-@Xa|1C1@8;5vPL#eR*qTiS9Q{CwVG!Bf|y^TCFlE z-K4Pqv9rBF7Q+|4N3ZVIJ#Gj4ol z7mcE1O7#X&8R+Z)cKur2V3_WhlBKdm`kUue%(r6rojKDJM#nBx!IbcRFwjYAE<7oT zM2&`eRE+b~#_qiS5z^DThw-97a_wTCy%8(w?K0-VXI!m`TO}8HfFSr(Kf4lM^qB7P3IZbOKI5XHfoNb&QefA~J)-$&4FDfcVy1Y+s|LRsD(WW*uC1`%x$rWgs zD(*k&+>8~NRiy=cvtFe8E?Rlcd+(gDf>@Z`3&uBFnO#f;7XfTzwaX)whq^N z%lnfF(@8=&Qi&=)_Ps95yZbi6%C6K4jQ6&$r9f@9M5G*pcx+-q`A{DO0kRY?T)m#*wB9k%??<^IRCE81)tcVqz zdZPx8$Hb^mEwlW^aEq*IYI@a~(-t zCe2ex5~}CdCvX$~8Ka*oTe84LzM1Cc0_}z8`A>OpnG+skLTnK^WVm3V@2ePUQ=aR* zc&pFT#}$f-l!Ul0*)H5qVpCv>eU~_?R<5HzH~ppEYo{$8uw;%DZg0gS!&4@vNSv-R z4Q}IdOW8jqcFcLb*^xY0Ue5*_Hcio#wlRWP>cB$d#_4O$$q`d;%mCf(@5Hxv%b(ew z*QC3`?SuYvE*x|4Cjg+bGj4q}CViShDt#AxVgB%n#&2BOj(5JdbBenys^O_HUwkVdf5rVU7U{0#8g>|-}{)!ja}iN)97 z9rPn3jR_aYU9<`3#bwE8Z>Fxw5gdrd>bb#T)wmCy4Xyut+DlYQnLhC5FFq;}b+jXTF`aOK)f0 z9^ByGUM0=0h7bF$Sp2$|^p*okNwCN{-BT{c=xI|CXB*|1eTZX)wWTG;^}~)^=H7-q za`O?)=~<4P`VYRo+HP+7Koewl8JaBqaiCpjuBqKo(3JmknOjS($(8;6sbUPg(>Z*l z@%jDJMR{O~S5rQDs7a3}2H=_=Map<1)rEI4XZjmo%qu=?%lzYjMuB8=??E_Kz&83` z=WXNj8b{ZbXJNA)s+_f4D^KyX*7Y3WL(vdj?l>DaX%d-Zi%u#1UJL2+=0wnin*nz} zN-fJO^ZeWu-}JRbE=F`~ICIh=2+q(7*E6~HF->v}JWi(KJQOAKuc>{eV~Z%d1hUT<6y*{tFW1laiK*z5i++!5up5y6Zh-_wPj2_9>%y z|88M55)h@0_e{V$J~ z5UH5#>F2lGj=$clKP{v|Zn2$=itnd?R}72`?+N90nSQ_nq1P>E^tTSP57LV3e>(b! zw9MysW*#v~8%y+}9p%QP2{0ICqAU*KSH=9`(Dp<~8MCkOZ6{8w3oBP2&CDwmjU{n8 z+58L)l9VK@fMAI)cqAWp{F{0Wx!wmSwh5thf9H7#`JNKiTP~fB61N;)cW90hAs*_V zLJR%_&!xPT=bO9P*4}^r+Ri&P9x<7fq$##ZSih3J62!H-e|~xNFRtZc*wcOe-l+3K z`X12!B8P!PBX!K`{RaD;gvjA_)3^I=-{ARfTtHzMe{r|xCoOzENkVtWxZ8MsmcLXw zdHMuh3ao#6s!S0W=BYs-@q;@q6v483NWMd~BBvH z0Fg#K8Eu8qha;%T@+zqL!Y>ZNpi%+H;m0ip7PRY62AQ6uSPdlSoN<%oIJQ1@_J71# z6R*UIPO;YhfX7OG<{P+&F`E+MbWZaOb1Dor*2ARw0t);O;*H62!lJjI{tsoZ7m7lI zw8b^3qK)IcF<9GfzP7QYIWiN1Wv;akzFLL+;2gxDd=~kY_1kC!{x_!?T0knkW=U+i z^9YX20xd^#HGn@86JDM8b~NePW2BEB6%!jtFG@FG{HQ%*4gqcI>w$X2-^^BJ;C25a zstl_ItWz?IwT20Lh13xwdJO64!=N;q>ZM7hNhxQ?$BD`QaiBm~;kPF&jqg@0>}(#k z5#ycZ>o#?5{AgHphxO1bdQ>fEA=2UA^cNYP~%f~yG_)@A`qU`2C zkEIqLfICNn=q~TSz0-~W5H!`LF1;!~l?9C?CnWke^a@8MvKkfk*xIuNYG*Sqo8JN9P$c#oraWgX+4Q)0*pj8(69gKoUXP-78Bl5?aQQ~7 z=z!~M{@i37R7&{K7T>=KPP1n#%yslcw+fVWjNcY%cQwVc9@MIRYa~&H!Y?~yhg3@X z$uJ=9bXHkO&24TFmx1rJKBO@9MZXFR%UL2WcV7f@ND_;t>-LmpA-K(aeXYwq7DsF< zqyc!cvG#_wkDYn{((@gx#!Q#A1bNsyoEPHwR^l{@gv_lmdUx0o6SfmFs>(J@ttpDY< z4QlIVr^Q)6(SIshRW|s((|VI^?M!gup2*QA^TZg%)<4@q>%wa_j5O8Mu6OrcjB`!M z9wv-I!1nRPP+)KL=v6S)5na1o2;HT9y}J8Md^`owe7Q=6y_4_w&RyB~PHL{hV@>99 zhWwBFbQommSg9XWp!Wce9dxGDGVbh^)48tqfb}>D*%S^5$C&S*%a2+$`!s$>@EY)7 zB~^@hM&O0xHFVk(`$(*@$@9GfWuo_OHrTizHE_Ty-zJEtoE(}n%m{}V$#7BVp zMgKYxHk?Jmw;yG&b>wl#D)pf&Iuvz4Cgob2g-xJge>D{&_s~*-ll-5-2BNPxI_Suw z0}XUY6BB{8gf=KVK8WnS9~y<2Z@=Li|B${AuzTk{$s|c6 zNW?hol+(`1xnjueT&-BMqO4ui_lVYw7odbJof7Mt-g6rnq`zY1{D^(Y5C!u7I{9el zP^?v4a^3$>ZT8X09{L!l-^2qQx^;}p)U-`ZlF<*#8hQ`2o)D_{3KH#hU}~T zrF?kRR|Ua>1{KFfrpuNF#SQLJ?lraz`b{)CtKVLZM&t>+PfP!{I?Ap&YO-%04Y`GB z@3_;Prpq2Gm_jgxVyV5PkvRAi7PEX%#b%Kn-FBKmRl*1k9Y&SygWwBd`xuSoCH$lR zJ>9NbdR1i5M!6E0A{fNT5f>*J?WN~qK15&6EO)C~!IDrAPYtQi>dlpXqy+;Z=xbp4 zZ|cZspeZMqb6nh1aLa(%om~BfC%X%u_f)QNHn_;YZ*LuTDRR9C7C8}fbPfz5OfO;c zwjfDY{C7!EdQ1Tv6k#J8i@{$Eyv8mXddIUwsNnu^3L(fWv%YLFQ2M>7Hk3#lG>>s{ zB%S0=6r4{A|Lb?UW-)dZL;8wU1CmjKz4mLOiAiC=iK^w&4d#S~r%r;BYLHJ;Xfj+d zu+aM7;}oF>1rTeya~1!_y_78~?`3|Mh^aH$(85p%0lHZHYE4)(W&|%A61<`{#3|X^+P4Z0q@RAt zk18t8gP9SoQw0nYQ2ozUD}sZ4;@izL(n=z#ub}A~O!ax=Mb6MGu_wBM|E!tc9&#*i zGVS@j*+YVt{j(j6DLXDuT`Y8(7sj~dtcy1LZ`x0wTlq_JUkp zb<02R$+i_k8e@!I$f8eOsP4AzNOPxMJ0EEu-JxY5`%j+^N~^Z!WgZ z91aS>ie=R0p@zqh7O)av_)qa;h4e`%N^)W4V>a$t&xE3+HImx8baNTl$v}tIQumi6 zrq6eo*kQyWrJEm;rFmtPDf4E&pV;2Z)%7}o8tunm&+9puPS{?bAtS8X#x-2GoQ$vC z1*F#K${E`oY@yvl(iS$VD*GgQmSabWl<*%uvAphD67bT6;kFd}|B0)`N1z!^*&xJ2 zRDo%eX!A_PuUYMrgQ*|zkjz{4gN@SmiM|=zfe~idv3}fvDEUK`;z<{&Phk-N1SY1e z>El!#jHdedQjk<1PwTxTJ}($ZL+urtl|!!amSG?T-M2FQsK-|f)uhwe((?=bCHw>f zrQ@}XCG8nkjVa%P`=%KCR0FoHc>2b=!X2WJ6l#Y>!$~woX}>@8GC_iVGPpTI9UVb| z+_gk%P_9xBJ1(89>_1|(X1u~A(iEdbt9NJr(yNdqbi5<~4QUF+)8hz3pvyToY#5R6 zQAMD^DDq#VM3?*`i{pe$w&qhbsT_uSjshyhNV|NSdf)HB;_5Q>NZC*_yPoN?A^@lL zekA1_;))ApLYf7)84u6F+0~a8!H#~M@87cM5nG?*>h^pa^B@L{y>;xBoIB?eoo!-5 z8T4B86v{RTuwlxhc{WL)uCK|a!7aLT=k1lYI5ejS&9FD$yGsXvvysoW!?mvg{XtBv z&JKU-1jQ;bonj?CY=eGwNiyJ?HNa1lpzHfX-bj#^sV2~=M#kOI zKU*k@66ZZ)hf=|);v$`N#(JQh?sVEgnGHY3PKm;o5``Bvi0O74@R|edjUXf)`VsA1;M?YI_S_KTRg5q zM33J!fx!3?O0#?sQKeCLX;pmMlBD|Po!vpUuZX{bBeZI17Uhy~95m1@Mc&SQcm%!r zPG(Grfk3H%Wx*nUGiTj;B}8%A{|%l=2dZ9Z>IXFqb_m2NT&eIMdq9Ov%@lWbrdZ#f z`rD)%9*R?Oq*~Qq$*LA6OBUk&w@l)e?ejzOY|M4 zLl3`zOD0esW7jMcr)oG%xXqFA;WRk->9(nqHC=`*Z9DEecl#rqpX+AcIPvE>dC2h@ z#>H00w0#1>!kTwyM@w&qMg^wLx%c1ynDC!oE&@iMF^E5Ij0Jjp!+6cvrq1F#KD*qX z*K^OE?++=PvV@l|-bL`eJdPfpZZtms43qdze4ZVFYRkB=taMsDE{_Bcg1%SR8UA{v zEf9<(@Y@m}B2@7ZdiRMA5rgq~5*AC69#Q|Ik~k9%N%u)X;pp&_>@&zja?6Sa zV(~yS&>omtcjr~0B3S{o7$_n!D64p8K7pQ)f8*Y?U zH469P69h;DgDVZwzCs9hzi$w6y%5DRP+)L9} z#$hb|s5Z&^uMPa%Aa~FXc)l!H3qtNxKUST*T#ddj5EsI1^=Lo~>NjqOL^R@ml&xni zI99c-XO2}zPH9)M>kt7E;eW~A_n>3ra&J87;V>YsT=6y4b=?i4LlTLR^6C-HiK8a0 z={NwOE<_0yQa@Y`Xn=SXl?GeEHmvLn#n>(ppd@$xl7#>lABvEFtm(3p|98YhoKUkX z&Hp|9zgPTV>I0b|_vsDl?(R3C1V%sB^ofJ(*EW&WWj4sWHn||f8Z}}3@@2Q+r!=OR zScH#~*udBWoe68|kOpjWUmEjQb|O8ESp$$`;{QId6XE|3&=-ss;xgUj-+S{JNY^Q- zn>X~Xks_|YIY^(NAWZTa5JshD=fkJBQULB5#)0J&l8Imk$n;Zs!p zt_ELNMBscClafZoOLL0O7xSniU8+bM#9nTZ!Ib@hNX>|dhV~8du**0WvZBQqFEk-f zbjHYYXLzn%#7?ewW6apRcdM9e7pvDu=JFgT3}79e7yUOMHrB;Qe)rzeo~5#^~-7t=CoGcvuoq)g(i9?H z(Ztm=eH7I;3F{tV_g$Gjt(Hp6^=uTkMB)&inc?eMmhU7GM@l__#`0>bXUyb1`pcgG zPH*CuxFhTs_m2$sn#R^mKf`&#nqX}!umZ+fY0sgHTOa6;)H^>=t}x?=@FZjyG7SH_ z#LSQy>dXY;V0mPYjAfGA-{b*isR;3S<);3_CSMK>l+)jGKUEzT!XZpZ&g1JRkG{U| z5j}Mq#lb~d7H#MUhm@JfVQ!;7rZqQmiJ`>3P7}4>6DQB%4IfztW0F-iO6z}*x~%2K znqwIu9Y=p5sM{?W6$VC!x{-Aks8x<76ZRoA$OD-D9NK}2dtzaV%_LyrN+}9 z3>X&Mi3~Z#fVn;uxVn^8W{CEQkf$4_Ph-Kq=jKlbYp9L6vSsRy|L-i&|37D8sn&^t zT~q`}(|)|yPE5x%G+m`)Q`ykbBq8%J4;mmBZ=AYnF|vOa;GLU0V^9evc7v=yPM#@V zIfj2~880#g$^B|vmFn1ZQSfs4w#OCx`p+eg`1sP9@#L7@{iZIaqik%{9Bqi^(p-L+ zaa=fZq|GWUwWZh8tEkKx>>n$M6-5lwB1J5)s@rD2zohNC3_TT1TNN8!G_Q2(|Mc{c zP##mNHNoT_HyHQPfEP~Nenzi1RC17wbWXo!2coD18*MM(FKh&df|OM6k-OmO$}+^e zRCZkU6Yk9K;$9bsqM9-y;!QRFH-U@q%{JXx@wSZ)6hu-eT!_R7$*~0>5!~tXQxmpX zotT_-{CpB~3hM9Z>Z8#XyIPISd`~u@ymGf|jHEhPjcB8`R`y)2vz0RrM4HWV&c8o< zKK*oGsv>qvd--l}y-#^Wy{H$-Yt1f;3=K-e_2)BMyJXAhD4KLVlTI#p3#{;#{#ve| zuRNVtV;K$<*UQ;^6@WNVaV}ff8yqafV9#yx=HXJehrElB&rHMxMe9}OmC+^-s=TrN z;!H)A2r^pDS5c~chbqp?8cW;)g32Uhp!qX- z|F=NP(ERT@SF;1)Q(6m&yBsH6D9Vy_r-m^o=P9(iB5euED&Q|{`sm%l7ibB7;Hk9K zxe!!bwHplR0Odd%@VB>YQxL1iuUO4G9e>}hC}Xw}%1`pRDQ?;WWo45pH7AB;hZqqR z3TCJinbw#-3V<}A$Oyxe;{;iB`s;6u)g4C3p#9|xh_WF<32gf>unBm-vd8C;H{m}# zHBM3%I7u0wE%SIQi)3um;rs%T_5`v;W?PIVqn|7G7AG`P;&Zh7wwd)rPKU9$3OGn+ z@J;p6Ick3Y-@s~;QE334OMiLMfC+)+1jpskFUXeeBL7JVH4?ILLqvVP$>hjmR(G54 z$m<R-WKy1OjCIOR$1H9u!FDg4tu? zg21>DGX}eIr4!h6Z<@Wo)kasp_C3P&g=_wZM<&pLq9Ew`7=c5jfz;6@XT`~##f2By z+2w@eyU%?(MkK&sI2>obtzi|Hn`HcutQaE62?#lml&pd_q#)3+>o-+8l5$R#snY+C zrmFyoYiYVKAwbXscY?cTaRR~J-QC?GKp?owVvD=GI|O&P5LgKA?*8Ar_x)8{R4vP1 z?o9Wc>FGXw4wFQ_a`MucDF`792~Klq64>}!(rf=PUuqR7N>t;1<^r%ze1=R|mUhR} zB|F8to!`ZD-b*M85)QoUl*eS$7=yo>Ad^`Zltf8TBD%lAKot)0&=?qU*H~t#T>{oz z@BHMivH7f{+v(HZ6GJgm3swo~ZxgGeH)Vvu2Hj5l#_Pj(n6x~IH=oRZhG8mY&6iIW zFYcb%NZP0laW30bsXEADZ65N=#gPG|HIiY#R_d4>Ulf9Dl$L0taO)LW#G09vw}ZRa zW4=VhhASUNZyT8;D-M)dKM}H*yR4J6t-!a*-Yjm@7(A#CeiDNr{ZN>aD!Vz2U4yS8v-x_`p0wX-OmwAmiEa%ueHRBaN~9%L~gDd=>uiNSR*~!+GrJ za?b%p?AK})AA-S3`D9so`NF3NBqg*^aRKIVc+NE z(|f=-_9u=1moDKjeC3pnv`of0ulv2Pmdg$0I*QqsG9KepR5S?@M| z$y@IA{L6~G?1}DUsP-a9bEjg@pR%07f6!`D$3BU3g&j@UI6n>UMx+{!< zrxEMB+GCR6;rIay&MeAL;rhKybVvC^8t@q68@x!}LOuVfOHA#mfQOKU>tlHW`r)bf&+85jukp7$ zeA;hhNKqWAG0ft*BSZ%25^1+o#-swAJOv%sH!@bY6%|NmtOFri;i!pPXxhF%RBiQ< z5TH}l&TzrFpY>asDYrEEX^Z4P;L#8jpVT#VbpM_ob)!R?q4=qP#pQK|m-TXJ-^?3x z-kDRpw-_I*f>hVufAR=tX%|&d`ol-_n`Oapf9L3n@&qdXdc?AO%dN#%_d+F$NIVz$ zW_w8wr?_-m#Yd|cQ^NQM{+AJRN~|#3koMfCX}Z;Zs}ZY~zH1>hw5_AqKcmc^9z~N+ zI#f!?_!a0VSSI_qabD<5kf?9zS*ZIhaB}n65Y8zX7}qyS6ruCzL4`rs)XkTl%`DL> z)QZ&X6==9r)_$k*zny_h5q;h#zSx?^K#gfjkHTi42wC72*bUYyu-V(Y02{cC&C0)0 zXYobvNfA8N*9OPc731Q>V1&E@^i9QQfaL}H6EtTpG1xJtG(*vs(Z=u`r~$4{q^-*< z^7h1aWLcC{2>?VoHQ%VB1Hc$PS-jgxZr+UQsgXGlL7PgCrQNg>xmg)GDz$Fmmk((3 z#jaMEbf^ujQA_}aS>9J-8ss89_>qsU%N$5#6lj=DL}8hxMF`zt-pt2$EUt zr39ymq%z#^mwch?J8LhTPncl)BkDWX%wtj|WMtkL+g%z+vhnKG2JS6dL zDL@nXg%~wL=dtRQ)7LStw{1LvuB7n1Z8S>M6@8M;Ne4@qQC|~kaRJ^UY5dQA@7&xsN zlDETu%31n;9W5IEN^X)nOCwSmvGh&p&5>g}TKw!FA#tWd6Z|*RjD};|)uoC}jo$v`)))vvS z6NLp;%m(3IvBZ%H_$SaCNhKyNUJHOWGN*&__#-A3!1k;Z>kk?FfH0GwakeAg2s~hy z*xxQsCR3UM-_?d271IO<35Me}h5pvo(I5SM6azdpenqpoBc4%Wtv`tfoqy}kToU3R z67f{9iAs0m!_WX>v|Cs`w(KQ)?I{ATA|X2Amjy^je%!L7+QnMrvMZ@wKd))?Ye zfC~#c`zB&e$ez=ZJzV7yE(uP9yK_h3y9z)9#iUMAhHH|j)8WUFq&~E?4jo7j#OEn}+*<&MgVb&>I80dFa=GPe|6AD#P(jW@5XfiU=p#v-63_P~& z!aX>i@(B+?VQQRg+bX03ii*`g$jkpn(O%HL)qtH~ikG*jEB1Wcweo1rVvzx}c6fXA zs|e|NPd`x`14c$)i4s%U){6|%XVQ0;so;E^QJ8S=n%jK>W{KKxlVn=ZqD5tsB`#C< zU1X8Gd`heHPW+p^I%l}qP>_B>Ylm!IcD%2(GFKNoX`C2cYHHpV7pU|ttuD*aWQsUt zq)?(5c}%HLwH8~J9G(|i&xmp*XR$UuH*72>3nB7nalPc}O;|+$oWgEG+L2BmjUOM# z1W3KT4(pygKV;qY3q1MzK5Y~6d$IK+bvesjb1H*OiX=-q2DFM~_%o^rGaa3N8=uIf zpgthWwaL82D$ppZStv}Jt@gE1E}aq8T&YsJoCT4h0q95IB(I|+(73F!gC389(V>;& z?V2`_w~ToruzmL@lH4$sQ*4D-(Sd_trL|LRdZ8}<7Co%@ANzeaH(kE#SM$@()Ge;M zfXUa{M>fsEvNEDpL&+(lVEpmOBl?b! zcGH=YO@bqO*0i8)KEe2hfwEvS%BUC>N1hnr_-(?3d0J27xEF z%rREO0wKl;tKc`a9#I)ZWnmC=slDPwaSogu|-L42CVp5C(F@@$8+ZGxo&6D3*8%Kp0%nH1<(MZE3*b?rMS8BPsaaSffcA z9bA}aNvVW|HX$}f^|`Pla{07wgLBUc%L?ryW1$SS^u}1Pv$o4J3i5Rw+aY>sEKN9M zTxw>e*Y(S9Mi^Be{@ucSi()mRs)9I1>cCCmqX4`(6(#=U?9Fnr?u&zZHJv=z0J_%ZMk3EC3^^9M;`HEXU_IC{pI#xJ|KO#(g2s*MW^Esmb?ou>xA zc5!-duuQSh$D@C}ZZ)kCo5!nh7;%F~ByHK#3?kRaRCZzRgQE!4p-TQh{xti@gYZqP;~ZDGWM(bWu-hZnDET zo@n-ThspDdLjq7Gt_(VxNYaxBHt$4Q`AnT0($Y>(*m8ne98=t%cvA2A{JRdO{T}@J zq$T1LXc&tzVaBVAm+(hs&B9B;r4pfe5UycKN{mqsM+TG>d!+~O1wwNk?sXU9S_aot zDDm;PD12B7=iK}BB?`*kK}Ul613FV|jA4ARPLBE;M_e|2wR|OvQIG`$ZJ%rdBrEAu ztb(-M;7AB_tnJpApn@UGZpkHE?;+x}VPJ{4?~MAJeX#r3O=DjJ*K05mp0!Dh<6OE@rY#E2uE*%Hs4OG`QxAGgkJ6H6g5l?dKYX_%$f zufmJDU2RotOvkSf6N;cnD;|yD;1VBE3H2luQ8}hzmD1qceTx}qx@W9+f*(8C|C$dC zK~t^9CZ=-DtZu$1Lyao~>uFIhPrc5etKN)<092mBVOJ+vq`%vJ^5(L`I9GpbYqEV{ zgmwmRvqRu41W=!w5DdPKcn#xpZ*5=wo-}yx=<>*inrS5IiPIRL$j61wwdTH+fwW=psab;;&5a9s4+*dr)J;Vx@k|H? zE2htNy*YOrFj;uQJnKB<+Tut2*&-ycG2~EB>e{@r1db+#J4Vaxx+e6ypauKo|VxAv|F^|v$1_*a$fBp5dQhAVux1H6Ro zCS`ckUlSJH)S6o#u%Ol#>2$J^6e&8K3NjeNFGjn1f*;?lo09qqtWzo}sd9TJe%z&1 zOjYPtp2;`RgbaZJiNR%bB~>yUynHmt5^%9AezgDP7#MFE(XzZKhvZp5*6aWs#tbETxF1Efix?U~2mZud4(~)g;A2 zR?j4`39S`wygKX!&gbvG6dCNav}JYCaiT&wheL8i@`{<#!{z|7zT}V-t1(9g3qPKt z6Nn@ne@bd7+`Ji$gjPZfr3z}!cw60o3Qc_;G~D#$GW7h`x7y)_j2_>2Qs-=%rq>Hl z{Z4+pF77QTJj5*wFIC%G0xu1dK8jNx$)ks7hU7}H0AgxE#ZpA-Hxj#_{r72syd#1u z)#ngT1#xTpI;tke1w=&m_;EE9@$YD+ew3p4HH7>ozPFHG$G68wSDaopSE;`)W?{!w z6%`6;MKi&s2#)3G)U=e8wM@RQ9LjGogW72%;sa|Frd*I_UE@r*TRA)(y+A&n56Yc!{}SFVMLlA*QS?zk+F_jmQWXPd~%0k1r z78NxcR&$x2u(>2Ip$t$jn;cu6mKaB@rbmr5MB1tB_8TAxWVL$7@C(;-8nVA=z zj+KR(WE%B z;j%#(Q+Bg0usl=Qvc9GYNyj-v`BP|ALn0y3F)0R4TblLS{5Vyse;%x??0;*`mq6T2y_st{(7%r1hc>4pb; zYUl0BjfmQI9(Ypfjig{AC5`e08#$wNX2IUq1%~t&b|!b}MnwRY{7kR!E}B{>Vkp5h zy4NT=?#g1S$-o3GuX;)w4-D-TbQb_4CMws%mEYI>KRU16$%U^Oo-SjnCvT=37^TLl zB2mH_$n}^~WX&nQVRS%?N-VwO(X_!7q}KSYx!I1502(cR zL33YZUX2q~RK+rb7;s?30=^6ki2ep(e)TXJ9DFtQN-4r@Cf-hCC)40QjeuhEm$~2aLno++i^N;58!`Ge|fMmYe{m`ADF@J1^r`_iC z;E_xM(wf3mQ*p%3D16qJcp+$)_vo5x4quYL)dlB~?O{wJ#{+COg-@PNQc zW-t;5Z?yTRnmO_=+UVP>M0W2kLG{gHukRFCqK?J$X?NqoaHFB;78AM3Ap`1jzmjN0 zTMhVmHau`0@R#eEb^G1eK-^m|;?!dyMtl3bYTz|M%0PWT2Rz;o#RcxRFj$Z+`U8g(2iE4YN8Tj5a(F zS!rPZlS8)6%(-oTI&};sjd88Vz}+6C+fs;vQ?teFM*^6-30Gbof;xySj-c&BbQtkQ zSMw_uDPpqB=aiYsJZZd({Vz9mr=RgB@R+{Z+Sk@}4BUtj+}7Y77F`w37FPNLaGl?p zH_Tom_Eq8OP5?9n&yg+Dfsa=42rf!4xqBw9}$ar!X;SHP`Rp#}*V5hucXbcV^fAi?`xpsLy-$B;l z`-|db6Ku41NCQQ9SJGBy14mbo{&nFKsOQh#4)RhY%EJc^buaA7^A;Sz6w$s*jNlLa z+pEX&o?HmH1j&wzrr&hoM^!{`d9p{0XYN@Cv%dFL^hW0WGBMUQ=bsF#v9Pt9vVH`0 zHO{yBm!~$nW|@@*bA~MuL~C3Tm_UlXzbA;tF(T}eN5=%GPq-qM4epf5&S*(+f9ZSO zBb^>*ZEG{``JS9g>&q{!lNbw6F`d4|XOaY|k04|uV!>Zq|8w%?WQD-7-Nu>pR$vwOkz-%WPwrxoh%QXi(-WTvy>iUFSb zs5&k|9EXWAubs17G1Yd3%v^zs5m`8fjaD<$t$TV_CjfL0`u^;G{Ls?WHke~SwNEoQ zg5IXqYXz#-PHV1^ZLIWd%NmPKy<1JH!z_GQtnIC(!kYfDmsFY7sk|nXYd{(A%j_ z+^0ltRUWeU!UJ((R_>M@R`rJ?@pUhM53@*=K(rS`Hyi80^XG1z5p@&J@Q`tJ#b%0) ze56F)-8^6+AY|w<%js}69jSA2;=y-yNL>gkjtax94(%}n0Zn-1g&5u{rlJgxtcmI( zK}}Lo!|0gKxAQSH1rMs6LoB|F(D16fsB)CuBJ4=RQ9CDjN=DyR|FgB8aQ{-|{c!pk z<@*V8RE9HjjqQ}52l3JCXq?chx>4DL2ee=88%x|D>gCv?<)Yu4G0Kgg5~YZvkW0}B z`|l(429Tq|Q>s<<{+__@q>rCd+jn~?UpR5_bp)tQ-0|8~^VDX~_&Il~{AfrrVp3$q zkqZ&~&uJ^>Q5Qydb@X2`R_{mCxnS$|m8~x$^S(@IODg6AjedoKqJ=!=cJn2uFlG_7 zmn_sTMp8wkBnTy7NG=1dO|q2lj-04IGb-(l@{Zt;lAVGlzpOB+iYbMv;5@0cFjWyo zkBXTnha0aWX}OKN-Cu6mgc<`kzP2c})&$9(;#-P6K=bk22kF+CB$vK`TeI z`ul&@+Ix*^2T#_C^Q=+j3O2m$#`Fb28MW!iDHCwW!bpqr`}LfA&n9UN1X#Wqs@aQ{ zAYJ^CMU#=NCOQgwDnbVIw@dxDZko<+DJEzU!~P_UL!DERB_qls)1;#$29-;D$NW)R z0f1P>XUJc}J5w&y^+YHps%VOUxXnOZX72kr>|Qoi4VIqxg-UU)jQG~c`wj4SZSZ_| zci11=;1-{;t?DUeZKR;tVj|d)De}RDfvo+*|7^b$tsr3$-lBI@s6HGMYAVKJCNf_$ z#$r;;4_xug&2k%JvVFrPDI@U6U@9!_{KwFYzs zt*a0CO~cCb$p~bvUJ##8(&LvP7W_M_ib54$9HH%FWIg+S@p)*}@q`U^(QDc{+D$B5 zi1XG{``5otc#&h|@aiczX8#`x0PX091`rX#szrf8i2yiVn|?Tea&$j%$)t|~L>m)* z#+N2_UZSg$1FcgWLD!6n+e$Fu*tpvB1G3vR43ZJl$+S}7Xx+;acQp;@-gLdok-hf@ z02A~-nJYF&P$m8t;~cI;y@-ET`4DvEDi=4%KusE+G5w%v89?xf~*;tk}~;4E4}%PW!=UJw>N|dikO49<9;J zR@bw!==O7BhfcRku=o4iSw3C1272F{ylN6UBEIpToc9;5*(0>Ilo9bTa&XF2HQ`Ig zo9@eZ(P2!<9@p4qhh;XPQwMAAt-TW;;?CA^MXdS+|57DZS(FBe6nXQp0b~DR1SC=O zHBhw;e8;qDn|7XcnO|fsrpkW8`Jd44X@uVCbW_cXySVI`C3Eqz={*PDkzBn*P(RIO`EoyWMsu<@zIwd-P>=3ASU;LwI zPQa-{#@b<7jhK&)nQexQOKrRJcCi!+HB7{Pv4>EElbk$om$Cw$l>r{j^U3t|$N zAYI7{=@UgNXc({(E-+Iw&%^(xG@UI%lfk)1L|BRFHwwxm|EqIjsR~8^z_q%@^fySE zE}!_IrD(bByTE+st@|~#H zjrABmvm_nXT~#oJDYO>iS)h=LLO5FpBz*jo3b)SvhaJZF%4uY>60i9yT7&Zb8G^89 zEj(Z+H}V_0FdLrkz4>rbnJ0!~Brdx6MN1Y&I~*eS7F$qEbL5wtSRq>~dr@eIGtNgtMQA^FB*+$K$WQb9WEAQN_}(8J3E06Bc}&WLE=DG15ayQpB>5 ztY~gzFBdCYCR+;$Rmsc%Dvnx`eI_yIv?$JR^;K9;3{|mMu%evPE*OtXZBE%OuI&ws z3;up40tW4mXpd?YW6Xguo`4u(@0&ti)`o@G3Xh6%DQjY{jC2bR~P} z5}rR2aP}GlcAHhq0#Zx9ByDqE^6=R}Eal>b6Z8V|5=Zh1r-U_+X}$(aT|Z5B*_M|X z4*yD#y85L@1y{h!Q133ECQWaI? zPsCx^h7Oim%s6;LzH_aKpwO5&I9E1p6$P{Oo&d#3mWo;1Lin03)z_xOu4 zpYk|O6gB_UTP%2gW5m%Ok<5$Tw;3iYKV!C^)>gKVe1k1r>LJL2^gdWxs7^XpdoBaw z#BJV!oKnbP2Q5%kj?48k@a{3;AuYC_X`)EC$alX^032q|TF(HhGO2s;K>|W#ik-;l%kck2o%94X4 zK6a}Oi6va?h4;uQg{XLg3*RA<{uHAMwC5tTH@@dnn`UZi*gl5^e}5COjT(72rv}ju z7dQU6flM=kt+IJg@U@8K8x#Qk-N&96c1>|tEf*$0{&N8_BLg8qr~k|w{}}6cXAol) zjX&$GsZg;8q{5ZMi>c0FLWl`cKzex}86PJ`Q3BGUb6pl~VwWMveB2j9Fzs<7{>WgY zgv>D6?`m?j71-}GV4(QpI2S05aBW=m`6Y>uebzZEAg3Qv4EA;Vo8p2!QB|?xqi$02aU2-p zSDl~2o|;Q&QiXj?i2#i}zHJYDg+g|zqUb}u5~K}H&wS0(8okq+ml1VBrLp(Du-#6Q zu?HsM@^xkk5w7UapL52g3`X2|&ZT`I!k7Wy{Oqol((DoE8ITcwngdS?n?8f48Pe8L z;H)K#ay*L*mhN~cj@E%i9t=Q&5BHKKCGf4V)sUDkILVUNILHe&$$%eVuf zoU3plNETUHIGGIWFkxX6yU*lSvB4+DIg-vcDFKEoxr}%;8lb(~8i-u7>G9afrDqC; z(_%O0@EGcS6qXysKCY1ESUhyeWmUvwlc!`c8G5_16zjO!SI@{NULa-Grzx7>be2X? zew}*dBb(rb=uhG;4;br?c(h~$!hj?xO`ut~cPrCM1j}qu<7SxAZ8&hUDtuyDrlZ%; zGQ|{|{8MJJS^K35s>&qBcGcR>MDQy*z`TSeL_8A2<#1@zu9dfnUUsl61r~I4 zSSEm6^Opq$=4Le{y)HzI@a0Jv)#ko!`%zFe>wI`;CRY8oC!ojh+emk|sI5{ z!ee6@0KUv1a`t$|;J-WbS$%#M_x3*Y3*+y_8))t)(DB`-!)bc3;V@3xgy(C&w|?1Q zi>BfDJ|bsUv(sWx7_@7pL5MykdqZt|bZxtE1gCos>mG*LnJ?pf!37T;sGnf-uPn;0 z$0=_NVYs#Ho=O5_#G+DE_)8-rlvc-m{D@!1=|B9cQ%Rd<=YUkla$LU|ltH-3F`XO;?mr&7C?sm!=|5vPu43j2@hpMyGR?*z1YJC1^M&lbMr+wSxhXwz! za^t%%zdIwWznHqOROR6pN5^!vj#DD1uVPh>eU|D7h91qF-tONsWtNbS+G?dGdr&40 z%j3`CqiU6q;OVw5quZyH*^E2ar^;6>=grqT%5InMCR!O4?>^!ETTc6|r23_?07CNg zRW(8JD-RJXH=oJY)o|OgPR05C4yyl|ZYlZ<*PlC!J{P?oM-KNFh)LJ=$I7tl`>Ok) zEL`g^hJtkWTzY90nZfsbt?z)y=shz^+{DN4CKIXF`JN+Wa(Hl*LsO+c=pI_$Gb>>W zf^uYbFl(g@*^4P0l@KSzJI5sCjKdkkIZW$YgDDE@ko-xW{)F*`oNX$pDwwHwN(qXp zo~}2$rXIwnhQIH*REyijQlwLqq{=imoMW83#E&O=@2eu12*&)F$N^}T@?fJ#KV1Cr z`n#aQiv#WwBdVF{Gg&s2fMzc@>Q(l zK*bG1zOjTGF0+^k`<>vO;zzHSz)xAF`3y)SwYgtK6)99S6L=Ar)ikjaL?tyt6VJ!MOT|QmV1`}c;6WJT%pnQ8Ea?o_1dG1Cz1YolTf3Lr zNKm_APRB?=aCkxZnLO}4V1n96{DIWngt+Qg4s*wEKVMegxQFmB+v{u}XH{dlVZ@ntsIChoi;}GMMeG+AeA(YkV**Z;d!iu-FGvKrk4{&jnNeK){u&2F~UY1ZCXcQv5V~Eh>yC$+7cj0}4hDqVzA~1s?Hy z9|m}Q%;mUv*SotTMH0e*4FtHhw=vlzHE>~YtO=~Bnt~r4N@&p_A@n&Rz)^IoV?^F= z<@{#60&mH^g#yu@%z*dUO#sn$VGb|KRpAiRz=rBgkV--97 zZI|lxueARzk-!5+3{*Tx-tXp(k>as_J7em4+dqYG!qOJPst z<@DI?IyqBMCIo}1CF!O5bC>jbs}>z8@mvUI-OgQz_ASQxs&OBP9+IuNIxlO;4wJP}Rd)MDj5 zp*qxsS5+%c=QsuklA&4!{K~9Qo{GwtwR#5>)*P|_9`Ll-($Z4BtB8N!{X0>a%#KL9 z|NnMf{Odd4|EvQ16nIN^hw<--{|*}MnnyA{Ftc)l*lbb znjtJmM%aoIyT4(jcdtbN?Mq2OU|MFd*VP)NgCZL@dA$FhbAAu~*Oip%lgZ6K2y8)p zpVj~wmSd{ds}MBG7$f$u%M!|Bzl-4ziPErz-|N45eS4W-54z3-UcBS=pdWES{~4P4 zqctV)&r|bDX_CS$4<)7p4Q??|g+uxh^bu zY}@KRx+I6V-#`S$XrWlYalVi6zV^P3tvw&13$!T+CkuYx;Ta1rWuTc!;6g?S@H225 z8Fq-tdv06lxMpqQZyB#>gFlLP8X0~Ae{1jTbp}W8n(X$R2AA>Q)Czcyti3)1uZZtx zf5S=%#M)fL6dpQKRSrY<+rVKylSY{^dW@?5Sv~!nLjQ*`(`*lvChyCjM<|eBoi)l4O4H2HIiZ4H>s;0sYo@Nr*lv@*!1Xm=5VRK4RmO>xGPqj2Y zpbMts5BNK`XKa8612?3Q|K@TNex>C;w!_f>IlgOWq;*oX=EG6T)CyG;Qq|c3^Gi~1 zeC+f&?d!9}(E0K0U50jE)2ev9>l4w3l*_cYZ~V$h2>3G^Y+Ymria$VxVF%&S4wtbD z$;2T1%%<%mgrA(7Utfv?=-XazmE@K z0q@g{aaf67+ROMaC%$L=O&`n%19>J+eM7){!fmyZlW%qVV0NXHP>`#HPe-)d&+Ets zHZh`K_o>?IbZ-Palh>XOsfgrz?K?-@WC!>badqBmir#u3)Q%NunWwg@d<&!VfyVwk zRf1KOs!hj`DT*9K!d4VZPsH^6VdYmU)u$Mg|LvD+)-@9SoDI>XsdSPmYy#=JQxA|u z;452irnHtC=xFnb6bjL>b?8^N!Pcq>gEm=0Ml=o1iupjYM*b|6%p+A9w9(}xWjw8hhAH?-RJCE* z*%qh`i9}3Y*UB4z5}+M#&c~HcPJMgEeP7Lg(=%#W``{;AyAUQ`R=&i8;492#W_;T7 zvrA2`m=o{SR8$4y3i?JVr`b&Ks7(q)Xv_8rgG@DlC54%m4w(wZiHQh)#qAfd6jP(6 zX$>>{Z9b?8boP>{1HirbKGJS)$pmckL41xz+f5DpLQJ6YflEwS?asI9!e`E-&62@5 zZ4Fmw4wh4X0_ayW*sXq(>wTS3S38PO%e^;1v7+{ZHGsZHFi<6PZ zJw9;+y{D;qCbGXdu$gDuf&ak8mFoELa{8-oEx1u!n~@ahee`Ly`z?0Y10ZT9Dx!oH z z9V-=!Ou(M<@kn6nX7JP5`3b_UIH_s>rhT&nV(Ge)c1KTtS(VfE3@ir$Tj4Lxf1{bT z)W43)E~%y<8zXl5w)snI6q3sUHqqxiJN#eQv7+S)?jRYwi4j;=mnPXdeTNE*8tkI2 z`FJN^bg)?tH%cnKYicxv;^h-XtcpvMwDTrU)$_2v0~azkcgE$(x!)%5>E-v1?g1^F z%Oaff#)G|dcN=n20aiu|@=>_L#hiKFoUWNa3xjVgw?1mPJ^|TR8~f^oO2abz)b(`^ z^}Snw8ORHXT#rRs`)-x)Sz5ihdLidHb#F)_{Kq5MqS zFe5&Zv-x~f|6*2}h>14_by0Q9M6eP14tYqc=I32T#_SJQ zjqI!C_~m+>v{y`vYg&W1$RN7#@@yKUVkZ~&Eud|@2b_-my>4>g26n+3Ya*|#hN2_? zhn%V+7M>A*BR}ecRt;#7X4T|xolF`ae3@NN>MSv z6IQN4Mo0wW5Q&X&zSl`{)dW*P%)v2#zhR^9+HizAf0|7s%`z}3^t~9;Ms?o-$Z>Ju z+=fW@Edqk5vH~6K2qLZSN9NtJWZIh5?i-y}y&xgMl*~lp(bg9wI6u`maLlLLF0Y~9 zZvUZU1BRR7!8Z{Fa=Pp#-01gPfr^+c%vf{RM8Cs>NE?U#9zA-bfjkN@2qd6QBohDo zE4unx>X~`lhZNJ(&n=!KS1%#nSIhh;U9wd-9937=_4;4MF#xnUI~G(WHXqC<8@dVR zdyD~+fcYBH@2OzS499X6fJ7LZtVAui)Vsc@nvNs`10JYa%jCNjd+~PwtvG%v+nAa| zMj#VDNsR&SMnLC)&9q%6^oXahK!M(z!3+tk@uuIXpe*-rl3a^!@@9z1e5?q`-&D$y z!{LzqfE`|WomEzq4mgDmIe|@oZU6w$7e8a#pQh3AKWq|2E@4pZ_KU@Sm@eT)@wlpX zf7EsR8lwVbtd47yFgI6%|)xzoMgLMx4pbr=vH43VpWK5q?3v z`S|64C1pTF@F&~*Fln01=BBeU2??-EW7C*hjV=7-6O-O6C+Qm=H=o3pejwDJM8%85 z2D*eU&OKtFG2eUbSMZ-Juo#r{I<4}g)@dxoZAaH^hL|I8#lffjDz9`&v`dA~C+mnd-5r#rZa& z*HO^9Zeqh^n1PnYip>-ooJq{et^0ACIJIEfN}VsJ#6uNmK5#bc^+COj;pW%;Sb~E8 zEUU)3plQGKtM#HKy4+k>$r#KE8(~_NOC9k%JJPIzR5{%9){Ewv$aF&h1di)s3pPj9T!R`=ZBF z!|v>qT~&4tXC2QKYfpNKYANJ97lt(5{n39(TzfkB!k@VtC~racFi$}--(zD}bGgIp z`A99W$z1gfq^Gd7rL0JF^#Dgu^^%@Nl=U$ZKJs;&RGj*@`Oz!cS64I7cKB*pec$5j zwa#5%9-O}4vDURO>#0Bg{o50=-w$ZNktYpUJRet(*2KOT>6!5<9&=ZOkd}fDHF>2j zBx0NC$w23}o>NtKwLo4MdG@QinVP!UHuKu85Ah~#p@8VTf-J@? z8|xgN6btzoUoHzAri7V{83qqbmY@QOI)kHQ%V>ATyC=V&ND@j!GqJwyBAWk?1)xcv z*_Yiz#@ta%DhNVO>{*O>QxH2KQZwl?m*Wh|wQp2-izPY<{$%HLW(sWNb3@zo^+`^1 zIMTTCCUYPBr~TH~ncxR)TjNRdER&DrU&AVWP#xgri#^tE?Z(pUv^b4s(zXdP3*g#cYiYNatQRj{GK0oxIE;71`od5WhnoH5Jk zFoWMkUJeqE#nK8I`8tus4_{i_np(Ve12?n#{y4?^W3Tr;dOr*^O)HqEYwtq0$CTgu zB9@vN?&34(w05Uy#kD4X3(Qg2@XCoSmr|}W;U=AQr-0NHN*rVw9QGdQ z3exl)GTGWJ!oJ@oOI6SDniP@#l1tKe z2?OS$fXG9x;A9F}tr*3>=L8#jANrT#?y1F%078uyc*Meh(EA@RXTC{uVoM<1xXJVD zAs{X1Fomy0CKG5zHgGcn6GJzOn8s6L+E4FSp~XP&4|`&p@|I8Xzzg@o6n?X8JCDOT3)`R zAzP)uf4i7(htQ-{l>ldzDKHKgRaQkxM7oQ`3dMDh8ds6ew3QCuzUxGE#ZjS6T1;O>l_?aUsH}`NH$;9WCNs$N zEGXogkiAWac>Na7eW(vKB?}{q5Y|guw;wC0FMiFp^FuC2Ghf3g%StgG6ehVt9t@vm zv-Sju;gMCVfVDbQZ&qOYWQSIen?rynbq$MsKrq+TYSVbj{kyDYS<3Mn{1p{#4%EOg zM=UQr4ov`%F4&+XS(k6uz=WBniDkqd!uEab#q>S+oDyl_4nKCyW@jB_Hjr;nY*B3S zz$tKG>7;eTe`S7WCwx?R29-&#=- zD7VNrhgg+2_qL_c2MaWfOf}!PV>$Itjrw;Lm|n4bFLxK4TeSwZEMehLMC(|Pac1Wf zX7M)N()0#RbSm?jm||&nhI6xxaxGB{4UP8^E+u2uyP2rx5x0Yon&;Us3j1dPCWAff zZ`Wjpua#okQLoVgA3!VKVMa?-mo(1u>?lr@wNZ%ksggUZI7cg}c*Yke1()q=_Kx2x zz7EWFa%*MYiCpp@LmzEct?PUVjQ|8oOZ`BLGYTTz(2>GlgWppC1~*We0dXIn;|PKa zA!Y!nIxBIy0~-q~&>yCaMfiV&y>(DrTktM=fB=C&aCdhfG`PDv1b26rgu&h2g1fs0 zcMBFgxLa_)n{(dp-dnHg)vKC6W~Qe0?7dd^>TmVx{yq`#&!HUoR0P-$X^>X6(ps=` zvoo@2eTr}}AueB@#${48ucwZxZr+E1!4e;B3I^ee?Q#~))vDTp#>U?B)A{9~bei^{ zhZmVxcz7Q6K~dBXG2|OAZtfyJErYToEgDnmRv6q%%N59p-f2Wx(@~q{?F*CP+HUEI ziP;LS-#kc};+Y;I9ZDfjE%MMD)ga#!Q10cW&5DC;FYZf)*huf(k z$>PXS2ZZ=eF4Or~yVML#7L_1s3slk|WZ}?yN??2xe^C=(4PfLWhTsG z<~p3tYS}qOjnc;assMzL!7Srj_s?NE)+SDB@VLc%!>ja5!Vqk5k}$rIs-&kC@?je7 z%lky+D76AcP97;)?e49e>;~$7U_8$CZKn0kpVG<2s~>d5ln`C|dghd`T}H=q*fhQ- z+JMEysmvj%i%BHdy5ao^4Vj0KdfbmpoISN$VPOTnfikxcZZxN zKH`8^+CT;^R6KHd#b#sKaHYIHuYD&OcSkR`$M)S;#7Ka#5L5=r`LZSy9&Y>}1s-a? z=IONcyghd74z61}xA=-uP5f!2w4)S~qx4819fDf_EZv#976fLykBd*@KL78*cl@)Ocnd(h!0?z$@$8xps zR(j}NltsHT9!>T#tc^YK7upoE3|$t58IP7Wb|44@dVrjY>GbFUUe%HV9^|Q1M4l5{ z6B_Z)+NZSkgJg+2p;csJNXlzv6h^%hD# z%b!~G)GZNa5;tdHzHkccapt%m9FEa<-F!aR)iUXPbfGhOojGh!=o?lkWpaMCir$&v zZ0T6Y+dJAwH!JyJ$!OO!+PiFe@)s|0y<$$UdDlZTzni=418I1Y59~y z;}VGUb5SIZMCNs|EPBSMQ_>}N-a1@X^iV-2FL4$Xx#Le0kP*+76f?ED^iCZTHqEmh zd~MbXAP9~0ed^IceFF^5nys&xeZrD{$paU{*S)M!$JV-bPo9i;LrTtA*D-mv#_*n7OeTm{5g6M$<-_#R$Rvr@^1?5QrZ}`Pw+6 zo=*?0mi{E<1#uG0tNRAqlsW!x8BFbrQO(tVZ(+|Je0xaj`O4e9p~cv1om?@e^h2~G zUAN(}v@x7UIo|}Pr%xe+9=RF23(+{LRoYy#)zt?)r$b2OBop4r20LPjBc+Z-NFGK*{rL@>e|=2MJ_)b_z&YSUx7NELl>yIQQWcps(2GJ zae%a+muu_ZAYFvl{A<23c9KX-6#?e*GiO~a=HVsD4)`|cz> z&&r|*Y|Z22E)skq(jhI3?jbuQA|Jgh8;{WSW$S`mq=#0i-375;*?2}%v|4Q>ZA0l& z(I*7`V;T~Yg}v{{x!)5-h6tYNF3)+FZ<=*EM)*QKk&v1y;@V{HN*b(B@T(-dEPY@9 z=<{@WcC^{UdZv=Us6U7*luvQ+I)?J###EY3)6r8J5wTlF81=ye%(0fwK_x;o`YACT zu?#xOWZ9&69Y615@rwr(OUm#$?%?m+%+f!!;>bsX0cc&S4CT+rLtf zuZCpSsMO@|DMu&}7^7fhVaW!sz6r{tO@&16<<3>tXflujPajGp(wpNk;4_cKoXJ9n zXhC#~UB=M`CNdfzO>i#xK)H67$rTzlD`5k6 z7z6}qQ$HUN0aD2mX@8Wpb&Iq|l-Tw}8+j_VIOGtOL4dE}>2m1#EPqxqg80Yku+^7~_B@x>S5t=-)>L^GXI$SKxfZ-ig(xATfms7|Q zr=rOZj_;%B9rDn9@=RW28~?n5@VV(>xT^NT44OU)1jA`9;01N6AuSC$X5;Ca%G!7d z&d?!S9t0M*E6nPzT86C#hBO-+n43e=9W?6~sgpe@oh{+jVaugXD8~; z>d=&w1;huB!|*-!!EFnY=vT)!A|@VwU`puw)mY3M#T7(OJdcoQlO|jw*&6#J{q6Co zARxU^QDExPnpUa8*}8dZ-6Q3tDmb1YUW36!xZ@#lbGT1q48+tazrE!N@9sbHQc38& z0@qF_lj<0{S5n{!mQBwc09ZU@sd3BffY#zt&c5TUX@ZH%NLKk)Nxe%YksO@QI2pxw z@$aZo;~Nkuq@@x99nM&A5OAWX3IFy1Kte|9%way=| zXaEi8P5vi${>|+e{_R=AtOXtWt9AX3zMwLhSGcc+^3Cmila(>|C);0qSnTRvRlszg zDEI1ZQ18?z#_ilC?Q^#zppU8~xVR0xWrn!@^SOPdl@Rj02^{^Fe2NC!l}eha}V zQz38mh&tYN&O{;&&=g_^m~#hNF>HJV&H3{<;c;L+ag$|gOLDE?0k!5IsB*!P4LD}v zeWRGu9o!==eLW+o(`A1Wk1AAM_qI`}P8rbz1{g~cCt?pbKZp1QsOg!^?c%#NW@iJs}Jsch!T08$+|CsONCe2U%WTSwdi03cb>72E^ufKVP>OY$Eu( z^lw&f{C$}CYUipet+BDaY^~94x2>A>Rm ze)W}jmE^3F$DTi@`Ixn zRM7HhL;*O4$XmsfR!!pk8b#S-ajIq4Ui_UFveg@X3)VaJ(6nsP@z1BXs?vgoEP2SnIC{~7BtQkFF8l?r)XXRv!cYhGOqXmZQW+3?7cDQC9| zSHS)DMqMo>o$hz4A0JE3;)sqSPV$4(od3+B;ep0o;Dx>WeqZ0YKE+heGot(1Ak3;& z_8|=xhCpsAwtB9Vb5J&(BrZOeM=MhqTxa;FV^{@;Y`PL5%__mnGt8_~e1ZX)se(BR zcD#}BE21hLIICQdmA$urCKHlH!Wsqz<;H_CFYkZY4U%BI-nago=6K?L|^S82i~^i!j@-m?K*o zkEM<(G`)X6Y2WgYp?~TBw#B&pm))xREwkIh_Ph9cuU`R4cOocCDj}5mGh814>^_>Q z>?NRpg;FLjAz;1RZR~98I^Bm~9dkCRd$d}5mK9!u-wxmIys}H0Q}4T$Fqf2k0v~i zKUb@YQTl5M#bOAHs)6H5F^|6-~7ElB@)Ti|kx3C3dyE!_Ld$=h@Tmkq|KOHOVrTpu8 zQgIhlfgT=Gk~@fpXKUN*r|mv|-YMILao*EdAIB<|+f(>> zIsI#x>Mv!amo3i=O{dg_?5&6ryDFVXljaXiMwO{F>|f|-t%)D_ijT`QPsY-;-PKpFE&}b?5)@>+1(JVcw!ZuIrDyF-yE3 z*ua}+BiI+e*RXyifnL_E7jj~DG>ML=yI?F}l=?Dh$} zGR2TcxqeUBf4uZ1e}*F=1VbKRtH%kOh9$XT;hK(WF%!Bgd-9THW;(REMtsQ_vbm8B zrz=N4MW@1@J-a?QwfW->f97osg6F^)@&EThk$?=($4hMVpZz0D(+%Z`DNyKR;?93q zU|%G`aO(y+r%@}bd<_RH`<~~WIZj>i2A|zqUsjMF?k7LvN$}5qLbO?=ylTP2_;>ii zqi6ZP%&^5Wxm}jsLdDm8nMZ8EPsnm| z2UkIXzcQ$d;i5(|VVfxZzpF|2<{)pO6vlq|P!9p#wr#Ta z8{Kovf!ZLc>KuYSKLA;CSRDXIyB^Lt#NR=_p(*NWsuMqJ2=bOPAAF)YGh(esimLKx z;NgLMVy+bpJip@(Th{o+%SXVX-wg=~NdJ7iw21%s4AIjtHh1;$)BdnGyi)g2<$7q3 z$s}(kGQM5S!_xk0n`g`m%{>weoeGOH*8rtVioP*BTfe+;FBhp)_v;vZZa`k#KZfzS zVl0lNv-|)C0P@K(fLZqEE2%0n$TmwhB`RLGk4KY{3iR5lI@EL1&x?+!l~(JLvxLt< zg%VOeA94g|6wj5!e)4_(5nfbM?EBJ1NkJi}f=VnVq@*e@^5gxQfgZ^3z9>-;klimgL)qZkMXgrnMHCLd_XjIB0?-``)8Fa(xx2jJ0q~aDMhtMaerWQ|5K>@8Si55>z zDu;nS{}Y7h^7YGX{<~KOdMrscD!kuk;%uX*bRcR}+BMHLC5(z~*sfTJkvz#q)c74k z%m=>Is$;Hb5y}jq8PyJEVrdmrR6wsG8ueHI&uQl!XB_-7u6(HfF33GH3{2V#4ZP!@ z%^0uiwy%TXBFeOJQ3|Oyq)jT|GB(pW?!EhiK%rRVqKg+tMSyh@p;@xDOR!I>cGT3W z5qAg*+WxmW`e0%{I(zE&1Q{tsOd4ISsyp?b$&SMNv~4}TyZJM<6f&|br7RVi&pe4E zVtfw^nSfcrUQHjzX;%B{%U^!jt5i>?Hu3Xznr{I{n2yq)=z~7rwj$6aVSbXKb9woe ze~BV-%3&635T$SsjcU{`R9e%k-B*|y$NrynY)HIYpM;Vt)T|@Tj?H*a;?gUL_k-!= z*OA(eHbJ#&6}nFtCc{iYyCAgx-w!4;T3vep}#UL@Z9fr-uV7FW5_a? zW}8u0>+TE=SXW?t{mUBm_21|4rm=ifTx$lN2=A9cfWYA|?%$@}Im{owmH`0WEXb)) zP&{ZTD>RJ~WyVIb+xe$dyNG#FY(efJZfRVhqP3DWsHB}Xc>M9-fxp*71zhi6yWYYe zMl1Y3?*SwKZ-LZ<_`iShe|`PyNa&+u(XVN;RK!E~Xp6f+7YRbgKPW{ozoEP#VL`@gQN0%R9II&%EN&Lhe1f$$C?aHEtv(pdk~c>@{kKE7EQ)ADdA=Xb^QhIG{` z5leGf51r6KvHjmfD1cX8fxi?_|0ZDQ)zQ}j=mDOLF*L!j_%%tDHcC6!ignuL%ex)o zpVT%A^doJXcP{=r4AlrYz*?Uf1q$M#Oq;q0@r3~=o_UCGXlOMNAaI5xOc+?R4FZA; zuh{-}Y%(g4OvI4NauV|{4dj$^Mu5`@i8T|@uk-q7S(0Ric*s2y2U}N6CNJ zAw9|WIX4%D0J)5bHUET`B+Yw>y`14c?IX!5l{xGEqTA9kdebKUOM``tJ5w3Q_|3VO zoN}hDp{i@p$ZOcgS-!h-V%-N$p-D zyI&tNbTx;SoKZ~5SE|tPYG)GQ$`rsHEkH`)tenLF81J~EA!Ff@A<)<5=V+fTm;|8u6H*f?M% zPm_K|sXr5x{U+5tWw3{$p29MLyloPar4`qrW-`E@b7S}p+=M$E{`D(yToI6=heJY? zg8ziTtN&Zl)EyL$Qm_|0xRS!6EFj&!)}`}j|mo=I%oEwju(D^@?l};}@tY3#C=^rBo z7+0^0#wm?q`e^j9(Ox#;^K(mZ+pZ>wP8zk*ohHy`}lz@Bg2W4L~ROcNq3RKl%Uo`tS-s zY8E3t!xha_lc&JWc^#!0iOMHm_d=`D;Qj}0f7$os(qFpmy+LCdEwy@-=LZ(%4W94w z5SkMA9=Jthz;IWSFd5yiNY6uW*CcP3`ps#B@Yozh85H`ov91U-Kg%#pxU656@;T*F3m6BalZ*!Y=Y>0ZSd8KOTPY@U zbPQ|bf5gX)+z59Z{CnrwMtM4>v@(k=uahjZh8Ytt{(JdrpC#`2H#c4juP<6-2MZiU|9A$*36~xH#=(>Gp1V`$y^9a!g1>l4)tm?7{>q%9+AfK}EKTgY zSkNCda@;aQ!*t9d_)!^GqmCo_>X7e5s2|`CV1QB_>}7XdEF)6?{*k@?)n}uGsn7cs z0~Djs39>wYE)w*e+OwQ08d@A)*e5yb=O%Cx))bb)(#J>b(b6$kqscZELQ}roBE4Mz zuL^g-$RU+f(bop18SuY~rQuJX-!1W-vEBF@O^DTxRWM?VaKj9ytvS%78UM2caC>Z_-&JVa{UE2{y3m9SX#&d7&UNN_iHAtyXEn-wS*JBNH@2zMb zs9ec7X)wQrOt6{kog?Bnpo*10AhN0V-Y3)vG2Tl(XvI&yjnBfWZUY78PV_8bx_7T` zd1N9V!?+EKzuiLBxI~`c{pJsyfj`#ud7*lKo?72MY=nB3y}=P%3A#boUBCUeKRvk(FOrc+ABmS4qP7( zuI-%cYbI{7x_A4Gf_Bv*c9$VjtZs3l6=_P+gVJVbv@o%zM_L$LJGs5K9Oo`+fFja* znan9g$grW7jXe|pn95ETsV=D>%0GWKvX$ASqfSzd1N)H|!tJo3aU>u$H^(eAA7<{1 zKG8d#RLaPtGO@HX!M1dN#Sle;J8PXY&5grCBJ)E%f1NtcQy2*weNCv@2|bb{K`CR~ zGtkhAe%@)WUf|j_3mKMeFhmFcgwXjnlG5>~gJ^JhmYjYuC|c4CD!32gWi#~BB^aw% z^nki74A+a=@tZmNh#KCUH9M{+!Ihe1mZju@+`-uipa9@gFW5L=kjOH^A9oxFqa7Ss zu2QpaLvV`H566NVp@ubdzs*jXB_}0LW>hR#r29kHzDCu(HUSC-97@crbjrFr0F9Y) z3`+N;ZG#euK!Nv5q{?Au)(bx_Ll*uQ$j+?swk~)wc0BEOxUUuhWny<%jNmM$7E9Ao z#ww-p-ynE~zrjvToMYj^MmyB=DK&D4YkUQ0$K$XNQd+Rv+!^VKlm$|v*!O@&7xq9d zHFa4ykW_1nGPO!=du-GXlic%tlz6hSCvXHY)z#=4Iu=Un!EPhmhH?GGyE`B}t*`eN zZC*46;WOjP!JY7yW)0vYNzT)|*(Qyp@f5wl2X=!f!_4kqd~eU!c5l~2qAhDY9#}PO zLJBj(%FE5WqUBkfHKCIV&0-FpV-s#Ubi6P{W~o~qW=k`WR!w6Je(gFqC%o8=Pgm3~ zXy)pU#(jyff2>|lILwvX{}cMM%>nicNtns(DvnL1SoMg+kvr6iXkhH>QOlPcnb-S% zk%IgH9P@wW5O`wH5lM=x{~6T3^DK;0Z(!&%wQ(k)1e%sfEN8p+81L!fUxT{9z+1Ha zVXBr{y?zIhRD=w&DGg1gOQ17jaZwC54$upk{P-LxQ=6F|yI9KrZG_kWX(wJ-W-@H< zLJ!2O4)pgm&X1g6ZB#|Cwf82cYs%x7>Hdzu)zT)*T9m^5eNM*Q7~`%P*!`H6`|89V zADu2ni^CFI?Jv-`{OyHTZ{8@zVR_r*i7?}f?X5heMOBztOR8O((G}`(glTelHZt0fzETc5c1xS(}hWks!S9nFgQHI~d^;5yvX z3l3YOys2f}F_!zo-**<_D~|jv(%mu{y5k=)h^%{-U-MG@vkW0U5NmVdJn^3BrDQ&a_kzDoF0$orA#0o>TO@yG>^f+up= zIVZL4?)|r~ESx z(9!4nhvzIay`wnSk88V~zr7vH`89k0d_DEw&fl1$nIE0wZ~3XcMB=@`IaU^JW;VRT za6(NYhXFcWai?aH+F>Eea_H!sID4^eis8BTO`4`xw4<+UX&L@23?5L&B+FzyCv>dw zjLGVRx@|WW4+HDiDBCjBb+r845)Sg>2B&$9KZUq_b_3u<1ULbw?{{xyb!|so@1qlV zKskJ4ZQsE!tX5WXAPpkrL4 zS(w!ffBV#xhBfCJzA6K?87(%Lu-;A>5<3mGHRw~OzWj{J1zLpBQa`+xi}w)z`MD$O zU+f2(kvm)QnVAWMR;vi{a`{em@~71*0h#aLMsmkSUQtfJ2k7bT_vV2IGSiBYKd+pe zo6TU-r6wWp#Cnl+7>4BcK}A2JdCgvwOJ^YE<>7MJl}c646ll?@IL*ywSc{3UU!lu* zrmH37XF+ssGphTE+ERcmtv7Imr2olLIuGnSCG$!^HzrXq{UN--;U_w<20Jrzjqniv zJtCr1czs1gg?Pc{L^x@|Dy=+%lFk{LO@kx{%GGHYU<3>~MO)tfMlAhWP;y8_lWXz& zf%d^FV!$lRX@UIe10jA^R3dpMoApNV+SyE))6SxLNeP_z4qJNUk)KH$JP94hE;Amw^cdft(k3az6j3~ zhIF(rx6V&h!FgHGME}FGpUAigZ^7&#s}e)q66CH=c14xrqg%NF4|Zk`Jrqg5vlwvN zz)yiv%W1Z}wD*cdbfquw96IIyWPkDjBX3#F@3F@;S(?!kBa|%fA@#vS)*aPIovGHr zQ~JKgTGwK)&2J8efK%Z@B#z zmUd0J%&UDv*0yz4UrQnrn4IiNLyb8cKMmr<;Ag4Bvdf}ve^)_4i|-%8%TXtP*~xiJ z)AzY&aTmv&UFBKac>9*qm6V(QxiCHGGzQ1LY3cPI>p4Z=cevZHcH*T({_1c0s>iu` z2N9m;1HwQZ80G1HTVz>>=*s@>A;rhVe%Mek*K-?c{RT)>78b}`ZoI`$3A7GP2t_%c zS2?{@egXyOI5Yh{Knjt4MrMlarkzImfc89t0y{+2V6N4B0x6TkR@G2!MJ*qesYaYH zSk`B7;LMx0Jwz$rC2VaOHQ;F>p>T~-td26EnE$B-#E3pqOm?MZ{Jocb@eJdWP3_UMkEULaRZ=9hq51AxjHb7Fa_b_M=@~iWP3uQ z2PQPCN1zmSEdl+VJBhep!kLk8J)6E~8!IOHe8#x_8)%UjiU>|ouIc--6*h2-9NFg= zSV0~yjCwY?bBs=QH@p#I!{U4#{A;;H-uL+^dJGDKziLBC@Y%SRjPK51+;6=ipTAN2 z{=sp1^rT@>(w1de!{;7)G`@#Yo$ddsP1()a-`YHNVUeT9-q)g(TX01%n}8;{A2}ql zOhpE13qhq(kT|tfa^&n~2Tw8?4xEhYD!bs-PZ#*j?`GL#+sIR$5#&4JTs3y@p1(CW zw<=C;(PpZ5L=WEgLEYNDgzLW^$@tw7ojGv5c)#A7@87#y!vm=0e&>pTzjMVbyT2c) zOHFJ>c1||waanCrzisqsUuNSz55r%&F{0&0Ce#0z$@9%Zvf6k2?dIXaUZ?%CKn zEwgI2W2Sf0CR~A+mtbO8#p3Js=n8yQ74jq{HWjp2)ZP8@+rzoXn^6RvDc;ZmKr^@> zASN!Sm=H?7Ai1Z}dTZ|AxAA=H-}fbgV?Hye(4s^<+UE)tYXTvxb@)+fG!cH$&nYa( zD=rfg`NVhRc8}6M`thFbT-kDtOQWu4H9~icq2^g!)xy{O^;~G z=1+tAunwiUwuOR{;G)t$>`~uX)_p|%54NFk;N_#W2ZX6e5J^$RNZ4H}gcBBaNehz} zJ-Z6XV{%$+T0)caAF8CwEV zRBG&ZgJ)SJ>qpUtcN3wDKpJoWOUMiX?Ar~EmpGaVUq{-w<{1o<)6pk9J7 zvmp@Gqn13WbySb(X-Oy#~=$f?teXGCIn{dLnOy5J(mauXqCx<}I zHDfQgE*rSEiHTa$t2`w->SpI$`SNvz?`yaiVn878W9D4ikEHVf2rXhbp@0t%0S~DV zFft|{!51Izn4X{37ay&8q}9mEX^^i=Ef?FhDq8 z&Z!{9W7M-2EH=#J>t>tZht(2mJOVXWJ3O3<6xFl9*1zp+Zc=I;X*Q(KbB=rXUGoZplu7>CC+dx*PQ1PL0GiS`CKs9T_FN{sk+g&E5 zc{Gmb9U zt+=tv0^=D|2?}e;IA3NM=5sZC`39P_Pop9x-?hr};fWN*(6={E!vPl3a z!kjT$AU3)#id(;cLTn+{W>?*LL8s^|~C`eos>JlPH-ydTpBXlURp z^@Cmo75`RG7 z4BYK;<$tn~&0Q`D4(CCDLxsYJD@A}a$Duk5Y&9~Lf~nhAx$G#q@3I*FT@|(AQffEw zp`N>bDc)uxm$fT8) zkIRS@zb%TRQwZ%eL-{pNFp)(IWL6uQIshMU3D_%#fNT0DQf9TQ*0p<OGRC1~C&#j?EUsX5iwLNMIe)##ZQuw1#wn#c=zmjYR?B{~>&Rdja zrBv~nVa?K@JD>KHYxsFYh|yANS4`F^D#L!@7`NffPmJZo56NYD#Q0gv5vY)Th5#e^ zVYzG3v z+5?`AUfZx)x7;ZW4y!=AO3;Xf+xU7E-fE|33b=sO+s1c}GcFcj>b9F%;+k5x)ndGr zJ;?#t{(U0OPj&4$^JMJ0#9QafWX6$y&|kzFcjw<;&N+U5+WSY}Gir~{wtr8oaXc@=L^$T}{8_EU0ujuYJ)nJu-Xnxi&SK`K`xM^#b2DnV(%QhhP_fQfkAh2f;6xQ7xk zld2Vqf|0w(aiH&b$pJ~)7)%L=;PjWaSQ)`&ZNSyXDvFYQ>gRo&3S17|Xdo$EYP5Ky zIms3Ak74I&IiUQn*0q41{8I{jex~#l^ULR#C|B+5?|0~VMp|*T_@87_6vIoG`OFtxs?NT3XAWN41&2(}4=>giY0GV*`Z+iTNj_A$v+jM2rU)?IK zT;NpIq>CR2G~hAJ9R3!$+Bz;{f2}n|&IPI zB!6lu2d2`j1gvS1TmWVLB&`1)(jw(*dh4*eecf!GWg5>*QH(h)cKOmKus+b2 zuXqnQhYPAgJK{6rPjTZHeyo{vq&kozR_Mz(n1n1&ir&Z-vR( zFhA%{mXbK2Ojas+2;b)w;{5IW?%qWSIccMr08Xlr8E+-ido9;#VaX21zmnUVP)Qcl zEb;aX(1A>{^z4ML&FHsqtec z0lb0ag~Kw)tZJC3Fc1l*@&!#7It)!uRJva z-G_{DUka^sWP0OX1QTwFYCt+`ta#imss%^0VTG}%%9mnVX%A(_X#Dbwk?M!28HoF8 zl)GtC^S=9_gBK!?G$!T4w#cphxf8QCb9%_m7@SgJEFPm>e%M#&8eYRU1IgTLW>^i6 z{qyvWykmu-A?5gKdMJ^k>F`8iZB$blxMFZKDQg)idAQRrVJNksx*dC(jqo~Ro$;{z z#0F*N%J_r(PyBB_k}WxCa8cUj-#168;Xf)Vo3e}nzTpjvkHKMQAMrZqsn<$v{G68( z@*$6&I*+D)`|GXSEm!Jb;24}EIt%>~SCho-EXz*p!zDizm9zMQ7Nf3jg8RDDgⅇ zCp>4C9kC8(vZ^2^ni!mtUYte%K*WVbMhV-z1gNYZ!^#xlSOh~}CJva4j&Sui63Bkl zDs->byo9WWe^uu#Mprcz#3y9Vl;zS6@N2Uc&mHa>(|BpMT z>l~Z?mB9K7?CV1%dz1DQt+cYDOU~nR`SZ~m?-?FSs+OU!EU4`g_dv9ky>|=4`Px1Tf;@%#DHW1aAD|l2gQm zrm1OX#FPE*FMMA`q37dA4gz1YSn>>wU1cNt?j9}_&M!k0__tN=)bu<{$LKPw z`=9h3ToN5Q?P~nkjoSAwRcTkqaa0M!l$9dj;|ff)q-cL83(|ZNO^+K4$Wx5NfD%dQ zD*Q`xOnJ5^7TFly$SO{5TVW&3&%K8P%xHV##3`HkVNNYGMjEXQ+^xNX3uu>`jm6vi z&^@D~mGzNH54oT~5-OO}&Y@vA?1W)bSF@OeKn34_{OwA>f6Dv||Kc&${i(lJelj82 z`r7VGCu%;&pXY(AM82m>fh+Q1+;}S^Tu5$4KunMv1HCXZZ^Z*IrR6tY-$Hr!rv00@ zu<}RvAGvriMV5wXl)+V5{1NIEnwPzG@5Ypq$gS2yoPENI8^xX8zq1*du#y9817uks zaD>!$cPs^&Wj;Qqv^>Tj@|ZI^+-`BK$e}$+%=5hQud1Yibb0#*toicSJk%vw#0HbhUBee=jj*k-za1`8-!H))-}lG*22*Q-5+5sKA8rbip4m(&F&78giK z#|0-!4H&T)$64=)$22An`WQKylu)Y)rvd0PQj#LiWzYnL4NH!u5oY5 zjv0)p51Ua%A}L@`DvKHmb}km`H`mOmMIot4VbBk62de&3(y^XvxAlq&w<;o4iQB;t zzPo78u=#pxVFi;FByE7u(y=%FsKm#0CbBgbEt0G#Dwed5ZYo46C@H8#`ZuzJek2YV z2;V+B9b)mO=(GHY3PErj2n)^J^?oS|A!x}!F5T0X|AG=Zud~`Y>|5K2R59o#Jc#nPM*ddEgrduo562p ze`c0>rk0{#&`;@hW*sFM<3#1tu+W2Y%LL=mRr|!*Z7Q%-JzWRFF*c&qE}FMmMH6vM zK~(r>tl5mI`&SR0Qsbpoh9uDu<8LBw*hn6? zR4m&kNYqyFp8KJPObxrLh!7^XX>#l!i6wTzz^5WdF*~G-4j#U%p=F`(B>k7jJxfO?qFjfq%>l7bWuNnc|07;8Va&oCb=7wUb7$&J)Nl8}8JmExWQ?*OA+ZJk+`OYbF`KM-= zwxzxmRY6;2d;6N!R`I80bJ_i&lXD_gzY(EQ%7P(pd`6*C&coY9Y!H3Le$ym&883-~ zZ~!yqh|J%=-e#JBix?R!b41%39>Ui>$GTk8io}v-Qa0%hRkK^B(;o4f;)({AM(-_H zR^3^;FLH0^4ER6TuE%4b%ZaGX7i)5Qr_+$iV8l}+n}(IhV>N43Xx47Y{EJ=VX{V%8 zWGJ78#@V1OuSo4*uHFU&I=d!yI+;S`FXuPv@_qn)(52PN>e*B#1oKw20(ZF8Z;#&| zP6F2kU{^=>WJ4rQ&Inn%R>}H2e;zHU2*$^uV~7c`>n4u|@}|{krXnz;(qm+P7jvH# z*FZB-6UeHO;#NaJ4rU7`Lu6+d{*=`i!5H;8E5(4B3B$YFDG-D34+Vi*`RpN(P*~nw zIOFfj=W{!!UR}WN?W1Ys`$?F&Ycu=fR=4=`{?15h-|_j?X3lGG2+^8}K)|)Pyur-^ zW+j`3$5ocQ=eBOhRTiwoL3|z=C#S^|hARn)DuEmgH8}LaW}H-d7$ZWjUas%5#uWOn zTu{=ht;<5+E#PRqyW4)@9xCo1oMQFjZWe?3OK71wgO>KOS6d)%J( z*i-c2t#%Zoa|e%?nCJZ*{y&ee0pNi<`YLsX#6f61zf;$B&trIvDUM6Io1U-^X@Wji zZg-)7fMU=*OIF7g6COe~blfDJ;w7tTkeaTDNH^zvd_hiCmnYzLbcBPn_d1vOq||>C z4fyvh{KxBY9N+pC8AlOaBK{T4@J zJZ>qCZaIxr{=|m3sgtSE`yb*03K}h&v|FNs0Qcg<_)QLtb-5nhy<*?>xoB;mcADI1G8xomi#g zY>0~2idHH&4`>yH?)GX++z9+nNwM^sFPeDqb4yHURZYZ%;)GsX5wPggEAFKmv*Vj#*u~Al(^HBOFbYr{d(%0dE6?n29{KgO`LTR{F)G37Q1wj zdik5|x5b}|y9-~~2vl-Jty+1o00k8iRb)&wc9k_YL5{ZlxALp$kt%BEGG2;s<6qKZ z)RbN3xim% zq-0yDG09XMkmEk}8#Qk(TFu03nCkAq({M?@Imb%{xUv8t#W1#C(n8G)^efN778Ci3 zN;kNbmB6dK-xJ{uYQOm0Ghl}sL z+jzJB3>N$N9jB(bf1gOf(5uDcdPMu&1WEmgmW0}L7i6l%jaWnekC@Oe7m%8eNNf^? zDNRY2Os-9vMHJzh5aRh6%H?aI!WyHxafZyA>%tSe&s7FZI7VoqiR18PC0@tdOln=N z(EhKnk}hzO@5Y~M990FIIVH$yLh7_14?zQ}^94Y_H5v%7u6@T@<{y#aJb6rNxlH_39r|lFspgzBWs2m>)}MN7-8YkvFG>+ni&aj$rzx7V zgoM-rDx%P);&B=~L4k@0b6n&Z(b#gN$$0<=;;dCEmz!9eSmbT=$E^Tm&O@8Z&2*kN zGv#B>(o^kJQ+Xd&vi0!cd7{`#8rosj@H$d8)j-Q1N4UW*Q}#;g0KVvpS4@GHiiSD4`I{bf|4p7E-la#Km!RORzT5mfMPOXbdYVHuZ524$8w&{J9| zoJx~aUaC*T?sfld>k19qT1VI8N<$a_-iEgthY(=-`V`;tj|qCAXi5mZIh%Msq?F|! zPeiM(sJvklK%|380znP7bLq!|%`ZivyNvrzMBK-m-&yi-X(*Vn5kwb0)lQ<>vF514 z$}{wceX)ufY@HZ%>Z?OXaWz{H!m6=DCRZd8ng@RrSmlW;GakR)Rm7S1B~&F%c!2fYxlJ z@w=XF)F*K)>$_#~ZN4zgz=b(oarXXvO6cO=#M<7J4cGiZF5)=(%vV>MFA-nNsif+OOhC6+t#hYrgah=@l26*M#YG(5RWR(>8FpNisopP3GI%2d1VxxgAdeBuoKGcnQAhmA z@lRcru%OvNvE4``Tg+EQ6l1`|G!Ioj2|FRQd?509&=#l~rS~ySb%ye)7nz%@%Fybr z2r&cV5$?>(Rmv~SzUh5CxLAj#f|NE;`qH~h>WMySJ{G}WY{N~jj5po9zD+gM+}DK7So z{vaF*Hw>nv{h+82HIfLzVj5PTaLx-lY9bCdOt^%Gqe(fOHv4l9-iA|kaR%3lylzyQ zeG=fRq9Q5Y8hXreCr!vnCUTMP+Vq#_G0BfUGwg?*jOxhD* zAK+%f(H1h7bU(fD&^S0Uk+0iB~32f6QckDZNH}{v+w!=9i zksj&HO??*w-Mq`e3s9C1@ud^O{KA;ENkOonAm-pA=7|*wywevbthocLX8vQ6&NF3b zh*2MR=Ec6J@6K8!`GBe3cKF&8)M;Arq-$pWYffOnz0=(IWk^HB4ZE$wy>w)O*Q>VL z#;^)pKat(eHv1mZYR>gysnraqWBOzmzJ|hxii@l8;W1JrFb*QmBfXTXJ8c(<1=0BJ zhGfc0$d}0=c=0#j`B_NzJ;u7t#YJ-zx5UWNS+Ku`Y$wb$Y_B6}K5!>6aSR}S%Xuqo zcA0y)=`f=y1zAOD9T4}t(=HZKz=|nI)6$s_dWBqkwaDqv`Vr|q$1+^mi&&A0XJ z%e@tNtl($?eps?9bJjS-)uT30HI`^gLix=UU6Re7($wHT99!X`8fQFah!T|#-D03* zJ6m=97#rw}-kYymxjqj!^2JZ&E9&D})s~@x00tu`r{U`u3QKcf=j66D&HN`5Py|*O z1?N)1&3|a(@3w>$2CQ0y^$lB*e0oF_GC;rMAvmKA3ebfc+~d~Y7mFoJY}m~ztR2^l zyA>$(9l9bovnHE=r`m+(_WE7TX5Md3B37ir__T^STBnbWBFW4Nx6h%T#~AV%rqMzQ z#9CEz4XD-mzdo0Qp-qX1mvEZt`Uk4@C}ogQ=~Wx{hK{@i2}jWodBiZy$XV5H<9Z>_ z=l5zaCS$fN1f|uYrd5L;jY4ycOl|`Z$+%z;X*!~YbiZ^QlIW^ylL6y>nO_BG_*|%h@*;;6@~mYswexT*=7{0 ze|fO#D30?4SFk6_Q<2?(Tu(hxd#LT1i+AXhUeEshAB6k$K0xVCh5?xXKB&841#s~u z3VKUfwQO0|UAesi#!(=v{=$W;vlVE2RAxeGbmzwDO2=NTw z)wr%ntDdR6r?gG3ICUubw7YCfY7&t1Ug~o`;ZH;jDN#DCDC-&IGCNAf5E7G|)!X2E?WsVa5W9OQjfDG_kpk^D??@&Ch`(vCUtp=nE(& zE`=g&2po?Af;c0EEBl^prorRLw~Fgg8``3fFgGqBsbRvC&N5_OrkQBd*rU1B_a{TG zlMt?*FUxUX$7fT=Fj=rTMO_z4j+RMegfv)O@~7g|Bp3>aac6(*@sD$+V&K@ipzrWvx5U|iUqr98bn#}ZrqX<_yHpi|M|5uw)7$C42&K9KTr zn%{q#zvsrN!}^X6p;P4X$kkj+ejDX{BVZjcGwJLY4sT^a?KRqzacgGlnj^$|lK2*A z{0Ls8JE$j7z-8hljI}z9OYm9yP$j5L?G83!#QUH$PEXRWzgEHg3*5AV*@c+vFHE#l{8eNRPE z%{M!Tf%SB)<)=Fqr1u}wS!Z=`-KAJFHvh^AO!8P9CKi|XNXaeB3TXTuF?nYYrGSCk zk{0uU#52fq`Q=XNWQ;svmLf5n)oab$>r5>G{X9TIKIX5HJFf>K+S-c;Y>WzG>vXPe zrUE}U3aC%mAgIb}WAK(?6%KIB)s^K~;Dun8{=M0^v7J&-y4t5FT3IDeA#iYW`gPG3 zX=<6IcL*ZiQu@WH-&Q29f)SF$%=6dHAyzAMd26SfQ{m8AH^H*$`Q4~($61lX5TyIa zE%R9`)4|g;QO=aGK3uKIt2gT;buY3s+&j=rH?d$Y-+d>jj#S()>fTLId9cVqM5S*e zQtSilT$AS`=BW(NBGxB|LW$08eSXE4IzJjn2LfmE&R&C9yGE`8KSsI+uz-a;y6cK< zVbFH)$M`|qIF7BaGzErhiZPWED49YTg#ev9-8cD~g)KZWi|VVh_Lc2ecL!K0;jS2Q z%x6cL7}al5$A!;3^7Z)<@2GUwyyLp@XNoHd7IHfjGiMLt+PP*Lvs#I$omg4?$Xm zsox3y&c5Zs1?kYtk6+hHHw$%yFD z5n*-ha-TEZ$fJt((E9|XnC&nLM$h*XdUNn(wE`6%~m9!^@`UGXIEx}dxX%;RBi0&}lG%-2bI z5Oi)Ucpx%chd3F1wKJxy|AMYrHm20>1Y_XEQdIj)B*{1&BL#`4ZO9p2SFKBkx@#7&3 z{R=u^=66_E8oMLRd9FI4s-?dp0fv&of6y|C_a<e)Ux@ zsoyx#uH0=#_r|RUEI5prF&S~hQ`xTlRz}1xl|6jovexQ}B8P~0OCJ~h7hRo3$HA!` zqs(U0IJ&5cHz(g&zDz}(_3%f_nvE?L!Ie3uH!U}p^O+7yCpuePq7XJrPBbmxt980Z zt5l_pfjP57xrDWMYI%1dJ`o6et+{6lRjDn#-P z&A`f_$MY5(h58p2m85|<8Q?h;IZh@DP854gpnN1>6tvdD=iN9af#NRy)BZhrq+(>{~uE zP}7vG{bGj>rhZ(HA&aNJ!fdYyJ+=7Q-RRec1sC17bx9q{L6U$TP>}@+1R=RBRC{T* z!vq!^c`q;!&A^rT(WEn_({td*D~qP;HV*G}_5UF>?ELn9?uc<-*VMIPm?MRSkH=tj zk_n7K7x_`FeS`8GcNGz6q3K2k zr$sAX!19Zj6fJ8J*SH4K(%NHFE&}+sv(ag52nq^*{Jd5dCa(ilE3_1Wh+&vl>$Jj?%2<+c zlw*ODLL6hnCUVsyQgpQ2O<^3UiJil8Ii$6!k$pONq% zvW&}=ysMj=yg@rsrtbR|uq^n@%iKGE-M%lD1z!g9^%&aVy(LT{=bAG{Z9@ z3rV%`nOiPVeD7CI@AkwER=r|<0n*Lo!#yFdlzSd)KXNt#Wk5go(Q4bEf)%Q|_k%OR zW-_**q8t1K&-p|1y@?IC4)R}b5( z2%ThXkA@N~Hbl@sAosn9|JCmE)jk6}mNf3)1uv8`$M6mz-byH8`kF+ zYtIQlubZeB5HKqha|IgbZgJ*EQ5j>X>>NJp#6;zxa&kjXcXT?Mnu)8}_A?hYMpW_i zFbbEv5>vN!#iP5f*cxrZn|WD_b$k*Vbx+O~vkYy0Wi?9xH_tDL@~Xk`$}$2T1NTM0 zpfG!up0-^?^N{z-GS~CVx#+}1ycKMl0DJo;!ZtGRB0rR4$q+6X3_Bf zC>77z;;cIQN0AXQbA*+&ojSi~7nv#kjDmMih=N0dgv;vmG^#=EZhlsg#gOA@zNDT5 z8X%C7Atf(T+TNQ4x(gQ5j@N}3Q79?`IC2~v-r-AgwsyzDeeJ{?b71+5?A&T$S(OhX zeJm80AykcK52%W4rcT(oH!yC25w|)n3aU}zxYs9KspN64lv|TwlP@1TZF6Qc>$HEi z>>C{(%(c^;CYN&`TeImhMYki03dn~2TsxSsVmEI=wP+xQ!vw{I{L#pr+;?oKthxO0 z3lfbYB4tubt!WcOMMJklF)kRxsE-3jHr#*3>(x#QmpCG3w4?Cdu*fY!kd@aYkl01b z2}8H*;mbSa-wMB-8py^l%7BE)4(4&M_0ALoPI57l$b^*+?0h3*RM& z*0?>JW4Me_?$IG)ju231O%o0BDGW4CP(Du^1d~W3Di=!m*7{S(BoinHgT7=iBq0VB zHH1uC8Cudvf=NPHerb!k9=bJrr^AA53IRPO68X80Ts6TzDJcC-3VoI;prM}r_IHoMm9Mo= zEc4j0NOxx_fA0Po*s|2;`K7&*v11ugzuP`wQ-=c8&UBQKZ7O z*Wy;3h%|PeFbaBeAc=Lzj_v=c1%Ul+Fc{5f4(3)5e7Q6EFX}6^-2nku2g*tG(?G(z zdlRTRCZe6Ko0*%G>8y3InU(I#jV~4oP{$Qc`s=-9<&W(L@Rc9h^sfn8Qj{v7r`3VT zfUB+~%*uYm%``|W2*+U;1l-l8`DpR!fNf^7VJT%P{iquJ$Rc#uC96r)vkjG3IN~p| zh9;qLZHo5RsUAH&10ZRk9%Y)L?X-!wT>X1j$7%?63i)pG;7{%?d z%;MmxHqcl0BZW&2FD%OcvEhlWA_;Em8G8w6&-ZJz|H*=9J)7p|#6~WQYADjD0Ds{& z=2b*`0MlSB|43i>YAUXR`5_iZAw?mDK4Eu*1ErwKuFOySH)K5uj(C`@g-+=wY`wA| z4k|gu@JK$OT{O;S&+*FKdNB#@zO5qIWqzF)3?G?mEDRdQ?ABN4@hS@;F%cjMsu+&) z+-UTGG5`ToVw1IhdypG~5d8tt9oJMMjzQqzgh`IM1+r z&>Krq13kEh$-efAy!z-gvO5Wr`0~hqaWi90-=hCCUmIDHCy6!U!oNP-|2p{kSozwQ zX_Jp%(>wFpBG9@}K-t4Gc=rSkEy7f#gC)lQb*vvB$+KuyMDvAukispQe6& zW#`3pPSowsDzB(T5Q@P3f`nXHlp6N3&>>6z$^{4WFn z+bx~0Z1Ec_35g|F2@HP|0-ID(Ot3JMLK|QTBDG|b)95*H7=*tkIDU7zf`4k=-MXl!PJ8DkMM; z6Tg$lUM-rmx^F^+?hl_gTh{kQXKW_l)ZWj&qmZ5c>ORpM3!Z4b8Uve`sfd>ZmK2+n zcG&_^OQgYDt-XB|1Ty-2O1kWnsu-C##E%p~ypM7ODqTU<2#n!YB2+$IkRpnG;95HU zAVMrjMT*(aK7W73>+@R3FfYZWZfVLn4L%bQW(NBxwbagRlkrMn;|FK;Aaa&0BSP-*Bz6eI1 zgNQ|)S2<5iSTr!`bz|8R>4w%f93)*R@Hpk!X6w2q`(?-^Q!`hpP&ePOqw9%TMvTSD zYJ8)07NHZZN3hanqVpivnI&e3;*fx-e|Z1c=Nn2{ZHIW)B%m)%mp#rG2uv&*Zl(v^ z);cP7iu8l3ChaVFTh#d1WA**hm&sk1u9oOpuHifGmD-7C-bHGjGPm-VPK{{$`DD86 zp{ge?ObH#0`6(!p6tV9);eoX`7xcpRC<3iFUbCXH~hS%?*$U9(bL$ub`A1IyK ziuKjB>Ym{P8-8A9{G80JArrn_Dyu*ILxU9YZf4ZA*`Y^N#iXb~YV@5nR;lxk<6DcQ zbn@CiJ@oq8bS6=MRv1NZO#%DU_R?aix*3G_8$q2>U^E$iaO05k;NL|#- zG@&K7yE65i(aPrTznON+>Cc2gRS@1KhOGYtafGGtc+eUV-khiA@*x@U?c| zQ(WW>WDKTXU!l5{^`%#y%Um}o@n{NNUgEd79tPK+^o%FqR^?Kre zt$ZSS-F+Q9t#EB3e4&!lCWrHzk;lFI%3Haf;B^^sGH?5MNSvwsr z-HxWwkDZtEpXt5a@ShXCtaYvv-56rNUf|5GJ@G%SHAI{X66~O7$shPW(GH`k zU~b)uP>oE*k;x3!_`Ux$YO8o`UF&WhWa%ArGtFfdoX8MPjH^^21)uv)_nCTyD&VhS z{8vt66%Y;vym8Z?sxxEr9DrKG3=nX&q~CFB5LQbo?r6l`c!Zkx#_m{s<>B2Odv zSo&_hi-OuXW48WGx6rs1=>@Xzd}A6q*Jd*@cfH`wUk; zX12uyW$$B(<_makGN&#bI`KYkpV*>~XAQ(l6sXvFAy=xB6eV8>kY>mVBwNfUh?N@~ z1*z~X#gzaYq&C5eWV%&DcxB0KLq(bBX3Gx-sn;pvB|DpG^n-n3M=}hK-aU}fMB~hq zZG*WvjmuQ9t0Ui--eiJ-4AgUuWvTTN2Y*w1_MMFrey88ITO7R8rs3bmr6=!TH?~p6 z>I3T%NtB#ioIvmxDu6tc#_b4hREMK6;3Q%ul;z-JGItX4@J@BI>zZ^Q(l?$yY1ntc zt4sL~Qv1j0`fU5g8TcRg>l`zxUh)6``v1e{*uML}|K$JrG0rt{z}-9asOpq7CO&SH zSACdrsXq-B4$bf<$UHqo%!R=P(qoYv+}yiP#o6ddf!}N1TcopcJrnBa^~aE${yWv$ zKX@Ok{8!l;d`6z8K{a0<(c^h5a77Kuw?}^@9r*$&%w1%+v+Z3kchAUNP}iUC8Il4) zBW@GQTRT@liwqJ<@IN4rEyc3g_6XkP@@x{a|~Cxle2xQ+{GtOZdq|9%$iSc$K#28LeQbQdT*Lj%ilAnUYFKy^0MathH9Kt4fqeSkMg^FKPOH@zD(v(t0{;uU#4SRS#`%O*%0s00;j(}z+N9u&WlPM=dUwqQTK@# zwM}PCjoE_JNRjt|Zh4VO`ZED0a3Twkdv*EKP`~xwvU_a*cGF0mc$6gQ{@wO zlAGa@%TtNy#-VR-HvSLfiTnnBy7K`;m2vs>6c{}e9kJCqbz5mndHIIAvW=&K~!_fKT=}LbivXLDw zjLJN5v<)f}+I8--hYzD)*{wnSy~6#7?@Q`wTnb`EP$V>B60?TFKy*~`LC0=&2N>^9 zgOD))NANR$8v{2I_c~HsBy1#6P&u1Nc}V-b5&Agx7JX_rXMdxO!)2%^z6i8JaR>Q- z7T*F*=FV{st#myzksGAh7IkJHEYpa(+?>WZngv-Hs$(%GOMo01$2B3hC1H69=<$E2 z`8Oa8!qZ@>EoQ-uKZEK^`6J6~p#pZ!ZWL?il#hZ%Y~64gg@w^n-?ZsyAuhtq(*ae{G$j z5~(V}cF}&K934FxC~fk|ZiiRf+ZikI?wv3N+Z0O%26AwwH(~MdkvX-J zKd5;$bx0isHHN)I2VA8u;y|O~(|&@~Ll-&H`FLx}_^e={Q&&fOuFnkz(Q@^D31~nK zje;@=AHk>w)5`kF?pPl8{NLem-mX}!L|sNbgYR$m$`U>XZ^(`_-+_u5EQ7g9%MjHR z&h)ep(rpAM4=z*4rwxumWoQE-%AXka5F_YA?Z-3RQ?Du+C0HfDVaNS~A4@A)82x#d zp36&*XhAgjXEt{A1)GBm|IoYEZ`?yKIrssI1hkzVN2F6CMs-XOYi3sc*sN;es1IV$ zt`&_cbR6wYEE-Z|M6+vwf$g7#WgsL-n(rHSuX9I7lQESRbwn-otKE6SigceP)eeRv zJBQ2Do(Cs^NE0MP$5Pw8j}3W5Tap+FfZ8KOoZl2JYx%1O4(=-=bb%wX;~eQ*N#$(u zCc&(2<7RP;!(J(BwiC7wb<3xAt|<{V_a8=K%4d?M2T`VDjU0HhE?03yd;1ce-dJ&M zm~Xh94oYbBt--K`d+(E{Vc(tUcDNvO@y!R@d)n#j=}H6sQ!1Lmus~^;{v#q}j#0KI zT}yl8o*ws~H{3A`D%w+wb7=~t6G4If_-oI8p0_6smLE#&{jX_pk44ir zj`)yY?x=kihv8PeGq3SdKe)aQq;nhHsM5L6EG4bFBKVqp`;InSTz+kipU%RG$J}J; z(6G>y^lT>a@b3lF5f~WZzo85nt(MvcIMDEt3s>W#yT^z-A zccb)7zTccenvo4kL1HN0gZ;Lya@I=mtclkHtpehRK->7!Qw8WQr!}6%-7}Jd^;2Cn z-Qr@>H@1$4k$UGdqu#QYepkttlwk0vXsy;&Lq*Nw7%QKTZMaFVkIjEC3VEMGws9`E zWB!z_vo-9Oo!BRga1hC<_ePENA&i+K6u!&YQ7UIQbDmSDXH{iM)ZT~m-nQv|>2lyM zt1p$_r5xGmU*^#^(Bcb^@cQ#_nnT?S15eR^1S{Zbe6(rRy*RU>EXC4IPd?0X^MoAK z5UU|Kx1oDt145O(@)Lt}~ak*Q3WlHm#S>8;=sto*8i@(UD=DJU!8bWbn{ zppUl*P6s8An@Vq_&6jRIkPwWMBP=;_g%lYI&itu~+ zFzpL}gpXjp?ZiT;?IKK?^2>YMQ}1n!^>gdW-FQta}k@!fg$U_zZGr&}VR+ zy(KvD92nJ^!!66MQ>{G4hP{Y=bz33=BP667G?{VoL7On`lIcGEq`Z2JS|Ig!_{s(1 zk6xhsBnWQlFX3sK#R}0gQcG25s5Y(&y=;pF>|7R;TDmdS&ky8S|wwY3yU`hG*&KqAbq$v80s5 zk;ieCgaOlQ`W&bKc6`9^ztVLy3_=e;8Gpy#8T^q4Pv-XQkT2m@(&d0RN8D&?CT$-w z!aO%P`b{%eV5aswbCT=QP<4Io6k5eFjv9z53$nugn{)lR;zy=gqfL?59H<9pFY_Zo zI=CiD__n(OC57T7RCyl^6$T%%iP8k$j?a`i&Y8KR?SR0T_YW%GCJDr1mOC52>c!Q5 z55x7uenGm41DC-)`$Wc?V0B_;JzXATwP-8osw7hxM4a2h@LE$#vZ27o&bmBQh5^6#enT>M} zd_O39!tXa?j?FXIlb@U ze_`j#+%D^|g%tsVr+cim4R1Hs&IcKMMo-t^iXSUIp0y>?gu@DrBKm|xqsJWVfBE}9 z;RV`A#83!_2LDTnwU~KQnq!J@cg!gAC;Y9a;8Iwig z1T5!W2)i#R*k6suR?E8UeIGl|=Q5AZLZ#w^dEt z>D|hy@1U4<`rmA3^Jd&yTmt)7{jNVphV1P3`ndw-wPQCo0p}av){n`1rr~G22Edcl zDuZX2zJK+`@zSnwl~Z|V8@*=dKxJ5jqgn5`5{x%J=nJyZdf|o_Vrrri7~VExrEhnF z516oY8i+SdkG*t!&t6?M&m?oNqvK84mS&TFMPLJmpz)42(Vi(YTkPNGVe4Q+4wbvZ zza5xM^}wFD8_}~&?=>kC$GOE`LeuAU(=71Ee&e2%P0dO}^{AQ-FZK5TGD4Q*G<$%# zn%&6AUJ`J)R5k~$a~je=Wqa(usm8*J zwgUh0zlW-eoh@R+ z3owBG;stden}Q@8y!Nd^qj#L8@8N@W%QzALqu(<(UB~B9fu>rW8~7(zq%ggU(}z!_L_0Ky0GOj z{B2#w#`^^)bA@x$>@-SX&S0S!wY)$Y)&Ga;w&G0Qdiw$8d;P3b48I$C_QlrayU|h~ z9)@U|Z0%^#FD9Gs{F#b$)5ms@mWZCx@OWb-J$`ktnz%oZQ^K;G5Q$mUNmcy$k2!>t zeAsbnxo_4QU(B}#E$>913u#o>-voIGGI&5`s0DQZ|SdHefTMDos|R_ z&(6VVOy4}Vm4MBKtL|4KKi`H}ZtCC0kI$F}ucVO3G@QPRU&l-_p4x zBO)qAfYV@=fmJ2uU|1Nn! z=-TzXTn()LXq_V&j77EySb$36YMXAh>s=hKdHuGT&b6S}vX@LK7vG4Za-kxsa4Yev z85yjN0X0@JG9hH7!aGfO*|P3gH!dt*-e1&u_XQO$^Gi3?rALpBaqx2NoN2FDI4`t# z{0y|+Y^ydGg2ngC>Jjygr7f>a8Y@iWncwZcf{|hG50m5M;8=G%iE{I{IdU#DFang5zg>0xwok>12~B261Ds|Q7(1@Y8n>HX4us&Q|{J|_?Zzc z!r449W5-1iE|NThm`1CA9dMLY-Zv#g=;omh#?0IWY_9v&<_D@A*UVbh%px&HAM_w+ z5BWLN>oa9AB^N-hrJUHg|Y{mO36PSZco0J%JG##i&0UYj3{Rqp&Q-O7 zvHfNMO;q5IQdevp7!VP@qYKX5ABW{E6g;E4O;8}R}yZv7OpqmTjJ83BP&hG2!}9Zw8~z zN^|YZ)sE=V&3htu+kCl=wamoBgWw?ekl3)#M*D|wwW$EzI65|;$vh<{fvaU(e+en0 zJlC>PNZW&J<&)haZ_AQ*3M}$Gw^x^crOl?Cjst^fvFpNK-NI_grX}*L49yVf7dfRE z4vPM-IBXGz>q!rhtMfY>tj`apx2eATCp!OLew=`R-&|n9;a)?yb#hT9LmyEm-;6ZD z=nP{!dW348e~ij2SKvzC!|1ULY>(yVx>@r_=&tcD<`pH95& zLtihFb8au??#^yA?G|8elVKl=T^>Qy!*RWazw8?HQ>ZLbdAaIoWS%zyV#-v*V1F>NMU`|FDz0+Rm@Sd!uI3Gm zW-7Ogr>onMuh+<1bCqabZa-FBUDa*Xig_@fh$%DDnRq<9ju~v3sA%Fw2`bty375*@ zbzb{D2M!KxO5i6Dp@!=iCsxmB%HFiW9YD&_C0Y~_2@XvclqLD0uaRAQ`S}RICQt6>G@b0t;(uIym_}B3MP+ciuql2ujT5N3MHv8 zI79C_H{C}_ODFbjif2mH& zf`~*078M}*{JO-K)}eV*s{i+D*8n4e)7!vA&VF$q*Z@ zv4baQoXx6fke!*a%ixHB!Je-WBELGrhr%!wHb-a?^!y&CiHUQ57q#i>dVc`!Sw8-I zA72>2FQTvoF^7T2@6T2|XS|*>VgOPyAJ5r*1Yfp#mE( zz(WZHpVEqkmf=1trsZ5Dg!oK9Q@3={pkRk@&S*&DLx%H4G)A!EM8Z!UB!{N`%rY49 z%9AQoM{3A7&y&n%U^7^^&JWMg&ttaRh(}YvG|nD6c$d&L#V++yw?hnf&bu(lIz0%u zA5N4|Rg$|8l42QNlE+`J$Y1X#a_x_?yzYiGFH7kX&lU~?i4^5ak~C`c>(UrAB7;Lv zF85;w>&Pk(M;!j5?i=aaBW0DJ^+V^Nd(%+` zT|UN`+8$jg0k`51MO6r4lT}yqpG_$_u*|VbDdZSKi@x(I7hqi`v$HA-s`L(xW7haQ zDmo$+J777%tQtqDXK(2?GN}KXxI$ia_U=q=Zg0-JBvRX7?sIiSDZ^e;9*Yfu2wa%EF_y`eNGH zDvkWP$_;fGprbB`WTxtuL}hPB_|{?Xcdnu*>d{-xW$4Yk4j;WU1+nE^HLXa|#jn ze@Zk7DSrb{H4YNT)~0eK=cV7C-%l9;!`qTS#my?eP#LYmC?yl&m4#!3M{?7Y@0Drz z!drfv(o+yp(S*Lt47IlH2-0fr`wM@l>< zj*3>Gmi|{O;saV|-un1l=bNfdf80O)`+NvU-`K{H(gyDWLMfa*-S-mv z$qzg0OL;iwUSn5R-v;N6^1KL_k(<2SL+d+VqAY#u$z(wAypVFdGq+7?6?DKKaZs# z?5Y$sm|(Q7N*b@f+P(uPa@|e69`jl?=;1yF;xVL=ra;@}Iiw+x?-(-(*AE+nPv<># z2GiNnurhJ)aY z^~Z+!yFA&ZOT3Dwn*a^v9JMYch5|x9spLYk-5`XBNRA8$Bptcw5AUX=dR2>eYU(f( zC2)x%OMff~%f((II!|tJ#70b{ri6QJv6WYX*ZqOr$SJMOYRmZQNS4bpd)sB`+Qp;g z3}wpzK*!9?aB#5;di1=#KO)X|YOP~;z29P}m@M`9fZX{!^j;NhVimOuZL+FDxmQg4*=V^&AA{$3dsKxQ$d>2|R1W{@7Z2Z6= zY->}yV7rb3V_a;+{jj-!;zTfdV^@l3VLW8PWSl~cNt@`wLhKfesKk#E_`^W`gU#2o zKX`lC4MC=!ZtIQsVy@N8Fy*R2x^#xDK$A{G4o<*T3UYb^kXH=p-3sg8=M4G;Tf1mb zxR$M@)dfkHJ$<+C?`Trk&ofVSZcr|1#@mKalLul3YR0E0g9q)tLc)_lbba5Yj4$C^ z4H8w$lp27Q(@WZIYgYkIf!U}oiA9t8f~-$nG%bP-H`Ti#B=nRdLw%vhT%UvE-5*f6 zO^RWdqr+(bv{Qx(KYa}Jxl`A|AY9KpS*1;N^=x*&KeLC`4HVMNZW`gq`QJMu4}l-E zU;GiJ{M#6h%K}le{}#mkH;<-$ zN7YBxP?z|igjnhXv-Fy{Ss^LPAJK9>hiIKVrZaIDX31_a`$o*uJJsp{?G81@0 z`6mr(P4Bl!{jN!3LvtIu;w59()`)U^nqz0KL*B))PDb1l$JeoUu`4=){oTqTsAxhA zRG~?|UPEq-hE5)RBa6FaPUh?l%`Yd275A8YQHO*H`TVnNqTeOOhr{BhsMBGxJBcq< z5ioHyH0AkBMYCy8FWf}aDh96pTPfZ=*oj>~O+CrFB$>Ya646Ji=o?$r*`vCYpHm15 zA$%TXtB-X=8ar`3eThmp`H>#-DgXV-f8|}E9pO^A-1C6iTIwMV5zBh>rn#mL&mYKK zd>#r}scbFA{Q1m@3PnlA*#pwZOO?|VVZkQQ_Gz(L2a^k7CB)-~eYBGN~t%|ckT@+9Y~cOHdsSF?9^RkB|i+TC^!ueT(lAbKu8?TH+@B?bRv1=ZN*TJN z!ee*TwPYL3rgZx2{iGXGQ!lq5<9>s>$Lp>;W{S|hG<>33{(8xJt zS-O**d?#p;=w~1O=wavusyA--LnP1@ZrF<0Q_GTh7M=D`$oCC<53GJ!v;}BFxt4!_ zsgq?f7UkqO@NyY>S%@jF@AYWxKWPcIJpB3%!)9V>Ip5WDWF?mO#>RKhM{84ZK7b?p z%3`lVh&B~%yf19mXl#RXaqwM=ah55ek9_u|^@LOR6vK`s-+h}ks8+U7D_ih8FF%Aq z7qwNVt)A{7<9bhb!B7@6-42|_BMy_DK44} z?6S|qu0JA?9!6ei7|(R^A6z$sNSiOjcciGe8M)RA>7FEwz^GIZ728IN=oBkUMHHSTb$uaN6aiRjUL?<9uE6c zHraAcuhXeNDu)whWAFBNV^(O@I>jvzI_1adL8N!Gfi}4A9KDp8BxO9g9AQM)|HcD$ zd}2abqS$HOA&@-EU|CItC(!G*CKKT4%kiVHz1;%kYf3xr|c&MxSrp(cR+EeX-+bXYlj# zs1_SmE`R45EYyWxWi4xMV{_wKjL!1{CDYSpH2vwxo{sQsRQ21JlRzmr&8QO zQbc$$N|A1#JEuN9O|X2p`03Y$dF3&s#yO}29nPi(Nfd1rbRFLkyswJbrqUV^#biu^ zC2Z)Pp#@em>qVPv@J_gMbd;IP%L?m{tUZo6t*QGGN`!Y2AQCN7YBM&sY0lh6O~d5B zQB%*KvDRS+%=z^G@-u4&j&3=*y$j6(g zShu%cp63Ctt=3y;_72D;6Z2_C9Cel~OjhgxBq`~LMk}j}2)ybU5VdtK8vnET%N3Fp z{|FoV@xv`RC+Sl4BgG|4CmSpa+R@P84?hG@pnEK)TW_E}0W|vFGcj6ESCzTmV%wQI z42h%$qh`rx^kAD2^K*Zg$ikE)&WwaeEPk%dxcd@c13f>FfxYXnbqo>;ciZ>W*)d{M z*M4JK!<1Bg&-5reMI-1lSR6-7bG?ViKpq@>_yxO49Kqr+(gE^kC-8txIg91bOh1j2 z>K}UtgG2B6ef#q>x9`^t?ibkDz?)6v!g3JP^G39!&zUe32sE<9NLLxWzac_?cG4bt zrtZsH6e(61g`$fPGI3s0x0!s=Z-)z0AYT;CW!`q?)McZ^n00?{_B}+_zh(e;dj0Oz zTC+uKc^RR(`{F4o%t8&Kf+6!mZ?A_=^In&{FdIu6oasM%`Zms;gUY~-L0^4rj|Hy4Q>dP9=lUe= z{&x=FtskY_{pM5VL+bDB+*I&_Po_-78S+UJrHi-RDW|$e;Hvq2c5D5nzB1>NUpUoW zd_TZ^9AK9y6kwTpAqh_>3CC%CoqQ`{{H|`PxpjraqtEXUdwVR|I!_!SEt}Jut$Vbn ziLz2EtI_gzu&Q^Y5Q9WRgsv`mRcj?l_T#or4c^Cb>PZA{IvcGLLi{tkadUyf1L8zKxPkBg93miT!Klm0X=O`6m1ytv?oj|;D>9~07@bmXTP zV_vJn$aN03I5-FpUp)K+ftvuSSQEM8w_fUb1T1TS29+W!=13jfpw>>L6^@>cW8GL( zLqGrcV9NWa4L9*>E0Da#k1{-X8`;1Gy*$z?F3yD?lk|tE3tiB9RTU0|IL*`*%B6W` z&kUq6;oyl=V=IDn6TAsFLLZw6T*9$78+E;f-m&y?(jx_+r749en5QBd5sdV(=o*|+ z*lQyZBT!C>z0hy-I~2pqMZ(>2aAzm!g$?;s9DuXbVeP^=NrI8KD!h~mj<;Ch60-G% zr=@_&zZH%j&vTg|hwM)<^liwT!dtp-Pmhc3Mxr&_9uR@XP7|INK0*%&-j&Z#XAX{_ z=QMATnxhfD@`<WW@9%u^|CahjrKd=^+~#$52~^Yk0w@L4yiy-V5Cu&6 zBUGu~LUqV?bm~lfj8KVaV`gs)*=x2P%vP zj-KyzdfPYq;URm$CTu#j_+BC3vleomrvuE0m0Z)~r0TMNWVVS9OSj#hU^{Y#0L~vV zv7~l$xc(5Nbvl2sB^S~0Y{dPxz5mW*CzL^sRm6PWZI+yi{`=3pHPcre@YB_VQ{b=G zc4;1%8k2sULA!6_As6xC4zClxVVOT**0|~8-WP^g__!;(8ra+kkY9ZdaeXovwX~cCsi0q^xMS@8ssCJq{V;^(@w!67M;8URx zvzJ)tvEfpe6G$}3`FI}9k9T9b-ASqj0WSztI-j~unO$I{oamZ|8h%WA%WQjcjUeK>etDI&8dm!cY{j_t+=PRH$f&V} z$VusYU$m~kbU5{G;l;#MJaRTt47Gj4`1HwU%(ljTEgzP17SwL(w9!$H=-H^X;Uc&N z_=`KiQAtg7ay+l%>ygLCKE{cYF&?;IJOkxu1M7;2OgA86ri(}twtQR*&t<&lY-Euk zwo1IQzV~`Z($eA(GYnPQ$621;cEa%C!v4SqAX0v;fHO+A8g(-mH7_QT8>o=m3ib({ zv9vmr*@6m3-Kc+o&@$jf4wfc{qW5H%!-zk3G@9Nr=w2V{G?D9c5mh!6<=ZYC*Z2$I zI=|;hh422tm#cZ6coiO*PYvzbdfL&WFMeL`_fTeKAh4vw^*GZvxUo{5395O^?4mDQ zDtlMpLJRxaj5>^A-;82tP$wB7f%^!+!=%OE2kjsq(u6k0t8#389#@So{<$0G+Aj1r zqlG${yEGsbZ%;7&tuvHjCsZLpl}+8khvjtYIP$>Fg_1+KrhpGMmMF!K_umKm@aq-+ zE-BIt8QVkU*ihftz>s4_Eu*En^Q?-?a74$7J$VM6S0#-okrV-1U;@UXq+gzvO$u7j zL%r7Jhp#|6kbma)pvn7H#O?j#y|OB6#^m_)|WV4#(cH{YT=lthOSV>N&tqtm=g{;+F({`StQ#tx_ScOJH% z+|xGly>(MFKZ!UHs`S9)9kBjByFf8ZjlMHXT||(3x_M%evB%1-A6{yB&2aL%gMNJ^6(3EYY|8#eE{1neMC9jW7F?LZ z##&*LX~o?Rr&-D{E%H|}4JBoBdxVu5Pe>XulWqzOqm&fgP9h5na>v`qq{VeSyl1by zcLIR*JO-Fc=D!cB>F##Pq5G+e<$`Oh(=#87nN{(fc#4~9x^IICO_|X$+_!?o+1fI6 zp(Bx!ncaRxV)fGS2K{!E%j8)r+bhrKvE`Bk+%1ao!+*6Ow&yhDWX$4KEPYb?;gy~AW$JW*;sHXP~ec7PKmGD zy?j<-Xa>eop9+-?%8#^DF_)1dUth@oD=7l_x#&p=;ir3pXd`jM3MF;m;jYR2*}wEK zja|K6+ju?d!?HQYf^t8`^^z3Ghe+tBSqW|mB?9!GSqT+k?G^Z zA92Vk#)oDrNnAAcm$q}~_+QC+tF=u_QWEF|3=+(y5hIn~&4aR4q=g5lirHN!hu_uz zPEoH}rnY%C4fSjLmeKJ1Y1^QlB14z|zRxBjUlm!48VXVpp;9C(tB`Pm_(CgfSa2|` zWrp}bU=Zd1ITnB0Gt<(kcQEuKH;zbZl4{ZcY-8l-4Txp&aQ85b;6iW0^Sg(A5Fx;y z!ZuUEL~s%K>juBHv}{<)KvFuM^MF(UZ)sbh*fVJ~IA<<#8zfv9!38@uD3hkLI~&h( zIS^=Wezv{Ax$`=oxcb~vQ9LnQG}b_tNijWmh<*DjO?QVjgqf*E3}0lB{#H%MmZ6#w zKbZe{=(82Q!4|}iV!&iMsor;+wJ{=G@3_c>AJNr$n@(b)IT~8+& z(=;KGukDsP*7hlI4gaMp=vCWCrM429S%(Ku zN+YY2(q%4Hj`$asu(^ON1AQc@kg)%0#eB`9b5Jwq^^E4>u{DBzb>G@3Gq8cjDDrEe zbw~na!fzBe`VerT;Hy=PaZRkt`4%$pSg2jZ(78-)<^280KxsY& zCW)2)O8P-$`O{Q1I+9=^7{_y)Cttw1;r{%(3lLP7WOO%5=wnE9-rf={*W?`Qvx7B% zi|X>FdE9aW%#5Y2E)IP?;9}@^9~pjUwDrc1pgC`MLz#)A*iHp)j!T|-T;g}UzP)xD z!GoXpvr!bTZw=p?wK~{@&wxd0pKQxyIqrglpLviR<6Uarf7MdyqsY{y>X;z2{o(*C zDA@iHpL^|q-5%SlL`N?%W%RdZmiFA#u-#}PFF6}BG>Yxqe>IAES(nHPZ2eNfN5M>}(vh6AZNPE>f9c&NmYzZl{7CFM3iG0_aT>N4BR{TNO)5Q%9&4b z+9b%0bDEfbJp#il4<6-5eGmKB-+s25nCf(^n8hOLKEHG@18pZzD8em&P*gxFCdOk!t* zJgrjFSi}gf{&a*_#y%7I!3mn5){-z_$jFQW0watf3~|q-> z8NqGh~@3ibj6wM@vw#BiYQJj4;N9;uWmF%s-yZci`;+_^tU#XY8JzXi!w-$a^0 z)qL*8e{GzwKH0{A74xU4A%+$QB@PwMA5vneLc*M$~C1z8E1yheL}Q z_Qf5RF)+Cx!i0OnI<5ax6^{-*=4Ky7@Lm)Rs*S}q&9c6}iBN)pm*<;4*9RSYeZi>mehxB)5@aUciE<-XhOktME%kS5rOE=VMwek36evq=bWC?>&pv|c6+ zIfrEO$8ecofq)6h;FeL@T{l`r_>|?eO`60;ihq(=oyIPUO>{mkL&p$93bHZS3(9hf$xV>Ap2%gM3y))B9`suI0(B~czZ#L% zhtfd~<@_Q8FbrWk?iwN@Tqlf3aG0L3->l-($+J}?u;C6Z);7=n;&ZI|4a)}0 zxOIOM5ecC%VI<}R>in$Tq0s0Nd}SFr+=(?4xC$M&g)o5e!kI-?U6TL{ZO{pOS$r&I zJ?7~A6>GDP7=Ox-&z=%-fP=U9F{W`ft0J(cKXd_UM?^G?NN_8+uP@b^*CodN3aBF~ zl!@x*Z2XA2`!xs^)^BHt*){#`8lHv#&xybjIO+;{K!HV|Yyt>b3I%R`yHEID3o+_?Pxx#j(?QPBDOe8V#l z!;DD6J+p4?=;1~|Ce7J8x7ojgyBCvOor9iD$%5dH)l41ZU}DzS&Coc#eH5ikVn!NrhLnpOOpsx64Kv&yEa8Y` zPljcL!!#tobZ>}hf%UR~rFH4}(%P!KV-2gi%`PJhW8HyP$^0<{*g-;`x;c0nKfQZ_SbEeeI-dn2s_|`Pb6WPC?jy=obCi3 z@)pt1AwqV%`*pc)YHAd5&YvM|3UgM;gAC=T%+DS_qL80d(1eLSV<_ZG;&B@39S8E4 zqqrXAh%n3c4QJNJ*Bs`NR5x=@&il1+Rl?YU5;Jr&YgA`t6O$CRgNS$?47!VWNG)Kt zf=GfwFYo<`#|UiWi-XmEy;yXIj_5G`MB(C$BP7kXou_=MmQFw1Kx|SF{Bd(VBh%Bl z;5-723xY}wj9-6kuCqIFxAv4P@mgf;4BSE$SZr}lO>vgcCRbG0*0&EY;qes4dJ2-K zL}(gMtGA81cy+Ju2{g}4EOylNte4$C6mbg_vrq8vg6v6nZ-rvM$|)fCbXrrwNb&^} z`g|h_;hz@KS;nHp1^=8ZXj2uox4_zJmSezegT4uYZ-R*6s@K29y)EjqO!m{9$vVtx z^(PAG8ikx1r5wj_Nwo_2VXnzoJKmo@%z)FaM!5R&i$n$=1`&^f7tm#_RP!@`V}``0 ztC^8j2iE{w$DoFeankb*T^e+T#q}Jwk{^hVKidA|nY6)Tt_ujK&P0FT5#dwZ<3jbe zWMo3V$zE<@7a@>hL3SA?mZih3*n}hb6O;)B6bt{DikfPaEac&%+Dq0@&eBC8Q^OF- z|51uqIi<9?mTt==nm^cwB=;Xm%c}m}jlufgN4RuvX{R@Mce=%`O*F4R@O_AO(319J zThpu1N9KhlWCg*7D+d&0I=nj&y|2IYF=sMwFrr9@l#EdXnq7PY69N*1@_-+@>3jAr z9^24DVjP6lu2PJ!(MG!Wo^j;iA36uF(eUiduo4f}t$vMw**@?;Pxr1R4# z@E-U{6RV}ReKX8yR%l4J$nLrqvm?&hJmTo~gY@d)7VZ)Wk4g0M7UM`LIsmTXZ&uBF z`p}-~$75p-gpEzqqERYs6!D^?xWF|J$7QaZWe18ecJU@;flCZGE}QPULN2EJBZa745Oeufl>R8O#97Z(JwX)^kCs#%eW;NlnUzIQktP$)1b*vP>?ZO zRt=5HCWF9Y-h$lvjODhL z%Zp!k$A$tx`6$3vI%7JJ-cz>t_k%yud%Cw9s{F`Fypi8=3F+$#=ca+@=HQ>a1YTnp zg5dIbn>%;?SGiV!tT8Q*Qa3IAmWdxvGCjJK2vy?NDmKcDbI8R#yW-O`YKXUGVlj2v z?#Y}6_!^g`1&kNAoSi}Y(T9iB9oFR96};MtrouUh6KehQOS6=G|2?2U3l`8fi-Q?$uOxj@r@OS zkr>LOf1A!XBXX&>xc&&ef95&4wSSJgLv&7N4Sct0=6A;0?l4xM@(^SkL&u+v$Cc|e zwQ}979K(52vJ`)v#-xIP6iEym>`9B%uoB6eCMMfm0vBX?zz@EQ(VUX256cPT#C*DV zp{Rb|`uIDtB%nj6lqAIgbANVqDa_J%J{MGK^bpvglB?iYnYjsryvARVse5aMIZOS5 zgS4{qs<&(zXu(##^slz0z8cKCQz zTMwcHvR*z5$Mo3WomG8j$_V1CAx%VB)9DXj*|7f-)wzhxLDeV*lz*1!M##NPIwOj- zRGz)k1LtsBJa1UyLZ3c8j+08$xm?ANLhgDThq=R4dU_6^6cs7(06ztVTSjW_W>ZY8 zu(=wrvN0(ZBQ$DlB#sA)L+A$u;n{s(oeu5q*w7o2j1>|n*eJ@qg+M|A3RKXWy^AH1 zq?%70!A~GY7*`2um>|^lIfO3(1=7*EqKV9Ju%Sf$^ezH!cL-8~f^^ucA^sYslM)Q_ zl7dg|^w}XkK0a6JR<$4@pG09^lW0@2u&(p`*%PwgY)FbhLWB|w^K3+t`tt((H&F+V zDWqFX<(MYZ5cB8h%UXr>=ZluW??P2MKJHTn01(ACspMdHl<^LdA4#!Hwk8vKV-)eH z^&;UyAiYJ_t5=o(j&fuglHuy7nK@<5YqTXRN}pCM>2!|k1`nJd)^XukBvtuv6UHl} zp4u<&U4ag&VI+YJ2y;5GwAqJiz`aRUq_KItQhPobV@kMcoxHWp$|(YG-qbe5aAnrP zbapNYjmgv@DU_q#l$it;({<$L1Su4k&liwF(e|JE)tPX*7-5?_eSt>i` zw}S-@B_$yxxH_`3@*=WdK;;o{TEk_?b4|2xW=DeDGl#548O5fcT!wEki3Pl_Zaq^% zRm`ibv%Ac5a#VT2U`V}cg(f$Q<5Sz2B$78=3UzVPAY;3J+z=5~pqogKH^DOm$blBNMvYkIo~3ZRoNGC}Lsr zlmwr}k&mTo+t3*%*)Kgl>xFrQzT}OKkEyM$K_!t%DypHBpkNV8275%BRE%WROwiVf z!rv`6TOb)KTp6iSQXv-&(4~}TV{Y&qT`!Ly29d(t%`Y`x(w%#(7nIV_d)=}xOpMp4 zdR3v&zpdq(WCqCO&8zS1G=Ut(i>Ik1=WZTtkTK?Dn^0S}OPTG$INl=0f8SRr-X~XC zZh+_@`Ucq#^MrGE4`J`hUA+0zl4{a;Os1jJnb^xlb`XRfh5mb>ntjpE^=w#0y^{!j zD(!9mO(4E!45?Mo&MaIypqp*huw*8kB%51h8}qyTsB6Lm+dW?K z4zNrlW0JPsE0JP!^Bz8o9oHjgrjNa6z5TUsV>`< z7rOmda9!2bTFdmW%%nu(^cCCqSjLV%REb>Y-v~Y1QoGtKl#;^o7!0`PTPn#}Z(%tC zqyo82%LP4j^u{?5=pUS|EWKFL7_L#sna4w1ZH(SFnZ}Do?2s5MZ2V)dBNikA&pMf} zStDJWapn~w4h7@SCy`Cn7lfYAp+Vo6tSL}J<~r0TFd|7GPH~a61gRFtY4XEZ;DZa1 zz_){lT&5MtfO+HRj0iB9E~5*+!X%%p>TX|4KaLq8KJf6!ZbWzbJytR7*dkG!e-AA_@q>?0E;w2TV)%0 zU&A!hMV?Sx$Q`_pk4Ew!794OY`@OT2y(pfTd~>h|O9~S7XDM@tfxBL+pE0Zc^f^7c zJw}-MG)|&Accke&SvjLIqeU&Fz#LPpRk2^m0kcrMgrFScGwus3Nd%?(NWOg4)Xoa> z`+=nCJwcD8^dAK7-cD|~4Ypat3bhUBo<~V7>$SEG^>;;O*rmjp?Ylf(fhb^wne%^@ zz9{ezY9D7b`$?sS?10o)X>A@$26^$9i+$=>j9Oln0Eu{PJBhenOy$Jp9lI0HTb%S6 z%$NQ0D)$$Sb#9IU^C?%jE*ioS*=ZtT(ND-Q0s@a`8Q>GaAVo=15iwAf^MwrvbU2^= z#_9cSlNIp=lu+n3<)wQD;-iVkV|6<1u@Qy99lJX1Zz?QeNg&q&=Q!4WXu?|eV8%Q2 zGs~*o`Jy;;%rR_1Dggyt$?);nipfc^I-mSPvBehYqkWq9f9leD4XHeXJocadGp)soI%I~!>w7Z{fzstrLcN;%3J8{1z z!SgKrskBWWQL4CXuo{z_NS-(}M2aQh?wN`jQpOjzFx(4C+8b%CD=wnQ6ANHr&s#XB z|AGV+8Y(YNd}Sk&lUh{LU8*ocL?Y=CfRs7KNIWi|A_%tdc*IODib#tMliW`tb&YJ* zaY-GY<`$t%tvLib_2jD6E&?eTXqHzY)wD3PIIF^;p7UY|Kp2CC*<0Z;c$FPmoCZ;QJqf`Lnfk zNRSF3+#Z@#C|qKz-Ra+YE06SvTe3X-?Y6o zvRG@nm+e@W_3*`qVtx&6l5jY2@5V}>RVGvGl)nZwRAg@6NO-Sae_>Y#haOOP5CnbCDx{(P~ zxb!Cr>}o}OxCt*JEQX{zNwlP)JUI##RPfMZZRMCB;|=<)t9@CVY5T8e!Ov|tj(|GD zNdT=~1d_M|Dip%@6#4|TNKIH;LX?E?&2pBR1NOawo7a0uWLw}JdoMN+{lU0s_;g3= z{yb&m&TdTabc<>Aa>8!rkho>n+{3wi4vwYe*=vNiu@^c;S;|AtxmMkW+I0}nU_DzyV{FTZIg12;+Nk&SU_F{#psLdC40Fw4r)ad;e23TS( zBCRAn5~b`cXI8tX*}wO!7w}7G^5ir$o2o7)fEYY*Idux6^?nz>OSLz0Ze(X7amtR^ zwmu;GZpjQ!mzCJGMqzJ+-C&<1Lhc&Q=lu6(G>=kP@pJ{5+jhrI{;VOea?=TU{r7 zZ2hr6tCOiDi0TpJ_aY5`ll%g)f^F&E71;5Lw(j;H$Fk`9%l=!$u^FsXe8vqV_qNRL zctz`U9HXSjRuWl6kUPB9tl{~3;p*ef{qqqZBq78Ssnjw&0SHCLzg=35U)9)6|Jt65 z=1ZVIv_CkdjjA-d%_WJOg6l_~Lq7LSeP z+Yjc-!*tLho^_)`VoSr>#bcS|9Ry^oRAxE^OXKA#d}kLGYaJTO6{yPehZq#+yR1zlRVdOl8CaXh%gu^9ogy2Oz?DxT z-1n4V&7^#XBLbuGib-3lJdvGJK^dkS{$ze?;y}Rtnnd881k)={45sz*2vA+G(MmVo z7M5%dIIUru_hR+#V4_)EsX_`El0eKqIPU(P(DS}`0o2k@DxSc%|9SoYQ(we<$65a0 z-d2R?4>F4SgfR2^sm)h|xgp@ET0w1Ne=xz~gmd7~bW$(Yq}92#^`xO!PLx5G8D?^H z;cQYa9f!b-0$tuf%g2uS@&BE{F}@;6uwz@U?addq=zk}^v-eP`N^e&Om{}2*=o;VWvMSMmqiLexgp9r(=?iBo5DFp-YCbkEQ|a66ls|dfPgwo*Y|U zuWTWf8K!)gZ6AV;?jO=^g)zi*qS%Okarx2^jVMCS{+LpbT>Pe^yyGHS6M%zThKXl) z%@&%Pw6XUew63HACB#60>o-4_Rw*I<8Ksu;(NRv(q`;z<6M-!B2zW|0_jrW7=a9RL z0WrLWEzeNf8dgP#H-i3UgS;t8A|WJDtsZ1yd=TOj0utg=o=+wrnv-;C%>VVrAeH3% zP;a#i#m0Qy8Uj)Sy>8LODdWy>^pL*Pm&UzPw8CcPA!r2+-W;-`d==YmguY8|H60(k!d{^6a%5d;6S%^1R?X%8$EG_|rIUQ3`l|}%zWWI! z@sMma<Q4|x_l0)4Z+vk!}gl}4Nm_4D#n_`$P^jGF^W z#EL&CLP6(*@6iL`a4;gReWAOJ(_hwO^rv$`MGKJ+Au;)#g+4y9;?MEavC<`k&5u#pl&g1Xau6WgRS^zg~aJ|Y2J4svz(uaU(CM@5LQIDHt2rSQcGb7=9$ zuq8&a7008UGU}?bK4!utP%Qm&DX(i4;OFifkr`t(M&s7oCiPsUsHGbx-po z_tPGthf2;wu}Dc$ea+CsVvuM}FV`+p?L7a41H+JWD+|{2`g36lsY-Ekoc^DGJV>{9 zRv9PCTxHdj!coojXfI@RA_6J3Wp?kXZhEz9A)T8KQeuWDo{74?B@^KguhP8AMx!_y zSPw0*HTtpfns?D35v&z8?@#F0 zEn|K12f5ZZh?Dh)U+~<|QSb{+jU4ijwFHVyqE(9d+Ax<85GSWMLESqBcy%As)J#C= z{WA#2bWucQsu(<`^{>QZkL|LHI8Fbc?^{M0Sz;bL}jvtJ1eWAL9H%2i`q z9VCSG@FBzRCfZ0VoKG>LF4P_7&Hi|#+`sN9fphe~y245;E32Yaun}{)YC?xOm79 z>?2+k;!Dc_W0UhsSDPIyWR9JojAA#(7h&MX8W06N9O3x8o6IQ7sO>DM`z1gtLzU~; z(z1GrW{kXIjLwz;^Pa=Vhs%60)h7HIzEp@6P>^JjcRtgX%US&$fIH!bjI1Ca$He#z zdf?%O%W=V~W^L>OYQM?z6cbH~Nu>xqPe=&87sid^bhML-$tFQD*=(Lndf;X@ZV_H2 z4aOc6xftf(^J?E2dl8xm(fM>;MFL)L`0x#I2Sy4ZrG+j}WlXBXsho7P5ZWy8mY z$B^{sm-6-J_by1!l6sPG<#I)W@1PAe@#f&t_A-uDxSln$J^m1kc9y;RObqajG4kj( ztuuSVQ{As#pH>&;4v3iMr<3x~Dlw$d{V_~;32vL{NlB5qhmuUt5tNP_^9dBV1TVR| z50PoYL~P;2Frysd4|*9IBg9_}GD|+@6nqr0-g~D+^uDm$<*K+E1KOeP7vEcL6JaP8Iz-xj9a7T8rjTR z&Z<)+QgZlzP-kHQ7>;;BS#Q_0o5!S79rv%q+iE(WAd@=On1NIp&(I-TY8tcfb>47( z%7m$Bu)iUk#@wK-!_jxNraz-HmUCo8u39bRYQ%qTs~fXdU+f2dhU4Z^m=Xxlt2W7!I~M9 z`yDsP0bc(KLryz3I330)DmvrGC>oR-MF#c79ex8Ik^wZoy1y^;75;gPXK@ybjZ%Cd zz6s`|g&U&pDOy#r4pOvJ|a3-QA907=- zBya-V-#YL6!-ToO+n7(=sOkaN$k(-&)mEEKI3%H!*WoOH(B?jL0dC4&wmI*2@_Y$rV2-5{nz5 ziWde_r7#Zc821vCRnqjz^YpkzfGc9XW*>R@B{@m6LVmq<2K2&xG7MZ}!;2aBvU!cu zJ<|G{WULU^#EE;l83VJRxJP%1EO3g;!XQb}(cQg5E}GKD82lD`@mH-D&%KMZ_-$n#o=!XnIlujz}))_vUS5i%gB0=!Ri_Xe122U`^DjsGj_Wv|Gji+&H}>1NDRst{;Vb@RA3bgC zrRyM&kPtxmJ5=%=Ii3G5ZxKH@LN*@~rwWUWQoDTvgB%Gt@MK=LvH5BkS>_p{F{YQ& z?Cy3yEan|G^-9um+@P{?LMviV-w>3`^LlQC3h`qN!klOI&$urr94Pb{BYAVb9hd86 zSPcHFbt*^ZnxUPQ2+dDgJGg-C%UgF;0Y{N1Yks%1!gkwuGpn|-7M`ZTJ_cCZsiaCC zV#6Z~7ya*z>(+mc+>1l&AB zt~v645p?6FPi|~%pJhmIIutQd9E2#dr*bPn#h7F+RStB~W>;dehNH}zE;9(p5%FfJ zfESd?z<|Tt5$|CH%~+Tg1UyR82(l9=-z~1KZ)?MNtLyd9(T49%+}Y(zh~{GWuHgt} z|HyM?Y{of?h`9cJ9rPPtKD1eho&&?SHvQ+IPn}eJd`a*h%^Q{p@&dxE)*t0%lg8y! z7H+@g#djWmoyrmnS^VyYI<12{KBh{^@GF+2y9!d+^fuDP1W|d#A9WE=pmaf?^b$;< zRJoEMO9))y8fj|q>{}TC1&0WP;l`z1fAo`f2;5sHFRAYm%MUFSn_$5tg(RBGpVu6i z{2bySLZkF$08&un)2$mx_^=OPQW%@WIwVqqO#~^L5UmfEjed~AE4TCXDlUW&fsS)p z<8dF9TRD6rv7H?Yl9Z z&5sj3_d9(>fZz+!tU{pj)(INO^Fqz*iaNa1uspwkoP|3(f?BH==+lgNzRvv?>hb(a z?ZoYx$e|ZpJhf|HZf98*p*WXGEqM>E4?Py6ypcqkdTQ(LmWi{(tN6Lz;txgWVA$6tnTDJ8@!7(dZ?AXIs8s6@ zAyp!Ky?3GzGV)q(yG!(Uo)?T)^G>NZt%rk)q^^Cui`NbZ;{~dtbd+_|k;digjpPJ- z__Fe<9Og@1KK!nGdfFIape5Ul>;!dPA~aal(~0rf%?Rwtbm#oH2P5rjzQJ0+BWE))Ym#oMcW_iae%&PV zAHw#_#M0x9fMo^@Ys$`#&pZ6SS0Eu(;~}4xYgX-5AkHaIU3phIHhZSH-3FLb)VAF< zy5xz81cfa#^V0=zyno6gV}y_qVy4kT@)wi{<|^i&B{?6p#pyHz8!EEOK}DhXfec@D zDZh8#m4`YB)#LX(N~jS1@!AIQbL~`)Ko7Xcfv{)4Zj)(ad1HmKK2Rlh9c_ddT>>>p z_QHwkrQ+#gW38HRs#h-p{4q@OEn~xni7vON_)i=Vy&WB6nU3&_9j|cbFIAFd3Wc|! zc4;N4tP>pHNWXs>>%X%P`<+Ee+^baIX%|9CkaowmzHWFw&b%VbB~&F*qEJ-vyQ;pv zzyAozOap=m_6vkC_G)|I`1+?O&`c8@T?G!t7BlnTW!3e|SsD#fAwkymBInwHsSD?} zlbH-d4!`fnnVDJGYO1@Kekc4+VyG8C931K7-22Bk&~q$n;m(+|8=(O(iST-NbWOLBFt$HbG_~i1 zm89J7-xm;#4j6S?NlSxa6U9j@bD$m}HjV!C#4UOr1u8C}RVGJ=d{cms#KA-b+p9J{tX2~ z1shQcT!No3r=s$&?dVE{7Oz{efMjA~OOh9r2>lnV28R?mC4SGPm3$t^C61=9vrDG( z4yA#ck~GZXGuOeLBY@dgohAscUI5Gcz`mYJgN1B^{!FJ zpTY{X!4%Q5e7#;kK0WpH{w;pvbpY>SjdW#oXxU!VHMG>~EiH4GqS;8UEVal*;snpu z_TFRtG0|(kO$`Yy7An28<4>7#UnQlfZRb$>#KVKHnmfCt&EGPr@>b7?_@RN-VFIC8 z$QoASaa*x72M7_v-WlMk=u_G#j;vAqZGdRcYes&}YrI?mz9_3s%$GdV#M?b~C1$GO zOK#sbjWalpY3p$^>S7GyqncR-NR*}1pEi*uhfg;Uz?bA*!EvL*Wy03=nA1$bIuxOSr?rnZG`LW%TMDu^icNkB53_0sC}1S^_te<)~tGlq1s-kf<+r~Pg}7_v81t}O5#=%Sf6$}w zXhZu*cq<8A3}U%3OM0dDN$z=`J-2lwBZr{~DG z?O(B7UPdJ^gm2cWxp(1~U&Py`2Zc~dJ-llw-jqBY8Fid(N8cVV^=01fg#+ITTf9rj z?8_bLT&6;m!LnWDn-iNJ0{rqt@~$yVJG!lREnYV>--0vK&uy#PX=kFCaIOK(BD6t4 zp=juk3&cdP$H?dHinj!o1(=lb2x>_ExxQodKdpvx#%5`36p+T&kECeI7D_gP{MGju zD-Bk5+r~dyA5p{OQ47u3n;kMn&M2@d_VR>$OUz!`j&LU24F>{Y0tg8#z-n583(e3+ zDktm&>oJ{6scBg3phWp(86_kG`oRNQ_`lQe0i+&`)8tS^gU;S->}9H0Gl5LtvP|>7 z-M9^3)0+`1p*Tpyy%hT0zCL47Jr-+5+h~w;`QVqeeA_(-YRh>2eBLPs#!t2;)_Xv( z9*pA`T&U|XXOML^7D^2_<)cNP!MkI_&ghyFSHDLfR2?1K!uQqWMZ{vA6STY}k4HCMv?urvOVi)+wQJJT(AOs?>-JV^^zD-W3owt$7L9du}u z>P(YE{H0sLvwb;V*K|bVtb;@!u%edTXzuP~fyW4kzz*{o7#QIC>%_g)^M4WcmSIsw zUElYm2+~TYNHcUdlG5D_9YYMA0+IsKIdpfIlr%_pHwXwrBOu-Io_gKS{XE~^uXAuP zaqhkL+H3vS@4s&MZJrG}SKd~eXC|VKHC9JSA&VMb^h>L(KFw`e6V2V8ZAO8#TC7m5 ztFEI7pU9PD^}DJDB1mjb^$7J-gV-G6VT4->H3;oRbMQ6~`1%0Uz|E3Twn2<|J8H>w z%ua?F6sA--m#bT8O#c#m<>>ahHAws^@3jsJbNiyJsfdxvtPsY*+~_5kWznazp2fg94?eR>+H@FlDI8V9Ubn1uAGFfK<~LYARAkUR??RwK0b^Mu z1)HF3LAp!)x;HlbsqIv2e{MeNxM&1#VXs=O5Tad1;(jlMxF$9V^A`i@dwvD9? zyjFVU6`B|qC**;EOJ7=<@c~CbBv*83UI0`3Ne-pnECQl%JopD+WLQ|}OeBbzewa1M zh6Weq)HYZI6PM#@zw~zC~MzgJt2A zkf7N2xcJ-cH6eW#tBr2C@?_%TAcnc3kPcot;Vcf~$W%824s=|y$US_QY>&nKT?vSw z#vvX= zsS0L0rSb;6rOiV9!|miz-T_0g@o=nM2xY6Az!6ebsp$h4lFW4Qe#C2moN7e=#Z9-0 zB4nm#o;rcan1_TjZI?^Ew9!53SY`^ zX^PeuF=eeKSb7D^$tt+GKXLqOBdM8pmk7R6zp`!!FTI-D6+VT0e9MC}!tlKp;e%j& z>V)g0r4H)155#k*+y>q*MuR{MVe%CJx483OIZs1|U6(CS2I+FX%z(|tG)t}Ckm+p^ z$+G3TFPb^{iEmZZe*PShJl@FecKP}nW4mKYMoi37t6Rj;L?eGFDr^%vK}CUr*JnMc zD>AY(4;`;2)M4eaJA=kzN#Qm6B%N1324s_A5?x6>9A47LXWDpQ*(a{syPo!z&$7BZ znrAsYcRGk-zs$9^3J#~Fiw){k6;ImsuYU_UC(1vKJk^)vv}<9G=*iFEP?CWM)lTLD z7;pY34}gWkK7mer2&nwv!g?NG^7v<4(`}X1P1*a_9}`wi$($5{oWqkoknJ0zBB`bX zZeKT)105wVL&r_k4K5#Xec!wwZ2HYTa6uwatT(-6rqP zU&~OPf5*SV>8}gbsiew4vLmT~pBkb-rWp1>@#vfV*@4oJY@nIaCh4Rl?;ce z^j=kssWsnO@<5`eICeA< z>5-$Q`;XP!VD~$2miEu73oP~DeBVCJ(MXcv+zycbyz#$&K3Db@7)#kz_98=(WoNh6 z%V;iBU$n91zF@T(?}$N0m;>j!Twxe`9i}Y(30-~i^5$8zJXy}Z>2YXrJ>WT9CEhI~ zPCDCEo1~_Q<;EDBRM|$RM+G{COk=qT^e}&89<#mT(L^M}{4TBCpowVtaB7NZoME;6 zQ8U=2CEpp**8qje+UeSoA&#NDfMV@;dM4HBqxv2WPOT5Rg z_^7ammD+>BIG}U-x;5dDc79n+V<-mkJb=x3lZ+jnF!-K>uc;?fuoakabL2~5pV6&o zf553Kabsu+W*7^Va=(38^@GEGx+VpB^cwIq6#D_-Gas$Ae_lQbQkuuh5K~#nBt-=Y zDOK!R*XZ|KADvLHBSmVdDNuK)p~2L+u00gdrSyiZ68cckZdoH&1oYD)6n2jl)w_zQY)aBO~b-R472br z%agmVzD5PTl#*Wg`LreQ-aCtG{4wqMwli}>e?(N_4dJ`rfA+gF_HO)b76dCgcgX1| z9?30}bZ60{>=UbN(w@Jl6})}VNqV_Rv^APJQju9})w*!A8f9?zx}4N?+_?~3JczLQ zgc9QQA(~dxR9$Srx%O9VAYAZgi)TojzLX zrNP<&R_tdOlNs3n#5_y|*HuyaGaoB25%!hHZqK#wR-IYm!>q_@=kpy?W*J~+#CLOH zhM9-{{EMaWTDxW#hBsvy3mGkB2wp3yV$fNChHf>(l$DXAk8649hYpIt)m6r0Pha2p z{dgKjvDsBWU}>T>clI9b8uD)kE6Hoc7UBj-T-mRg?jEPam*#vr7D~6&TGFY6556g~ z_eF$aZD?zLsj`58#S`z64SHe5w*;08HbtG>-M1N26UnkWt?1cyJm8B6F6O@9ihS}2iHE2E zy!rJ;<3MqK*>51-GR;=YaPr5kyci4hgy!2I5fE> zqy1L$V^(jkstl3*D4e|qI#^Hv*X0(_eD@fK(L@ugi7O$={^KdQT02Pv0yt{LCz1oM z+;6RZx*rP_XGDcQ_^MiMXMe@+7X))2H(ZSBS6;=jEh)#dV4?q=D4FPaXM}^mV3AmrTk8b^Y z9?{pK@G36wHX2Fc0L2T`TJ-P))g5|I-B?Ssa~kl}Bre97vuBf#FYxT;vv@^P3a?-% zNwrLa`ENTH@;m){*^-@5D1KV*M&}g&$6OX{k+27nin?nqZ}Tl0DV;-2YqK?e=#h|e zA?9jiIU8nuLVH|`?RvuMTsod=J;!>lnQq(W8un?PD4z9_EGD@{&`C&Z#guEGNRZuYt0GIWB&I7QsSg?b%PYM1tceNmUhm znp$cqYLu?z&1#^G#wIS_V{2RMwvSq@&5%*Ko<9B#XQeWC1Sy1$DtO9Y?EMy3A?THE zUDyVnRe}lxXm`L0f}mjqRsb@jl<`_u*?S}b(LC#Ih)Xvcbtp&eCNv-Z5?r#E^wpdw zB{(>i3=m_5QR3~TDOMW#Cr__j^Yf!1M_@8Hiq-AsAcyu4#h=DH!6e3V*Q}@6FswgG zX|PXz{fJfg(f1=gfsArN9u43iE-TfdeVt)RBzbDi;sH*;^?ZSdCV_ujUS|pu&DitE ztgCM+wz9RI;?|i>OTt&06Ro{wKe-BJQC+7@%pdT=V#RWy1tda0}n9TeiEx^6Ba3hTh%uEHuP3(q{ zNwov`Ne>Wl&g7|8tGVDYanqvpU)&=EG>JCYa9MLRDB-EgPZ@m4-T4SccM?lG-LpK3 zWBRF0LmwzqJct%9BKU{tZy`9s>~F2)wH%PGqWav?QAK;PTLU`z=P{8#htHSE`qN!W zoqV;gwj^U{#zYrp3;*0xP}zVi;>T09oA2rnXyG`Yir+i(rm`Kpt7-Kb{I!XSauqmL z>3}9H1?(F=F8idjP%dKjOyUa#!n>EPHq&e0CKHgsQ*VLGRw3?EBst;CVL8Z2Dh*nZ zV$J(5hr-o2@{Zlri1XMSF1MPMwkj+vq8uJTzF;N`J*^c>TjoIbsNe|k?M z(SQDXf4-+SaHG=s?jXJGXxkN9S;?xx`S>Tlk~^a-<3!EGsu}YA3aO!Ah)CPHaQ2ZRUy87~YP~6?_Js33P~Eug z$20t3Fu*w%Lb;4h4(D1SOe8MU=Xml??rAspTpHA-X4bHhXGgynnHqv{_ZZ7o!+yv( zYpuzoUOXti17{aYi_>K}(v3=Yv?Af}3S8R>x)GZ!;qVK6b!MJ(m)AV(& z@e!|#D&D?#JFab72(%l7a2a3!uq4}-308#vl+@Dy5;AcE$$o@KLakkP=G153A)I&c z*c*90IcyCaT-~y9)SBi1&IuVE-F@0`JZ^Vh(Hv7|dZlU`>Y6t|+nX*Vpi{m;6;(r1 ziiI-3Bu3T9Y|{fb5wAinv5eyF*WkB+W+0y)vFjB|N5qmt#Qwa+i#$xG5wC-6ad zFA!o~ZY340p>!G&Fbx&03o9;-XjxW6niI$3(B+}pyF@Wd?AC*u8VWxK@Vt=;pm^N z+ZbC0wTSjleL&YxEI;1MVzGQRu{woWuXRl;fie@y5GsrI$Se@xlCW2xEV7a4sUW;+ z=I%GRMlM-ZRok*`T)BP5=ZD=__Ny{$_h-4lmBk>RcMFOdjGMY#($X%`e(a<6R`o3t zN^TjlW`L=}-Wz`Yw6{ZeX$^SGl}OQL-<|l?`YBCbhvu0Tjx?G;6?kyIvhS>f8P4g`Da88J{m4X zb`xZxqy{3qWJs#YS#LyU7zv<6Nx``0Z#(CIZzQsDL!C3pnDL#*!_J_G36sC$_VwB$ zmnExVkI5to=!;L;Rlc-h}>hJ=v3^clm;4soK6eTd*VvRgk?B#vd7f%M&! zp8Av?Sz;nf^i@h!6c;)1NuB#4j{QVB1S7FwOkmusH=FuP1qdXbBS&tDVxAT6Wb`S8 znxb?Vev-;WL4*pEp*PF!)gD@9>9#XPHb1?E{byB@*N)UcYQp=0i)K)x;Ed?=4?L{> zwu#fsLvLS7U0-qX`^6m3LG_r&o={KV;vHCbGb*k~Pj)0V#hPqIc-4>uC&Er!( z$)gSf)}+qE&T&;GCB(I7h2APbqUsvdvatj-&?I$X2sRDw7ZoyAehoZyZn{jQkF~NE zXcuK)Kd<-Zrr;N8cj1!5LL>bZVDwv-i{V4+;Y(Npf`BoCQjm`N+wWs?Bad=8=l4^L z@0JrWkI+Os?Hu5KlwlD$2O5wY9*!>8<)|8 z-?9;ohMKY|pe?Az4#)0WjS7Vh(YymUI_jfI;0b-B(@0XW*g`C5u3el|H^((!vUC9w zF4nBSoulOVLfo!|J*${gK2wGRTYFoza?PommV}g-!=ZfdI5CS!r7%cYw`*s2McjiG z287|%0~p@@?PNW0;pwz5u`ZkOD?fdn8{6FNMnC=B+V*=gYHFF=s<_;4j-aGTK|~Km znUOI+5>FRu9Xs7%50o9QSA*@C(MsQ6bQ4qcNHL1T9!Y*1-TV7_Ib^#&T2{0_T|e|7 zM%}6N_TD+Q`m8CZ(iP-?z;y5#Zm?PT9UfuZafar5dR^_*0o`by1j``FN=`*eW_Q*P z4E;)h|DklTOH9^JOnVW59R8OQmzR@>V^R0w3G}PU)@8ivnq^oLGc97S1EhJ*MSr>QFUw6oZWnm1+BGQC@yfEk zc3m^ka7>u+m^ zCsD3FSg!`lI%x8hCu(VSUMTkI%Ih05hxgvXmpVR2miq0V!x#-h z!ms9*D;x;EP(wlCVY#V`MY1|jwUc_N8&LRmUXN}UP13~Gl-A~EniDH+*sExS&f76< zpQ7o>PN|GCaL@HfAc4iyw+1?KYF`D1nWhky1qh%GZAxg-!YPYyHJrh$#q*m(Xu8@Gch34*Vfhhfon6K_m?g!HxHPPF zIahD0!#Yi^2v_nWE*_*gJTHy!yXZovkkT9%(?GX|c{dXU>Ta)OSF&%8vRsX0QoR9F zd-Se`lSUW9(x$8^4+#e*n(2l~liR`f@Iv7pf7zF^)tlTx6~r>N0hApZ;ODAXIs9|~ z=-hq6GEp2NH35s+6*Kpfw<6~yD|p13Z{(2^_{h)iBP}SXI?3aMBc)iv^|}n2dkf3C zDI3DpptYN2DQ~JP!e5GKQ!9oBg`1`lwuDo3SZ;a%AxZ@GZ~2K+6(8`ujSX^n*myCp z0tn%nC#Ga5wU}+Ga+ypYnuE+kL#DHh;h%~azb?-UI?jWnoZBkKq;-Akc z;LzyzUKNcD8aDXhM8SR_Sq!B6=E#H^snJ|l@}+`xl|nJ^N6n%Z`Nu5ObMq8X zytAi3;#Fx}f_An&9~p&Q8zoom)VTC@G4RZ9lY|h^=!RxROzOR&Cf1()(?b|K?y)=X z_DR~Di)61!?(=*|24!HuWqeIaf%9?!E>|xtm8xsj8cy^`{Y=KH@((c$8-~i-CAWVQ zv1C|JR}jY-)+YjHelS`T)dW}pe<70!1{z#8ZvZ&<#Os)t3?!8ira`7@-yCs$Hr+f? zJikzD1nG5Y3e4&!FF!_%)%x2?@x4hwqCw$SkSMkeqOOY-gS{z5#npcVa`gMEu&redi!J%C<3wUHaIA(Ri!R6XX$yr+|A8=7hi}c6&N8Hk3z3tLu#sn? zr&1%9+HW+oXc4L3um|!{j#5L$^b7cOm-D!X1G8&A24;fzltS|p)U<$hbdScZVVSQi z(pExdE0f>0PIm2dfjj1#^zGVDL!2tG z0Zt1*bS?Zu_1>U!=stUOYgsVc$S4qf=+`uU51PyALPKuYs|xA6H!wbjy#1&x~M z3^EGgGZ7l!*VicoH^yxWpLz_svfzXZWEP3fDbVK=sj@+68Asb`v+{%zu<4i;*davC zput@iBx!`5VWRp5byrsus*C+w^*b|+W`n}j(ws7O=niMZ%lk0S!V5xrst*N*SVzgMKhVHz59`R$*QMh=J%lnr+`OYsig za9JDPu%q^MUA1JiTo4}}lW-aOd>sqFz2vrC%HY~_sdZ02MuE}pT`a#9_V(#s$^wOOgOb3;(mT1nTL&wOTrc< z^Q9Rr-8;APZ7tTnyw^v=s1e4jYJHzjHny4(y6{Ep;Sa|pC< zje_$HdPZ}R;M`Fmbp>?^`3Js>eT9mjWT$F3SHh4ZgFT(EUg3 zk#92N!CsWB99{9HL2UQJpYbW>=9on~`!4eOoi%CA`4CWmmvPLMY)~!KntLlwn~HeT zF6_%@E+C(J%dcOj;zm-wsd~wf5*!c^bP_1x^-Pv{djQGGLuMiWA6rtm_V-S z%S&kWAL8$f5;um?iWCO(*x{?nH^1Q%9?$3Ove)J;hRxl2td*0W8V2TveOhIZ=YAYz zZD;5f6XAgl4VE?GSn;_*s?ZweC+@Whdze@GA|n}|f$zt_-;!p*e5k3>MUjBchwRH1 zr$Ab6J#WdF$;>9n*)=3qfoUb*(ET)n-UOFzZ(^_v-w1>5LmCIG%wwzvF^n49Sy6&# z_BDQCgjvz6_!n?!jOqq^8lQp%-bFujo`vU|mJ5evU}bQ`V<^zDCB%-Ax|!iO$%-E) zs_S|YHYes#46(}`AmHziIgXmLjT8~uv5JK)9ab2vZAC)OWQ6yrEemuBmEKjhkI$D$ zkEv5AhtlEfm`D}zf}776Fu03y`_S(j7uPwzG2mMYA*xTsnj=aiH+L!;31{QPNWJnz zi4K{uRhye*UH$q3_jRB3bXhuje2^1|37aBRfQI{AR{UdxO@=fI94eksni3vlxAts+ zKM>TFF=Z^nM#RCYpCB6_XJQQ5p-O7}eWlvy8a?6!L>cIWI{0}O>Uu``Gi8(CsB!sw z-n{IG^Xu5nv&^%RzL`3Szjkl-S}C%S!^K0>!y7!H+`g8tG>A1v>3K?Eqn~2LD~n>d zQs@85^0$O{{;!0GfGy5lV@<1Nmw4HE<4q%jU7MF%LY#+={OBLQPvO-X5*eW`v#Mzw z91b3p3Glx)mPuPmkOI_;1GYbR$Gb>HY@JoDn$npSP~`RvgH-XXP`Av3L^816|8{ZZ z$}!^E=VLLb79FCTHWue2;fxpPJ?B4tGWb+|GD*@`V39etjMUPM>u01amUS~4+zRw~ ze1tnZdsjWbR%SmYBpdPfY=3`xcj78PSoUR=|LZD$-#jmAr5A>4wb=PZd`2s|ELu0A zv+TepMdGl2O%8%~`g~ z9qOiWv`7ke5{Gqzc>7B4OmASE#*+9PNk#n!r2q;z(Dx_gDCbKkx_brgyslzTo5>Cy zH76>6CEqI2?&vh?Eo?SP!by_FhRJQ(E?4dwjaF>5qp$+Upbn~_M8i|`(YYbmk{o9O z4NiU2Pq&t&N=XQkl`>42*i=71f+6nEOArs^bY_97o)Mlxhn?0SziC$~%5fd!T zU9!zsHLg5Tos;`Wgf;q7Djt1l<=1Q>nr&6ftIpfbrPNHv`a>t3##ptOGP|7Cm(toD zxPIp1X`_4xuY*#5lxje^44Cfk3nG&Nd6AhZP)7D103r8vl~&Gx*Uj1ZH}3AAzp#o6 zqq#Sq4q=`*aJmY<6Veou!+F?G$Pe_9`f6Nc?@aBsv}ikH02m0rt+yV}OM0n-j#Is4 z>SGh1-}>RW?cVP+Ju_%%%HaDOx(mkSNo!4Fxi6%>)cF*?Cn@niy3STA3YmGTzFR5M zesubBU1It~bFIVIG=8`8+xw30>HNBJQF~m?53sm+B+<(N*N`a)K6Fu-@sVMGySX`z z@1%dfF|)|)`P?vUflyE9{RwxV#}J&qM96VW6GZ2A5s#!*s(RZ`k`lj*5>IZy!5WGd z)q;@Z^vsUv+2N7gAILt_VOs@ZI6x8fkqK_qnG(tWh*eltPBFs3b3(Vz}d{o#1RvQTy6oT6Qt)&4`i z+Q@X3(-DyQ#1KUlD+Hz}oH;U*N%8x$BU4ZThIOt#WVBEiQG@@KP^`+wGx^7ciR_kS z$H7${=5_R3R6AknEcsTnjECqf$n(43P0lPt5DFQD_TDXWLxl5|-e%;;cg!tGi zQ!wa9%0(zC_T4L4e}3QdJIL`wLfG^A+MC#IXr8ftVyC`XIstyz=F&c)YFO;_L}S=o z-(@i)$;i27>MxQ$MIsBS3N*1^RFVau1yzt!hX(uff5iPNJy*kCaBq0wD$XHd;$DWW zmapniqcu|^1a|qa&gYmZxkkRj?6`sbj}|~#MzZ!v{8SLHaD961g{;qzh_res(1PlT z`}URkU3*Zf5XE=QrImQciE8K1KAGop*u@8?HE;c3)+Y1w;LbDN$>>GW0jnXbl^Fyj zjjsm>3=P(J#Y{takSSBsNjh2U$YA{Y*9^mjX!Y}Hwjji`Vl&qDG-(wz2-cKU`q6~& zPR|?r8ojD%0k5yx>%L)?MS%~?d*i69iDpF`p*=S#?ePCdbC+mzY`kEC|8*hp zu03o!dwg2u&mtA1LZGGyz?Fqkk6~oRRZA>wYqQ*U)|Y$RCHq(ki4jAkG;#=I&32FD z;p1NSlIqx;FTTn8|G3kLWA#6FxkBNye7>s7Y8b2~ngJOnSyAhT)#m!#`$f zAda*}&a`#EVRgvq=Vt z;ulWeAy^Pda}-<)I%{_zhsX$>{!Mq$X1?sTWINKHVQp3WFX+E{Gj21Vd4kZFYFf0G+|NE==k`q~#tt^YPBz(9=m9g}eL z0%u@fiZKzpHp7kOybdFQ#t5Qxoe$+XNmf%wPSAlhAy$SYR(ot;QiE#8s_(}e3^s{CYU@F>3|03D`KTT2 zfCf_~JZRfv(2BznpD|$t!+S*(Jc`neomA!X=#slk_$hN-E@a=k>%p=AbS<{%@S84! zS(%ZOc&6mmP$YRosK)CGVj6?{i?v!IA!sd^9=5e&TNIMWlY9CWU_jt^Lg7wkS7+2{ z)!@be4%VYLOGlDRi!J5{=jIU8wiM;S;uV8O`*Ea9f~QM11d$3|#e!mjgCB(wWEqLA z@EBI*^_wir<}nGGsqiDH$S$$DIu+gQB1V!YYIWU9pZ0&Z4T{pM91(9zA&yzsO@FgG za8o!!Pd^XvwqhI6bS+m{s)KsG_iM&qk`0-Ff1r)$cbV(aTgq7~nd0g!SPHSoNz#Va z)7oN4zY2UYvme^-l&l7iXtDPdPl{Kz+)@=c(b?NZZ8`G3drUIlipLs}?4Gt#S^pgP zzJh6q?drzw$t_#fA=|D~YM})7nI#FT%87ecL9WQ*%*7=ky@1EXOqHU%|Nb%s59#}^ zD)Ul_>_=i7P}0}Swjhz>;MMlg#Kw2SA!bN$njzP8xDL(Ci0in~=FfQs5=Kq^#CS9= zqFDSC!^E>P+4hw}bsLpy*NQqzD4IJGa75e^?KKy99&!$vF5a>~NL3 z3c6|$dlWsri)q3V5A6itBUz=c{HAU0=`p_N*FPgCu(;MY{d^5fn(M~8#y(;ZvFz#k!L84X3W~nM~q*e{TU(9wRnwhArQ~ zmO`98;yr;DfEv$67KtprSArB>T(|d*jr8lNDUQ2&gjC;;35noGVfYY?OBHlZ}EOJO_lk7}Fr^LUvZZdYIB~MCrhwtZVO&jgCRUofdUQ@Z8bl5XlA$RphmqDT6{N?o}RLePcYuF z$JJT(N*9rd;RsWbj6L)!1wG{AmVp8Yaj^iuMSG!HRW&!Zz|hQY)u+xP68$()~< z(})S2rvi*V2@VX2@uF)m(@wlbm!g-Q{c(*hSI9qd8u~PqP^g?_sB*NC z3Ny%H>t_SAR`nJrILe$Pr6s`Y^xd!?do={H+1ezP_B+(r+k2yQkn-%*2Q!%S7!d=Q zhng2;=CKjjSzvwy=58Bh0K?^eTn*g%HgdfSqP|9tY8lzUjOJ(51;hIn)rNa2Gidc7 z+8FV0A!)nJ!Wy-0Th5R4T~1eNl6e?_vIZUV!gBbmMm@#4jdmZu8q(;ZIP*TeCUg*RIB0S$5Y0Drlzqo4|8 z)$*mPAU0^!0)h5Z2+Sxiw=4$l;Xf+e8s*{*?fp_nOZgN-&I*3lp~DvM=AIOC?s3NY z{%GqgF{qBqgS1cvG(_;Y&iE)WC}H}Nmkc*!nC1(8RgonNpD&UT@=7Hgeorwpsw%vr zA!c8`jg7GaE-i9zM9Ckru54dZ-Avq zUUjYSEh<5EhUFZhya6_2jxN4ZzP!Qpo>qCve1IuOp&&DxVy4RFV!g)F`8A#ACytZT zKV)wl)_w)1dy(z|^~f{sr-RH9+nZk*)+#LI6Eg5vM`7b8ulP59&(dq1PCq(s1sse% z>DcYZ2x4sL<>l{_ZA+zpvg{Yij%DC4gTrS9W}_zRub$;lLHLFZUrmVpW&Kc3A#xd- zgEz20mN$gK%8d`(jruuXb~fh(T`%w|>_cFdFy5pJyHPNb7t>gPIJ@H^hAqLYw?Z4~ zl;F?pjjG{1r?9a(4ldFR>vSovkAiCa^W1D7TsxJ@3pP3v%C`_>vA(j8NJj7QKr1U| z42=p+M0R>HSNkrwdB*!eSE21DQfx8E^7N8R1;5T2L&EJ%>v^FFN34P@k`y!gZE}GP zYEeqX;tj{}0(!ke_TOWvw5Y)wzmnb!Ya%d*hwXmoZx8vIF0Qtg)1F$lq31D&bTr3f zX8zI2W-BQ~-CpIBkQ}Sc@Q_(8wXx8`#7$(Ufw_G%kRsm3{3^m*d0||>$Z2GfE zN_m-Xf3~qOP8ERr2!tCR4PBwzHedkBDa932%YG!pFGvm7=1@IL;R@IJh+1ZE45s~V zm*+E=m7Xkv6|Hk|>~hHa{DbwG@7GSj@b>eC$RBvQUR%wvS!uENoQU#JK7CJSOw;p5 z=UL42pNWSn-`*GL`j6F51WyBu&F5)?ON4jT4 zX=n|BJJV5(J0IPGjjf#QI#OM&ua}M4cIF4iWxP+UvS-G+13wrR+lvDA zt(68ea~IXi)wf_tvA6+hS*Z;CoK!$|ms_sW3B zQaRzcEKxyjxs~Kct`##rzF${a(WaG?wv~?diW01pdF14B9L{5++;*fhy|dgG$qj8a zgM)QJAcY}SRabLT*a~+1Qz%)vsyzp#E_zsbs6>_jf0^jq7VBytW$^S=$P$ zdHPJL*9bexuKE0uaq+uE;3NP!2gQ#2NOwMHF@qAn;lFlD)*5qs_Git&es#^fz~PsX z)s%3ZRJ-ca#b~{yxR@%2!om+%`C`|2hVUX&f&S7ld2Ik^#ZK?@{bI^>Qt|a}1ZF$i zH^q48B^m{dfV=?cG603M_uBg&;x0FEZK^Vbjy86KB%eJj%L`G5Ul@964*V%I`et1L zCmK&~3&spK>~4H{pgG8lwz8ngjVE!@*Jh;pzn-LFBJaqTVUz`fgAbo8p zA>G4{sXBUCNnAAGvgUemJZ;KIygPdoMvScAS{>ONF)0cbM#sOUS6D(^q*ny7zzq*S zA|zxz%&JNbe@Unltt?5eqJgvGJ0F$!7qG(&y`c>9u$62hPrKqgF6R^uP)jqx95tAmnmLaC)n%IWj;mp@&< z#eYDV`mT7zSm*n#A^95`&8a|e+exPqAy(0%jF7d#&`G$1l$gU*S(Qlzf-4P^Lu#2uUyA?@Nt#e z+p9L9Ww`b`ISe}9lc|>c>Tn5G>g$hx_{TOpE&Tg6J6<5NISrS)9?@P#5%$$ik=_JH z_~M>sIJOPsdo?z>7_-+-oR15N?08cRWc+qKbno0~Us?Gn7-?m=XWYuO#@qg1cRhj> zE^jPxZ?m#0Gd@iF(nvFKiud`OWNIA_k_$dQKGWE;f<#R2nIALE8Z!e8%%iU2Lf*YS zkN#a;B2gife}C-LZdf9)c-28NJ%}5wy?-2&yM#<(D|_4AJS}cK%WJ$HAzaZY7V5P5 zSTzmNW-B^n0aXlJY0)O2lD+`y6i#ARrL-|)pYssffB!AuFXhog9C3^N)Oqw~4=bjs zbK)@{>po5b@D|VRD4enTd$%Kf6(sgCLqb)kU$LA4@GD=$+~*)ie%Za9AuiA6hNq~i z0&EgQO-7Z_!RgRGZ&}>J|1s6PasJ1OqgAFL#$iQb>W(dNPI4}ZjSl`vszfw_5CBo~ zc8s}y?>#tn=)R;UdO@g}8V>F*{RHmxPGoin$fTnN%Ncr~CF6-AN>aUs2}#Ry*6I%n z|6}lUg#X>e@v0gs%nFU+MkA$C2uafP(1guT#7({^^4wE$ip%K)Ls1Mzgwq2kel1ZO zNu_SY39wMBygd4YA^lEe5C{|=Knemrdt$uGKZ8Yzj=zh&7e`Hu)g;-q3^l0d-S_-h zu+^mD$#jW!jmEp;4%yO1bYABPxHOsU@2?2QG4PiKNNh0YVB(~^TeooAvwP>3DmWiz z)=91vg9&y#J|aI5?BfdgCGCy(XohLt3~(szzxZdE*_Hy?1~7kHxL=tt!-^z=17C3V zQB=?UsS_SC8P4y{*=I_*islpe%^B?id)Xm?$pC5z+|Vj*(B9`m)M{5MpWC#mc&j9( z5FhzjH>dxFNi2-Pd{iy!^1DO>H6!394Qxdt$-fb*bjwLWD7!9YB1|LXC->lhv_gJl zscyGYH2+#hPbSHm#Wx%Q50IEO0`>m@Q_q{TT3}_;-*sf^QFvMlyhI<_L+T_jV`A9h zq&D-GY-2;eF&lYnBP1E^YNlp3iA8Hg zOYJ|tHd4Vds*!!ObF4~Q!c3N$lESmJms(&j{DrCG)t#7U^Xxa8Yz+Z9e@Yw-x0d^~ z`PJR%<+1+D5Y<)-->fNeK%wX@1~#jea86@q&l<=wqlrt;Eo~L)QVLP|tAlPRc#D4D zxx1uM`MF8jp){5tXP@}%hB~xz^1#)ql_6Ne=il${O#?)f|6yuj$BNVc-e!e|MI)mtLz2GFKcd+U z=HIZK0ecx9Nu9!Wbab{iZ%0O^$d|!1L?BT#lA%&Qxf zU;OSsbDjqvYVRa5r!xAccMb9b-}DSOodnoN0TBc6ERl09Od~sLMoY4nTsQ(IrDy4fN^_G z6i{)~qRaNJJf-3+w>-t7!|eriz6Vw^mZ<#?7Ej}EuvH4N_FpLSysh@A`xKT~Bj(v4 z-v~2f#H#ZU!(|Fnd$;=C38<}Fg>)VJkgfX2bgIaXFjuHW>9SFP$5TVtDOkoLssZ(O zdE2y#6Nc=6pPBMM_LVCLbq`aiL1Lg(-9VL%6it0-(2|N)+UIj%Xw#?E%LdJ=dgla> zehxXEUZT3S51#}7vrHz^{!NPc-RAX`$G66wF0uHEPr)wc?-wSsE~);R<=z@{^N+W#yX58}U1b3ILn6z78M&#!rDTV&&pf9t+j97A^*bo1nZdTIYkhVX<2}}mwc*OLq zN_@%}cmk%t6EVi?0qg5-(ZAN$*k>S08S9&Ef%I~+s_*1F(S%W!kqGZcuB>>uKx(xL z@o)bH$Wz>Z$Ght`5xC8meR12^J^B8gvww$nYz)J&{g)Xn6>T6&yUE9_V8~R!wvcJ+ zf@3=eEALiiIngaO3nCL6zOQuDf49dCI0OuAq?;>u;9yt(rQV61K;)aPk}+c zXa?I%&8Z$LOn{%um0F|1Q}gJidzE0tV}g$~%21wSo?Voc8`(c9P1QdVThROkN=x`? z_dQv&HjyE{>bBy2(cg5W_xi85YVSUXLuOaus@mn`(GPy|^t9mJL@*=&VOjBw-pG^& zVnbW^oeiGhV;6rOh!)ih+x6!a>YUuyTGX_>d>f?TGBu```1y$OvWUgjx%~Zgz6Jk+ zz`FeZ>^BO7+Kdanwe_8~N1!igfsV82^`9KGChjx>Yc501KV|={uXCq0`1Fj5^{RiB z5jPujSG(=iBeax;Ri;47cky+&|B63;I>Dt|1D#JP#GU+ zq~7f+6Cz5^P1?Pw*2vX3b4(273Rm(~x^`s7ScOW8ltSTs$XKDD}HGBFZ#~|>tDY4-FwRNY!AWr`pq-R^KR$QU++Z@;?JG5 z)cG=X16~ex-bv%G_FHAZ0mj+L#1nk|kH{k=-o6j^|Iu`oL3wmdyA25v+}+*%#w`SQ zcXxLP4hin=65QP#g5Eg69fG^NpLyO>UlsqUf|S7v=#8=I_xo5;_mwA z>gwk^h-!%l-CFMT9!tZ(&ZGlNZby~4`hQOh{Qqvgy0YfjS#67*WUe+Z?@S4I_cTH2 zkvF6Xc88lu|CgTY&DY1zLV_wo|EaHe#{BvclymliO8NT%lp$37uRDw26^X4jVm=SlTa_=4FKB5+OjyhB6Gz`b*A$rO*Sw!^wl=Yw#A(j8+xfVO z^YZ+=mv|YErZe}>cF|!h_xi?)fAdd2sKqUv-JxeBc7q=*y*!l46^z162t0{l)VcZA zNI%>n?_?Zq`lo}=&QPC1!E5K6I~&CQgAVN+coTGciye)==r`dCOaMexSV>LQ)%B0F zuKZ*~#@vb9$^=rhc49I<-yS#Jf`NWR(cQ*2I|dp+>v7+e@k738(kA!H_}Sv?Zq}! zA~ovO<@PtcQvZ7`aMdL0PUaT$cV?QxK5Ad$rcd>dHu#Kh zF9ifWTExm$wr#=vY~>)kvm|*ojBjAa%sH-d)zu2nqJ6FB4$~rXsOSx=L?pqY%Cte) z@zm#tEC7#=f7;;UkRz-uURJ&3R=$K)g7$t5jPw56bO+FvmE2lJs%mgzzZkxViOkC} zEcVWEM5X4dSN`Ouj3LXXAr%AHGBB))0w&Js2nG`UTkaJe!?a{2`V&j@RP*Jbw-tIk zD6!vhOfU!!Ez9di?CdKbOqdSk!56HUha$CI46AQA#X+>CA;8k3=FqJF0;Z=lzd*h_ zi;;toqJHR|{g;Y!V;}20A?ge;q)PJjvl{O@A}_sOyS(tT;+9|M)P;uXu}zKBQ5Erx zhJ*cI+OpjSR>TKhnZZBS+(`&`gYA-3z#;VCF|06nX`?#T*=Hm4!UOY0`BnhY!^^#Y zIeGCEXi(hI9g&wYH=iY!uLgnB)m^gZCyZVY+6C4R?|>ftX;LKBH2X8yp;o4?aHSZj(-XBcMJ#k+H&`be(6cXET-9qs*x?_O76xk<{gs%o-aS0DF1 z?KpwnQ#s zd;T@$t9YjUNT0fbQMouk=`cwF(t4hfhVHa#s;54o9mvROIC2rnnQ8?ja^xwAlu8Nl z0-*{QWn&@s>g(Y2Mkcs5AQv)0PL;02Z!EK}00yIJ4BAV_=} z@_yiHgnyl(xS=?>vWf?DsIDa*y)M%~d&x6$U9>MT{E)_G{Vc|cdS zmJnHFPBR#^>?&GA9B0G0rW`Fj0{#oaz(ANaG4qZ7K3z))BePhz9ErkA3y5NmFo67f z!Vtt5iD?}|ctIS61}zAEjFT0#SGZ~dv5V`eABPFozGuio)NPY*6X65l>i}#ENVIwX zj&$gjYsIPUauM|~`4hMfY`;$k&7OiRE31^dG>i9+O8n5uafrm1i;Wg&#c;*)jQ#Ax z3vy}L0AZ*u!&fXBEF;kb`rYyvD?aX+z>_8J=9ml%Q>Sk%ISmNk1Gq_PouV!eZ-?aR0UjX%K#o~j&i87y>{I# zoQ_()jFUjV=OGFnC=V|ZV+fV7-Q*~H!7Eiegw7sDrousn_#lNd_xb_d# z+u4o{%wb?aVXXhLtW+Y7Nh2g;ITzY(-8JIU_HZM7bNL99hc+2XB--hMu|@u}eNA_E z&%0hPb~M7Z9>J{ojR;*X7WY(WdvY>MO3`o?YHK@g<5#5BQ)`NRfvJ(umGTL=w|YAN zHzUpF+fU(-IFYe}`Ab$rL<5aaiOx;JZOH7R$%7q{hJPdyGvrhU-Ik4Hb=Ke`Q<*1UksFpDWYRP zt&ElVyrbb4H}*>w7mkt`ZF#t!-jzWtbgCLmE_ohsvq?SAY_96AA!L2N{@@8b zeKwPJ|G*dGx8MHnAAbEX$kYTwL`{(wmqR*2yEWB%+jr3c%aeBJejb?*?zzrem`vSm zQtm&py<6;Ed`rN>b;1Q&J2UP6%4C_7QdknFg!fDMCk%H;HEw#^dn&quYKW>WV)Lcj zSaCX7(|&zdWE4ywVDPiBOrIs>pvIQF(%9Tx$vN{oD(-ZT!sm&7W-Ynr7ma#rcW;zk^7e~Kh7`m z8X`KBz@H-q^C06GWmR)VIVxO_NHJXLhO^vstvaKis*F(dq%v(24^tk7hD#^rh9pEl7Q-nT;DzWZU6!$5JO#pl3g!z|o{U+8tVNfz^RMkypLTsJPlPSO zP#Eyq>cn5|8pkK?KzotU0-aL;xE|_#%8hg!F)DpV3*P{2hW3m;ol69PRqmgCo4xUu zLV`cc3T*2!sKDbeG9fPb4QfTYF0?On%-^9pQMO%yDnmhHewqQfrA^$zZeV4LGj;=? zO-46jk{7$Cb2PnJL5h)NY9ya$%l6OJyU34+jUBE~@OVJa9=OKN(d|uV37x8&9BA4W zZx%OS;c58aUMvgg&)~~Gt&4t2xBR~>z!qw#`{quUbaHeP=l$vdt)1F$FNJXp!ocU` zFHmZ#^LwV61c;qOezF zuB!FgLIZmFAYXiROtFUASG=Z4JbE3AbQ)4W^_{iM8poqPxU+=s{7Xg$?}YY(Yb6$X zW<_m%ZB0z`W>MvBOJ_f8+X1=GlS}A>E04)E@Tv=$7FXtTa9VmSfHmF~POMb^G_oSV zXA{h&nekh&!G1-D0ayLC*SHeE+uh&~COM^B5d?ut3X2u3R8H-||=J9Z?phVkWO4St;qD z5o=^5Ett6|ACJ?%N~S_D-ESSk-e?8-otphy%Af17 zD}XgcLE3DcBxBZ2Nw^bi>2sT<2>L6Nlwo6QX$My#U8J9XeDaS@GdfM&bbFp)%|RKt z@(?FQ!lvpM*AY75!y)ngVG<&5@{GZTOHNz~?N#oSB@wHt@2hsQ^Kzc)h(4gIIQZ`g z5t~MEt&yI0Yqc~lmC6bAw`AqgAM}24cvKMbPmClaeo^R&V+=Ra}>)d#HNB0qk*DZeN<}G?=6ThEYbo%BE4hpG>rgPqxhwF@|6J9vE za_`f04!2b}+}tbpk0P%sKF`7x?{BMW9R22KRae#WoSF5o_d4c9LiL(hfpCYd$tH z`BlB7_f*U}9)r|-{I86v-AlJulA{zu`s>Dw9i=I-X%o}?zb>&K@%22wk+r!c?mHke!&2RV!qiEt?E^ zWG9Sfg!Vdib6E`fD#=mMoEI533M*MT+kUWb=9@5tnAkjm?AVYSp)R-=UFZWr(`3$bIp{cIm09^)iC@o?ELWM%0BG zgbqEOX2K_{Dr>#o-8P<1d}E&30SB=z@pCxB&>9< zOs8h``qWjEcZ8(hCfvnpl7wA)6)@;JKKv;nZO?ebm?#m0lS8fFS*_7SzA=qG6AUSa zIa^=Wp3}8r5Jw5o>-x>#KXW~hRU$Ddf3CQrZgR*gReoe(MsV4=J9ilHg-T(783HLu zdCT)maBF4R5mvzspoN(@(C?W|R>fmI=_*EWuRXWqmlq3XLeQu zVdzOL&Lv*qSa~^bNl#BB;IF#Xx?;Y~O*H}(J@A7bfl45Sso-xENH^!TScAnh1|61k zNQN(puGpLIwUtwTO*ujDAh@sQ|o%ubi-!_Xe8wQRUEpL4m>Pjs_|+HU|@u-tRJ{coSlETW4G>Q_2nv)z4FRT1Yw ztc>U)diet~+bk4vY~OzQjQH@BaK+$&F{S76u(_a5Hz!FW!u!)Y|K>?bCPH-qT?9>1 zN#6wx0lZ`dadO0UhUtw?Nt}b-Q|E_;nn%M$qY~r%U7mK8p(;1cRqftufpIc%*e?kr zhUvSa&9O!+NplMNB(y)%o;?0sZ7{t^kncB;2TY?9zs+v;A9E~hK0mxZ2=Vk=55A9e zuaZ%PQxOQQZ8>7FgY&%4;jkC<_pDPA%Bl4z)SM&8N`MLlgfQ`kMGhg*f%G50#0=$C zBltWplz)ZT@ox@lC`7QzP~}3I2I1UZn4!n`6*onbc2YZbtMeI5mX&8?4}dQyFE?z% zYK9QULt&y~*pB<;_^ByucosL(Of;#~P>1_>z|*pLq8QRs*7W4d+VeW|)5`|{k#IK& z07+r7f4CEA0OsxY6MT%HHd=4a4DH8WD%ezqYDcZvRZZm7SE0F{W_OH}-o&{dd<_ zS*70S9Q3>+b9&rDWb`hee9`GjGlKPwYrT%}94ysVjO1UN*rx^k`6A47I}o)`PHZ_R zVrxJ`U<}0h+p869?w3H~t9#3Vf_|tEFaObvcSify`_#(jF%UkYpI4sr#B@&wI=Y+~ z2cj%^;BN{r^v4h{w33duqG;fWyo&Nn%ln~D8yX6F_D&NM#sdc_$;Pjm3V-7!VkJ}v zzk@UP4UVud@;`3kSzfeA;%l6;wk*Q5PK?r>Wn~~NqWQ~!y;`GK!`)gOl7NkIH6kq% zhdGcEXq}-sYVmMx3HWlQZ4l?H636w9f5=`uGoD`v{Yz=;OTN+59V@oUNlJrmxcZpd z@Z}hBGK2m7(Xl{;O2kG^*+`*95veAiH`_HU(7^8S(%ii1X18c-;XR=425bE}NVahD zZ(q|&=%IiYTmC3*b2|fFU3_y*ixMJ8$K?6-aN^Max;+A;F7}!W@r=Z?uLc zyrJd}4+tx@9?lQSGJ`Y{%_mIjHu<2ARma9CY5-f3a#au$jqrm`>z=p9Ct|rAdwlMktuQyNNn+o(! zkmldARmu|Tl2ZleU9V6ty^_^h#cS5tL_MOl?*6XJ&zW~=6Aa{82ix+M@*mVD|0R3tWr?KNred#F|mp&$&NVivfZ48hf41(9sETp(ueIM)g7Ym z^aI<=^26rK4T_XKS2B4ns$XwMqsVm77?E+J#0lhF2IS!N7*LAI&H43(htX#Y2etye z*L*$3{hH+;h8#Q(fDXc@fwLu!!!c!RIg3@xq)U_A?+X717viZCN=df***uqbfocgs zuy;pP;1qY8%kb5i{~mJ{6Nf`~^bq1)b>K^T%7-Ybu#zGIq8J)VJ@`o1>U%sKWFqdE zr>w4ZYo=Ra>BwPqgsM0Ix5l8ZaIJ70appHWIta6aY1tf7{OuxwN%7a3y9-Yq`Nt%8 zCmS)hCkA==6KuQ~cv+tN#QO_xcIMyM2tdo9_#U3v~j|mZk&l_2h&#B@dyi<}E^!bze zg6w(7S>`@DEwC8SOLX&VfMkmHI_tXQh1bVF;8T4Bh4iqeFe;XWK)7grM@Ro?3xMF z;?uo-hN%7jMJ@|= z7`*-xYUNnqaeLPTd1HQEu~ASCXXbc0HBVEV(ix>CdUftMv1G4&-Q&w>Pzz! zg=9sN#xpd9QOYS>K`KHKq=D zdK*QUNPsMfk`2hqci{(<^LsWD-$|+mGwKLsqB*#K!M_ikHu5XkS2Ou|GgC47(Vgx{ zvF;Ub?S0eFN%dhgel|H;yws5)2+rtcXN1)T+B>839G&gqq+entI_f91T~b5q!qVh< za49LAgh{z^tkD%xo@lW+{ihQ?ZBuG8wV&ojz`j>OjA=v3- z=ILiSJh@DB5pZ(zS9zj;SnxB3qB!C~!Lmx-YyC`0C~=~wWv27YEi^Qv;0xa(veazG7^qZiP5Rkh{jW|n2lYO$ zFw&6HTa=R#r3E;QD>j+8oe+14wEg|Q_YZ1FZh?DSaazUXO}v#Y_`oa-yK_4=o>H)3 zM*!)^!;%oUS;n{L2zLGD>)MPH+p{c_2D8~8zYWU8QA{BVeyuj6;Gv~)R+Co3RgRZ1 z^d-r%mbLJLPKXdYVoEy{14zP#W8tk|LBBOG7_|fx>Bp$4J}PYXYWyEMcTiMKtK@C; zfc!@TfBWz7YC(HuGWt1QMo3me=QPyGRE7hH0ET=HS%fJuHPJ#gsz~4Beu(~GQ~aO0 z=6h`xuZ}s}AMsY;b_K7Tho=KWPYDrth?v78)B=-I$pc7CS{AJAPHP*M3#=-ZraC|r z@Po&HH&JLKe|mV0Ye<-w=S8TW{5_v@vL&pC>UI2Mi@O~OUA_3HB7LqAEjWpPBHR~M z3-tGH9-Qlz~#pIKPpE5zI z!VjHfe5fslMfley#(ou1_(9b}2iT;502=zznc2kzQy`^_Xvc5n)J~$c&z;GLpaZr# z3`46}AREaV9ML=X^BV{(Ab6RPW74xs4(+8O_yD0nVI_iRPK+Bq1bJlQlAjAs zyf&`9NHLW0VAk2KpIRvKmYmg#xkmV!-$Rn3U|-YHYYKo=WwqFZpZsbH_U~eF6(>;- z*jTNpLAmVpYx%#LYk?$Ft8r)6gMW_WY&M2&3(KeUptV#FyVC}OoLc__ESMcA5g}58 zaauWe*-T^H1PQ2!Wy814H}upOx8`gO?oKjNWNO*i3#XHNR0E+bG_${LPoxL_cT5@+ zxV_VaL>r#N#69ZE@AGbccO4at1H=tcZ#ueXH>;w!)3z!G9pg_G60gVEsM>x=TcbiZ zIUiTNi_HS6`Wj;}u);Hn80c!rC}Tedk7##(jrN_8)aVVAcPxDkE0s+6ReoscEZj=K z&bMZ=WW9aIY~1|AQ7sy~iJl>V^k%2S=QWkt6NPi6lm4~Dzg4ow{li_@-=<*|>PNdWrbz=;QW@kW)pJWU_(F+p8I;Hz89aMxz5Zf^-T+g9#GR z+Sa|%A0xxR8{NZuH#S)pi~b?zTW}E@#%H6ODyy%UJ@3q{NAy+am0#;4D)G`%f}dnh z0@*Q0JwZnN+W%na@>lw8IO`a8#F$AGQpS;pFE8J}5E073TJu$&>2AL+K>KEDc>lbc z`wK;>7=e~gMjkn{xq+_qT~XCk>O1tcZ8DQC|1y_a5~^7EJguf3kuOy%np+&hz;&7# z8XF>|Yj2;roA&VzT}{!i^7+FS#`}o?3N1%o#3PC2V~egCG38G((8%xO>r>skKmPXd zeK4g~8|)~5(Qn1ntu|_`cG~e@-d=Ms&ZqDm1P#ys8qN4+uALS#Ii`y@Vmo?znAWdI zdX-UG({$7h*PIdeUB{>_o)&%))awbO@F$4+$TXcZAyWgJ3M?4dg7gPHAeicqq?*{SN6;HGVRS( zT>PAPMW!tcn1Jx&#&Msu1!3bzl0r$8B^`Z;XPKTc1+!2pO2~kPTMuOqH35rtldsUy z&S)HdGFj%eS5U(Hp_P4YC??`!Ir6BZb8ud;r)b>e+Hlm?arEd9wQIGL-^&-K*L8`` zj=kyTq(!cDR8dG_VRbhQ+CbZJM~}Xv`dDU9TMh=i;s8;kzVeY~GWya0g@3U;c$3`W zEmoOKUB$ncdbsE1;($#$DVsL}vF!vtw^MfMYWV!0rKL3G^~Z#%RJ&Tz$^q}PgHsNu zl%f^C)@`S4I}QzUl(Eogi12OX+J8UYMr?9XU@CF`4UY2h9DQu0U|BeHz0pwEp=Tf7 zkBW)m79?Pow#CEueb&*lM(bQFqOW`&P3KT;5PwsP-Aaya3nC+*lDYn_2_;jfz=qF; z_r&0gUbZ!DYrO>g_5o)$fCDY9)q8(jv45BlWIp!QQ<8;y-!eb1RlrN9rk?FC%R~mf zzLNyi>@R}pUijy42~nk`0EUTd-_%nYfGqO(cW4Hw{kh40;1>S=4Nw)NJP#;m&sdXK zQ5|y~W%ZS#esvO6H!Z9WFkZrm2yt3ydOAghRCVo;Yw-W=QWm)GRC;6qDc)DkT%^WT z=XVXigAbM0W6JxxUR113SNjf+L+v{~7UWjkGz*2iD?^K1!{Y$0B2 za|nuD`WoPk>m1vvG>jNqnS}cBEVm$VlRo!AHa3!oAeAx=g3?m~4l>|8GX&}*PqB*n zLo04WL7rVl1g(<(p?yx9_J|uj_Mi1XLB(HvuNfpx*9uFXJjMb}jRw}!2b52p-s{B$ z)0}x}EYr}K4U9S=rLXy^W8nK#dtGI{lm|wt!YHJ}X0t%ISJdQG1*|S-(3VvD^a}cu z*FQ8~UMtARV-FZ&&o2)r3GIRN&*S2H!<+bu*v~hfF>|r=Lq!w?({%7#vh?l@b(qNa zY0=saS4Lck;CZ<4D4Md^z@9J=Y`98TG*a_U{l3ow2e~zq_}IVvhF(rKNxT#$KXPr^bX&5qNI zBjSP{%f4w#*1SV0VZ|}0

%-ERYjHGd7!|TNFgzMCw*D(Ojo_2%54*r%8}S%=S%E z0|vDc@*J}*vUy#+>YzM|!rrK@Ez+B>EH<{SND*Y@GH^d820$1Cog_%)^&m0DZii87 zK)53%n{rTCA7%L8ZdeNpM1DZ-F-~z9+t}CZFd8N)c74WZVHAx$kph&u@pw7RqJ1*_ zXY@r6so!P{CF}t-l#8+%(a_aqhTYc})Ssd4AIQvo6YYdW=Rg>DshqT0z9ke+0mP!a z2@!THbBypR7$^m}Tf1qA!rzm;xtp-`*Z<5>MlhJM670YThFb>4p)yh-P<@Fxe+`~e za7G#>IL7r(r+}RAwY6(dAG5@vVlZcbCT%c_GUn3k@koA8iFU7}kdZN6 z74|)n8b5|@$~noSCQh2h`ZA|*50#c^Hfbk*G~TX zomAi_NkEE~e|VS?Y~fbN+1&P{O{T?+%vroRlZKRzETb^LekGIgchdj^TyExY$gk>Q z8Y4+O%155v&ps9sQTe%FeP;%f31GyB&Q@XT z3oBs_7=25!*o_D<(^@KTw!TCnv6M`Rwi!vY9tR;`1qM(U%|pHKDGVG71w`6m(#S{u zQ0eorjtbz9O_wzfQVPjGn&Zdr_i;kI(V|e(I};94!^hHhkGRrOSBs>S5>rD2>3vs9 z2195Hv*0;Yb zgPjGAW8SOg9_D`!bBDwBe-*o9k%RANK{068mIc1X_zi%oY*HO7NlTQQ$H@6L?8Q6Q z<8t|9cPzGNx0hv5(0AZ!UEyg!o4osP-fC6BO_rfF%D04g1biuG#l3*Naj*ds&ID*q zJbE%D)Qm=RrMyv#G;&Ii!=DZDHa$JyCk-u4c}!lIX>Y=^sqmT)@}f;`v8d@*)DeRb z(V@o~mHmX*bNGpSjDaVu8B+Sx=_65W_iLK}o6jH34b!(bLvMtEutgbSYcA4QetPgTa#nu=c5t(ru zdIWIJ^%N@nobBw;0aLfPNr__8t57$d$jYNZ{CDY7a`ydCA8TIflV{WuLc2;sl4Z`V7A*$e6eP)Y=`8&em=a z?y$=ntH=c|_k<@5A%rV2+@g(vItGHP7c6$5k&w05M=ix>s#db#$T~r-v7<^cQmo#< zI)Tv_w?{@2L8xzaR3l3(HKK+-ugQ8Lu`|uuuSkKSo3YNZpv_d3@ebd)2bUI&wSGo8 z8Lg1UjLg$|XYpRoGNK@8@lnCY|5Z%4LB3!)w|KT{QGCZ#UTMq%^>_)jaYM7vsRZf z#W$w;+_OtpTgx+_tj<_!;Te-aA&iXMl6Jf>RP=-`hE_cb6W?5mYDivgQKP}sVl z{CZx>3jw3JtU1rvfLViD!G39lzE*tCN>2PwOF#4=b%Vwl`@33_bV5gu3mL(WQ%-|u z*>+;xoxq-tIDFqP4;Fkip94zsc?cJn*M9zpx!+J@s^;iPR&UdOO1uNoAw1Qc%!&8* ze_MTiap(+q*niScE`->6P3qkc=Q+>3(OE$H2YgKkHfjUm@lH;M zQ6S;Sv$3goO@@@Bjb<@q>?p`{17*fAW90@<^^;1(Y}oV_YG{Ajgt&0aeHO9)0LDnb z6WNf0YaBkP60InWl~^3oNt~%vG9!Ek&$9luio~-?I^KfTDl0As)rwY88ZN?~^xf1B z#Sbzds&Hkl zNe(gOlTwF1Jf12%;K2JfGD0+U#Mt=LKhkUHK=&=j%}Tg0cYN@)z)(_~rQQG|jxSP! zz{U7xT%A^*J8TR&(P!&WH!s7TCB^`R%H=3hyxqB%1dQkma?hF$JrD`RzEAk}Sq>Qf zu9H=RtotS-F&_G|wpmpZ0b|8m4flC(=iz7suCwB8c#OrE;FzWgFUI7bcHe`(ShXr$ zvV&@`!Jch?SS}BDCRf{1+qa9rG>RChgrGu{c-1dzTr94Hvw#13Y$Tp1kSTV)jr_@+TQYADLWZQf3!2}kI~nBE>AH=%&L_D1gidP`(L z5co3vG3iiKb8`|+T=RaQQxGNEZ71^%~IO4I5tM~So zZ$(H8jmyzO)PMxZ&K50Ks<=o*k>yN}BvtAhq|XGIAuUH89R?Kyl9tFMK8q*bRS4Yk z?3xOigLt+b9Y!1V0#{s=Zxep{@ED;&K}N_~Y2%EM1M%jyHt$G<^Qg2keC~sdJ)!qh zWbV!8tKZK*u@#{i0E6+V;O;xNJ9o6Ham&<7lYxs}#Yk|m*8=l9dwe`c?EYZvqv4K# zJq2zX3Hb_d?fO$sE-++3~4bkfujT(+t$3wyqU&EoT2T6$~m8^8dN6%po6W ze#x4FE)PBE#D9#Rec&dM=^jjwQ znk3fv5FWiQkRI?kZaV{4*c34_`{(}NQg_>2BkX^9Wig^#U|q*zT@D#KgQu&Kwe~4O`u`#YBl>(kXc26$`2|L4+93~64V8Ji3+=3b= zZS&s6tx8zpqO-6!%W+3!z0A5p=#eS<;N`YnOc!|y4pwbF?e_5&Y`Zaj>ddLH#V%NW zvUI{Y6KSE8uGMuLhur*x?O8CQ>><1~ZYS^KPDt{)Q6V@)$7YG2xU+SFZJL2`T4YYGTTc=1id@ z4gZ|aAfThC8uzW9MK4{Psa|(Yg3d*B`H!;=PW!uT(^!s%G@b%?+XHNlzu)*--Ow|P z-b%691TE}Eb}fQ*!V1#Cq~6Z8d~9?^6rFJUE$k3FR$G{&!;H3$g$OY#K`@4vC_!}E zxTw5iT@`OYVXgow!-3W4^`+~)$&8iqiE9}TXNcyRTn*4L(fzMsf-j7MLJ6y;qCr^^ z87I3yn=P2igao_ybNZY#;b><0d{%SwkD4&13!9ikbH|ab-u>f6(dX1eH8wh*wxj) zD|mfMXfKhEJ)sGC>HX6Eb^jPoK;s3Lim76MMGRm`efk_hM%sC=+OKBxb-uPV+%QFj zDpol_OV-$SXYS-S8%+ztqaJECQnEO3`gGO`IsKGUmMS#sF>@&;CJ*kL@Nej#NL1=j z>L_fqwvED;Ch@WPY4qS97Kt1eq<8CjF%K6`9y5C&>*?e%u?1^P49Sv^<)A7^1|K>W))aTchMGPX%W_wz$x!1hEXUfslu+St4FVYlvCV)!789N z%2E=v*Fwu8a^7y$Y~p3Ci7ghAhxJ?Yz9@^$BMIE-Q~C~Ryl*fm)$n<`a{APxwfUEB zicr7BgP8L*puOea-Mx$ptov0jU<^_&wSWz*amR&(Q}z!X<6?5Ls*nPIicc^@sm&S> z6N8-q)e+*Wu(5I=>PgY=u#N?fODcXV+rd!iEHjhFgUKS0)g1bqv6#PXv&}2cVFaYY zgd&dhl|AJ|MWw)(&Dr_@O$lk%g;q=x|vito)FZvoAhKGRWt zw98rE0|MNKj{0IzSmB4uAA*0hJ0{yUlSFrXhdK;MqLBWsV?BH2WR&M8Bw#`qb>ayP zA7{B!WL+2xoHMG%l?X-#*0kMRfnT2zC8F?%uQy(ZFJprE_mBvjrrz} z{9NyXs1*P*9kOd@fGJZJ37i-)i`Z+1*V}a)^{Mo8MrcZ&SgMet?;YVhXiXIIv_atUbJ1 z`cT0S0SbZwik4W|b@a+=l&xu+k8tI8M4m_r=5YNZJnSbmj4H8@nb1z^AGI+S16Slf zK5l;o0-t9qjgt;8ZWfu@`iP6FsKgik(c6$hvaF2Qi!Nm?{H}JP`xGW;k3W~sX(MNf zr>9x?3Fp1GMT<ww^flm~GlL#ru zzF_6b)#h0Ct4J!$Q#76-{0&xE9SxQ@#D9EuQm~`|%81J7p3BPK_V28J%spg}E2S2T zk>B;tnvd5SpC`x3GUph2;_j)53LV=85NNAJ>VS?c$MQ$tzsoeIjqkNwmvFywY(mq& zNyjt(hbgy!61M)=_W3)Ti3bLm`=TT0j?(L1O0qnBbv5?{{CE_%b;X1(0etowpd8O5FU%%TEpvl<_4!DhWQO7YpS$+#MAY&5SL~dl1HmPjqy?jJ#QoL zV04Mi6jyQv`Oy6VJ~fzh+EqTTEX_uvwN}YQA~O!71c7LM-)~i%#`=~K3KCNdRmni{ zbJI9l!j<68bdphi-jC)ZSKeDasJmdLtg!9IvOD8RWHh8#o~^^51!ch$QXbEd_S#TM zf~-8hEc59Qb=PyN`L%RtLX9V94A?R-3-d!4t!FoFQO=~s`;t6y*odQXQdzlqL-K`j z;=nFc!Vu-bMm%$}>CQZ0pgzD8t}NGV{#Hl8n(9n3R;;F>H0i^8%^M~e5xm;dM_D0p zlBJM_Y3d{%|D{->U^#!iT!o!tw?_~Ml|_5Cay{wE&N|Q2rjZ|A4(MD2{IayGkCMLi zN)%r#FseA*WJpb@CqU#`7ci&gPCFB{$+YoEiFlW-1Jd)#Pk#T+u*OnLF!F!~_%=0~ zAll$#(zMU`Rv^0g*yjtqbeA)^3_2Q5QC^|#-TRBD9ldmzBi@L%;5L3k?(3^Fdfk<^ zt^MZkyiZcns7&Dp(@T2@g#Ai+(2P%S3 zyGY)HSjSJB*O|yQj%_D~Zx}8q^||9J0avj75)U4=e19BpS~;>`SA*&FE0Xx(uioNF zeln>29iYt1anU^nb#jK>JLi>=&|6LrRk4u8C~pUv1cXmakBh0W#koec%Y(HFjLJL| zkm%_QT`!wAx5`TsrE;zfQP>4m%t}Yn&hY}u$#zSEdIPj*;yN^V{2QhQ>8Yqc&I~*q zokx2G68j0iC?iTFv8ZB7|6&^(c2=*_F@+Mtpe^`m$!`im4%>xp*C=5Um9&!m`Kw5% zMDqwgj{@m4)-0uwkP}?_Pk_3FgJjlbnj%rmGBS{gxMxwrl$ejt>G-Gl88^Tv*Nc$9 zO>DN=sfaq_M>3D8N*{|U-Y|wWVt-@lG8_(XMgnOn?ATFKdQ!n~u43GyNJ{9#ld(`? zWz{V3Ke}#@#DErUp!L&AkRd_Yj)jqhhm~TnYOPtwc`uxXF*aCZ_}!C(ku-@t_--jg?~=F#Ql&&kq7*9reUL6I7TxXaE` zj$Y%Y){aS>9w4Bq()*|FkU7!|YduwT)ryuuLOWb6<7=1Qv>dfO{qw~iM>zs7-!DG) z{pLk?&3abj8|FKwAGc<-f0pN|f?P8%(W2L?Y%H`TVXBv!)fukY?}SMt?#E|z!S^u> zAKsJN`*#?hTVlaoRENQtkmuhQ54y=AH-5A!n}rPjOqN`g`QmsReB{F-)ZTXTbaaE zTVxKDv;A9~0+DAE2w=5l6*&;)#+3qjri~{VM#ILT+pTtJp+vOARYgTv2Xm%ysPN(o z>$ch`t^ypnw_Q`n=i9lnne^!U4JL6Bhbq(%HTq`RUkfA%2BEA?0<*cUZ*JtIP5)T7 zlgP@bt`AgoNCwUm35n6f=i~N@8Y(V*b;BM+@zh_hBqKnVyI;lOv za>K6J7;@2Rv_p3>i5BYwd$^8I4~V&}+}=_BCPSNw<>`Erc<=e>R+#JPeXhZ@RVb;z z0fg2iu}j(VJTY$8KO(DblpRha9jx-I$imZwI>C-utSwxJcKW6TtGO0g^Z1R*Wvcpe zK+)}Yb`mRi!KeW{yWn^G#;vH!R?k}C6ZUiexP$Di{@0`6xxS#&q0EwWo z!;O67Jh^Rd_h`OfEDyHIKxO)msWE0IIULvT3)SEGXXu`j&mO)@{bltL^V29uQ|{9K zEqtnHZD-+6q0$bp%eRi{^|M^x!LoHTf`VBzp@b%$pCZ3JSEnCbkGby#K2Vp;I#^g@#pyo~&; zw(n%4bmf)#8B+^&3@SNf5yJ@q-xsFOIDb@$t;Nq(h{ zUFx`_^l$I_e_Xv~RGdxFEgC`~!QCymyGw9)3ogMuxNGp>?(XjH?hFpWgF6IwI1jwv zcg|h+*9>czd0MKwtE+bHEqttNa*2ob=nIt-MnPF57((zUz00dqDj*kU6UNT?&+q$^ zp?Dg}r|4jcR*njhQX~0X8H0wtbMRe1%7U`37FLad;1}QTJOXU;X>2F7K`o})YK}ab zz=aec=Ih9iXu4aY@Vq$-6U1CSL#M=NuNyQU-xA8A2^PcG-Asxsr-M_9HWM*a<4~tY zfpK|;iB*1^N0(85VXGNa7Y7~~q39@V3kSNk3HM7bnA~uqO5W6*)q;k5y0c*%%Lk%j z)0xvoGgtTuvX1P9;l)o9qNTU{B~~;JX`f1R&uO*R^eRxeVJm^{kyz=CN*r;D;N2nKd<)Lf(O z?A;ttgPaNlCT7eiG|NP=E-kw<=!qq`S`H@dgpV;kY54ADS-@+CpSkmt{s5IZGaTV@ ztve@?|Axl2xB^v9alc-@GCd^PJlec)(#I}qmMzo5TKKu9#HNrn5asO4NS6+WUlVNo zUBk`E(YtX1S@J2p;httw?>)6#h2r=H6Yf7rgy~w=xY~xMsy0+P16=;DBdWS9JNhb2 zXIByy7M96bombP6U?e2!J_LpSfb6rYpEJGHk7KXywG02sj;6tT)ZJD5#jW%DOzy6` zW;9L`6f$>Ro1@5AKkxf3V)Qk~`3kKcQaVHtO7Odt$fT8S{0SnW355WBI)#Mfmt0dC zb9w}38m?Va=iqbD?cyrm=3m1eOPwEA?#C-UgE#%W;R(;N&m-1E0`t+_iJYp-dbG5| zq$om(^4l?|`MOH$Zi&t{A5q~%W)#pMzQ>rJwoSBN)0Wv6ekzXG5Lb%{-muDAq{YVI zBcddgR1jHUVfpUG75*=r=$Cx1{VAS#JGB-)DNwjEhlYCcQ4<82UW#Q#NK6f#QjtS- zL0$3kg7e*f`#ww}0};?*;41i<(~*oJ2n42{QWYS)<8`Y(j`){-`910@ellbB)5a`U z;s6Kt1f-sJT)XF5HfMJ@Qd%(%=|_KeeEZtt{oMIN@Uo1dMC8uzX`Se|Zn0mP=6pY1qAQ!R=dFD*8skqA z@x_lc^giyup~sZRmoN-tSp}dY1LqtMF(Pq4NVuqYkmd|Yc zM3_4Solrb;g**F)e-@8KK~T{U5KpSlXiPnkA^pG<@-x@tkt77NMW4t1=Q_GbOmq-b zOo5&neBe<|huxAr&~0Te%Qu8%05u{BR==IiBivFtU3-hf?7>vV=dsW*@wzCq^n@2r zx_xAU7vm@N6Q@+2@vo+p1G)*E(S}6S*fQbfn~HgcQ(;pt+NS_j+Fs)=NAk{HFJ%xy z=k{pk(+61T!7fYFU=TcaBAxxgH2j_>Rd}Og!gC6mnIQf{oNGwYoV?{{0kis}*tRR0| zfi$S1l)#G8q6sS>kDEL7lqfPNJ(3)ArW86wlG5{7Y2mrqGtQUP!Y~Z~8DjX3mn69k zw;>FKKz}Si9G8tqoT_Ff*ZY7>wPO8mZz#TFuA8@)8^nhGfE}9wmT}Qf@WIO}!wopA zE&2P75u(B|d%I7FBEkxSPrn~LRjA@6cXqyazahuXjL>66q;|KIAW<^UneNpigb+!E z$9pQ+i{0_@#6*g7A{Vkq!VNYl$VR15g~XU0NJ=E$FsjN_ujs%%@ckX&Tqzc}L6p!G zzr6uc0KkhY%>Vz>H{`~DpA{>weFWz3|Ncc~{i|f+?PduEL_3o*m^i=bTYJNgTbZX~ zaPIlOfS)lKMMnoQ7x)Ru%6(3|`)CAJL!v;%R)2$iqLUawnWJ33`~J*g%JtYVp(CO}II?X02(c1&*)i%q>}ogm<)?uC=jadwx|6w}7qYOUoA|^zicF z^fCT*+afGQMGDyD#V8cnJ!d);=Gb!t2Bj>HOEz3&HnJdwoSxudVuq zw>r)rjf8fWt)8U5zZEIR@n?B!(i(~N;ff1yz8%>%gL%DkB6k&RMqs2j)}pB(d{4Q2 zfckx?m38vo5e>JByI8IXQNo0_DpB!7zLq~EiKzYw^;Xe9pAQlPLp2tFUNh78-4Is& z>vvcO8G&I8l3LQw@f*pGw)|BlGcBqa@~79v8Jk3=88e5_IaiWpUhH5wp?Td3Sv_dk=5QEDs+ z*wHJiuT5b9!#+Sowa zk&76lKTT4=U?+T@`a_W)Q5aD~5_+14Fhr?_=JmJt`Tsn?d-)v&)RqDOee#C%?F9JC zuB#GYR(7BsC1m5!3`GQMFzp`p;dQ-T6Tt~K6QN#|Kj*%@);jCT#b_;btal#N*0i0J z+yEF4{7}doENuYLV9z1X#e_?;NRJX*yKj%Kp8yhuiNBBj?rO0JkxL>^)3_tvDND-M66gLe z79b_haHNaj0`-CuS8NUR-fVo4(*%FSNVx^VP>Ei~m#hhfx-TniC(s>!rhzI$wKB#Rycm0gHHf4VY`Nknr;O~r-mI{ov?9cVhc>w6ElSiX`6a1kF3_C@e zP*vObdXrU0n_1ngZoiJ(0YQ&rp9$8vh!mPTtv0Dp*bS|)rq7sMtes@^KL%3#cd{_< zDHgb1fIJzG7V67@!GpG+Xsc+k4$+=@-8?f>t0c2x9~O_>a%Q0MZdDufoJzdt_yDu^ zJpJ9+EahXn`^r=MCQYIqISQyXtFfW!&yrs4u0q1^cgEddu{UbLJ6VU(e#%+Xx6Yx_sJ4sdu{P>g@n8}$x+^o;(c`AN#uePeQ4s|X)6&0f%gF0-uukH5e2_- z`nvowQV*0Q>N!XnE)u)lPO~+PabxA;)?|_5q?)Gu{$^m5Z;Xe*7%HL#$eaCP60b?I z?V4JzGljU)xIKpuYZVSv?-a7YuLr#Sx{F@Ep}7DD0aI#ZasW&Y4OyCnzXpFyku`_A z!dr{zkryuk-d=hdIGIM<3nQv=vhp3WIYs!vS%u$3qx=uw-Wc)d5t0GM!C;JpUq3OM zL@?N`e`tc4uwOLIf1I7^V0-Jr(;vfKx%VD^A=LTEbV;7UmrNw}aW~fBE?0w*_+jkQgz?MC&E){DncE`=}`!2rh(lfXrSL@NH? zL)oalsAZC`kf%_klf;Mw%vxWq0H8wgVu%G`G`wZ4&y;wdo>T9i>_3cOXu3h~Yi7&$knLGF z7*Yo4)RWTIxBfm@-!I(qZ9hjMG`punwcf!mRFqwexIy524VUl*qT^8#F~p;lRp+8Z z+?8iP&gv-Cv3FsjoPf#zb?JW-r*^Ng>*o`lk3M`ld^;~6Boo&*})l5Z=NCqLAL(dZzC14s8?=cfZdxx3ZZseJZ3H2WihyGO^=n%r+EiC2993sEs` z?M;bnN5)ZQwzx4@%6T!)s=|ze4JPnZl#9hO>0ntYnB5@UdK^`o@i_IivG?7+NvU|{ zGah)1mAMbuu$TxYpMaplC9x2`DiyJiKpWrr;jh;6g7cA;o>a9cnzZlebzKs$Wq?t^ zLIn{A4t{&;`dVIR)=(N3a+-)=XoekVwCRFg0b|ZCY#Y-e!C3Bpt^W=&fvlwweFKYa-oQB+1|AV>#-)9~)C?zo>r_NymU zW&r((nbH}pRXtCG&`>G5jOQ|8U)bQ^zKppFnXv-=rl>`A32IbHsGW6bD%k)7xJ%cf zS?1Qy4|Cs_QjaXHXKha~c1|e#Xo!-4dclXZaO4=RX!F`(#kHJ&`H98iGg0?dgNp|~ zGXlN}>sjs11G^eU!w5YRX zC`@smyuQpvrTQ(g8Qf1qHtygsI&iH;BQ)qzX4V56ANVPjIl|g===1B1Sj8jM<&~{& zDR6+>l;T)+Ze(3hTh8L~JlY;T$)gql@&sL`e|8+wvNg~SrKDK2L!We+%mXDq`T`y5 z1wSQ_<48_4)$;J8e&fzkfm?7*soZjpqm;MzUG(X$5_2wy{!Y!3LW>>o`?jAEpx7Ap z+42KF%>*3`d|yh`*&C^c(ON13gr;vfg^GiJ%ojR)^mVTafd*lGVJCNC;cq!;Ic6{D z0yMw|1>aft&p*Zj(=LQ%2&V97@K%l!zfZWCsNOjF@QIh4oo{o-`(E|sUe3hdqVvbz zS!Gla>@$up0TszVIS#&+y@$cUJ2Nn6v-r|8oowwJ3O-CJhX$ zDCvj8*dibe{M`8*AqS%Mz1F=Mby&vah5{xb@FT5=QxFd$iU z)LNc=m7o;Y$o4f}XJ_X{yr1$^Zgm7)tyftx9cD>Q1wA1X9A~mgU&GBr*4W#*pL5TyFRYyL(Vyy;51A;;s*B!W)&B~V+mkUVXI zH6|s{s*7c4%3OC-l2gv@4l9;>Z>9N}G86a7->H5m#(+0(I21A^z{nl74L5$pmxPrg z^8;37^Y-OVba9*uTld+`LHhMMGlJ51FnQ4NDyz--vB1Ljc;8dKJsg_$2Rh9osWLjW zYDb->Kr;0d#7BdHRo?c~U^A5g8S+mrV7F)390Pj>F$F)+ZJ=dT*8k|)mk&#p2A4|^ z6TQ1v3;;pPo@@c?xqkOu+u*%fX0<{=v)gZK>yG{j9gFE%S7w@z!?E;$Ns{~G|ghnhBd=YFoPqYw*#m18l(%9 zfX&D?{r#8tEddKFEBAmbVQcdb**py96aMjaSaMjbX!oj)5(@oZ9#kvSVtlLht9 z*f=M=jb{Y59$P3*^z)n@%DGm(3+$uHeYQg$Tn0QEKep{z5;U6{?(uE}+hJFE4V1Zz zHZ$#bQ>JxY;s8{Qn&zHhp@7uqM?DELDf#oTMTemxK4Xp)#z-`UvLU8`BQp{SQQXvh zmE?KzP>>{^+}^S`Jrl%%@4ewr(fZzgAGtW(m|!wcq%!^yQ1jaxEOZb<+$UwLEK?lj zZdzykWrSq5$&3#?QG+2YRC!6$vaGy%=I7+307x6-ZTp-d0&K_xRUNx3>H6Tt6C@gC zaaPsbJg_rISU|0c?5|>pvcM@m`G1P@K-J?A=|GC40MGQcvlzq7cRG3uY*V z_JBZW}`UEiOXR3zbI(gR`+wC$%oTaC*}cx z=lkr5z#73Y7})!ai+9bzg|{I`2K!lQS5G`!TTqHACP2Wv(he=wqcEb>bD6XW3%I*r z@Os_)^twCW-#susW9`SoC)!y#po#)4Y2@D957FUgmYe1E|1RK9+4;JKGT6R`Lxzcw zUlkA}79n$Z=O& z$4y#IjtRJEUXNAV&Qo# z7`H>^dihVS7+RJ3*xwO0@;(IPd=~Q9W1Y7MNl39-Xqrj}bPkWelwa7xn7uE30m(5iD06*r;S*NYT@G`%YE5T&CO9wHtJ1@8y=7 zx?o-7eJ^8o|1qDwAXZwS?rR2oGQ4}*II?*!qd@0GUy;&rQd^8>_TqezCHuj4x7+qZ zFGlCG33lM8Tt>fG-dJ(5(uRXFmEyQn>y^>MWVQm;oY`5*ck^^L!Kj8916s@!}T#VyuHrf9b_O;{XkX!FhD)L1GW@Kqjj; z^YFHN!=SXnZr^?z@iT`Z7Dh%3sk%h!I4KbO=T4TdP=$BBye1|F54j(V+?BbgS-5Gj z3nucG^WE8u5qFC#>(q2C{+g}Zoo(-35Bl+%>=8foepu=8dpLn~+!A=cw9iz~%Ia9j zsnvMBxqf%6$KK9Y&qcr9g)N(IeUFiUfAJq1Pi>|zv1WFC4Px>sW6gZ_7L!^6MFXcD zSsH`2izXR7;pO$Qi4)dtTW@`adk>B{pKb*_j_%b01??Qi>s zok-UX;${tH2?HbwW<0~%P3WU&Wd6Ib+d1`3wR@hfaBr>9N6q7EaT6&K&V1lm=JyuY zn8CwnG}lWk!4ws5*|)W3BoEfMIdo7-P+zsI(($>b5t_koL;-jz)m(O{8u0Z+_tInw zKA9m&mX^)JU3BAm^8jYakjQfw&Xr-tbCar{Fpy^}j5u~48OhPsI~S6w|G ztQ;`*ap;?aG}E+;z~9W7Z*8OHIFHAt2>6{sbsC;08{a`$&z;HMzf<_D$F z5e@J}YZMUEw5cou*Q4U|WJUGO{6teqrF>mW+WM=1Brm5vpT^!{D|-CgLt_~|;7`9R zMxBo-De!afZXJU@d$>G9dOvJ4pL$*KF32f@>VvsEU+JIN@Ump+F91KY4jNLHM{j9) z=QPOsFT(4UChscucE-BVTIOZv5!fI=J>qo^VqI&O&rf0=Ru*kjW59#Obeu@)C!Ic} zbZ2KFE0L}KJN=V=Se-1eAp4w&ZbPZ>66s|T|F*)rYcSJuASiQn`+>mP7W?~fg5A?b zCe{8+YF{GV#ga<0@8h*KV@pNuGM9Qnc0Y4Ye^N4^eo9JSGg*0!$dp162dNVDD$CS3 z{p<+utIIySpwNs1tPr_`zTkQxUkWmpRof1lhEoV{2GhmfT_|pXX7&_~o|i4x?ZgCF zq&Q!QDccVZyUf)ig7aaM%!`de_PeWI?yDNE0h+|PYJ@39+*XE;`nhGu&xdwJOd$uW@~Ko9*f@YH-gcC;kyF+Lz4)!RH~&hz9>-M zLv4M2`cW`fxExR(Ts6+uE-=MP+Ba?SJE=F-bxCb3R&2ewh5Z|;NW`Tp3U_qBq ze7*;t(+!9=VWKh^=<^tR3hQz|}bJeq9!{>y1ww(D)H&gL&xhhmSgwK%e=>+O>9_l*+EcnSDx3*Ci^OfBjz+5M zzFq4kz=7R68Q4ReiUo3Kv#P{<9n|$Ld7ETc zT1{4MWVbuBz_H+svQ)uM#zJ`ArgfiF7Op~}c*c$k{xVk3EAi>R|8~Rcmg)Us8RB^G zjm|B#Oa<0Xw-rmicPyS_R}wX`;m?b#K@J#~Qw9Ix1p2OB>rGAYCEf|N=MFJYM+7QmRlct*ZzVA^`QjXYoa8`eiC(J9nBhL!nf0~)nz zCY}el?ccM2sUuL$AtmA=A;5ei^GG! ztYE0{^dnN2H}VLL0(Eqj8b8B|KOrZdQ9U6l1+qkqbZ@8FqxV+OIdofd*|PI=vpnEx z5XQkf(T0cQEO|ejlxl~_mA3aQ*)Xbtanu1Rv`&PZMDG()%cE(EXo3K4ps=lQ3D!0h zt6f7NFV5dvF==D$V)bmDT1pP2YQ7wAheW^AG@WgQ<+cHh(jmJ8>zS&8Z)%&k5P+Us z>>*jRWPDnF_BiC-Gh=LXL=Dw!DQNFH=nCGMa~}eBlc#=MRm}qZz(dCK?fSv<2*?a& z^N%`6bITPg<*aHL*DL4!Ocs{1u+-rRn(UJ!s@bHv_ec(W+Vv2_{`>d4%0DXVGA*|- z`tKn$Nl5esV_Q*O)LB^AyOw<%(!)&Py*0yV_{Z!3_{2;Yb$|vLC)X=E9nFt=G4AD> z^K$BwZoZ3!RZ9Fv*#iFY;2z3Ykv^hvr3DA*yRkr|P-*bqp5Z-PY4D?<5x$g&pGkib z;5DQ)JF8o>CAh##^=#h<0Gc6ESCvQMk~i>q9{eUGEpXs^YnZU%s*{` z-|*fg9km+lmPl9EgHriAB?~tdq={#@ef*9xFNVj7e~K(?x#suRUx#f0N!0>61>1l| zXLAQ^ctgfd%$q-Yh@gYVc+8g!ob3C;)$1m&$1vBO?@QriMhktlRt}Y-9Sx$bM#ywpDKZ!n?sqKtdKz&l zcqvkzhrOPsYfl)wZOl6=OFOa4-*Pn4cXs!#@nF8`7RsyVt~vzg@|0T_y?YrZsVn`^ z*;u9pzYJP9?&-Y*2N|Sk*yT3Nv{Uc20wtBuYq4Ik28)~r%GmT`;?zw=%`V@VJ?D&K&Z4FU;NFKDE zl$^M&;_Zep&IDeLDSCSGi3i7+`~9qd(gfViKe@u~Zy1dl`Sa$Abu=`zr1ScM`O)UU zH-yVgH^1d{y!-oBZz35JU;&CqwTpoEN!Q<}u-}UYYV^#`T$VaIWZ}}&G-8X4)hzro zQ)xu`yU^6BSW5P?n2@k7WEy&Y*P|GV%}t<~$G=Hm;wd&4)A~(=`SzzZE%bqf$87`A9g>r?Ar$zdB+koMOzFauRA!%MZdTBZr#Ax4Gf&aO` z8G{M_5yfh*=_kWbLU2CP88~V7pskiaT>I+M*brkFSjh|7&9&VLg&XV4i&A2^@GSdv zYGw8q4mqtRudZFmG1Fv7%wf4o|YhcUQA z?|!RXk~ASWutoXeBAx@nOiMl9VHrDIwrmV7i*s;Tb~SXKI-^RxP0BdE=qBLZ0ObkF zYwfi=hYA;p9cRj7V&hmgs5aFk57s*dgU|MubR?k|lTkt)oXa@10^SGYr)DlGRb8W_ zLsGVHHt5;~H)k-;lzrYKI~9G>w9=g`dY(KY zpK}f1Z{((SNsmcWC9{L|QaB>7KQU6JG9!Q!wM%v=>`gBp8Rpu%-A*j7t``=ODUV^- zh3*&Jx1WK}mEk%ScTW$nDH(( zsivJ8ENx2V!xGbCLgjCa~r?W3q5z%7g0nXqq+{c+%7=)ehgP+n%iWb8#afu!7|+U z8oW)k)aN_Er4-Lr9!hB&Ban~{B=pU;cC|YGn6kkdczAPt47(E}k0Ak{>UOGaB3^bYhT(_ZR3^f;R;{H|HApR45<;Jy&0wm)(uxT94zcMp`j z>^uO?{@=CrIL71T8ov|DxzZ%8|GoIT5OhYk!g5}+3S}G)4J&k00cgv5xVAbCyZpLT zjWk#}BEN1Vz4w2y0HW~mw?mw?AxC7*`T_Hb&y{dS9o8woUiK<#BRzgV3i~T`Ib@5M z!Bbnf&X+ir{TOhV-1%1}t<;3M9Y4ZFt^0H<8Z^Mxc9D0@iZN*OZXOO~8> z1sG)gV8#1!RVXrAL*u>#B-ar)mn8{P84nQ-ZprRoBF$H`RfhjffH(;9rMGa)o%}>| zrSrG-{&Aq#QyMA-wi7M7Z$sZK@@o{*wjy5PpC8wSoqzQU$22y~bQ|BF z@1j1`=7%UpB{kdwwb2yHhs(sK*|bAOO^WAf*LPqRx%x9?3oD6ApZ7{#n6lb!34`vv ztvX~tp1v{XXV;*3G|DR{Qe=7yPAUr!2 zGr5ON>B(WlkjaR}wkp+#YxMg?hQu0V4Xn|jsU20rd#CP@fJ4bQj7F)5ge(MklSGKw zie|a52G-&4k-Y|_x@dw?o`fK7K%cF!F%?-XQU{+N1GT(uXk99L3p7*#Qt`;76shG* zluYA)GbBd*c8?JdVK(+dfk*h9c4bgEKs8D&qmnSV|wRl%mkT#Z!T1MEbZyzTQWf~m>_(`JtR>Lk|O8F zh~eap;aSw0OW$Os-OWK}(_%~4^bY%7tA!P|E6yXmZbD8>R5RZXh9ss7jD08RO82qF zHQqggbbYpd&3#m8n4T%#R)XZP_#UQ9j(+S2y%GBVRHE+`hMx;vhACq>40$t|FASKz z_1YVUSwE?sdO7(!8BZN5+i0hzfJJ3bN7?Y^dE0euEc$K;<~ApYIn&?{3d;#8G6(6L zR-M2@U1L4BD_sc&JtG{0?WJSFyriM9|@iE(c zy&RS|)8_njWOK(WS-s$I4OVbu-^JkW1IAnD)}kfsbSaEKC5LLM7~)>YNC)U#*ntVr z#s1RF{OpWy;G<3qR#ir||I>?TU`FXV;a01v;9!;mXyzGeu|_c(%@$l{*JBZ8c6il5~&C@8>bkAPOJ@&sXH6W@2WElMKK8}y*q2nmeJMFW; z7Xtv{{WbhSO{0Qz=&5_g)fup7EEm;AGrD-QX1T`_?@#KG07;Krl8h&$mv|h-Y$ji& zCT4?Fg?xeHn8KCif#I7o@Z~%V2-ox_CSi(3E4qfyImOl=GIoAzndtV4UUdou3d=j{ z{TpnfL(7R+&q#lBQ27oM4idazc-_jq4!zz)I{!JN|5E!obN)gmWK`Al8RHfFb*s}o zUAMD71P=Mb`!Ht^zO@}0Zk53n1`S(^bqVe>Z!@S}?yqxz1r zPhBiTaD`)#g=w(64kp-6#UduflC26|+j@Htyq{U{Xd<;d(?R*pE+%Vwy^-QCxGyVA z%@0(m%d`n2oUj>N3;*@$O|QC7)wJbT{Djiac{4Vc?I-TE_3?8v_t?yiXXtPzzx0&r zM%^N0WuTbPDX5h_^6rX70=_1-vdZ*MIAd5{UiwshV;9aZS?*l{86q z+Tq>1hjy|JXKx%Snt~7F00->ITb8+i&@mJ(~7zYJIhDit*mW z#8OJisL`S@`e-QrgqNLonC{0jybD@~|_#0VbY({`^G+)>O z#gL~}ij)GCVRaH?GTEnUDf?pC;>~X_j;3TSn)w|Wg@0rh2l{QLJA_Ez4Vmx*fEDye zh8Euihcvn6JS2xz-?(0Q$P0oR6#IO9ZJ=U4dDlYxT=OX&q(0_Brj*KHR#USrPw5$y zk(fze%VLSLFj6%&mGAhj-Rkf15wNWf{J%oJ6nKiZGv7oQC|34A92rd;WHP_{pAHj# zek6VfhsL-qpb3vBu@5n*K%~W9H@C}nD&C8x}ncTSoZqzz? z?W_8ZA|{(@)6I)Jr)!i!x3ZkN)`*q!FT4AJG!f!^ytR4=e2z(+oMVeouCHNJ?aM12 z&Rs8M0`tK|x;lkg4|aE>HK=H^$ybpa9gU-d?7%7QA5~eqRsOF9*vQ{E0uN`PzeC8= zEF&LNV)ERT8kbVZq}M{xpD8 z<%B04z-Pvlij>7SIdi+CNb1%0NwGy@^-qgoW8Tk47lF48yOIVR4Q1Se%#W~LA+UDZ z@Sul`6+sKHtB3Zxx`w8KyG7>i2ItF$CvSVTfEgMt?&Jk3G?xO42~#o?CP@@$+yy02 z*e~`7H|CLgvV_d3*((@r#uY-J@m!dFK=!jbELtQzdv=psep*~t)+s&opK@oG0+FZMmtGB!tXZ0nnX`j?~qowgP>k=(Cm zVV3U6@#Pj}R(0~i!qF2BNKA}$wf9T#rPh^Or!T)(+lfz~Qo9G1T1l!!6i7|$xgyLq zUUu|ZSWX1Q>%5|{kd0K}D&H<-zCEKxkQ@gb9kU}4KIS!EA8z-v|`4vwWOh#NVgVixpFsEf~ z(k%F={?CNI@1p;KgD^W=@?eN)wSRKp*e>(a6z)z!wIrJPPhreE08s>jBy$_g*BMR9 zz|S^;D-(@v8Ca*mdY8BUZ$Z%0%ZSx#;g0r$jUae`El|q(LnUu%Ww%k9DJxWC#?O;p zmGqe=1gEJVT4pfk$c5t+)g6h60AXJfUto7q9H58y_x9*I!6Emb!;@U5tE?BwF$FoG z|DC`+rXe|&zj?oDRYMzg9;tf zZXlNKxke$?n2rE=C@|d}Konh&hfs!nstvn7T(wzoB}@Nj%{<)(2lgDuh^|v9yMt5Y zJ2tAhlya#nF0}wX-PB6kKz*nEehI0av2U)X%Z^b3{lU|iIdkphem$vqJY={Xyr%E} z_y!SmG^2)S$%t}7=qO^$knMCPtNsjjt~*Oi_idMTmD2A^zRf4kEDKRi3R&=P?yjdI zON>XlbmFkfe=D*#id%*-0}z29|6&k~lIk&)s|C_izqrNx-;aU4TPcS@+-B++drmT1 zf3*kjPDyp}y>-qjheZ{E|JpPnbO(G}Nv3>x$>;*;Rfb6!p?SSf0IM+m%q z2-J^H;QWtIZ%W*EZ~hE`vlT8tp4IPj*=EidAaU~3sON7dk_q%O9d_vJA(%`hqiB?_ z(8^V3sD_pJ1&pH?PtCDX+hh$3VYpCFzpt8e*9AojS0Ej`)_SRQba4{JmoHmkB+Rxj z_zlGdBl3JWHJ^Ze@EV?z^U$7Wgdv44YC#HE4Mq@v#wU5myZn(n+P=K-f7;j%yfei&B_`uAqTHOt!XRVT{Egh zW#4UCINc?H2nvE60Gd2Eq@>bdAi%YEau`}WKwLNfTf}*~kKTATS4|UJquR~PY6!9K z91r-qB$$jGd>cQ`l4cY_m}H=vgV);KakGh`~utX;`&UvbHXplH+ga`hE)15zQGi-!wxtz zwl=sJ3ywD0ID^#;A7nf`gk5*HC=EB=?$uD%Cm@@4$awI0m3kuuU1TEL^k{t}5{oPF zMDdtL2}^n?9e?`UpIl9c;zlYKE18GWH;eCn^WbsO#-Rqu(@xem87L6ToedLPBEp6S?m zZU3!l^is6^dF69=ejpiiTyuX(byra_p6|Gh7?}R_1@SATLXDwB#|_6Zcf{}CO&RRB z>uJA}Fy+Fwbb|1fM36Tl%BS}0Z`$qnIO(y0)sWZp>(kJs>u*`*J;nI+PB)Nig!qv0 zH@C+#yH}8V+l%Q4i#Sr|l9MEuNH3jZQMvAB08V35or?bIE419OI_!*)TTsxkvuYaJ z&zeT1y#bYt(azn$->B8tOdM^a&j@Q9?A9HzFJI63yzU`8J#NE9^wR4AjDGtyxK6WcY-y?y+ouE4lb*gnlnW;e;E@A;O{cAf+lXR{ED(*BI(zh30LLu1GjI;$bX*W=K%~fUWMM3tJLR}uj2w+zu zz4l*h?G+YLh=LVr6?V)UpZudk5b5)15L7;#ZFFw-dPdePCv&Xy>36-R75i!@5c2E$ zT9&6-`o)bA8~t&OyIy*DN%&(xuYhQRzqGq{;4{?a2k2DVr<%yzk&<=tA~LsZK}YR= zOU&&Axmu+G5Km1^qym&gIC6t^miGbU7&HZ$$a?P5zv_vWu|Od=@^9$ZWDRB`d?PU= z64OeguORVt&XAu54{S1>5|=1^j0{!;oz2g*CyUPEfd$-mj-NYUwkIr8`X5mC2;^B= z3I&Zy1&xldRXdXLJbUhaEeHb35fWP;mx{1Mv~y+|8SvsA+`0}nqGm)OZsR+53%xIe zUXCK2C_Z9yy3!#60g8VAo-Wf<+r`ddh{E1@3knje2~m~aFAe@_^f z`s&&l{&SDn{eg-%@3buUlm*+*bQ=5mgqBnhs#&Qp3rZRbl%9}HI{9uBN>)Mh0?e?4 zTr{lr+lvr(Ou6XT19_MUA$5J9O0CTJE#-yYoXpqhsGWcQrw2Z393+<&Ri4>`rKcNz z(05gvr9#onI1D+GnRT#9+`^3|247P|n4C^f144$|%o`K_ZjTmO!bVvtJ2 z+2m@Cd< zu@48W#1lwFq~U@Z!U^z^o4Lpf#2B%nhZkoH6^HfXWJE!S^g9X zG1?y@&wmpzh(SdW;+vzc77@CIn)yrQ(0&L)9XYm-Q7Vrn>tbjoh1iZ6>Vjafqb$tiT+ zEvVq~npJ-|H`tKPphF93pVeV~keTI}e8M|}xF(4uA~+|BVi?hsqUF~PYBe05(kS7C zc#jW5@E0YBRi~=7k2jZYGMBK?WI)Ucm$Xkpw7_&<1#Gmz78dRMH(f3=sDw`nk~GR; zzCl(8e;yKfO#As~aNBYsiU<2fv9=_JN|FU6-sS;V+|j_|ju=8BBFsQII9=bd@y_(i z{~Cs32kT!uE(&)T0P%OOs|;7Kbt-etf(&n1sMNQ z;GXP|%3CK~*i0~e5x)vxoED=x`QaKF5j4a1Fq4^~|_oqne(ts4$@f0}zDS^$a z%YdX~^+($OV=R6gd#biucfq zp8-68^*0VU1hG0*wsn;QluF1X-BGoT-ukN0|2%@IuWqLyv}3SCwp26Z^1sobN#;kJFr#tk+P;uG8F2!ekD+}7sH1zM%G z^H&s@OPQazd{|_D=LAzoC_rPYbc=qUlcST*C>QsGdiIJum1e*o9Rd08{Po{D@NH|5 z8n0iZD%lQ2iro^!U2*S9Hwy~Y1jD$9+Ho1OnKfZiN7nfMq!H^@F4_!<%S;n&ay>aOMW} z^joymM8`N-Uv?iNH4?l;Z*}Q6JB4Z{j-p}&jYULYg(fK*Mg|#V1a&ShdY*Q8CC+pS zS?O#KUPBjHUG%#dnijbsHFk``Tx;vxozHMySf>R`^m4`uWUeVQEO2Xex+a(Gqnwe` zoIZ!};e$A-?zB4Zsc7kY)#2~5GGmRfl863!NL&`y`9%hiiGod;4|^aX=VN73G!+m^ zM{w{Q*v@M*Qt)gxVcO|F-l3^{fEcf0unfvM+DO9Q-J@*U#WIBH+3`6qn)s0%8xItv z`eNb(RN9d%FTH1X*Nb{8M18j)q};f+_3-xTaA_w>ys(u8ODDfi>Jk3Y1lP7Z-Tt&8`__vRS%guh#>>p z#JH&D=|nCIAFx4U4;8_|Xc5|2Bbcf3_FtsWw8X@PD9>w0&fo6gpc1Di}dB zxo?R)WRr*wx18=wT|f7lH$v{HxZi9Be>F&P@16 ziaRah;qbu^XoI*ZT>jQ!k@m(+Dtpd-Y|2W1>EOW`S@PoMTb7681boKZHa3}#3iHKF2yRinYqLL4UccEEP;NqmRL zx$}MsqGxq~Ni}=Tky7c_lRAEPOa{@cF6RN`SG1Sq^7Y5+9W!f%>^&M9t8xUzU|}@) z0TrWiuA*}3O7n3?RNOcikp-g?gMtI>&&!eXc70~uMszOY-dQ$9Vii`Z92Mh=Q9O}G zZd@i!b!0Q70UE;GTQB%OzPbq#7W`l%sz17gFsU@w%XX>s&w_4Pz7Q+o#lhsM0BQr) z3v%Vi1RnFnI&*d2rdvgm0zagDyGfT35X#H*^K$oi$uK@8kU!iU)BcM@3{#K-etUe6 zG;Z@$PeCq{s5?>R5{V*Dd<>lDFsjzHUa+yV^K2!4pv0*m{ao(#_Fr*kj{?(|DV5)5 z;x?@t8W(O^eGN~apXFy6KrJ#wrX~Q?uXl*`qjRT8T_&40RVhr4w`ENGu`*+Zl|f4V zfBLi2Io^0uQ1it~1_geXR5jtSD`Vjs+kWo#xL`lnS7OU;NP^ps7>$V4;@iN|M>96Jih-_5gE zUAre3t_8##p&dnaX;%?KYBOs93ydl7-q|);a*D{i!%ITceO01MXMxu6H{V)4d?54j z0doJWS{xChp>J8BU$`X#h8Zswr5gMGDN3eGWd7PIg^)aIG%1-!b>xN&Y`>+O>z6Q= zWf{)|xrycF=QDYq`EDKm*)NY+8oynAz}}(0yJ>JpCn^2aa!;9#?m)<4&|*U7GgTEhh1;OqN1Pw7FGb64uxZj9ay|D$=9FWUwivs` zEbF#;tOnhTUCRX$wC=o!Uww#p?1)M|&;u1k&x^OEDn2#BJJPiE%(u$*c{mk(xg$;u zxUg)N)?jHL3wrkOI(HiVajk0LpVx1w&*UFs_>y;RinymL5yToKEp>GId#S6hDb--( zC{|M3S$o-)>D=Ds{sawf_AOP1650#%0L}3yzTPy)EOG$-yg4 zL0uOv{}$`AmT(JilNYW|W0HVzFZ3nD9q$gOvXL<|3z>_6E9ILER|cR#17TKWn=epy zRJx3WqgBG7nG3Z<^RJ1Tx{3E<sC;AEYe*S zS~!CVD*+oWBQ6~5ZcLP3XX9YX>9to-`Ic#Nv-PQ-<#89uW+7dJA@uWVKRWrkM7~H@pc~HFfbtkeayUCn=RnOX!V9H)(CgVx%YNr?HPs z8u_c*1?G5|gOOh#ECftiRdSeJ;#Jzcw|2o==#!QV8uZwuxGDG!GlScR?o;Y+ECd`( zZ=Y&hgDQH$rP+FMjuQ%VOZnRMb2oT+LV7ywLZws#MRGQ+6ogro_>a{x%>PvXRDv$9 zfDbwhHZL}9H$S??7uT1J(=cm5OZq}JXNy~e?s}O0K~a>0*4$s1*`y8-wV#3yy97qo?+`(*nltC#u)Y$D+H;#0MG+=8vGjzz zq1S<(=g7p6k3&94CLd9ak`gvO4CS0vnomrFtf9)1=WE) zJ~5Lm9%hDd0#vdVa>M#hv*FTP$`1C^Wtvuhp0-1oVB6L6yPNwb@8ARkcsB1Xp9TI3 zZ>^0|>SS=;B_aAnA@%WY+Vlb%btga{*K`7fXIa={iDWjzyl{|{i`l{1xg`XU-nWK; zBaE$f$jD>!72yLuTwQ+G6o z_nEL6H-Ca>xh!|Hsg{+Vn69U-cnlupp(qj?te7rsgS1O<8KTLRFrbTAq+t?5v+`~3 zn2oe9ZhL|YG#AQh9IyK)JmJYeVZ`MKN+eI~@Sy)kXZ=wfUe7qev<(sOPCJWu>A&BxGJyu7`FKPd8U z;~*Y0mdpkYeyt)hH^W@Cy7U-a5FBVY@TfRco7Onr7(x}R`;!s>GaQ2^RNE6?mTWeT zwiKYajxvQiiLqys;@%*?dVi6EN^eY;ZoJLCu-pki#KKTLuVct3?@%8$L~;mXP{e0< zFz^h`!gr&MSk3WaE0K~I;77fIQSY33^%?$qP8B?VEEcQiS`t!`?UB@Ihd4H^EGB~v zYeu4xAyl`$^)eP`HcIy?!Zj*!dlMX0ieCsM+MD0sJO@=6jTZ}HQZuvm+%D) zy;s26?;JT@?pcIz8yQl)J5cd`(6f&WNm@^&x{v|ZGI-U8P{8x&ir|kr|DY(DkcsBF zXR!y2wl5LrV&H;fScSUp=J@qj)c-dhr<(LA!XNQU9A5|=U-r0P49~Se2CwkK4>MQ` zvFEM}87}yk2TS5|s^qew#k25|)UNFqB7V9XPXcGtxbc$`3=)Eq*tD10IeW@k-=3*b z{a+B6-#N^A6>G~mU#NK2E1Dovi`5yoYujfTJ-hF(sVhjb%qm@XbnhUq$;-peKUBWEM1d`pyumKLsc0}}vrthD zs@Qp7uG8mq7=71Y&BP@+m0qz^Vr1&CF*u=1LYQb1yL6dho1*NvHC2P6H2bk~?v+zlW$^MQq9{)-2 zV=k`cH^0#dw>_{0P`aofoybHb+FsfzD`OI^*48l)jA=}Rh{RzM#Kr-=B(J&s+?>zu z8S;_@YnN+mqr7=PJN!{Xv=O-yIcgC0ly4;uGkF_UDd{h?|yM0>|q4h!L&)i z2Vz;L17Z}_`zFg%e;yP5B>}c(4@ud!2>ZxLoTo1$oU+gs{p^#mdULgbEzSL$)RctX zQ=|N%Z!B!meGswRi{|o1KSafVzv#k9S^#4bPT!&~<{--%G)y&F(duJsXYV;Tiz&aT z6vNDubJ+1!SxIRI6Gk**6f8KjDtXcYo3>i$CM}LCdbLKh_GJGP5A9RRxI_I+xf1g- ziMmid51HP08Z&r61Fm49*aVMfYEv5PGSZXRcusJ02k=_-y})*SyMtci*TBO?8NOfJ zj%B8q&0l3w=J+a~3M4<7#Kc!t@8QPp@%_dU+}x$u>=Midn?o8IP31A>nW$BIllyX# zF3s7strcDeZS*Ut%Bh>|v z=yK9RC~bV~ZNxETp~Shnnxcv5${uja~52l!$L3>}w0)EFKrHZl-tHm{+9}3B4IRf)k<6IsQHzyPnlJ~Hj`Ef=w{*^f`j4hpg6?VT?GFo z@iGUavfP)pjF3+wTeL~$GG7pI9YSnIf7a#XC6NQGu^%-MjS8--Ay=Zm-Hqwl>zi*k zA*mrxOwXtz%a4AU^1Q@?iu5*UQso5A_C1tdmwXLRHfl2JMmN)lBB*)A&>j5#bR*>0 zc?pLi3#-vES=EQI>N3I*7m2Lsx7=v>KK?H!Bjx*h_8HrdP`p4N}^aMkV+|N7<$i?d-P4l5p!-7XLFL(zlZ+;k`ck zo(+=flv3=RRoxUDAD$|G_c0%=>@gITuxk|M(OR(u5BGrr9Z`p)P z4L1Kwy{ElnOBA+!tJa3NCz#Yp)fp+XaE{;r9xR8x(z(qSE!Ts*o$`#-;lu1ZU=*=)|R${K|+rHi3?k_ z@wR2>lT2D{O)eAh)!H$hN!e%Tw5nUG4twY^C8=W4io-;8mE6t_$)?Uh`a8k)SG2fT zhiij^$aGGY3T*8&C5D5X0NP;3ukHBk$0V-rz3|)P{p~NVZw>_#qdEz(sGj^MXyJsj zf48<2!n_B?C&-cqlbzB&A0X3l8|<1;TlQyM4Rr{@#@%^IdX(*9{fdpKwruwIe31I+T@Et|`J`H6*7;!x_6E&8C9!N=sP&MEH*0dX_g zzwHdb{0JMz@P<}V^k#u7COziSjoMB<>>FN9-Do?uaRxE+ z`Pe!FmbxfABIfvqkSX5+KVK3g(Adw0&Yr*XYzQM@jJ<0Z*`{!n)7ts6gk4v3{dh)A zhCLwQV>N~-TOTAxoo#2$&cpyBAX!gN3c}L3IWcLeQQ=pQ0%BrP?ME(m8(fY(tJ`lQ z#@EBC%QQS{kx*TLySNf5eYLCeJ#4D`f)&nBB{rZ$c?jxd`_Q3Y(%vLbE@aMoCdxsb zE)PM*3ibLi*Zh;klS|`j}G{;RHL)?4t8TLe zk_IVtwH}GK+1?f;2JMF=U|Y>*!+WEkRUDb6?6v6=nA6@xE;mOs)^qX22t{=TbuTn8aarHlZD#%{ZQbG97pB1A2##->6o>07`ljPQFvn!eOj{06DYfu z7UTPm?V&R^eXRlGmz(7IBcg{$c(<;5{p8+oenV=s_WBn4PsBLKT-`7xDQM#sl^UcG z<;JNpn5+N6Wdz!r?!asFn6SYlXg}CQoD^h;qip$FM~gU$KvsC>>0$tUQl9Yrgu}lU znPm>pjY}@tahAdtHw!`c_K9(uDlw-Sh~ct5M&*@)BP7XEIkEd)OJ9kn$Tc1>ghTp8 z4}EG#u2{5v2BF9!&|i|;Fbz{bRi;FupNmxuMx592;JQggZJJ1~u4f;Fs-b(W3a_QsDrIu((l4r%+J5Qx%{81M=6JZ`xsr3BK<_bwp#9Y%~j)ln}N7_ zgw_8vUOl|74KadE3YIeT9yTf6xpeKg^a)kP#XmJK@<_gHT>332VHQhd%~%Z}wq|6cp2@kpJic`|H9=HIF^OVyu4QHI?u;_y)2~f!Llvfvhc2TwXz06KMf5c@cbM)k z!D}}t)L|$ZMbYzfG*(o+unHpL&pHihA0k7aTF0*{HFYsN#PYn-##(F|=jhT6`{|Ez zPikFP^OQ(1beSZY#H)@}>F{$ZYiQ{X#5;A8nyM&gOUGQeHcvM3vc@>017jV)rPYSU zH2}@J;|nIQG}%aS;GSA3*Ad4NmanXzz?3?SUFQ%N|Dt{;BHy5UM!Myuj&7xCfu^Nh zFp5Iiw*uuNo$0#lvZN{#FSjFpeC`*N6=S*2h*vx!RxqFvxvu&AJ)Db^_rJ~)ASdo> z=b6>wY;8<_%5)}7mlWAWqF=V86=DT*HY#P$$(g9@J$TynChop{R*htHvU3X_R!uf) zaxn61s{iVKj^7jaz25B4gDIrf;dr$hDR{i2TGoA&Rset~!8<+kJUNqVnBnV_Tj;!Q zEAvZq&&qtQJV{=PRz*3ap6+U%l0DEm74Cd>e@4o^f~``>2pNw$0UkF0mWxx@$;F?F-nb1lT!05O+pO9mJMIR^ZhkK^ zWk*A@31^Viu57{-EW;4h2@Jd2{!K^6_8RBPc?Qg^ zsHPUH#DWb{1%=ADm^YR-r5mntGfK#CCBO5k+Lq>nwXSJ}iK*y<)&aXXrolga1R>a% zzc6Klx{FK%I%ehnUEur+u#`$ah3?SE#M)rffcZJ(!>TNPgj#N7*xH?))eETeM5(fM z1t0S@`gyuPI|+rUArDq7HPa_&tlv%g_TW0CCF;HrGok$pnFM8bGJ(c!H))`r83lk8 zGB5l#c%#R_C^=!W#qve&%cz^&*g!LqoT?80Y-^c7r@3 z?!I=(^+_uPzRV=o8oxcAd@G)3LMkNC<`1B+k+&DlK{mk|Y-5b09|``!*s=a^av3K6 z4@mIu?0m{3pPubIlJ%{-SBy}dFqhFH3u*?1GpD(%8DzPa7(uQKAx3J_6X8M}EcmV{ zJ-=JaPVb`8`Q}@DlE{BIkO{y}{@qD-vjEu`wwwlDnMTo{tAj@F(g%DEfemHmO`6H@ z1~P~154JcqdN<^WDiY2g{01c!-QpXJ{*7x5P?P@mue|@%V`d$4cE_s41gM1Fw3m-F#!j+ z`_d}S_A*~Rci(JMR5S;K^^|Bv&tK5?`D#R<6jjHxc2=L8V zFFS{q-{4NxJBG8ivGVqeHCHMf|EE2qQz5hb@l`f+PC!-~Og_|QI;jxL!*e)8R0WYV z0w1f5F_|xZgC0Q_OaC0o+Q(p;`p53f?sr++oZj|hS1}n`%$}ULe!JvwCSi^f8!oFf zNM*J}!*SZC<*;$3QAb`T_D6wvd=(^{$m!~W_}u>@{7ip5VR_L%@hp-EfPct_$tRnRK&rxoa?)elPy_Ge+hqC^P-1G8k@BhAlhB~Q&kZQO)h{M&|tUmM+fQUPdy0BSfV~<1~ z+pR}?-WEkca55f3uZsG9UCU9BZZ^s~zHwK|OsNwr}bMkSy!M?RGB)l>XMC#Ae- z+v-2Q2V?<~PRH9|DPXRwWBqHmQi!*(%G#%E5*fJp=_yhZxG699cfQ5F+`n&QF>&e> z!i+H29& z_oo8+1^4DQ7w4?@{S9nHOooU00%-Nsfol7D{prgilyogp8en}d+jOu)e8 zs6%VffAalKFTM)XY>d4P z35>9mR<*^Aq-k+Ppw2~^M!9FZ|651|u*y*QP5i5J$wx-!A4AH;dwzd+q3JBY{rJ2kt_&a+E8+_X5WYxZ zhM5#i{F!9ZY+hKhYfUD;H$a<7bYe9IlsggRZtm0_3}{r#xl0!-)DY;}pLVoAe*srw zvjeuy(iYn|00>>ExL7b?U+&*t!ZZR@BsyH60O0*OD@o>WT?maXvQ8FPwXrYTcp0Dv z>zx-~L~k_{eYuPWpx?^ACq`yI-(yD5kl`!h<{&{r@U`3I3-o*MPZaG+Xb{r#OnG6O zkxe))_zq@;3D6C0Mv5gf*8<{Nh~?8@X}47SbAY%~|43;?YBWkdGWPXvh%gU{McO#k zIGm|O!S}-2pvBTz8}Eas$Ej-uDwGnrFhN+Lw^<~e*F5QMnRS~OSrqU(%ozCHiN|Cv zt6om9(Ix|knveZmey8QrSb-zdS!(4(*a%n;QSneLDXb$h_gP+gA73TMwHaZNLQN&= zLX<0iJIs~hfCw3>0|eH2Ah8hCr_8(k0gbe89fJ$r$WvTGuiZ(O@spn{RH>41^EjLZ zb8L#f-(gml{ChQj09}y=xldO{;&UV{f+W5`zE%YK-y{)aSxQ zt`wDQ4?WDqqIUcEda_F!Y^sq2)qffNwQA$pKD~*rx;Ss2R=d*(ISOpvNo z^E@}kRh$=a=R3?0@)*Bs*6Wn_nP2@RQnsxyUpN(m@?Vg$|8IEMWy3RhKH=S#fI3`F zjz1Jhq}>+BJ`V6}4xnBBLythcYWMwGH*!5^%Q)quOmPH6XF{b!HGsYS{>&K=+)q;a z{66^gx^Nh3xNK&rb!6cVhN;Ca)3SK=`LVNzCzCA=iI*ruEM2y3Ie+)aGlymhLCoEN z@-Q2j_b^OpIk&4}@Jt~qQ1vGWBscv2#?dljS`QjB`@L&dZ}d3>(-t`$D>WS(Jq{Mh z2Uue9*dsAz%<-G(Vj{y#1*;UAw|v77k9=`WJ+c$P0yejN6Zx?f0WK>HF-T%mG5z43ybG)fq>Q9l1-bXs1K1YQIrB7I?L8^!{!961zKOl%KF~!c-OD z(ApLY|IpOkwUW7XYb!9J_Z^0B&Y+>5XR=8P{vGq_d;t%AI-eE^k5_nco-kb3}g@{6m3n^DX;>oh&&dK?t=`OAmC`S8)!sbvmHjxnISg5NB1 zSzx(Am=FrspISJy3^*@92Hqzw`upt!eMJXS+A zQi$X2y5_pS56fhbmtlSj#>uc}0ud6|{C7`Vla^o!?~I8?g%_bTBTulxRvSIVn#%C* z#PlbA#%hFRT3N>&|CWzawd7)k6DyqJ3j~?R8#L1I@bl}O_DaVj;v$oab3yRyc&B1d ztAOk$YVx61_SM+@-nNbUmgO$68PIA^xrE>CvJuqxC{R} z6W+iJNnNy38*7Y4-9HB&29@?5Z1TfPESf@gM-{ z$iKw#VefrG?;C|*g>$^_Fnk5K_`q&1tY6*-y!TxEX_CM5^#r3F6C?$jMWJ2$#|_GS zspPwjjAHW}d8-lLSbx7w?R2wXyRN>}v=uhtRu|@ffEtk9I>e(!J-_H3P24vB@w7l$ zeNyf0+!cM9`WBEa!a)hS!;7I}2$o&8{awB2<2yX#nDa&6bf_O{bu(~Arhlbesaa$C8M@~E&hTO4lzfeNsnOut z$%DyBU9cu708p8vFk0r{+1U_6J?on4IPdH|h4Z_k=9`}@QB$I^LFib?Xr$+&d}cRP z0>(eFn+5N!&{7rrWeczOAimdVWSQoRHp;){r4TYl{+-*BG8fDk@JE@3H3)$rXMa7m*c|3IL4 zOEd3xau&Zm`z+x55I<`lw<|#)`55h036%Giv}9zs&e@OPvE9Qg=wJ1&&;P9f)Z=h| zPp?q@DbhlG#U1b1j>Rx~$DPmS*_2{qyklOWYi*;lntzfPm}))DvlQCCzX}-63XsWC zM-S=4CgCNiM-$7zTe^Z>31(|lTw-Y{^c6^eCgcUW501x01>H~y_-!)GDPxdr_YONF zJx1GlwhfIf?)JT>i{Hm#N8nuW?bHtn|M}bJ4K@nPyut*#(K^-92-Os|au=ql!AI4p z)iOTyYE@~%6&;BJbL`1JB8ocbm^FT!Mh0zS?E)(acJ!R7!8tvSpQ)?JwE?f)uL7;} zTv;h76;x431X4t29fB zwm^ODB7f7Uo~|~93cG+)ZT8Fh9c`IT2&*88(+mmAg#L}4hyef2Avv<{6zSAR{Y|}x zPM*kfRnO)h?+k+#AJ!`P?x~0CXa*GcSD3fomU!lc>uxR@^D`ifF%|V(To2G}Prrj~w@qX3w zP~y?vx$?I4o9=zKr`#f!0K3^fe~jpwWW>Da*PvbB;Bs&jD`v;}#a#{1WqGXWF&YkJ z=40MTm4p|cX9fDsbF2o=7tkYHp8<=7Ak_CPeiHwmaKmWV7ac{ygVoAbb}rjlJ-eyG zD?6vBd{pb$-(9|#C3ddQd3(kr+@V}l ziZt^=&J>IK@F0wmM)Y@kW|q;x@kGgq&_9?+5+Gdap#eI|wlvfcqI*g3C6dq<5g`pO zF;&O(l{MVfFElbD1|c>%tlE5*T!OoH0+zKP+A7Doy5>m*Ko%M1nzQGVh8j_UQc<0A z6oCztB|WKBx9I~rV2=TNY7k^Gy7zb{Xco_`#RQ8a0sVxC(e&5Ubf3zxlKXI8P+*n9 zzNW6dt#@zRPw4R>yf;bmZ-8&oss!9{z31LX58?z$M2lHU#Pu(lg7|K!CYQY3XV>u@ zX)O5nycw`^iEK@iR2f~wEA+@VnuUfI^*5JrsZcyhf-<)JcB@M!U5oh|^)s$9d%vi3 z7Z;WvZcsDjVwZd#l1o~=lNktx{e~2NktJI7f}AEF9|K3phRZoiIVK#{S*(C~2q+)f({Y;4`4c5n|QdV~n z?|KP%8w}|Qv$tW+V;RIMy-N!zyo4<8gkLWw8tWAQIjd8tnx6J2G-N7wFj{P{1dg6p z=(i1l5HkrDeoGEQmS};KKYY5ni>(?hWq%N4stZzA<`$c^)_uP{pAAPVlGNRAu$FXi z{(_0RYDl!eP7GzYX!uXK{%eg2{T^gF`EU?jSWXI{YP(#>FoCQ6wDZ^yrTU?^H{o%v zA!!<>6-_c7dihWG!yJmtsnJ7d#-Gt7@DBI@pyV=kF?!NRQW0E?eLk?MDL)nd6uWGC z!VoJEdBBoN7sp$}7N44A(1oU>Kg;&;3Jcvd*ZHoD}`rSzV){6_AbPygmv%3cN4?bQkpo z-{AGlh`Y4Py)0Q4GQu!qm{P=&Q{TyB=_}O79SJ&;|8ol4Ty1#9FAm)#SJpf^w1?f& zo^$zj6HR@8-|A5-JHe>pzW_(3lgKnQ4wm)p`g(@xj9mgKNqSyfxSk2{Seo5jRCi4X zzaMwlaSPfQ29JzTXQ4purXX;<)^*}dUEj)f{CrZT2LSq=bLV?9+;IuJymh_ov9e5Ds_^!N1hH--6gi{Py})6>@}jFH2Al!uXV} zQ_cv^>pJ%8Z4{Q@FGPuR81U%S7yKV(tD9sh{{;B1zi6L7Go<>_`vnXw8x4#yP*;05 zX1EDzB|T3hx)hio|PsPvv8GGKf(%ez0l;{pHivn7mATJEPHW zPNR_|!uw0Wnh}2fkGR^kgEt_XKgv6MjqxN4ZQe8?;~0}@{dP-f=_Nz_7`*LTTmU6n z6`}5aa70abkGhmImxg1vR%$D@i5|dVidRIj?nS$I{cx!HEY}}zBw*~xW`tcvGmpjB zMVC^~*n6(KV=cjv!6HQB%8DeF$=PWU<38K_Fbhig5E-jqKBKj6bnG2A?17zmF1)c8 zM80s0a-4Ey7+g>B>C=!X)wb)<^>;4~6CN5Rk6)e{j!v^#^>a2_Flml;p zwV{*0=g&>)p#fHHX+Lm3B1)K~fPhXSrba1fp>>{Kx%N$_re7e$E>f6(--O2uciGAz z%c4tR_01+uRB0St!93>Hc2RphqdvfYpm#g$#J;AsX(s>pVqe@Vd5nt4i!h;(HK91a zO`LGH_+qiV<)2^>b3Cwm;g68YN*Bai@tO+>ZCah9!TG>tKJmh=4%Dgn3L72LXf9givm=Beh!!U(v%J7m`UhkmTmo;6j>hC? z@k$;`e13i5oYP>P&NkuxEktz2%JeO5df4|MFK<)@Jn@K)0r=z;dEzMk#}7}l~k39 z;7YdgN-P;rg!ZrbN$S=(v??5xJqYzg`&$`)$PzN70iEkGKZ$MLq@w;eYpCZ1lnm~G z-VBS-Sa&=IB4ozuMnt!QL23`48C3!sBAgzCV z(lLs`a$fr!E@3EzvK%3GaBujs)wmPdXHTZ`;(R71o{sw*-v_5(26KDuYyC{vZvrpo zyoY2I@?Y!p5n>P~$t;AB!vQ+|h4dCw&?cnLkiwl2K>}gcPvQJEHozx9YRNb3Hb-5{ z7R%|K>}5BeazI%Mb6jiko_A?|8?d0>@0Ov|WKD@4N0lPXTH=_V&lH#)aUmFH++3#h z293{#jYkN`3_B_u;Ak?4)k% zlLdhA@FnvVj^ui!1GUxTUX*yPW2&D$bGYw%@f2^04fipWUhnYyx?VKD2^Hk#&v* zH8gdA{5AA$0&zL<3k75x*H8}L4aauA*tvUZb0heAGc&?DsUE!fnI)51`y(rBfWMW$ z9j5xQ6TKS$Vryu~{9g-Gk6&iQNo}0vrzrHR#9d&?nHlCO%hjQ3kapXf?3;ph-P$EeMyek6Px*?W=x1cdLzN_j+b`EZR+R3odw!GZ-d zU)KwA1~Lsj+0nmz^S3RY$Em6&Ro|5zejnW)xZ`uk00xbfsKFmf4?;ss23Zh3y;9Cf ziB!3lChOT81#a36*<~lF6l&9}GT{HrWKkV)s%4BTFWL653JJ-lDFp{*$%ofdjy)!t zpXDa&Hri6Tqq7hwY6ZiWYv!s|D9<6!sgcI2aZD5|foL`LZY;BsA`#kyR2^p5zR#5^ zX?KmD)mX@(BbLk+&YVpjS5GtXx3&kC(;T>?)%e9!-M_&U`DJ7oPC<%M6pBPE8YUH5 zWF|O!^uQT#g_qGYW}{>rO1B@f4>6F=UEf=$df#BK=R_+&ZSJ;V3KMx2T?Y+-XzPGF zH6VB69T{oT-g?UT_YS-3-C=)QfPCzq4_+iW8`0h@Yr|pkX61KFFHkzH4KdodXd;DZ zMKTKq7Nx9IAWW3G)aM^Z3p6~iA&w_S?pXQ;7ucs{gA1@3>)ToNJd{_a`Aa{on=ZSdWNTR_RT}X7Vj?p zEH1w_bQ%RAnzc>^tcsGV7Tq$%DP;=+2nrJEa%oJ^FJk12c9Ak) z_u_CB&|T)gdJr;<^{H_-a(oE*1wuo!;*53)(jXmfg|OnvUx>0~z}U>Q#bzgbWSzDC zhJLKo9%vfOP=cX?r7}NIt8XXT|C^KLSMnconN#~}!NvQyNR3KW=7loHHUDml(=tW$ zSlo#Z7C*k(m08Wi4?2wuUWy7mI>lWVhRj6F{IT`S{-2K{Gw^YVk&sk`)_W1$ABM`y z(`_`<8PXy^P85wt1%T&7n{YpmGxPA{vESyoKJ#JehAiXlqXtZ!pPyWg(k8#{1zcBf zx4-05+kP{Iop*Omr?2$nvhADvFOEEEx z1U*J?Tuys<6L|TU>}3?FS*$!mb0k}T8ElS=zE9;vj6vi#6x4wD6lVINX5v>B_fmUX ze>v(Ekh_NK|Z;a_ZAL_%36_i;lQl;+NPds z^v==`lni-4&Cj2->(BparB z2m>i{F;eV3ui%MmXDzLx-S5@4T+>T*Z_c;Y9c_tbB&qylwT9YGszH~aNCMT0MHm)7rZzNSt@{{EzE0~YrmmRphif< z4<8O}m9tR&+6iBn*md!7!C{(HGaN*!no9Fyc!q;6tiL#qnuNADA-gmBXPq@HUiHJ< zU1+9$Q5wBP1|I}7&={zr_f;pusI+-=b?%)y5yYX@M2F{k$~-5=5*~!cHshDg#y#;_ zrP%N8WpInbbZusJ>{U3_ImAUcL5Gikg40$Jpw;Eih6#hIKU^zkH}-V`Owo>9gtD?C z`oX?;;}Bk_PR_PVwrZuHy;n`uWLAQHfz}&2-8@HSte0K}Z#tEnT#-DHh75^)#3C3V z30y+7Z4xl?IRs!Nkw0OxI_DelVuRteIV@`5@p9hIOoezD>+bGhkN&_SV;F>W-`9X; zz!?w#D7+$3;cmrMj)};6dWL^3F5%z(A0|?XRGvW((pP4ekL@CPbut|tMxEmkVbn;H z`7PYtfIOtDJ=JlhY_IRy>4ZUw=*E@e0>pa7YJI0%D8CbHa>N|wZ8;aZotJd8T$ zbOrVrYI7w&^;PP4s42FHRJH9vdSHNmpLSjJwz?Ikw^s9yJUxx}iAPpuS8PE4tsT%+ z^e0nOTkWlKtiP_n?(+CXHYlc!$+26X>{D#DQy!aVeNY@??9Zx;nPe$6<}}WsbdiLh zn;l9$R&5Z7boG63BmQmHk67?>Mu1>ep64(QZ=Wd9C9S+Z7$|D=X3pfxm8hE9&-c<` z(s1!}v?FSeXU!+d_QRwV!icv_XDlu=R5hUQ7p6yXeP?~iYlp1i>pF64b)|fMQr&tZ5~^i%aaCw+m#NxOrW8$^ z3NKL&93&LxI?TCeCB{)2=U&pUX_x^igRYlhj0{?t@rRiqa-uFCDW_RPbXn?|!{@F- z!dn}zDKdkkw%FE7bW7rPs{IK)(?GCe!16dt=Ff+THDBwDL{M@=WRN;!Hk0YZ+NbF9 zVQ@%0lg-;{WZ7tlZN^D+vGm@%a;d)a;(7E(GEX`?NsjZ?PV&e#%Mnc9oVdJc^q~-{ z5F#xfcBIXw8X?kRuz;kr>6HNKJSSUC!k*W>$VaE=u#}#qBe8v8hq_PV5IS z77Je9?ZYHh*g9E_QfEJTYH4!p?!c`(D>ptnprtP{&V~ee{61gQa+aGyU%Hw3xRGgE zA|>B6LX(%LqEZ~K7<)*f?}Uv_QndzPO}_hr!)w(l@T*`+X#U%&CrlOSO7Sx12WV3I6;n)UX+! zhn|ZqKVBRZ8p`nlkYu~e2h^Cz01}I9-{E)hN>)vd-y%5x3E^^^Jyd9JeP-F_rZfZn ztvhE7fw9~ne}xNNgaQ>K+bT9-f)F?tWA9Z-)9O8NuWcsuNTmecXc>A`Kt? z=0C7tE_2K<1{3J2#)-R7N!!7VgKKD}p%TJirNwf!X(v!nAe*u8)%WM~fXR}6^eWwq zN=MCb)L}UjoSK>Kp(d29_NYX8?eTAcb3^6#t&c;Djfe3E7vcWz@YEWC4z`}LA?4PX z2JR1Is!~)BvN?5t7o)jdi&T->20u19tzek-&1^s{iZz97-hwJ58YqZ#Vgg0fl+;1^ zQQyg{m*knHO^z~W9(QfW`6c~jz#u4go=%x{6Hc4*E~z+hOU1^aVcYHSOrr1~B7;U- zA=^AYDBrfU{YN!{7WhZ?H)6}eZpBWm_)w_!s?TyLo==;@zU|z-Q@=c`-2Cr6IzV(x z*?I!+xtRS!H%E;Ne97amyi4C%>(3qAKh7uhuOMKi)E# z3EH>7m~B3e40DcEOZS8sVLUbhFfOwR9V6E2E0oZ*Hf(Po#e_5i>Y}wOJ-0PhK$rcv(KJQag_YI!b&3gGE>*H>_?pr;PL1`;1u4GxJy;zWa zE46UKbjzBLIc|cRcOCn+uK9N4rmY={r!Tw_D%lMZRA@ggw_;JR>CVpiXe+whWWiQ(}3Y z&wA)ge|3y^+iS(ut2~!pbkMb63F~~7)$uCy7|h;c7LvDnwoBUF zXI@h`mj8d16dxDbc&pi0|{^yJB|BtnQ z=Xs&?H5X(y## zn^*0r-P`{8i!k4_TD#vV{c9zby%n8Q)LtsC<5|Dn!D-shAOCtzsw5ftbj(TC^J!LJ z<@R!~`HOWTDtI;H`F7#4|&bP=G#f3Ky#jV^_xVFp7#mwr-gA!TWlZM_25~4bx(`SM& zB=1-cJPCQ-4j$L*23&GWud=+>^Zl5GmS1N+*KB;YNLs9vduCu2$iPpWi>9o( zvh>ZB%6#!Zo0q?lmo45<-}Pv^!ELpvi`tiY1CK}qog8NcoKNElcKoPuHLqatj+3|g zx-wrzZ1YOp?pUh*IJ~nfbLNe0ot-xCzn@YuWbyV0-qO^bU79gP{EV1Yt!_$H;gJJo zGq+2BSzK2KP`ZO&YNiDRlli%&Nx;a^tSC1n5oIoa!a? zuZ~IOPb}lM+|8Rd9a>-iH#=?f&DC;!AYTDbl++O6TC;xr<6ZAo%XL*SrrdlkIzff= z^wUWX3p`|wudlKIsS<(=Q;Hk pred_from_est(const prob::MultiVarGauss& x_est, double dt) + virtual prob::MultiVarGauss pred_from_est(const prob::MultiVarGauss& x_est, double dt) const { Mat_xx P = x_est.cov(); Mat_xx F_d = this->F_d(x_est.mean(), dt); @@ -106,7 +106,7 @@ class DynamicModel { * @param dt Time step * @return State */ - virtual prob::MultiVarGauss pred_from_state(const State& x, double dt) + virtual prob::MultiVarGauss pred_from_state(const State& x, double dt) const { Mat_xx Q_d = this->Q_d(x, dt); prob::MultiVarGauss x_est_pred(this->f_d(x, dt), Q_d); diff --git a/include/models/imm_model.hpp b/include/models/imm_model.hpp new file mode 100644 index 00000000..16e545be --- /dev/null +++ b/include/models/imm_model.hpp @@ -0,0 +1,117 @@ +/** + * @file imm_model.hpp + * @author Eirik Kolås + * @brief + * @version 0.1 + * @date 2023-11-02 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include +#include +#include + +namespace vortex { +namespace models { + +template +class ImmModel : public DynamicModel { +public: + using typename DynamicModel::State; + using typename DynamicModel::Mat_xx; + using Vec_nn = Eigen::Vector; + using Mat_nn = Eigen::Matrix; + + /** + * @brief Construct a new Imm Model object + * @param models Models to use + * @param jump_matrix Markov jump chain matrix for the transition probabilities. + * I.e. the probability of switching from model i to model j is jump_matrix(i,j). Diagonal should be 0. + * @param hold_times Holding time for each state. Parameter is the mean of an exponential distribution. + */ + ImmModel(std::vector>> models, Mat_nn jump_matrix, Vec_nn hold_times) + : models_(std::move(models)), jump_matrix_(std::move(jump_matrix)), hold_times_(std::move(hold_times)), N_MODELS_(n_models) + { + // Validate input + assert(models_.size() == N_MODELS_); + assert(hold_times_.size() == N_MODELS_); + assert(jump_matrix_.diagonal().isZero()); + + // Normalize jump matrix + for (int i = 0; i < jump_matrix_.rows(); i++) { + jump_matrix_.row(i) /= jump_matrix_.row(i).sum(); + } + } + + /** + * @brief Continuous time dynamics for the first model in the list. + * Use f_c(x, model_idx) to get the dynamics of a specific model. + * @param x State + * @return The first model in the list. + */ + State f_c(const State& x) const override + { + // error if used + assert(false); + return models_.at(0)->f_c(x); + } + + /** + * @brief Continuous time dynamics for a specific model + * + * @param x + * @param model_idx + * @return State + */ + State f_c(const State& x, int model_idx) const + { + return models_.at(model_idx)->f_c(x); + } + + /** + * @brief Compute the continuous-time transition matrix + * See https://en.wikipedia.org/wiki/Continuous-time_Markov_chain + * @return Matrix Continuous-time transition matrix + */ + Mat_nn get_pi_mat_c() const + { + static bool is_cached = false; + static Mat_nn pi_mat_c = Mat_nn::Zero(); + if (is_cached) { return pi_mat_c; } + + Vec_nn t_inv = hold_times_.cwiseInverse(); + Mat_nn = - t_inv.asDiagonal() + t_inv*jump_matrix_; + + is_cached = true; + return pi_mat_c; + } + + /** + * @brief Compute the discrete-time transition matrix + * @return Matrix Discrete-time transition matrix + */ + */ + Mat_nn get_pi_mat_d(double dt) const + { + return (get_pi_mat_c() * dt).exp(); + } + + /** + * @brief Get the dynamic models + * @return models + */ + std::vector>> get_models() const + { + return models_; + } +private: + const std::vector>> models_; + const Mat_nn jump_matrix_; + const Vec_nn hold_times_; +public: + const size_t N_MODELS_; +}; +} // namespace models +} // namespace vortex \ No newline at end of file diff --git a/include/probability/gaussian_mixture.hpp b/include/probability/gaussian_mixture.hpp index c55b50a0..ef4b169a 100644 --- a/include/probability/gaussian_mixture.hpp +++ b/include/probability/gaussian_mixture.hpp @@ -27,8 +27,8 @@ class GaussianMixture { using Vec = Eigen::Vector; using Mat = Eigen::Matrix; - GaussianMixture(std::vector weights, std::vector> gaussians) - : weights_(weights), gaussians_(gaussians) + GaussianMixture(std::vector weights, std::vector> gaussians) + : weights_(std::move(weights)), gaussians_(std::move(gaussians)) { assert(weights_.size() == gaussians_.size()); } @@ -87,14 +87,22 @@ class GaussianMixture { */ int n_dims() const { return (N_DIM_x); } + /** Get the weights of the Gaussian mixture + * @return std::vector + */ + std::vector weights() const { return weights_; } + + /** Get the Gaussians of the Gaussian mixture + * @return std::vector> + */ + std::vector> gaussians() const { return gaussians_; } + private: - std::vector weights_; - std::vector> gaussians_; + const std::vector weights_; + const std::vector> gaussians_; }; // class GaussianMixture } // namespace probability } // namespace vortex - -int sum(int a, int b); \ No newline at end of file diff --git a/scripts/ekf_python3/analysis_py2.py b/scripts/ekf_python3/analysis_py2.py deleted file mode 100644 index ced44beb..00000000 --- a/scripts/ekf_python3/analysis_py2.py +++ /dev/null @@ -1,105 +0,0 @@ -#!/usr/bin/env python -import numpy as np -from numpy import ndarray -import scipy.linalg as la -from ekf_python3.gaussparams_py2 import MultiVarGaussian -from config import DEBUG - - -def get_NIS(z_pred_gauss, z): - """Calculate the normalized innovation squared (NIS), this can be seen as - the normalized measurement prediction error squared. - See (4.66 in the Sensor Fusion book.) - Tip: use the mahalanobis_distance method of z_pred_gauss, (3.2) in the book - - Args: - z_pred_gauss (MultiVarGaussian): predigted measurement gaussian - z (ndarray): measurement - - Returns: - NIS (float): normalized innovation squared - """ - - z_pred, S = z_pred_gauss - - v = z - z_pred - - NIS = np.matmul(v.T, np.matmul(np.linalg.inv(S), v)) - - return NIS - - -def get_NEES(x_gauss, x_gt): - """Calculate the normalized estimation error squared (NEES) - See (4.65 in the Sensor Fusion book). - Tip: use the mahalanobis_distance method of x_gauss, (3.2) in the book - - Args: - x_gauss (MultiVarGaussian): state estimate gaussian - x_gt (ndarray): true state - - Returns: - NEES (float): normalized estimation error squared - """ - - x_hat, P_hat = x_gauss - - err = x_hat - x_gt - - NEES = np.matmul(err.T, np.matmul(np.linalg.inv(P_hat), err)) - - return NEES - - -def get_ANIS(z_pred_gauss_data, z_data): - """Calculate the average normalized innovation squared (ANIS) - Tip: use get_NIS - - Args: - z_pred_gauss_data (Sequence[MultiVarGaussian]): Sequence (List) of - predicted measurement gaussians - z_data (Sequence[ndarray]): Sequence (List) of true measurements - - Returns: - ANIS (float): average normalized innovation squared - """ - - NIS_arr = np.array([]) - - for i in range(len(z_data)): - - NIS = get_NIS(z_pred_gauss_data[i], z_data[i]) - np.append(NIS_arr, NIS) - - ANIS = np.average(NIS_arr) - - return ANIS - - -def get_ANEES(x_upd_gauss_data, x_gt_data): - """Calculate the average normalized estimation error squared (ANEES) - Tip: use get_NEES - - Args: - x_upd_gauss_data (Sequence[MultiVarGaussian]): Sequence (List) of - state estimate gaussians - x_gt_data (Sequence[ndarray]): Sequence (List) of true states - - Returns: - ANEES (float): average normalized estimation error squared - """ - NEES_arr = np.array([]) - - for i in range(len(x_gt_data)): - - NEES = get_NEES(x_upd_gauss_data[i], x_gt_data[i]) - np.append(NEES_arr, NEES) - - ANEES = np.average(NEES_arr) - - return ANEES - - -# def get_RMSE(x_upd_gauss_data: Sequence[MultiVarGaussian], -# x _gt_data: Sequence[ndarray]): -# #TODO diff --git a/scripts/ekf_python3/debugtools_py2.py b/scripts/ekf_python3/debugtools_py2.py deleted file mode 100644 index 86d9ee40..00000000 --- a/scripts/ekf_python3/debugtools_py2.py +++ /dev/null @@ -1,6 +0,0 @@ -#!/usr/bin/env python3 -import numpy as np - - -def isPSD(arr): - return np.allclose(arr, arr.T) and np.all(np.linalg.eigvals(arr) >= 0) diff --git a/scripts/ekf_python3/ekf_py2.py b/scripts/ekf_python3/ekf_py2.py deleted file mode 100644 index 20375657..00000000 --- a/scripts/ekf_python3/ekf_py2.py +++ /dev/null @@ -1,101 +0,0 @@ -#!/usr/bin/env python -## Addapted for use for Vortex NTNU from the course TTK4250. Credit for the underlying code goes to: -## @author: Lars-Christian Tokle, lars-christian.n.tokle@ntnu.no ## -""" -Notation: ----------- -x is generally used for either the state or the mean of a gaussian. It should be clear from context which it is. -P is used about the state covariance -z is a single measurement -Z are multiple measurements so that z = Z[k] at a given time step k -v is the innovation z - h(x) -S is the innovation covariance -""" - -## EKF Algorith notation: -# x_prev = mean of previous state posterior pdf -# P_prev = covariance of previous state posterior pdf - -# x_pred = kinematic prediction through dynamic model. Also called x_bar in literature -# P_pred = predicted prior covariance. Also called P_bar in the literature - -import numpy as np -import scipy.linalg as la - -from config import DEBUG -from ekf_python3.dynamicmodels_py2 import DynamicModel -from ekf_python3.measurementmodels_py2 import MeasurementModel -from ekf_python3.gaussparams_py2 import MultiVarGaussian - -# The EKF - - -class EKF: - - def __init__(self, DM, MM): - - self.dynamic_model = DM - self.sensor_model = MM - - def predict(self, state_upd_prev_gauss, Ts): - """Predict the EKF state Ts seconds ahead.""" - x_prev, P_prev = state_upd_prev_gauss - - Q = self.dynamic_model.Q(x_prev, Ts) - F = self.dynamic_model.F(x_prev, Ts) - - x_pred = self.dynamic_model.f(x_prev, Ts) - - P_pred = np.matmul(F, np.matmul(P_prev, F.T)) + Q - - state_pred_gauss = MultiVarGaussian(x_pred, P_pred) - - return state_pred_gauss - - def update(self, z, state_pred_gauss): - """Given the prediction and measurement, find innovation then - find the updated state estimate.""" - - x_pred, P = state_pred_gauss - - n = len(x_pred) - - H = self.sensor_model.H(x_pred) - R = self.sensor_model.R(x_pred) - - z_pred = self.sensor_model.h(x_pred) - S = np.matmul(H, np.matmul(P, H.T)) + R - - inov = z - z_pred - W = np.matmul(P, np.matmul(H.T, np.linalg.inv(S))) - - x_upd = x_pred + np.matmul(W, inov) - P_upd = np.matmul((np.eye(n) - np.matmul(W, H)), P) - - measure_pred_gauss = MultiVarGaussian(z_pred, S) - state_upd_gauss = MultiVarGaussian(x_upd, P_upd) - - return state_upd_gauss, measure_pred_gauss - - def step_with_info(self, state_upd_prev_gauss, z, Ts): - """ - Predict ekfstate Ts units ahead and then update this prediction with z. - - Returns: - state_pred_gauss: The state prediction - measurement_pred_gauss: - The measurement prediction after state prediction - state_upd_gauss: The predicted state updated with measurement - """ - - state_pred_gauss = self.predict(state_upd_prev_gauss, Ts) - - state_upd_gauss, measure_pred_gauss = self.update(z, state_pred_gauss) - - return state_pred_gauss, measure_pred_gauss, state_upd_gauss - - def step(self, state_upd_prev_gauss, z, Ts): - - _, _, state_upd_gauss = self.step_with_info(state_upd_prev_gauss, z, - Ts) - return state_upd_gauss diff --git a/scripts/ekf_python3/gaussparams_py2.py b/scripts/ekf_python3/gaussparams_py2.py deleted file mode 100644 index c28af20f..00000000 --- a/scripts/ekf_python3/gaussparams_py2.py +++ /dev/null @@ -1,72 +0,0 @@ -#!/usr/bin/env python -from statistics import mean -from turtle import shape -import numpy as np -from numpy import linalg as nla, ndarray - -from ekf_python3.debugtools_py2 import isPSD -from config import DEBUG - - -class MultiVarGaussian: - """A class for using Gaussians""" - - #mean: ndarray # shape=(n,) - #cov: ndarray # shape=(n, n) - - def __init__(self, m, P): - self.mean = m - self.cov = P - - def __post_init__(self): - # This is only for - if __debug__: - if DEBUG: - if not self.mean.shape * 2 == self.cov.shape: - - raise ValueError("mean and cov shape mismatch :" % - (self.mean.shape, self.cov.shape)) - - if not np.all(np.isfinite(self.mean)): - raise ValueError("Non finite mean = ", self.mean) - if not np.all(np.isfinite(self.cov)): - raise ValueError("Non finite cov =", self.cov) - if not isPSD(self.cov): - raise ValueError("Not PSD cov = ", self.cov) - else: - pass - - @property - def ndim(self): - return self.mean.shape[0] - - def mahalanobis_distance(self, x): - """Calculate the mahalanobis distance between self and x. - - This is also known as the quadratic form of the Gaussian. - See (3.2) in the book. - """ - # this method could be vectorized for efficient calls - error = x - self.mean - #mahalanobis_distance = error.T @ nla.solve(self.cov, error) - mahalanobis_distance = np.matmul(error.T, nla.solve(self.cov, error)) - return mahalanobis_distance - - def pdf(self, x): - raise NotImplementedError - - def logpdf(self, x): - raise NotImplementedError - - def gate(self, x, prob): - raise NotImplementedError - - def __iter__(self): # in order to use tuple unpacking - return iter((self.mean, self.cov)) - - def __eq__(self, o): - if not isinstance(o, MultiVarGaussian): - return False - else: - return (np.allclose(self.mean, o.mean) - and np.allclose(self.cov, o.cov)) diff --git a/scripts/vkf_node.py b/scripts/vkf_node.py deleted file mode 100755 index 1db34889..00000000 --- a/scripts/vkf_node.py +++ /dev/null @@ -1,377 +0,0 @@ -#!/usr/bin/env python3 - -#import debugpy -#print("Waiting for VSCode debugger...") -#debugpy.listen(5678) -#debugpy.wait_for_client() - -##EKF imports -#from logging import exception -from re import X - -from ekf_python3.gaussparams_py2 import MultiVarGaussian -from ekf_python3.dynamicmodels_py2 import landmark_gate, landmark_pose_world -from ekf_python3.measurementmodels_py2 import measurement_linear_landmark, LTV_full_measurement_model -from ekf_python3.ekf_py2 import EKF - -#Math imports -import numpy as np - -#ROS imports -import rospy -from std_msgs.msg import String -from vortex_msgs.msg import ObjectPosition -from geometry_msgs.msg import PoseStamped, TransformStamped -import tf.transformations as tft -import tf2_ros -import tf2_geometry_msgs.tf2_geometry_msgs - - -class VKFNode: - - def __init__(self): - ######################################## - ####Things you can change yourself#### - ######################################## - - #Name of the node - node_name = "ekf_vision" - - #Frame names, e.g. "odom" and "cam" - self.parent_frame = 'odom' - self.child_frame = 'odom' - self.object_frame = "" - - self.current_object = "" - - #Subscribe topic - object_topic_subscribe = "aruco_odom_obj" # TODO: put new topic name - mission_topic_subscribe = "/fsm/state" - - ################## - ####EKF stuff##### - ################## - - # Tuning parameters - self.sigma_a = 3 / 5 * np.array([0.05, 0.05, 0.05, 0.05, 0.05, 0.05]) - self.sigma_z = 2 * np.array([0.5, 0.5, 0.5, 0.5, 0.5, 0.5]) - - # Making gate model object - self.landmark_model = landmark_pose_world(self.sigma_a) - - #Gauss prev values - self.x_hat0 = np.array([0, 0, 0, 0, 0, 0]) - self.P_hat0 = np.diag(100 * self.sigma_z) - self.prev_gauss = MultiVarGaussian(self.x_hat0, self.P_hat0) - - ################ - ###ROS stuff#### - ################ - - # ROS node init - rospy.init_node(node_name) - self.last_time = rospy.get_time() - - now = rospy.get_rostime() - rospy.loginfo("Current time %i %i", now.secs, now.nsecs) - - # Subscribe to mission topic - #self.mission_topic = self.current_object + "/execute" - #self.mission_topic_old = self.mission_topic[:] - #self.mission_topic_sub = rospy.Subscriber(mission_topic_subscribe, - # String, self.update_mission) - - # LMS decision logic - self.Fnorm_threshold = 0.1 - self.is_detected = True - self.estimateConverged = False - self.estimateFucked = False - - # Subscriber to gate pose and orientation - self.object_pose_sub = rospy.Subscriber(object_topic_subscribe, - ObjectPosition, - self.obj_pose_callback, - queue_size=1) - - # Publisher to autonomous - self.gate_pose_pub = rospy.Publisher('object_positions_in', - ObjectPosition, - queue_size=1) - - #TF stuff - self.__tfBuffer = tf2_ros.Buffer() - self.__listener = tf2_ros.TransformListener(self.__tfBuffer) - self.__tfBroadcaster = tf2_ros.TransformBroadcaster() - - self.pose_transformer = tf2_geometry_msgs.tf2_geometry_msgs - - #The init will only continue if a transform between parent frame and child frame can be found - while self.__tfBuffer.can_transform(self.parent_frame, - self.child_frame, - rospy.Time()) == 0: - try: - rospy.loginfo("VKF_NODE: No transform between " + - str(self.parent_frame) + ' and ' + - str(self.child_frame)) - rospy.sleep(2) - except: #, tf2_ros.ExtrapolationException (tf2_ros.LookupException, tf2_ros.ConnectivityException) - rospy.sleep(2) - continue - - rospy.loginfo("VKF_NODE: Transform between " + str(self.parent_frame) + - ' and ' + str(self.child_frame) + ' found.') - - ############ - ##Init end## - ############ - - def update_mission(self, mission): - """ - Callback which updates the instance variable storing the fsm state information - - Input: - mission: ROS String message from fsm/state subscription - - """ - self.mission_topic = mission.data - - def get_Ts(self): - """ - Returns the time step since last Kalman update. The previous time is stored in the last_time instance - - Output: - Ts: The time step in seconds since last Kalman Update - """ - Ts = rospy.get_time() - self.last_time - return Ts - - def ekf_function(self, z, ekf): - """ - Performs a Kalman Update given the measurement and an ekf object - - Input: - z: A MultiVarGaussian object containing the result from the update step - - Output: - gauss_x_pred: A MultiVarGauss object resulting from the prediction of the state - Can be used in NEES and NIS analyses - gauss_z_pred: A MultiVarGauss object resulting from the prediction of the measurement - Can be used in NIS analysis of the filter performance - gauss_est: A MultiVarGauss object resulting from the update step - """ - - Ts = self.get_Ts() - - gauss_x_pred, gauss_z_pred, gauss_est = ekf.step_with_info( - self.prev_gauss, z, Ts) - - self.last_time = rospy.get_time() - self.prev_gauss = gauss_est - - return gauss_x_pred, gauss_z_pred, gauss_est - - def est_to_pose(self, gauss_est): - """ - Extracts the mean of the estimate from a MultiVarGaussian object and splits it into position and orientation - - Input: - gauss_est: A MultiVarGaussian object containing the result from the update step - - Output: - pos: A list of length 3 with the position of the estimate - euler_angs: A list of length 3 with the euler angles from the estimate - """ - x_hat = gauss_est.mean - pos = [x_hat[0], x_hat[1], x_hat[2]] - euler_angs = [x_hat[3], x_hat[4], x_hat[5]] - - return pos, euler_angs - - def process_measurement_message(self, msg): - """ - Takes in the msg which is the output of PCP, extracts the needed components and does some calculations/mappings - to get what we need in the different frames for the VKF. - Input: - msg: Output from PCP, a PoseStamped msg - - Output: - z : a 6 dim measurement of positions of object wrt camera in camera frame, and orientation between object and camera in euler angles - R_wc : rotation matrix between odom (world) and camera, needed for the LTV sensor model for the Kalman Filters - cam_pose_position_wc : position of camera in odom (world), needed for the LTV sensor model for the Kalman Filters - """ - # Gets the transform from odom to camera - self.tf_lookup_wc = self.__tfBuffer.lookup_transform( - self.parent_frame, self.child_frame, rospy.Time(), - rospy.Duration(5)) - - # Run the measurement back through tf tree to get the object in odom - msg_transformed_wg = self.pose_transformer.do_transform_pose( - msg.objectPose, self.tf_lookup_wc) - - #Broadcast to tf to make sure we get the correct transform. Uncomment for testing in rviz - self.transformbroadcast("odom", msg_transformed_wg) - - # Extract measurement of transformed and camera message - - # We need the position from the camera measurement - obj_pose_position_cg = np.array([ - msg.objectPose.pose.position.x, msg.objectPose.pose.position.y, - msg.objectPose.pose.position.z - ]) - - # We need the orientation from the world measruement - obj_pose_quat_wg = np.array([ - msg_transformed_wg.pose.orientation.x, - msg_transformed_wg.pose.orientation.y, - msg_transformed_wg.pose.orientation.z, - msg_transformed_wg.pose.orientation.w - ]) - - # We need to detection in world frame for creating new hypotheses - self.detection_position_odom = np.array([ - msg_transformed_wg.pose.position.x, - msg_transformed_wg.pose.position.y, - msg_transformed_wg.pose.position.z - ]) - - # Get time-varying transformation from world to camera - - # We need the position for the EKF - cam_pose_position_wc = np.array([ - self.tf_lookup_wc.transform.translation.x, - self.tf_lookup_wc.transform.translation.y, - self.tf_lookup_wc.transform.translation.z - ]) - - # We need the quaternion to make into a Rot matrix for the EKF - cam_pose_quat_wc = np.array([ - self.tf_lookup_wc.transform.rotation.x, - self.tf_lookup_wc.transform.rotation.y, - self.tf_lookup_wc.transform.rotation.z, - self.tf_lookup_wc.transform.rotation.w - ]) - - # Rotation from world to camera, needed for the LTV model - R_wc = tft.quaternion_matrix(cam_pose_quat_wc) - R_wc = R_wc[:3, :3] - - # Prepare measurement vector - z_phi, z_theta, z_psi = tft.euler_from_quaternion(obj_pose_quat_wg, - axes='sxyz') - - z = obj_pose_position_cg - z = np.append(z, [z_phi, z_theta, z_psi]) - - return z, R_wc, cam_pose_position_wc - - def check_filter_convergence(self, gauss_estimate): - """ - Sets the convergence boolean to True if Frobenius norm under a threshold - - Input: - gauss_estimate: A MultiVarGaussian containing the result from the Kalman Update - """ - cov = gauss_estimate.cov - Fnorm_P = np.linalg.norm(cov, "fro") - - if Fnorm_P < self.Fnorm_threshold: - self.estimateConverged = True - else: - pass - - def transformbroadcast(self, parent_frame, p): - """ - Publishes a transform representing the result from the Kalman Update given the name of the parent - frame and the objectPose message published for the landmark server. Used mainly for the purposes of - visualization and debugging. - - Input: - parent_frame: A string which is the parent frame - p : An objectPose which is the message published to landmark server - """ - - t = TransformStamped() - t.header.stamp = rospy.Time.now() - t.header.frame_id = parent_frame - t.child_frame_id = "object_" + self.current_object - t.transform.translation.x = p.pose.position.x - t.transform.translation.y = p.pose.position.y - t.transform.translation.z = p.pose.position.z - t.transform.rotation.x = p.pose.orientation.x - t.transform.rotation.y = p.pose.orientation.y - t.transform.rotation.z = p.pose.orientation.z - t.transform.rotation.w = p.pose.orientation.w - self.__tfBroadcaster.sendTransform(t) - - def publish_object(self, objectID, ekf_position, ekf_pose_quaterion): - p = ObjectPosition() - #p.pose.header[] - p.objectID = objectID - # p.objectPose.header = "object_" + str(objectID) - p.objectPose.pose.position.x = ekf_position[0] - p.objectPose.pose.position.y = ekf_position[1] - p.objectPose.pose.position.z = ekf_position[2] - p.objectPose.pose.orientation.x = ekf_pose_quaterion[0] - p.objectPose.pose.orientation.y = ekf_pose_quaterion[1] - p.objectPose.pose.orientation.z = ekf_pose_quaterion[2] - p.objectPose.pose.orientation.w = ekf_pose_quaterion[3] - - p.isDetected = self.is_detected - p.estimateConverged = self.estimateConverged - p.estimateFucked = self.estimateFucked - - self.gate_pose_pub.publish(p) - rospy.loginfo("Object published: %s", objectID) - self.transformbroadcast(self.parent_frame, p.objectPose) - - def obj_pose_callback(self, msg): - - #objID = self.mission_topic.split("/")[0] - objID = msg.objectID - # rospy.loginfo("Object data recieved for: %s", objID) - self.current_object = objID - - # Deprecated due to not using search/converge/execute this year #TODO: figure out a new way to do this logic - #if self.mission_topic == self.current_object + "/execute": - # rospy.loginfo("Mission status: %s", objID) - # self.prev_gauss = MultiVarGaussian(self.x_hat0, self.P_hat0) - # self.last_time = rospy.get_time() - # return None - - # Process msg of measurement - z, R_wc, cam_pose_position_wc = self.process_measurement_message(msg) - - # Initialization using the current measurement mapped to odom - if sorted(self.prev_gauss.mean) == sorted(self.x_hat0): - z = np.append(self.detection_position_odom[:3], z[3:]) - self.prev_gauss = MultiVarGaussian(z, self.P_hat0) - self.last_time = rospy.get_time() - return None - - # Create sensor model and ekf objects - full_measurement_model = LTV_full_measurement_model( - self.sigma_z, cam_pose_position_wc, R_wc) - full_ekf = EKF(self.landmark_model, full_measurement_model) - - # Call EKF step and format the data - _, _, gauss_est = self.ekf_function(z, full_ekf) - - # Format update Gaussian object - ekf_position, ekf_pose = self.est_to_pose(gauss_est) - ekf_pose_quaterion = tft.quaternion_from_euler(ekf_pose[0], - ekf_pose[1], - ekf_pose[2]) - - # Publish data, update mission topic - #self.mission_topic_old = self.mission_topic - self.check_filter_convergence(gauss_est) - self.publish_object(objID, ekf_position, ekf_pose_quaterion) - - -if __name__ == '__main__': - while not rospy.is_shutdown(): - try: - ekf_vision = VKFNode() - rospy.spin() - except rospy.ROSInterruptException: - pass diff --git a/test/ekf_test.cpp b/test/ekf_test.cpp new file mode 100644 index 00000000..67e9c33a --- /dev/null +++ b/test/ekf_test.cpp @@ -0,0 +1,38 @@ +#include +#include + +#include +#include +#include "test_models.hpp" + +using namespace vortex::filters; +using namespace vortex::models; +using namespace vortex::prob; + + +using State = typename SimpleDynamicModel::State; +using Mat_xx = typename SimpleDynamicModel::Mat_xx; +using Measurement = typename SimpleSensorModel::Measurement; +const int N_DIMS_x = SimpleDynamicModel::N_DIM_x; +const int N_DIMS_z = SimpleSensorModel::N_DIM_z; + +TEST(EKF, Simple) { + + SimpleDynamicModel dynamic_model; + SimpleSensorModel sensor_model; + EKF ekf(dynamic_model, sensor_model); + + // Initial state + MultiVarGauss x({0, 0}, Mat_xx::Identity()); + + // Predict + auto [x_est_pred, z_est_pred] = ekf.predict(x, 0.1); + + + // Update + Measurement z = {1, 1}; + ekf.update(x_est_pred, z_est_pred, z); + + // Check that the state is close to zero + // ASSERT_TRUE(x.isMuchSmallerThan(State::Ones())); +} diff --git a/test/main.cpp b/test/main.cpp index ec43c686..5de89115 100644 --- a/test/main.cpp +++ b/test/main.cpp @@ -3,6 +3,9 @@ int main(int argc, char **argv) { + (void)argc; + (void)argv; + Eigen::initParallel(); Eigen::setNbThreads(8); diff --git a/test/test_models.hpp b/test/test_models.hpp index 066e6e27..c175361c 100644 --- a/test/test_models.hpp +++ b/test/test_models.hpp @@ -6,6 +6,7 @@ class SimpleDynamicModel : public vortex::models::DynamicModel<2> { public: using typename DynamicModel<2>::State; using typename DynamicModel<2>::Mat_xx; + using DynamicModel<2>::N_DIM_x; // A stable state transition State f_c(const State &x) const override @@ -33,6 +34,8 @@ class SimpleSensorModel : public vortex::models::SensorModel<2, 2> { using typename SensorModel<2, 2>::Mat_xx; using typename SensorModel<2, 2>::Mat_zx; using typename SensorModel<2, 2>::Mat_zz; + using SensorModel<2, 2>::N_DIM_x; + using SensorModel<2, 2>::N_DIM_z; Measurement h(const State& x) const override { From fb4357bf94609bfdf7299aa2bac66b226061032c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Sat, 4 Nov 2023 12:50:43 +0100 Subject: [PATCH 06/62] Changed typenames. EKF compiles now --- include/filters/ekf.hpp | 60 ++++++++++++++++++++------------ include/filters/imm_filter.hpp | 6 ++-- include/models/dynamic_model.hpp | 56 ++++++++++++++++------------- include/models/imm_model.hpp | 12 +++---- include/models/sensor_model.hpp | 39 ++++++++++++--------- test/dynamic_model_test.cpp | 4 +-- test/ekf_test.cpp | 21 ++++++----- test/sensor_model_test.cpp | 20 +++++------ test/test_models.hpp | 58 +++++++++++++++--------------- 9 files changed, 154 insertions(+), 122 deletions(-) diff --git a/include/filters/ekf.hpp b/include/filters/ekf.hpp index 57431a0a..14b82f24 100644 --- a/include/filters/ekf.hpp +++ b/include/filters/ekf.hpp @@ -12,19 +12,32 @@ #pragma once #include #include +#include +#include namespace vortex { namespace filters { -/** @brief Extended Kalman Filter +/** @brief Extended Kalman Filter. (I stands for interface, T for Type) * - * @tparam DynamicModel Dynamic model type. Has to have function for Jacobian of state transition. - * @tparam SensorModel Sensor model type. Has to have function for Jacobian of measurement. (get_H) + * @tparam DynamicModelI Dynamic model type. Has to have function for Jacobian of state transition. + * @tparam SensorModelI Sensor model type. Has to have function for Jacobian of measurement. (get_H) */ template class EKF { static constexpr int N_DIM_x = DynamicModelT::N_DIM_x; static constexpr int N_DIM_z = SensorModelT::N_DIM_z; + using DynModI = models::DynamicModelI; + using SensModI = models::SensorModelI; + using Vec_x = typename DynModI::Vec_x; + using Mat_xx = typename DynModI::Mat_xx; + using Vec_z = typename SensModI::Vec_z; + using Mat_zz = typename SensModI::Mat_zz; + using Mat_zx = typename SensModI::Mat_zx; + using Mat_xz = typename SensModI::Mat_xz; + using Gauss_x = typename DynModI::Gauss_x; + using Gauss_z = typename SensModI::Gauss_z; + public: EKF(DynamicModelT dynamic_model, SensorModelT sensor_model) : dynamic_model_(std::move(dynamic_model)), sensor_model_(std::move(sensor_model)) {} @@ -33,45 +46,46 @@ class EKF { * @param x_est_prev Previous state estimate * @param dt Time step */ - std::pair, prob::MultiVarGauss> predict(const prob::MultiVarGauss& x_est_prev, double dt) { - auto x_est_pred = dynamic_model_.pred_from_est(x_est_prev, dt); - auto z_est_pred = sensor_model_.pred_from_est(x_est_pred); + std::pair predict(const Gauss_x& x_est_prev, double dt) { + Gauss_x x_est_pred = dynamic_model_.pred_from_est(x_est_prev, dt); + Gauss_z z_est_pred = sensor_model_.pred_from_est(x_est_pred); return {x_est_pred, z_est_pred}; } /** Perform one EKF update step * @param x_est_pred Predicted state * @param z_est_pred Predicted measurement - * @param z_meas Measurement + * @param z_meas Vec_z * @return MultivarGauss Updated state */ - prob::MultiVarGauss update(const prob::MultiVarGauss& x_est_pred, const prob::MultiVarGauss& z_est_pred, const Eigen::Vector& z_meas) { - auto H_mat = sensor_model_.H(x_est_pred.mean()); - auto R_mat = sensor_model_.R(x_est_pred.mean()); - auto P_mat = x_est_pred.cov(); - auto S_mat = z_est_pred.cov(); - auto S_mat_inv = z_est_pred.cov_inv(); - auto I = Eigen::Matrix::Identity(); + Gauss_x update(const Gauss_x& x_est_pred, const Gauss_z& z_est_pred, const Vec_z& z_meas) { + Mat_xz H_mat = sensor_model_.H(x_est_pred.mean()); + Mat_zz R_mat = sensor_model_.R(x_est_pred.mean()); + Mat_xx P_mat = x_est_pred.cov(); + Mat_zz S_mat_inv = z_est_pred.cov_inv(); + Mat_xx I = Mat_xx::Identity(N_DIM_x, N_DIM_x); - Eigen::Matrix kalman_gain = P_mat * H_mat.transpose() * S_mat_inv; - Eigen::Vector innovation = z_meas - z_est_pred.mean(); + Mat_xz kalman_gain = P_mat * H_mat.transpose() * S_mat_inv; + Vec_z innovation = z_meas - z_est_pred.mean(); - Eigen::Matrix state_upd_mean = x_est_pred.mean() + kalman_gain * innovation; + Vec_x state_upd_mean = x_est_pred.mean() + kalman_gain * innovation; // Use the Joseph form of the covariance update to ensure positive definiteness - Eigen::Matrix state_upd_cov = (I - kalman_gain * H_mat) * P_mat * (I - kalman_gain * H_mat).transpose() + kalman_gain * R_mat * kalman_gain.transpose(); + Mat_xx state_upd_cov = (I - kalman_gain * H_mat) * P_mat * (I - kalman_gain * H_mat).transpose() + kalman_gain * R_mat * kalman_gain.transpose(); - return prob::MultiVarGauss(state_upd_mean, state_upd_cov); + return {state_upd_mean, state_upd_cov}; } /** * @brief Perform one EKF update step * @param x_est_prev Previous state estimate - * @param z_meas Measurement + * @param z_meas Vec_z * @param dt Time step */ - std::tuple, prob::MultiVarGauss, prob::MultiVarGauss> step(const prob::MultiVarGauss& x_est_prev, const Eigen::Vector& z_meas, double dt) { - auto [x_est_pred, z_est_pred] = predict(dt, x_est_prev); - auto x_est_upd = update(x_est_pred, z_est_pred, z_meas); + std::tuple step(const Gauss_x& x_est_prev, const Gauss_z& z_meas, double dt) { + std::pair pred = predict(dt, x_est_prev); + Gauss_x x_est_pred = pred.first; + Gauss_z z_est_pred = pred.second; + Gauss_x x_est_upd = update(x_est_pred, z_est_pred, z_meas); return {x_est_upd, x_est_pred, z_est_pred}; } diff --git a/include/filters/imm_filter.hpp b/include/filters/imm_filter.hpp index daf23384..57af84e5 100644 --- a/include/filters/imm_filter.hpp +++ b/include/filters/imm_filter.hpp @@ -81,7 +81,7 @@ class ImmFilter { * @brief Calculate the mode-match filter outputs (6.36), following step 3 in (6.4.1) in the book * * @param moment_based_preds Moment-based predictions - * @param z_meas Measurement + * @param z_meas Vec_z * @param dt Time step */ std::tuple>, std::vector>, std::vector>>> mode_match_filter(const std::vector>& moment_based_preds, Vec_zz z_meas, double dt) @@ -101,7 +101,7 @@ class ImmFilter { /** * @brief Update the mixing probabilites using (6.37) from setp 3 and (6.38) from step 4 in (6.4.1) in the book * @param ekf_outs Mode-match filter outputs - * @param z_meas Measurement + * @param z_meas Vec_z * @param dt Time step * @param weights Weights */ @@ -127,7 +127,7 @@ class ImmFilter { * @brief Perform one IMM filter step * * @param x_est_prev Mixture from previous time step - * @param z_meas Measurement + * @param z_meas Vec_z * @param dt Time step */ std::tuple, prob::GaussianMixture, prob::GaussianMixture step(const prob::GaussianMixture& x_est_prev, Vec_z z_meas, double dt) diff --git a/include/models/dynamic_model.hpp b/include/models/dynamic_model.hpp index 0c6c6fcc..def62ac9 100644 --- a/include/models/dynamic_model.hpp +++ b/include/models/dynamic_model.hpp @@ -18,58 +18,64 @@ namespace vortex { namespace models { template -class DynamicModel { +/** + * @brief Interface for dynamic models. + * + */ +class DynamicModelI { public: - static constexpr int N_DIM_x = n_dim_x; - using State = Eigen::Vector; + static constexpr int N_DIM_x = n_dim_x; // Declare so that children of this class can reference it + using Vec_x = Eigen::Vector; using Mat_xx = Eigen::Matrix; - virtual ~DynamicModel() = default; + using Gauss_x = prob::MultiVarGauss; + + virtual ~DynamicModelI() = default; /** Continuos time dynamics - * @param x State + * @param x Vec_x * @return State_dot */ - virtual State f_c(const State& x) const = 0; + virtual Vec_x f_c(const Vec_x& x) const = 0; /** Jacobian of continuous time dynamics - * @param x State + * @param x Vec_x * @return State_jac */ - virtual Mat_xx A_c(const State& x) const = 0; + virtual Mat_xx A_c(const Vec_x& x) const = 0; /** Continuous time process noise - * @param x State + * @param x Vec_x * @return Matrix Process noise covariance */ - virtual Mat_xx Q_c(const State& x) const = 0; + virtual Mat_xx Q_c(const Vec_x& x) const = 0; /** Discrete time dynamics - * @param x State + * @param x Vec_x * @param dt Time step - * @return State + * @return Vec_x */ - virtual State f_d(const State& x, double dt) const + virtual Vec_x f_d(const Vec_x& x, double dt) const { return F_d(x, dt) * x; } /** Jacobian of discrete time dynamics - * @param x State + * @param x Vec_x * @param dt Time step * @return State_jac */ - virtual Mat_xx F_d(const State& x, double dt) const + virtual Mat_xx F_d(const Vec_x& x, double dt) const { // Use (4.58) from the book return (A_c(x) * dt).exp(); } /** Discrete time process noise - * @param x State + * @param x Vec_x * @param dt Time step * @return Matrix Process noise covariance */ - virtual Mat_xx Q_d(const State& x, double dt) const + virtual Mat_xx Q_d(const Vec_x& x, double dt) const { // See https://en.wikipedia.org/wiki/Discretization#Discretization_of_process_noise for more info @@ -87,29 +93,29 @@ class DynamicModel { /** Get the predicted state distribution given a state estimate - * @param x_est State estimate + * @param x_est Vec_x estimate * @param dt Time step - * @return State + * @return Vec_x */ - virtual prob::MultiVarGauss pred_from_est(const prob::MultiVarGauss& x_est, double dt) const + virtual Gauss_x pred_from_est(const Gauss_x& x_est, double dt) const { Mat_xx P = x_est.cov(); Mat_xx F_d = this->F_d(x_est.mean(), dt); Mat_xx Q_d = this->Q_d(x_est.mean(), dt); - prob::MultiVarGauss x_est_pred(this->f_d(x_est.mean(), dt), F_d * P * F_d.transpose() + Q_d); + Gauss_x x_est_pred(this->f_d(x_est.mean(), dt), F_d * P * F_d.transpose() + Q_d); return x_est_pred; } /** Get the predicted state distribution given a state - * @param x State + * @param x Vec_x * @param dt Time step - * @return State + * @return Vec_x */ - virtual prob::MultiVarGauss pred_from_state(const State& x, double dt) const + virtual Gauss_x pred_from_state(const Vec_x& x, double dt) const { Mat_xx Q_d = this->Q_d(x, dt); - prob::MultiVarGauss x_est_pred(this->f_d(x, dt), Q_d); + Gauss_x x_est_pred(this->f_d(x, dt), Q_d); return x_est_pred; } diff --git a/include/models/imm_model.hpp b/include/models/imm_model.hpp index 16e545be..6e018688 100644 --- a/include/models/imm_model.hpp +++ b/include/models/imm_model.hpp @@ -17,10 +17,10 @@ namespace vortex { namespace models { template -class ImmModel : public DynamicModel { +class ImmModel : public DynamicModelI { public: - using typename DynamicModel::State; - using typename DynamicModel::Mat_xx; + using typename DynamicModelI::State; + using typename DynamicModelI::Mat_xx; using Vec_nn = Eigen::Vector; using Mat_nn = Eigen::Matrix; @@ -31,7 +31,7 @@ class ImmModel : public DynamicModel { * I.e. the probability of switching from model i to model j is jump_matrix(i,j). Diagonal should be 0. * @param hold_times Holding time for each state. Parameter is the mean of an exponential distribution. */ - ImmModel(std::vector>> models, Mat_nn jump_matrix, Vec_nn hold_times) + ImmModel(std::vector>> models, Mat_nn jump_matrix, Vec_nn hold_times) : models_(std::move(models)), jump_matrix_(std::move(jump_matrix)), hold_times_(std::move(hold_times)), N_MODELS_(n_models) { // Validate input @@ -102,12 +102,12 @@ class ImmModel : public DynamicModel { * @brief Get the dynamic models * @return models */ - std::vector>> get_models() const + std::vector>> get_models() const { return models_; } private: - const std::vector>> models_; + const std::vector>> models_; const Mat_nn jump_matrix_; const Vec_nn hold_times_; public: diff --git a/include/models/sensor_model.hpp b/include/models/sensor_model.hpp index 886c2aec..a160545a 100644 --- a/include/models/sensor_model.hpp +++ b/include/models/sensor_model.hpp @@ -17,29 +17,36 @@ namespace models { template -class SensorModel { +/** + * @brief Interface for sensor models. + * + */ +class SensorModelI { public: - static constexpr int N_DIM_x = n_dim_x; - static constexpr int N_DIM_z = n_dim_z; - using Measurement = Eigen::Vector; - using State = Eigen::Vector; - using Mat_xx = Eigen::Matrix; - using Mat_zx = Eigen::Matrix; - using Mat_zz = Eigen::Matrix; + static constexpr int N_DIM_x = n_dim_x; // Declare so that children of this class can reference it + static constexpr int N_DIM_z = n_dim_z; // Declare so that children of this class can reference it + using Vec_z = Eigen::Vector; + using Vec_x = Eigen::Vector; + using Mat_xx = Eigen::Matrix; + using Mat_zx = Eigen::Matrix; + using Mat_xz = Eigen::Matrix; + using Mat_zz = Eigen::Matrix; + using Gauss_x = prob::MultiVarGauss; + using Gauss_z = prob::MultiVarGauss; - virtual ~SensorModel() = default; + virtual ~SensorModelI() = default; - virtual Measurement h(const State& x) const = 0; - virtual Mat_zx H(const State& x) const = 0; - virtual Mat_zz R(const State& x) const = 0; + virtual Vec_z h(const Vec_x& x) const = 0; + virtual Mat_zx H(const Vec_x& x) const = 0; + virtual Mat_zz R(const Vec_x& x) const = 0; /** * @brief Get the predicted measurement distribution given a state estimate. Updates the covariance * - * @param x_est State estimate + * @param x_est Vec_x estimate * @return prob::MultiVarGauss */ - virtual prob::MultiVarGauss pred_from_est(const prob::MultiVarGauss& x_est) const + virtual Gauss_z pred_from_est(const Gauss_x& x_est) const { Mat_xx P = x_est.cov(); Mat_zx H = this->H(x_est.mean()); @@ -50,10 +57,10 @@ class SensorModel { /** * @brief Get the predicted measurement distribution given a state. Does not update the covariance - * @param x State + * @param x Vec_x * @return prob::MultiVarGauss */ - virtual prob::MultiVarGauss pred_from_state(const State& x) const + virtual Gauss_z pred_from_state(const Vec_x& x) const { return {this->h(x), this->R(x)}; } diff --git a/test/dynamic_model_test.cpp b/test/dynamic_model_test.cpp index d498ad85..2a1419fb 100644 --- a/test/dynamic_model_test.cpp +++ b/test/dynamic_model_test.cpp @@ -4,7 +4,7 @@ namespace simple_dynamic_model_test { -using State = typename SimpleDynamicModel::State; +using Vec_x = typename SimpleDynamicModel::Vec_x; using Mat_xx = typename SimpleDynamicModel::Mat_xx; TEST(DynamicModel, initSimpleModel) @@ -16,7 +16,7 @@ TEST(DynamicModel, iterateSimpleModel) { SimpleDynamicModel model; double dt = 1.0; - State x = State::Zero(); + Vec_x x = Vec_x::Zero(); for (size_t i = 0; i < 10; i++) { diff --git a/test/ekf_test.cpp b/test/ekf_test.cpp index 67e9c33a..5c2531e1 100644 --- a/test/ekf_test.cpp +++ b/test/ekf_test.cpp @@ -10,11 +10,15 @@ using namespace vortex::models; using namespace vortex::prob; -using State = typename SimpleDynamicModel::State; -using Mat_xx = typename SimpleDynamicModel::Mat_xx; -using Measurement = typename SimpleSensorModel::Measurement; const int N_DIMS_x = SimpleDynamicModel::N_DIM_x; const int N_DIMS_z = SimpleSensorModel::N_DIM_z; +using DynModI = DynamicModelI; +using SensModI = SensorModelI; +using Vec_x = typename DynModI::Vec_x; +using Mat_xx = typename DynModI::Mat_xx; +using Vec_z = typename SensModI::Vec_z; +using Gauss_x = typename DynModI::Gauss_x; +using Gauss_z = typename SensModI::Gauss_z; TEST(EKF, Simple) { @@ -23,16 +27,17 @@ TEST(EKF, Simple) { EKF ekf(dynamic_model, sensor_model); // Initial state - MultiVarGauss x({0, 0}, Mat_xx::Identity()); + Gauss_x x({0, 0}, Mat_xx::Identity()); // Predict - auto [x_est_pred, z_est_pred] = ekf.predict(x, 0.1); - + auto pred = ekf.predict(x, 0.1); + Gauss_x x_est_pred = pred.first; + Gauss_z z_est_pred = pred.second; // Update - Measurement z = {1, 1}; + Vec_z z = {1, 1}; ekf.update(x_est_pred, z_est_pred, z); // Check that the state is close to zero - // ASSERT_TRUE(x.isMuchSmallerThan(State::Ones())); + // ASSERT_TRUE(x.isMuchSmallerThan(Vec_x::Ones())); } diff --git a/test/sensor_model_test.cpp b/test/sensor_model_test.cpp index c870b96f..ebb8cd87 100644 --- a/test/sensor_model_test.cpp +++ b/test/sensor_model_test.cpp @@ -5,26 +5,26 @@ namespace simple_sensor_model_test { -using Measurement = typename SimpleSensorModel::Measurement; -using State = typename SimpleSensorModel::State; +using Measurement = typename SimpleSensorModel::Vec_z; +using Vec_x = typename SimpleSensorModel::Vec_x; using Mat_xx = typename SimpleSensorModel::Mat_xx; TEST(SensorModel, initSimpleModel) { SimpleSensorModel model; - EXPECT_EQ(model.h(State::Zero()), State::Zero()); + EXPECT_EQ(model.h(Vec_x::Zero()), Vec_x::Zero()); - State x{1,2}; + Vec_x x{1,2}; EXPECT_EQ(model.h(x), x); } TEST(SensorModel, predictSimpleModel) { SimpleSensorModel model; - vortex::prob::MultiVarGauss<2> x_est{State::Zero(), Mat_xx::Identity()}; + vortex::prob::MultiVarGauss<2> x_est{Vec_x::Zero(), Mat_xx::Identity()}; vortex::prob::MultiVarGauss<2> pred = model.pred_from_est(x_est); - EXPECT_EQ(pred.mean(), State::Zero()); + EXPECT_EQ(pred.mean(), Vec_x::Zero()); EXPECT_TRUE(pred.cov().isApprox(Mat_xx::Identity()*1.1)); pred = model.pred_from_state(x_est.mean()); @@ -36,17 +36,17 @@ TEST(SensorModel, predictSimpleModel) namespace variable_length_sensor_model_test { -using Measurement = typename VariableLengthSensorModel::Measurement; -using State = typename VariableLengthSensorModel::State; +using Measurement = typename VariableLengthSensorModel::Vec_z; +using Vec_x = typename VariableLengthSensorModel::Vec_x; using Mat_xx = typename VariableLengthSensorModel::Mat_xx; TEST(SensorModel, initVariableLengthModel) { const int N_DIMS_z = 3; VariableLengthSensorModel model(N_DIMS_z); - EXPECT_EQ(model.h(State::Zero()), State::Zero()); + EXPECT_EQ(model.h(Vec_x::Zero()), Vec_x::Zero()); - State x{1,2}; + Vec_x x{1,2}; EXPECT_EQ(model.h(x), x); } diff --git a/test/test_models.hpp b/test/test_models.hpp index c175361c..9c14927f 100644 --- a/test/test_models.hpp +++ b/test/test_models.hpp @@ -2,52 +2,52 @@ #include #include -class SimpleDynamicModel : public vortex::models::DynamicModel<2> { +class SimpleDynamicModel : public vortex::models::DynamicModelI<2> { public: - using typename DynamicModel<2>::State; - using typename DynamicModel<2>::Mat_xx; - using DynamicModel<2>::N_DIM_x; + using typename DynamicModelI<2>::Vec_x; + using typename DynamicModelI<2>::Mat_xx; + using DynamicModelI<2>::N_DIM_x; // A stable state transition - State f_c(const State &x) const override + Vec_x f_c(const Vec_x &x) const override { return -x; } - Mat_xx A_c(const State &x) const override + Mat_xx A_c(const Vec_x &x) const override { (void)x; // unused return -Mat_xx::Identity(); } - Mat_xx Q_c(const State &x) const override + Mat_xx Q_c(const Vec_x &x) const override { (void)x; // unused return Mat_xx::Identity(); } }; -class SimpleSensorModel : public vortex::models::SensorModel<2, 2> { +class SimpleSensorModel : public vortex::models::SensorModelI<2, 2> { public: - using typename SensorModel<2, 2>::Measurement; - using typename SensorModel<2, 2>::State; - using typename SensorModel<2, 2>::Mat_xx; - using typename SensorModel<2, 2>::Mat_zx; - using typename SensorModel<2, 2>::Mat_zz; - using SensorModel<2, 2>::N_DIM_x; - using SensorModel<2, 2>::N_DIM_z; + using typename SensorModelI<2, 2>::Vec_z; + using typename SensorModelI<2, 2>::Vec_x; + using typename SensorModelI<2, 2>::Mat_xx; + using typename SensorModelI<2, 2>::Mat_zx; + using typename SensorModelI<2, 2>::Mat_zz; + using SensorModelI<2, 2>::N_DIM_x; + using SensorModelI<2, 2>::N_DIM_z; - Measurement h(const State& x) const override + Vec_z h(const Vec_x& x) const override { return x; } - Mat_zx H(const State& x) const override + Mat_zx H(const Vec_x& x) const override { (void)x; // unused return Mat_zx::Identity(); } - Mat_zz R(const State& x) const override + Mat_zz R(const Vec_x& x) const override { (void)x; // unused return Mat_zz::Identity()*0.1; @@ -55,30 +55,30 @@ class SimpleSensorModel : public vortex::models::SensorModel<2, 2> { }; -class VariableLengthSensorModel : public vortex::models::SensorModel<2, Eigen::Dynamic> { +class VariableLengthSensorModel : public vortex::models::SensorModelI<2, Eigen::Dynamic> { public: - using typename SensorModel<2, Eigen::Dynamic>::Measurement; - using typename SensorModel<2, Eigen::Dynamic>::State; - using typename SensorModel<2, Eigen::Dynamic>::Mat_xx; - using typename SensorModel<2, Eigen::Dynamic>::Mat_zx; - using typename SensorModel<2, Eigen::Dynamic>::Mat_zz; - using SensorModel::N_DIM_z; - using SensorModel::N_DIM_x; + using typename SensorModelI<2, Eigen::Dynamic>::Vec_z; + using typename SensorModelI<2, Eigen::Dynamic>::Vec_x; + using typename SensorModelI<2, Eigen::Dynamic>::Mat_xx; + using typename SensorModelI<2, Eigen::Dynamic>::Mat_zx; + using typename SensorModelI<2, Eigen::Dynamic>::Mat_zz; + using SensorModelI::N_DIM_z; + using SensorModelI::N_DIM_x; VariableLengthSensorModel(int n_z) : n_z(n_z) {} - Measurement h(const State& x) const override + Vec_z h(const Vec_x& x) const override { return x; } - Mat_zx H(const State& x) const override + Mat_zx H(const Vec_x& x) const override { (void)x; // unused return Mat_zx::Identity(N_DIM_x, N_DIM_x); } - Mat_zz R(const State& x) const override + Mat_zz R(const Vec_x& x) const override { (void)x; // unused return Mat_zz::Identity(N_DIM_x, N_DIM_x)*0.1; From 037db691b78627535346d3e58af600079327ca97 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Sat, 4 Nov 2023 23:38:36 +0100 Subject: [PATCH 07/62] tested ekf more --- include/filters/ekf.hpp | 7 +- include/models/dynamic_model.hpp | 18 +- include/models/imm_model.hpp | 22 +-- include/models/movement_models.hpp | 160 +++++++++++++++++ include/probability/multi_var_gauss.hpp | 18 +- test/dynamic_model_test.cpp | 33 +++- test/ekf_test.cpp | 218 +++++++++++++++++++++--- test/main.cpp | 5 +- test/sensor_model_test.cpp | 32 ++-- test/test_models.hpp | 65 +++++-- 10 files changed, 498 insertions(+), 80 deletions(-) create mode 100644 include/models/movement_models.hpp diff --git a/include/filters/ekf.hpp b/include/filters/ekf.hpp index 14b82f24..b2960542 100644 --- a/include/filters/ekf.hpp +++ b/include/filters/ekf.hpp @@ -59,7 +59,7 @@ class EKF { * @return MultivarGauss Updated state */ Gauss_x update(const Gauss_x& x_est_pred, const Gauss_z& z_est_pred, const Vec_z& z_meas) { - Mat_xz H_mat = sensor_model_.H(x_est_pred.mean()); + Mat_zx H_mat = sensor_model_.H(x_est_pred.mean()); Mat_zz R_mat = sensor_model_.R(x_est_pred.mean()); Mat_xx P_mat = x_est_pred.cov(); Mat_zz S_mat_inv = z_est_pred.cov_inv(); @@ -80,9 +80,10 @@ class EKF { * @param x_est_prev Previous state estimate * @param z_meas Vec_z * @param dt Time step + * @return std::tuple Updated state, predicted state, predicted measurement */ - std::tuple step(const Gauss_x& x_est_prev, const Gauss_z& z_meas, double dt) { - std::pair pred = predict(dt, x_est_prev); + std::tuple step(const Gauss_x& x_est_prev, const Vec_z& z_meas, double dt) { + std::pair pred = predict(x_est_prev, dt); Gauss_x x_est_pred = pred.first; Gauss_z z_est_pred = pred.second; Gauss_x x_est_upd = update(x_est_pred, z_est_pred, z_meas); diff --git a/include/models/dynamic_model.hpp b/include/models/dynamic_model.hpp index def62ac9..70449179 100644 --- a/include/models/dynamic_model.hpp +++ b/include/models/dynamic_model.hpp @@ -17,11 +17,11 @@ namespace vortex { namespace models { -template /** * @brief Interface for dynamic models. * */ +template class DynamicModelI { public: static constexpr int N_DIM_x = n_dim_x; // Declare so that children of this class can reference it @@ -82,13 +82,15 @@ class DynamicModelI { Mat_xx A_c = this->A_c(x); Mat_xx Q_c = this->Q_c(x); - Eigen::Matrix F; - // clang-format off - F << -A_c , Q_c, - Mat_xx::Zero(), A_c.transpose(); - // clang-format on - Eigen::Matrix G = (F * dt).exp(); - return G.template block(0, N_DIM_x) * G.template block(N_DIM_x, N_DIM_x).transpose(); + Eigen::Matrix v_1; + v_1 << -A_c, Q_c, Mat_xx::Zero(), A_c.transpose(); + v_1 *= dt; + v_1 = v_1.exp(); + Mat_xx F_d = v_1.template block(N_DIM_x, N_DIM_x).transpose(); + Mat_xx F_d_inv_Q_d = v_1.template block(0, N_DIM_x); + Mat_xx Q_d = F_d * F_d_inv_Q_d; + + return Q_d; } diff --git a/include/models/imm_model.hpp b/include/models/imm_model.hpp index 6e018688..0c1af751 100644 --- a/include/models/imm_model.hpp +++ b/include/models/imm_model.hpp @@ -19,9 +19,10 @@ namespace models { template class ImmModel : public DynamicModelI { public: - using typename DynamicModelI::State; + static constexpr size_t N_MODELS_ = n_models; + using typename DynamicModelI::Vec_x; using typename DynamicModelI::Mat_xx; - using Vec_nn = Eigen::Vector; + using Vec_n = Eigen::Vector; using Mat_nn = Eigen::Matrix; /** @@ -31,7 +32,7 @@ class ImmModel : public DynamicModelI { * I.e. the probability of switching from model i to model j is jump_matrix(i,j). Diagonal should be 0. * @param hold_times Holding time for each state. Parameter is the mean of an exponential distribution. */ - ImmModel(std::vector>> models, Mat_nn jump_matrix, Vec_nn hold_times) + ImmModel(std::vector>> models, Mat_nn jump_matrix, Vec_n hold_times) : models_(std::move(models)), jump_matrix_(std::move(jump_matrix)), hold_times_(std::move(hold_times)), N_MODELS_(n_models) { // Validate input @@ -48,10 +49,10 @@ class ImmModel : public DynamicModelI { /** * @brief Continuous time dynamics for the first model in the list. * Use f_c(x, model_idx) to get the dynamics of a specific model. - * @param x State + * @param x Vec_x * @return The first model in the list. */ - State f_c(const State& x) const override + Vec_x f_c(const Vec_x& x) const override { // error if used assert(false); @@ -63,9 +64,9 @@ class ImmModel : public DynamicModelI { * * @param x * @param model_idx - * @return State + * @return Vec_x */ - State f_c(const State& x, int model_idx) const + Vec_x f_c(const Vec_x& x, int model_idx) const { return models_.at(model_idx)->f_c(x); } @@ -81,7 +82,7 @@ class ImmModel : public DynamicModelI { static Mat_nn pi_mat_c = Mat_nn::Zero(); if (is_cached) { return pi_mat_c; } - Vec_nn t_inv = hold_times_.cwiseInverse(); + Vec_n t_inv = hold_times_.cwiseInverse(); Mat_nn = - t_inv.asDiagonal() + t_inv*jump_matrix_; is_cached = true; @@ -109,9 +110,8 @@ class ImmModel : public DynamicModelI { private: const std::vector>> models_; const Mat_nn jump_matrix_; - const Vec_nn hold_times_; -public: - const size_t N_MODELS_; + const Vec_n hold_times_; }; + } // namespace models } // namespace vortex \ No newline at end of file diff --git a/include/models/movement_models.hpp b/include/models/movement_models.hpp new file mode 100644 index 00000000..1088cfcd --- /dev/null +++ b/include/models/movement_models.hpp @@ -0,0 +1,160 @@ +#pragma once +#include + +namespace vortex { +namespace models { + +/** @brief Simple dynamic model with constant velocity + * x = [x, y, x_dot, y_dot] + */ +class CVModel : public DynamicModelI<4> { +public: + using typename DynamicModelI<4>::Vec_x; + using typename DynamicModelI<4>::Mat_xx; + + /** + * @brief Constant Velocity Model in 2D + * x = [x, y, x_dot, y_dot] + * @param std_vel Standard deviation of velocity + */ + CVModel(double std_vel) : std_vel_(std_vel) {} + + Vec_x f_c(const Vec_x& x) const override + { + Vec_x x_dot; + x_dot << x(2), x(3), 0, 0; + return x_dot; + } + + Mat_xx A_c(const Vec_x& x) const override + { + (void)x; // unused + Mat_xx A; + A << 0, 0, 1, 0, + 0, 0, 0, 1, + 0, 0, 0, 0, + 0, 0, 0, 0; + return A; + } + + Mat_xx Q_c(const Vec_x& x) const override + { + (void)x; // unused + Mat_xx Q; + Q << 0, 0, 0, 0, + 0, 0, 0, 0, + 0, 0, std_vel_*std_vel_, 0, + 0, 0, 0, std_vel_*std_vel_; + return Q; + } +private: + double std_vel_; +}; + +class CTModel : public DynamicModelI<5> { +public: + using typename DynamicModelI<5>::Vec_x; + using typename DynamicModelI<5>::Mat_xx; + + /** + * @brief Coordinated Turn Model in 2D + * @param std_acc Standard deviation of velocity + * x = [x, y, x_dot, y_dot, omega] + */ + CTModel(double std_acc, double std_turn) : std_acc_(std_acc), std_turn_(std_turn) {} + + Vec_x f_c(const Vec_x& x) const override + { + // x_ddot = -v*omega + // y_ddot = v*omega + Vec_x x_dot; + x_dot << x(2), x(3), -x(3)*x(4), x(2)*x(4), 0; + return x_dot; + } + + Mat_xx A_c(const Vec_x& x) const override + { + Mat_xx A; + // clang-format off + A << 0, 0, 1 , 0 , 0, + 0, 0, 0 , 1 , 0, + 0, 0, 0 ,-x(4), 0, + 0, 0, x(4), 0 , 0, + 0, 0, 0 , 0 , 0; + // clang-format on + return A; + } + + Mat_xx Q_c(const Vec_x& x) const override + { + (void)x; // unused + Eigen::Vector3d D; + D << std_acc_*std_acc_, std_acc_*std_acc_, std_turn_*std_turn_; + Eigen::Matrix G; + // clang-format off + G << 0, 0, 0, + 0, 0, 0, + 1, 0, 0, + 0, 1, 0, + 0, 0, 1; + // clang-format on + Mat_xx Q = G*D.asDiagonal()*G.transpose(); + return Q; + } + +private: + double std_acc_; + double std_turn_; +}; + + +class CAModel : public DynamicModelI<6> { +public: + using typename DynamicModelI<6>::Vec_x; + using typename DynamicModelI<6>::Mat_xx; + + /** + * @brief Constant Acceleration Model in 2D + * @param std_vel Standard deviation of velocity + * @param std_acc Standard deviation of acceleration + */ + CAModel(double std_vel, double std_acc) : std_vel_(std_vel), std_acc_(std_acc) {} + + Vec_x f_c(const Vec_x& x) const override + { + Vec_x x_dot; + x_dot << x(2), x(3), x(4), x(5), 0, 0; + return x_dot; + } + + Mat_xx A_c(const Vec_x& x) const override + { + (void)x; // unused + Mat_xx A; + // clang-format off + A << 0, 0, 1, 0, 0, 0, + 0, 0, 0, 1, 0, 0, + 0, 0, 0, 0, 1, 0, + 0, 0, 0, 0, 0, 1, + 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0; + // clang-format on + return A; + } + + Mat_xx Q_c(const Vec_x& x) const override + { + assert(false); // Not implemented + (void)x; // unused + Mat_xx Q; + // clang-format off + Q << 0; + return Q; + } +private: + double std_vel_; + double std_acc_; +}; + +} // namespace models +} // namespace vortex \ No newline at end of file diff --git a/include/probability/multi_var_gauss.hpp b/include/probability/multi_var_gauss.hpp index 2b5c87aa..135576c2 100644 --- a/include/probability/multi_var_gauss.hpp +++ b/include/probability/multi_var_gauss.hpp @@ -8,17 +8,17 @@ namespace prob { * A class for representing a multivariate Gaussian distribution * @tparam N_DIMS dimentions of the Gaussian */ -template +template class MultiVarGauss { public: - using Vector = Eigen::Vector; - using Matrix = Eigen::Matrix; + using Vector = Eigen::Vector; + using Matrix = Eigen::Matrix; MultiVarGauss(const Vector& mean, const Matrix& cov) - : mean_(mean), cov_(cov), cov_inv_(cov_.llt().solve(Matrix::Identity(N_DIMS, N_DIMS))) + : mean_(mean), cov_(cov), actual_n_dims_(cov_.rows()), cov_inv_(cov_.llt().solve(Matrix::Identity(n_dims(), n_dims()))) { // Check that the covariance matrix is positive definite and symmetric - if (cov_ != cov_.transpose()) { + if (!cov_.isApprox(cov_.transpose(), 1e-6)) { throw std::invalid_argument("Covariance matrix is not symmetric"); } if (cov_.llt().info() != Eigen::Success) { @@ -33,7 +33,7 @@ class MultiVarGauss { double pdf(const Vector& x) const { const auto diff = x - mean_; const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; - return std::exp(exponent) / std::sqrt(std::pow(2 * M_PI, N_DIMS) * cov_.determinant()); + return std::exp(exponent) / std::sqrt(std::pow(2 * M_PI, n_dims()) * cov_.determinant()); } /** Calculate the log likelihood of x given the Gaussian. @@ -44,7 +44,7 @@ class MultiVarGauss { double logpdf(const Vector& x) const { const auto diff = x - mean_; const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; - return exponent - 0.5 * std::log(std::pow(2 * M_PI, N_DIMS) * cov_.determinant()); + return exponent - 0.5 * std::log(std::pow(2 * M_PI, n_dims()) * cov_.determinant()); } @@ -65,12 +65,14 @@ class MultiVarGauss { /** dimentions of the Gaussian * @return int */ - int n_dims() const { return N_DIMS; } + int n_dims() const { return actual_n_dims_; } private: Vector mean_; Matrix cov_; + size_t actual_n_dims_; Matrix cov_inv_; + }; } // namespace probability diff --git a/test/dynamic_model_test.cpp b/test/dynamic_model_test.cpp index 2a1419fb..38e65965 100644 --- a/test/dynamic_model_test.cpp +++ b/test/dynamic_model_test.cpp @@ -1,5 +1,6 @@ #include #include +#include #include "test_models.hpp" namespace simple_dynamic_model_test { @@ -26,4 +27,34 @@ TEST(DynamicModel, iterateSimpleModel) } -} // namespace simple_model_test \ No newline at end of file +} // namespace simple_model_test + +namespace cv_model_test { + +using Vec_x = typename vortex::models::CVModel::Vec_x; +using Mat_xx = typename vortex::models::CVModel::Mat_xx; + +TEST(DynamicModel, initCVModel) +{ + vortex::models::CVModel model(1.0); +} + +TEST(DynamicModel, iterateCVModel) +{ + vortex::models::CVModel model(1.0); + double dt = 1.0; + Vec_x x; + x << 0, 0, 1, 1; + + for (size_t i = 0; i < 10; i++) + { + Vec_x x_true; + x_true << x(0) + dt, x(1) + dt, 1, 1; + EXPECT_EQ(model.f_d(x, dt), x_true); + x = model.f_d(x, dt); + } + +} + +} // namespace cv_model_test + diff --git a/test/ekf_test.cpp b/test/ekf_test.cpp index 5c2531e1..202afa54 100644 --- a/test/ekf_test.cpp +++ b/test/ekf_test.cpp @@ -3,41 +3,217 @@ #include #include +#include #include "test_models.hpp" +#include +#include -using namespace vortex::filters; -using namespace vortex::models; -using namespace vortex::prob; +// using namespace vortex::filters; +// using namespace vortex::models; +// using namespace vortex::prob; -const int N_DIMS_x = SimpleDynamicModel::N_DIM_x; -const int N_DIMS_z = SimpleSensorModel::N_DIM_z; -using DynModI = DynamicModelI; -using SensModI = SensorModelI; -using Vec_x = typename DynModI::Vec_x; -using Mat_xx = typename DynModI::Mat_xx; -using Vec_z = typename SensModI::Vec_z; -using Gauss_x = typename DynModI::Gauss_x; -using Gauss_z = typename SensModI::Gauss_z; +// const int N_DIMS_x = SimpleDynamicModel::N_DIM_x; +// const int N_DIMS_z = SimpleSensorModel::N_DIM_z; +// using DynModI = DynamicModelI; +// using SensModI = SensorModelI; +// using Vec_x = typename DynModI::Vec_x; +// using Mat_xx = typename DynModI::Mat_xx; +// using Vec_z = typename SensModI::Vec_z; +// using Gauss_x = typename DynModI::Gauss_x; +// using Gauss_z = typename SensModI::Gauss_z; -TEST(EKF, Simple) { +// TEST(EKF, Init) { - SimpleDynamicModel dynamic_model; - SimpleSensorModel sensor_model; - EKF ekf(dynamic_model, sensor_model); +// SimpleDynamicModel dynamic_model; +// SimpleSensorModel sensor_model; +// EKF ekf(dynamic_model, sensor_model); +// // Initial state +// Gauss_x x({0, 0}, Mat_xx::Identity()); + +// // Predict +// auto pred = ekf.predict(x, 0.1); +// Gauss_x x_est_pred = pred.first; +// Gauss_z z_est_pred = pred.second; + +// // Update +// Vec_z z = {1, 1}; +// Gauss_x x_est_upd = ekf.update(x_est_pred, z_est_pred, z); + +// // Check that the state is close to zero +// // ASSERT_TRUE(x.isMuchSmallerThan(Vec_x::Ones())); +// } + +// TEST(EKF, Predict) { + +// SimpleDynamicModel dynamic_model; +// SimpleSensorModel sensor_model; +// EKF ekf(dynamic_model, sensor_model); + +// // Initial state +// Gauss_x x({0, 0}, Mat_xx::Identity()); + +// // Predict +// auto pred = ekf.predict(x, 0.1); +// Gauss_x x_est_pred = pred.first; +// Gauss_z z_est_pred = pred.second; + + +// } + +class EKFTestCVModel : public ::testing::Test { +protected: + using PosMeasModel = FirstStatesMeasuredModel<4>; + using CVModel = vortex::models::CVModel; + using Vec_x = typename CVModel::Vec_x; + using Mat_xx = typename CVModel::Mat_xx; + using Gauss_x = typename CVModel::Gauss_x; + using Gauss_z = typename PosMeasModel::Gauss_z; + using Vec_z = typename PosMeasModel::Vec_z; + + void SetUp() override { + // Create dynamic model + dynamic_model_ = std::make_shared(1.0); + // Create sensor model + sensor_model_ = std::make_shared(2, 1.0); + // Create EKF + ekf_ = std::make_shared>(*dynamic_model_, *sensor_model_); + } + + std::shared_ptr dynamic_model_; + std::shared_ptr sensor_model_; + std::shared_ptr> ekf_; +}; + +TEST_F(EKFTestCVModel, Predict) { // Initial state - Gauss_x x({0, 0}, Mat_xx::Identity()); + Gauss_x x({0, 0, 1, 0}, Mat_xx::Identity()); + double dt = 0.1; + // Predict + auto pred = ekf_->predict(x, dt); + Gauss_x x_est_pred = pred.first; + Gauss_z z_est_pred = pred.second; + + Vec_x x_true = x.mean() + Vec_x({dt, 0, 0, 0}); + Vec_z z_true = x_true.head(2); + ASSERT_EQ(x_est_pred.mean(), x_true); + ASSERT_EQ(z_est_pred.mean(), z_true); +} +TEST_F(EKFTestCVModel, Update) { + // Initial state + Gauss_x x({0, 0, 1, 0}, Mat_xx::Identity()); + double dt = 0.1; // Predict - auto pred = ekf.predict(x, 0.1); + auto pred = ekf_->predict(x, dt); Gauss_x x_est_pred = pred.first; Gauss_z z_est_pred = pred.second; // Update - Vec_z z = {1, 1}; - ekf.update(x_est_pred, z_est_pred, z); + Vec_z z = Vec_z::Zero(2); + Gauss_x x_est_upd = ekf_->update(x_est_pred, z_est_pred, z); // Check that the state is close to zero - // ASSERT_TRUE(x.isMuchSmallerThan(Vec_x::Ones())); + Vec_x x_true = x.mean() + Vec_x({dt, 0, 0, 0}); + Vec_z z_true = x_true.head(2); + ASSERT_EQ(x_est_upd.mean(), x_true); + ASSERT_EQ(z_est_pred.mean(), z_true); } + +TEST_F(EKFTestCVModel, Convergence) +{ + // Random number generator + std::random_device rd; + std::mt19937 gen(rd()); + std::normal_distribution<> d_disturbance{0, 1e-3}; + std::normal_distribution<> d_noise{0, 1e-2}; + + // Initial state + Gauss_x x0({0, 0, 0.5, 0}, Mat_xx::Identity()); + double dt = 0.1; + + std::vector time; + std::vector x_true; + std::vector x_est; + std::vector z_meas; + std::vector z_est; + + + // Simulate + time.push_back(0); + x_true.push_back(x0.mean()); + x_est.push_back(x0); + for (int i = 0; i < 100; i++) + { + // Simulate + Vec_x v; + v << d_disturbance(gen), d_disturbance(gen), d_disturbance(gen), d_disturbance(gen); + Vec_z w = Vec_z::Zero(2); + w << d_noise(gen), d_noise(gen); + Vec_x x_true_i = dynamic_model_->f_d(x_true.back(), dt) + v; + Vec_z z_meas_i = sensor_model_->h(x_true_i) + w; + x_true.push_back(x_true_i); + z_meas.push_back(z_meas_i); + + // Predict + auto step = ekf_->step(x_est.back(), z_meas_i, dt); + Gauss_x x_est_upd = std::get<0>(step); + // Gauss_x x_est_pred = std::get<1>(step); + Gauss_z z_est_pred = std::get<2>(step); + + // Update state + time.push_back(time.back() + dt); + x_est.push_back(x_est_upd); + z_est.push_back(z_est_pred); + } + + // Test that the state converges to the true state + ASSERT_NEAR(x_est.back().mean()(0), x_true.back()(0), 1e-1); + ASSERT_NEAR(x_est.back().mean()(1), x_true.back()(1), 1e-1); + ASSERT_NEAR(x_est.back().mean()(2), x_true.back()(2), 1e-1); + ASSERT_NEAR(x_est.back().mean()(3), x_true.back()(3), 1e-1); + + // Plot the results + std::vector x_true_x, x_true_y, x_true_u, x_true_v, x_est_x, x_est_y, x_est_u, x_est_v, z_meas_x, z_meas_y; + for (size_t i = 0; i < x_true.size()-1; i++) + { + x_true_x.push_back(x_true.at(i)(0)); + x_true_y.push_back(x_true.at(i)(1)); + x_true_u.push_back(x_true.at(i)(2)); + x_true_v.push_back(x_true.at(i)(3)); + x_est_x.push_back(x_est.at(i).mean()(0)); + x_est_y.push_back(x_est.at(i).mean()(1)); + x_est_u.push_back(x_est.at(i).mean()(2)); + x_est_v.push_back(x_est.at(i).mean()(3)); + z_meas_x.push_back(z_meas.at(i)(0)); + z_meas_y.push_back(z_meas.at(i)(1)); + } + time.pop_back(); + + Gnuplot gp; + gp << "set terminal qt size 1600,1000\n"; // Modified to make plot larger + gp << "set multiplot layout 2,1\n"; + gp << "set title 'Position'\n"; + gp << "set xlabel 'x [m]'\n"; + gp << "set ylabel 'y [m]'\n"; + gp << "plot '-' with lines title 'True', '-' with lines title 'Estimate', '-' with points title 'Measurements' ps 2\n"; // Modified to make dots larger + gp.send1d(boost::make_tuple(x_true_x, x_true_y)); + gp.send1d(boost::make_tuple(x_est_x, x_est_y)); + gp.send1d(boost::make_tuple(z_meas_x, z_meas_y)); + gp << "set title 'Velocity'\n"; + gp << "set xlabel 't [s]'\n"; + gp << "set ylabel 'u,v [m/s]'\n"; + gp << "plot '-' with lines title 'True v', " + << "'-' with lines title 'Estimate v', " + << "'-' with lines title 'True u', " + << "'-' with lines title 'Estimate u'\n"; + gp.send1d(boost::make_tuple(time, x_true_v)); + gp.send1d(boost::make_tuple(time, x_est_v)); + gp.send1d(boost::make_tuple(time, x_true_u)); + gp.send1d(boost::make_tuple(time, x_est_u)); + gp << "unset multiplot\n"; + + + +} \ No newline at end of file diff --git a/test/main.cpp b/test/main.cpp index 5de89115..8cf49711 100644 --- a/test/main.cpp +++ b/test/main.cpp @@ -2,10 +2,7 @@ #include int main(int argc, char **argv) -{ - (void)argc; - (void)argv; - +{ Eigen::initParallel(); Eigen::setNbThreads(8); diff --git a/test/sensor_model_test.cpp b/test/sensor_model_test.cpp index ebb8cd87..6d1f73fc 100644 --- a/test/sensor_model_test.cpp +++ b/test/sensor_model_test.cpp @@ -5,30 +5,38 @@ namespace simple_sensor_model_test { -using Measurement = typename SimpleSensorModel::Vec_z; -using Vec_x = typename SimpleSensorModel::Vec_x; -using Mat_xx = typename SimpleSensorModel::Mat_xx; +using SensorModel = SimpleSensorModel<2,1>; +using Measurement = typename SensorModel::Vec_z; +using Vec_x = typename SensorModel::Vec_x; +using Vec_z = typename SensorModel::Vec_z; +using Mat_xx = typename SensorModel::Mat_xx; +using Mat_zz = typename SensorModel::Mat_zz; +using Mat_zx = typename SensorModel::Mat_zx; +using Mat_xz = typename SensorModel::Mat_xz; +using Gauss_x = typename SensorModel::Gauss_x; +using Gauss_z = typename SensorModel::Gauss_z; TEST(SensorModel, initSimpleModel) { - SimpleSensorModel model; - EXPECT_EQ(model.h(Vec_x::Zero()), Vec_x::Zero()); + SensorModel model; + EXPECT_EQ(model.h(Vec_x::Zero()), Vec_z::Zero()); Vec_x x{1,2}; - EXPECT_EQ(model.h(x), x); + Vec_z z{1}; + EXPECT_EQ(model.h(x), z); } TEST(SensorModel, predictSimpleModel) { - SimpleSensorModel model; - vortex::prob::MultiVarGauss<2> x_est{Vec_x::Zero(), Mat_xx::Identity()}; - vortex::prob::MultiVarGauss<2> pred = model.pred_from_est(x_est); - EXPECT_EQ(pred.mean(), Vec_x::Zero()); - EXPECT_TRUE(pred.cov().isApprox(Mat_xx::Identity()*1.1)); + SensorModel model; + Gauss_x x_est{Vec_x::Zero(), Mat_xx::Identity()}; + Gauss_z pred = model.pred_from_est(x_est); + EXPECT_EQ(pred.mean(), Vec_z::Zero()); + EXPECT_TRUE(pred.cov().isApprox(Mat_zz::Identity()*1.1)); pred = model.pred_from_state(x_est.mean()); - EXPECT_TRUE(pred.cov().isApprox(Mat_xx::Identity()*0.1)); + EXPECT_TRUE(pred.cov().isApprox(Mat_zz::Identity()*0.1)); } diff --git a/test/test_models.hpp b/test/test_models.hpp index 9c14927f..a43616dc 100644 --- a/test/test_models.hpp +++ b/test/test_models.hpp @@ -27,19 +27,22 @@ class SimpleDynamicModel : public vortex::models::DynamicModelI<2> { } }; -class SimpleSensorModel : public vortex::models::SensorModelI<2, 2> { +template +class SimpleSensorModel : public vortex::models::SensorModelI { public: - using typename SensorModelI<2, 2>::Vec_z; - using typename SensorModelI<2, 2>::Vec_x; - using typename SensorModelI<2, 2>::Mat_xx; - using typename SensorModelI<2, 2>::Mat_zx; - using typename SensorModelI<2, 2>::Mat_zz; - using SensorModelI<2, 2>::N_DIM_x; - using SensorModelI<2, 2>::N_DIM_z; + using SensModI = vortex::models::SensorModelI; + + using typename SensModI::Vec_z; + using typename SensModI::Vec_x; + using typename SensModI::Mat_xx; + using typename SensModI::Mat_zx; + using typename SensModI::Mat_zz; + using SensModI::N_DIM_x; + using SensModI::N_DIM_z; Vec_z h(const Vec_x& x) const override { - return x; + return H(x)*x; } Mat_zx H(const Vec_x& x) const override @@ -66,11 +69,11 @@ class VariableLengthSensorModel : public vortex::models::SensorModelI<2, Eigen:: using SensorModelI::N_DIM_x; - VariableLengthSensorModel(int n_z) : n_z(n_z) {} + VariableLengthSensorModel(int n_z) : N_z(n_z) {} Vec_z h(const Vec_x& x) const override { - return x; + return H(x)*x; } Mat_zx H(const Vec_x& x) const override @@ -84,5 +87,43 @@ class VariableLengthSensorModel : public vortex::models::SensorModelI<2, Eigen:: return Mat_zz::Identity(N_DIM_x, N_DIM_x)*0.1; } - const int n_z; + const int N_z; +}; + +template +class FirstStatesMeasuredModel : public vortex::models::SensorModelI { +public: + using SensModI = vortex::models::SensorModelI; + using SensModI::N_DIM_x; + using typename SensModI::Vec_z; + using typename SensModI::Vec_x; + using typename SensModI::Mat_xx; + using typename SensModI::Mat_zx; + using typename SensModI::Mat_zz; + + FirstStatesMeasuredModel(int n_z, double std) : n_z_(n_z), std_(std) {} + + Vec_z h(const Vec_x& x) const override + { + return H(x)*x; + } + + Mat_zx H(const Vec_x& x) const override + { + (void)x; // unused + Mat_zx H = Mat_zx::Zero(n_z_, N_DIM_x); + H.block(0, 0, n_z_, n_z_) = Mat_zz::Identity(n_z_, n_z_); + + return H; + } + + Mat_zz R(const Vec_x& x) const override + { + (void)x; // unused + return Mat_zz::Identity(n_z_, n_z_)*std_*std_; + } + + private: + int n_z_; + double std_; }; \ No newline at end of file From bdf289e55b0a33ebd6aa892d70e821471bdbd1df Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Sun, 5 Nov 2023 10:09:32 +0100 Subject: [PATCH 08/62] Added documentation --- include/filters/README.md | 13 +++++++++++++ include/models/README.md | 33 +++++++++++++++++++++++++++++++++ include/models/imm_model.hpp | 2 +- include/models/sensor_model.hpp | 16 +++++++++++++++- include/probability/README.md | 20 ++++++++++++++++++++ 5 files changed, 82 insertions(+), 2 deletions(-) create mode 100644 include/filters/README.md create mode 100644 include/models/README.md create mode 100644 include/probability/README.md diff --git a/include/filters/README.md b/include/filters/README.md new file mode 100644 index 00000000..3e410b46 --- /dev/null +++ b/include/filters/README.md @@ -0,0 +1,13 @@ +# Filters +This folder contains the filters. They are based on Kalman filters + +All classes and functions are under the namespace `vortex::filters`. + +## EKF +This class represents an [Extended Kalman Filter](https://en.wikipedia.org/wiki/Extended_Kalman_filter). It is a template class with parameters `DynamicModelT` and `SensorModelT`. `DynamicModelT` is the dynamic model used in the filter and `SensorModelT` is the sensor model used in the filter. There is no need to specify the dimensions of the dynamic model or the sensor model as they are automatically retrieved from the models. + +### Usage +To create an instance you need to provide a dynamic model and a sensor model. The dynamic model must be derived from the DynamicModelI interface and the sensor model must be derived from the SensorModelI interface. The EKF object will then store a copy of the dynamic model and the sensor model. (It should probably store a const reference instead to enable external live tuning for the parameters though). It does not store state estimates or covariance matrices. + +## IMM Filter +This class represents an [Interacting Multiple Model Filter](https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python/blob/master/14-Adaptive-Filtering.ipynb). It is a template class with parameters `DynamicModelT` and `SensorModelT`. `DynamicModelT` is the dynamic model used in the filter and `SensorModelT` is the sensor model used in the filter. \ No newline at end of file diff --git a/include/models/README.md b/include/models/README.md new file mode 100644 index 00000000..56fc1bab --- /dev/null +++ b/include/models/README.md @@ -0,0 +1,33 @@ +# Models +This folder contains the models used in the Vortex-VKF project. The models are derived from either DynamicModelI or the SensorModelI interface. +They define the dynamics of the system and the sensor models used in the project. + +All classes and functions are under the namespace `vortex::models`. + +## DynamicModelI +This interface defines the dynamics of the system. The methods `f_c`, `A_c` and `Q_c` define the continuous time dynamics of the system. The methods `f_d`, `A_d` and `Q_d` define the discrete time dynamics of the system. The methods `f_c` and `f_d` are the state transition functions. The methods `A_c` and `A_d` are the Jacobians of the state transition functions. The methods `Q_c` and `Q_d` are the process noise covariance matrices. + +### Usage +In order to define a new dynamic model, the user must create a new class that inherits from the DynamicModelI interface. The user must then implement the methods `f_c`, `A_c` and `Q_c` for the continuous time dynamics. The discrete time dynamics are found using exact discretization. If you want to use this, you must implement the methods `f_c`, `A_c` and `Q_c`. The methods `f_d`, `A_d` and `Q_d` are then automatically generated using [exact discretization](https://en.wikipedia.org/wiki/Discretization). The user can also define the discrete time dynamics themselves by overiting `f_d` etc. + +The interface is a template class with parameter `N_DIM_x`. This is the dimension of the state vector. The user must specify this when creating a new class, or derive a template class from the DynamicModelI interface. Both static and dynamic dimensions are supported but as of now only static dimensions are tested. + +## SensorModelI +This interface defines the sensor models. The methods `h` `H` and `R` define the sensor model. The method `h` is the measurement function, `H` is the Jacobian of the measurement function and `R` is the measurement noise covariance matrix. The sensor model is assumed to be defined in discrete time. + +### Usage +In order to define a new sensor model, the user must create a new class that inherits from the SensorModelI interface. The user must then implement the methods `h`, `H` and `R` as they are pure virtual. + +The interface is a template class with parameter `N_DIM_x` and `N_DIM_z`. `N_DIM_x` is the dimension of the state vector and `N_DIM_z` is the dimension of the measurement vector. The user must specify these when creating a new class, or derive a template class from the SensorModelI interface. Both static and dynamic dimensions are supported (and tested). + +## Movement Models +This file contains some movement models that can be used in the project. They are all derived from the DynamicModelI interface. +- **CVModel**: Constant Velocity Model. Has four states: x, y, vx and vy. The velocity is assumed to be constant. +- **CTModel**: Coordinated Turn Model. Has five states: x, y, vx, vy and omega. The speed is assumed to be constant and the turn rate is assumed to be constant. +- **CAModel**: Constant Acceleration Model. Has six states: x, y, vx, vy, ax and ay. The acceleration is assumed to be constant. + +## IMM Model +This class is can hold multiple DynamicModelI objects and defines functions to calculate the probability of switching between the models. + +### Usage +To create an instance you need to provide a vector DynamicModelI objects and a matrix defining the switching probabilities. The switching probabilities are defined as the probability of switching from model i to model j. The switching probabilities must be between 0 and 1 and the rows must sum to 1.0. The number of rows and columns must be the same as the number of models. Note that this defines the probability of switching to a specific model *when* a switch occurs. Not the probability of switching itself. The probability of switching is derived from the `hold_times` parameter. The `hold_times` parameter is a vector of the expected time between switches for each model. The switching probabilities are then calculated by modelling the system as a [Continuous Time Markov Chain](https://en.wikipedia.org/wiki/Continuous-time_Markov_chain). The switching probabilities are then used to calculate the probability of switching or staying in a model. diff --git a/include/models/imm_model.hpp b/include/models/imm_model.hpp index 0c1af751..60e21ac0 100644 --- a/include/models/imm_model.hpp +++ b/include/models/imm_model.hpp @@ -17,7 +17,7 @@ namespace vortex { namespace models { template -class ImmModel : public DynamicModelI { +class ImmModel : public DynamicModelI { // TODO: Should NOT inherit from DynamicModelI public: static constexpr size_t N_MODELS_ = n_models; using typename DynamicModelI::Vec_x; diff --git a/include/models/sensor_model.hpp b/include/models/sensor_model.hpp index a160545a..cc7cff0d 100644 --- a/include/models/sensor_model.hpp +++ b/include/models/sensor_model.hpp @@ -35,9 +35,23 @@ class SensorModelI { using Gauss_z = prob::MultiVarGauss; virtual ~SensorModelI() = default; - + /** + * @brief Sensor Model + * @param x State + * @return Vec_z + */ virtual Vec_z h(const Vec_x& x) const = 0; + /** + * @brief Jacobian of sensor model with respect to state + * @param x State + * @return Mat_zx + */ virtual Mat_zx H(const Vec_x& x) const = 0; + /** + * @brief Noise covariance matrix + * @param x State + * @return Mat_zz + */ virtual Mat_zz R(const Vec_x& x) const = 0; /** diff --git a/include/probability/README.md b/include/probability/README.md new file mode 100644 index 00000000..d3d0d39e --- /dev/null +++ b/include/probability/README.md @@ -0,0 +1,20 @@ +# Probability +This folder contains the probability distributions used. + +All classes and functions are under the namespace `vortex::prob`. + +## MultiVarGauss +This class represents a multivariate Gaussian distribution. It is a template class with parameter `N_DIM`. This is the dimension of the distribution. + +### Usage +The class contains methods for getting the mean and covariance, sampling from the distribution, calculating the probability density function and the log probability density function. It works with both static and dynamic dimensions. + +To create an instance you need to provide a mean vector and a covariance matrix. The covariance matrix must be symmetric and [positive definite](https://en.wikipedia.org/wiki/Definite_matrix). The mean vector must have the same dimension as the covariance matrix and the MultiVarGauss object. + +## GuassianMixture +This class represents a Gaussian mixture distribution. It is a template class with parameter `N_DIM`. This is the dimension of the distribution. + +### Usage +The class contains methods for sampling from the distribution, calculating the probability density function and the log probability density function. But most importantly the mean and covariance of the distribution can be retrieved. It works with both static and dynamic dimensions. + +To create an instance you need to provide a vector of weights and a vector of MultiVarGauss objects. The weights must sum to 1.0 and the MultiVarGauss objects must have the same dimension as the GaussianMixture object. \ No newline at end of file From 1bd862f696a4811819dea2f324e6eaa6cd2a8e3e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Sun, 5 Nov 2023 15:19:53 +0100 Subject: [PATCH 09/62] moved test check after plots in EKF convergence --- include/filters/ekf.hpp | 2 +- test/ekf_test.cpp | 89 ++++------------------------------------- 2 files changed, 8 insertions(+), 83 deletions(-) diff --git a/include/filters/ekf.hpp b/include/filters/ekf.hpp index b2960542..f6a3e9ab 100644 --- a/include/filters/ekf.hpp +++ b/include/filters/ekf.hpp @@ -76,7 +76,7 @@ class EKF { } /** - * @brief Perform one EKF update step + * @brief Perform one EKF prediction and update step * @param x_est_prev Previous state estimate * @param z_meas Vec_z * @param dt Time step diff --git a/test/ekf_test.cpp b/test/ekf_test.cpp index 202afa54..3e23c2fa 100644 --- a/test/ekf_test.cpp +++ b/test/ekf_test.cpp @@ -8,60 +8,6 @@ #include #include -// using namespace vortex::filters; -// using namespace vortex::models; -// using namespace vortex::prob; - - -// const int N_DIMS_x = SimpleDynamicModel::N_DIM_x; -// const int N_DIMS_z = SimpleSensorModel::N_DIM_z; -// using DynModI = DynamicModelI; -// using SensModI = SensorModelI; -// using Vec_x = typename DynModI::Vec_x; -// using Mat_xx = typename DynModI::Mat_xx; -// using Vec_z = typename SensModI::Vec_z; -// using Gauss_x = typename DynModI::Gauss_x; -// using Gauss_z = typename SensModI::Gauss_z; - -// TEST(EKF, Init) { - -// SimpleDynamicModel dynamic_model; -// SimpleSensorModel sensor_model; -// EKF ekf(dynamic_model, sensor_model); - -// // Initial state -// Gauss_x x({0, 0}, Mat_xx::Identity()); - -// // Predict -// auto pred = ekf.predict(x, 0.1); -// Gauss_x x_est_pred = pred.first; -// Gauss_z z_est_pred = pred.second; - -// // Update -// Vec_z z = {1, 1}; -// Gauss_x x_est_upd = ekf.update(x_est_pred, z_est_pred, z); - -// // Check that the state is close to zero -// // ASSERT_TRUE(x.isMuchSmallerThan(Vec_x::Ones())); -// } - -// TEST(EKF, Predict) { - -// SimpleDynamicModel dynamic_model; -// SimpleSensorModel sensor_model; -// EKF ekf(dynamic_model, sensor_model); - -// // Initial state -// Gauss_x x({0, 0}, Mat_xx::Identity()); - -// // Predict -// auto pred = ekf.predict(x, 0.1); -// Gauss_x x_est_pred = pred.first; -// Gauss_z z_est_pred = pred.second; - - -// } - class EKFTestCVModel : public ::testing::Test { protected: using PosMeasModel = FirstStatesMeasuredModel<4>; @@ -101,25 +47,6 @@ TEST_F(EKFTestCVModel, Predict) { ASSERT_EQ(z_est_pred.mean(), z_true); } -TEST_F(EKFTestCVModel, Update) { - // Initial state - Gauss_x x({0, 0, 1, 0}, Mat_xx::Identity()); - double dt = 0.1; - // Predict - auto pred = ekf_->predict(x, dt); - Gauss_x x_est_pred = pred.first; - Gauss_z z_est_pred = pred.second; - - // Update - Vec_z z = Vec_z::Zero(2); - Gauss_x x_est_upd = ekf_->update(x_est_pred, z_est_pred, z); - - // Check that the state is close to zero - Vec_x x_true = x.mean() + Vec_x({dt, 0, 0, 0}); - Vec_z z_true = x_true.head(2); - ASSERT_EQ(x_est_upd.mean(), x_true); - ASSERT_EQ(z_est_pred.mean(), z_true); -} TEST_F(EKFTestCVModel, Convergence) { @@ -156,23 +83,17 @@ TEST_F(EKFTestCVModel, Convergence) x_true.push_back(x_true_i); z_meas.push_back(z_meas_i); - // Predict + // Predict and update auto step = ekf_->step(x_est.back(), z_meas_i, dt); Gauss_x x_est_upd = std::get<0>(step); - // Gauss_x x_est_pred = std::get<1>(step); Gauss_z z_est_pred = std::get<2>(step); - // Update state + // Save results time.push_back(time.back() + dt); x_est.push_back(x_est_upd); z_est.push_back(z_est_pred); } - // Test that the state converges to the true state - ASSERT_NEAR(x_est.back().mean()(0), x_true.back()(0), 1e-1); - ASSERT_NEAR(x_est.back().mean()(1), x_true.back()(1), 1e-1); - ASSERT_NEAR(x_est.back().mean()(2), x_true.back()(2), 1e-1); - ASSERT_NEAR(x_est.back().mean()(3), x_true.back()(3), 1e-1); // Plot the results std::vector x_true_x, x_true_y, x_true_u, x_true_v, x_est_x, x_est_y, x_est_u, x_est_v, z_meas_x, z_meas_y; @@ -214,6 +135,10 @@ TEST_F(EKFTestCVModel, Convergence) gp.send1d(boost::make_tuple(time, x_est_u)); gp << "unset multiplot\n"; - + // Test that the state converges to the true state + ASSERT_NEAR(x_est.back().mean()(0), x_true.back()(0), 1e-1); + ASSERT_NEAR(x_est.back().mean()(1), x_true.back()(1), 1e-1); + ASSERT_NEAR(x_est.back().mean()(2), x_true.back()(2), 1e-1); + ASSERT_NEAR(x_est.back().mean()(3), x_true.back()(3), 1e-1); } \ No newline at end of file From 1d2d822e0ee7203d595e3935bf83c57d879a29f6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Eirik=20Kol=C3=A5s?= Date: Mon, 6 Nov 2023 00:39:09 +0100 Subject: [PATCH 10/62] made an actual library that can be imported by other projects --- vortex-filtering/CMakeLists.txt | 137 +++++++++++ .../filters/Kalman_filter_base.hpp | 34 +++ .../vortex_filtering/filters/README.md | 13 + .../include/vortex_filtering/filters/UKF.hpp | 157 ++++++++++++ .../include/vortex_filtering/filters/ekf.hpp | 99 ++++++++ .../vortex_filtering/filters/imm_filter.hpp | 154 ++++++++++++ .../integration_methods/ERK_methods.hpp | 227 +++++++++++++++++ .../integration_methods/README.md | 13 + .../include/vortex_filtering/models/README.md | 33 +++ .../vortex_filtering/models/dynamic_model.hpp | 128 ++++++++++ .../vortex_filtering/models/imm_model.hpp | 117 +++++++++ .../models/model_definitions.hpp | 61 +++++ .../models/movement_models.hpp | 160 ++++++++++++ .../vortex_filtering/models/sensor_model.hpp | 84 +++++++ .../vortex_filtering/nodes/kf_node.hpp | 68 ++++++ .../vortex_filtering/probability/README.md | 20 ++ .../vortex_filtering/probability/binomial.hpp | 67 +++++ .../probability/chi_squared.hpp | 39 +++ .../probability/gaussian_mixture.hpp | 108 ++++++++ .../probability/multi_var_gauss.hpp | 79 ++++++ .../vortex_filtering/probability/poisson.hpp | 62 +++++ vortex-filtering/launch/vkf_node.launch.yaml | 7 + vortex-filtering/package.xml | 25 ++ vortex-filtering/src/nodes/kf_node.cpp | 4 + vortex-filtering/test/dynamic_model_test.cpp | 60 +++++ vortex-filtering/test/ekf_test.cpp | 144 +++++++++++ vortex-filtering/test/erk_test.cpp | 231 ++++++++++++++++++ vortex-filtering/test/lti_model_test.cpp | 53 ++++ vortex-filtering/test/main.cpp | 11 + vortex-filtering/test/matrix_size_test.cpp | 143 +++++++++++ vortex-filtering/test/probability_test.cpp | 39 +++ vortex-filtering/test/sensor_model_test.cpp | 62 +++++ vortex-filtering/test/six_dof_model_test.cpp | 12 + vortex-filtering/test/test_models.hpp | 129 ++++++++++ vortex-filtering/test/ukf_test.cpp | 96 ++++++++ 35 files changed, 2876 insertions(+) create mode 100644 vortex-filtering/CMakeLists.txt create mode 100644 vortex-filtering/include/vortex_filtering/filters/Kalman_filter_base.hpp create mode 100644 vortex-filtering/include/vortex_filtering/filters/README.md create mode 100644 vortex-filtering/include/vortex_filtering/filters/UKF.hpp create mode 100644 vortex-filtering/include/vortex_filtering/filters/ekf.hpp create mode 100644 vortex-filtering/include/vortex_filtering/filters/imm_filter.hpp create mode 100644 vortex-filtering/include/vortex_filtering/integration_methods/ERK_methods.hpp create mode 100644 vortex-filtering/include/vortex_filtering/integration_methods/README.md create mode 100644 vortex-filtering/include/vortex_filtering/models/README.md create mode 100644 vortex-filtering/include/vortex_filtering/models/dynamic_model.hpp create mode 100644 vortex-filtering/include/vortex_filtering/models/imm_model.hpp create mode 100644 vortex-filtering/include/vortex_filtering/models/model_definitions.hpp create mode 100644 vortex-filtering/include/vortex_filtering/models/movement_models.hpp create mode 100644 vortex-filtering/include/vortex_filtering/models/sensor_model.hpp create mode 100644 vortex-filtering/include/vortex_filtering/nodes/kf_node.hpp create mode 100644 vortex-filtering/include/vortex_filtering/probability/README.md create mode 100644 vortex-filtering/include/vortex_filtering/probability/binomial.hpp create mode 100644 vortex-filtering/include/vortex_filtering/probability/chi_squared.hpp create mode 100644 vortex-filtering/include/vortex_filtering/probability/gaussian_mixture.hpp create mode 100644 vortex-filtering/include/vortex_filtering/probability/multi_var_gauss.hpp create mode 100644 vortex-filtering/include/vortex_filtering/probability/poisson.hpp create mode 100644 vortex-filtering/launch/vkf_node.launch.yaml create mode 100644 vortex-filtering/package.xml create mode 100644 vortex-filtering/src/nodes/kf_node.cpp create mode 100644 vortex-filtering/test/dynamic_model_test.cpp create mode 100644 vortex-filtering/test/ekf_test.cpp create mode 100644 vortex-filtering/test/erk_test.cpp create mode 100644 vortex-filtering/test/lti_model_test.cpp create mode 100644 vortex-filtering/test/main.cpp create mode 100644 vortex-filtering/test/matrix_size_test.cpp create mode 100644 vortex-filtering/test/probability_test.cpp create mode 100644 vortex-filtering/test/sensor_model_test.cpp create mode 100644 vortex-filtering/test/six_dof_model_test.cpp create mode 100644 vortex-filtering/test/test_models.hpp create mode 100644 vortex-filtering/test/ukf_test.cpp diff --git a/vortex-filtering/CMakeLists.txt b/vortex-filtering/CMakeLists.txt new file mode 100644 index 00000000..f6d4e89b --- /dev/null +++ b/vortex-filtering/CMakeLists.txt @@ -0,0 +1,137 @@ +cmake_minimum_required(VERSION 3.5) + +# === Project name === +project(vortex_filtering) + +# === C++ standard === +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) + endif() + +# === Compiler flags === +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options( + -Wall -Wextra -Wpedantic + -Wno-unused-local-typedefs # Suppress warnings from model_definitions.hpp + -fopenmp # For parallel processing with Eigen + ) +endif() + +# === Dependencies === +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(Eigen3 REQUIRED) +find_package(OpenMP REQUIRED) # For parallel processing with Eigen + +find_package(Gnuplot REQUIRED) +find_package(Boost REQUIRED + COMPONENTS + iostreams + system + filesystem +) # for gnuplot + + +# === Include directories === +include_directories(include) + +# === Executables === +add_executable(${PROJECT_NAME}_node + src/nodes/kf_node.cpp +) +ament_target_dependencies(${PROJECT_NAME}_node + rclcpp + std_msgs + geometry_msgs + Gnuplot + Boost +) +target_link_libraries(${PROJECT_NAME}_node + Eigen3::Eigen +) + +install(TARGETS + ${PROJECT_NAME}_node + DESTINATION lib/${PROJECT_NAME} +) + + +# === Libraries === +add_library(${PROJECT_NAME}_lib INTERFACE) + +# = Specify the dependencies +set(lib_deps + Eigen3 + OpenMP +) + +# = Specify the dependencies to link against +ament_target_dependencies(${PROJECT_NAME}_lib INTERFACE + ${lib_deps} +) +# = Specify the namespaced dependencies to link against +target_link_libraries(${PROJECT_NAME}_lib INTERFACE + Eigen3::Eigen + OpenMP::OpenMP_CXX +) +# = Specify the include directories for the INTERFACE of the library +target_include_directories(${PROJECT_NAME}_lib INTERFACE + "$" + "$" +) + +# === Install libraries === +install(TARGETS ${PROJECT_NAME}_lib + EXPORT export_${PROJECT_NAME} + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include +) + +# === Export libraries === +ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) +ament_export_dependencies(${lib_deps}) # Export the dependencies so the package using this package can find them + + +# === Install headers === +install( + DIRECTORY include/ + DESTINATION include +) + +# === Install launch files === +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME}/ +) + +if(BUILD_TESTING) + + find_package(ament_cmake_gtest REQUIRED) + ament_add_gtest(${PROJECT_NAME}_test + test/main.cpp + test/ekf_test.cpp + test/probability_test.cpp + test/dynamic_model_test.cpp + test/sensor_model_test.cpp + ) + target_include_directories(${PROJECT_NAME}_test PUBLIC + $ + $ + ) + ament_target_dependencies(${PROJECT_NAME}_test + std_msgs + Gnuplot + Boost + ) + target_link_libraries(${PROJECT_NAME}_test + Eigen3::Eigen # Makes us able to use #include instead of #include + OpenMP::OpenMP_CXX + ) + + +endif() + +ament_package() diff --git a/vortex-filtering/include/vortex_filtering/filters/Kalman_filter_base.hpp b/vortex-filtering/include/vortex_filtering/filters/Kalman_filter_base.hpp new file mode 100644 index 00000000..07bfb9cc --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/filters/Kalman_filter_base.hpp @@ -0,0 +1,34 @@ +#pragma once +#include + +namespace Filters { +using namespace Models; + +template class Kalman_filter_base { +public: + static constexpr int _n_x = Model::_n_x, _n_y = Model::_n_y, _n_u = Model::_n_u, _n_v = Model::_n_v, _n_w = Model::_n_w; + DEFINE_MODEL_TYPES(_n_x, _n_y, _n_u, _n_v, _n_w) + + Kalman_filter_base(State x0, Mat_xx P0) : _x0{x0}, _P0_xx{P0}, _x{x0}, _P_xx{P0} {} + virtual ~Kalman_filter_base() {} + + virtual State iterate(Time Ts, const Measurement &y, const Input &u = Input::Zero()) = 0; + void set_state(State x_n) { _x = x_n; } + void set_covariance(Mat_xx P_n) { _P_xx = P_n; } + virtual void reset() + { + set_state(_x0); + set_covariance(_P0_xx); + } + State get_state() const { return _x; } + Mat_xx get_covariance() const { return _P_xx; } + + + +protected: + const State _x0; + const Mat_xx _P0_xx; + State _x; + Mat_xx _P_xx; +}; +} // namespace Filters \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/filters/README.md b/vortex-filtering/include/vortex_filtering/filters/README.md new file mode 100644 index 00000000..3e410b46 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/filters/README.md @@ -0,0 +1,13 @@ +# Filters +This folder contains the filters. They are based on Kalman filters + +All classes and functions are under the namespace `vortex::filters`. + +## EKF +This class represents an [Extended Kalman Filter](https://en.wikipedia.org/wiki/Extended_Kalman_filter). It is a template class with parameters `DynamicModelT` and `SensorModelT`. `DynamicModelT` is the dynamic model used in the filter and `SensorModelT` is the sensor model used in the filter. There is no need to specify the dimensions of the dynamic model or the sensor model as they are automatically retrieved from the models. + +### Usage +To create an instance you need to provide a dynamic model and a sensor model. The dynamic model must be derived from the DynamicModelI interface and the sensor model must be derived from the SensorModelI interface. The EKF object will then store a copy of the dynamic model and the sensor model. (It should probably store a const reference instead to enable external live tuning for the parameters though). It does not store state estimates or covariance matrices. + +## IMM Filter +This class represents an [Interacting Multiple Model Filter](https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python/blob/master/14-Adaptive-Filtering.ipynb). It is a template class with parameters `DynamicModelT` and `SensorModelT`. `DynamicModelT` is the dynamic model used in the filter and `SensorModelT` is the sensor model used in the filter. \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/filters/UKF.hpp b/vortex-filtering/include/vortex_filtering/filters/UKF.hpp new file mode 100644 index 00000000..350a5cb8 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/filters/UKF.hpp @@ -0,0 +1,157 @@ +#pragma once +#include +#include +#include +// #include + +namespace Filters { +using namespace Models; + +template class UKF : public Kalman_filter_base { +public: + // These type definitions are needed because of the stupid two-phase lookup for dependent names in templates in C++ + using Base = Kalman_filter_base; + using Base::_n_x; using Base::_n_y; using Base::_n_u; using Base::_n_v; using Base::_n_w; // can be comma separated in C++17 + DEFINE_MODEL_TYPES(_n_x, _n_y, _n_u, _n_v, _n_w) + static constexpr int _n_a = _n_x + _n_v + _n_w; // Size of augmented state + using Mat_aa = Matrix; + using State_a = Vector; + + UKF(std::shared_ptr model, State x0, Mat_xx P0) : Kalman_filter_base(x0, P0), model{model} {} + ~UKF() {} + +private: + // Parameters used for calculating scaling factor, _GAMMA and weights W_x0, W_c0 and W_xi + // lambda selected according to the scaled unscented transform. (van der Merwe (2004)) + static constexpr double _ALPHA_SQUARED = 1; + static constexpr double _BETA = 2; + static constexpr double _KAPPA = 0; + static constexpr double _LAMBDA = _ALPHA_SQUARED * (_n_a + _KAPPA) - _n_a; + static constexpr double _GAMMA = std::sqrt(_n_a + _LAMBDA); + + static constexpr double _W_x0 = _LAMBDA / (_n_a + _LAMBDA); + static constexpr double _W_c0 = _LAMBDA / (_n_a + _LAMBDA) + (1 - _ALPHA_SQUARED + _BETA); + static constexpr double _W_xi = 1 / (2 * (_n_a + _LAMBDA)); + static constexpr double _W_ci = 1 / (2 * (_n_a + _LAMBDA)); + + std::shared_ptr model; + + Matrix get_sigma_points(const State &x, const Mat_xx &P, const Mat_vv &Q, const Mat_ww &R) + { + // Make augmented covariance matrix + Mat_aa P_a; + // clang-format off + P_a << P , Mat_xv::Zero(), Mat_xw::Zero(), + Mat_vx::Zero(), Q , Mat_vw::Zero(), + Mat_wx::Zero(), Mat_wv::Zero(), R; + // clang-format on + Mat_aa sqrt_P_a = P_a.llt().matrixLLT(); + + // Make augmented state vector + State_a x_a; + x_a << x, Disturbance::Zero(), Noise::Zero(); + + // Calculate sigma points + Matrix sigma_points; + + // Use the symmetric sigma point set + sigma_points.col(0) = x_a; + for (size_t i = 1; i <= _n_a; i++) { + sigma_points.col(i) = x_a + _GAMMA * sqrt_P_a.col(i - 1); + sigma_points.col(i + _n_a) = x_a - _GAMMA * sqrt_P_a.col(i - 1); + } + return sigma_points; + } + +public: + State iterate(Time t, const Measurement &y, const Input &u = Input::Zero()) override final + { + Mat_vv Q = model->Q(t, this->_x); + Mat_ww R = model->R(t, this->_x); + + Matrix sigma_points = get_sigma_points(this->_x, this->_P_xx, Q, R); + + // Propagate sigma points through f + Matrix sigma_x_pred; + for (size_t i = 0; i < 2 * _n_a + 1; i++) { + auto x_i = sigma_points.template block<_n_x, 1>(0, i); + auto v_i = sigma_points.template block<_n_v, 1>(_n_x, i); + sigma_x_pred.col(i) = model->f(t, x_i, u, v_i); + } + + // Predicted State Estimate x_k- + State x_pred; + x_pred = _W_x0 * sigma_x_pred.col(0); + for (size_t i = 1; i < 2 * _n_a + 1; i++) { + x_pred += _W_xi * sigma_x_pred.col(i); + } + + // Predicted State Covariance P_xx- + Mat_xx P_xx_pred; + P_xx_pred = _W_c0 * (sigma_x_pred.col(0) - x_pred) * (sigma_x_pred.col(0) - x_pred).transpose(); + for (size_t i = 1; i < 2 * _n_a + 1; i++) { + _W_ci *(sigma_x_pred.col(i) - x_pred) * (sigma_x_pred.col(i) - x_pred).transpose(); + } + + // Propagate sigma points through h + Matrix sigma_y_pred; + for (size_t i = 0; i < 2 * _n_a + 1; i++) { + auto x_i = sigma_points.template block<_n_x, 1>(0, i); + auto w_i = sigma_points.template block<_n_w, 1>(_n_x + _n_v, i); + sigma_y_pred.col(i) = model->h(t, x_i, u, w_i); + } + + // Predicted Output y_pred + Measurement y_pred; + y_pred = _W_x0 * sigma_y_pred.col(0); + for (size_t i = 1; i < 2 * _n_a + 1; i++) { + y_pred += _W_xi * sigma_y_pred.col(i); + } + + // Output Covariance P_yy + Mat_yy P_yy; + P_yy = _W_c0 * (sigma_y_pred.col(0) - y_pred) * (sigma_y_pred.col(0) - y_pred).transpose(); + for (size_t i = 1; i < 2 * _n_a + 1; i++) { + P_yy += _W_ci * (sigma_y_pred.col(i) - y_pred) * (sigma_y_pred.col(i) - y_pred).transpose(); + } + + // Cross Covariance P_xy + Mat_xy P_xy; + P_xy = _W_c0 * (sigma_x_pred.col(0) - x_pred) * (sigma_y_pred.col(0) - y_pred).transpose(); + for (size_t i = 1; i < 2 * _n_a + 1; i++) { + P_xy += _W_ci * (sigma_x_pred.col(i) - x_pred) * (sigma_y_pred.col(i) - y_pred).transpose(); + } + + // Kalman gain K + Mat_yy P_yy_inv = P_yy.llt().solve(Mat_yy::Identity()); // Use Cholesky decomposition for inverting P_yy + Mat_xy K = P_xy * P_yy_inv; + + // Corrected State Estimate x_next + State x_next = x_pred + K * (y - y_pred); + // Normalize quaternions if applicable + x_next = model->post_state_update(x_next); + // Corrected State Covariance P_xx_next + Mat_xx P_xx_next = P_xx_pred - K * P_yy * K.transpose(); + + // Update local state + this->_x = x_next; + this->_P_xx = P_xx_next; + + return x_next; + } +}; + + +// required namespace-scope declarations to avoid linker errors +template constexpr int UKF::_n_a; +template constexpr double UKF::_ALPHA_SQUARED; +template constexpr double UKF::_BETA; +template constexpr double UKF::_KAPPA; +template constexpr double UKF::_LAMBDA; +template constexpr double UKF::_GAMMA; +template constexpr double UKF::_W_x0; +template constexpr double UKF::_W_c0; +template constexpr double UKF::_W_xi; +template constexpr double UKF::_W_ci; + +} // namespace Filters diff --git a/vortex-filtering/include/vortex_filtering/filters/ekf.hpp b/vortex-filtering/include/vortex_filtering/filters/ekf.hpp new file mode 100644 index 00000000..876593f8 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/filters/ekf.hpp @@ -0,0 +1,99 @@ +/** + * @file ekf.hpp + * @author Eirik Kolås + * @brief Multivariate Gaussian Distribution. Based on "Fundamentals of Sensor Fusion" by Edmund Brekke + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ + +#pragma once +#include +#include +#include +#include + +namespace vortex { +namespace filters { + +/** @brief Extended Kalman Filter. (I stands for interface, T for Type) + * + * @tparam DynamicModelI Dynamic model type. Has to have function for Jacobian of state transition. + * @tparam SensorModelI Sensor model type. Has to have function for Jacobian of measurement. (get_H) + */ +template +class EKF { + static constexpr int N_DIM_x = DynamicModelT::N_DIM_x; + static constexpr int N_DIM_z = SensorModelT::N_DIM_z; + using DynModI = models::DynamicModelI; + using SensModI = models::SensorModelI; + using Vec_x = typename DynModI::Vec_x; + using Mat_xx = typename DynModI::Mat_xx; + using Vec_z = typename SensModI::Vec_z; + using Mat_zz = typename SensModI::Mat_zz; + using Mat_zx = typename SensModI::Mat_zx; + using Mat_xz = typename SensModI::Mat_xz; + using Gauss_x = typename DynModI::Gauss_x; + using Gauss_z = typename SensModI::Gauss_z; + +public: + EKF(DynamicModelT dynamic_model, SensorModelT sensor_model) + : dynamic_model_(std::move(dynamic_model)), sensor_model_(std::move(sensor_model)) {} + + /** Perform one EKF prediction step + * @param x_est_prev Previous state estimate + * @param dt Time step + */ + std::pair predict(const Gauss_x& x_est_prev, double dt) { + Gauss_x x_est_pred = dynamic_model_.pred_from_est(x_est_prev, dt); + Gauss_z z_est_pred = sensor_model_.pred_from_est(x_est_pred); + return {x_est_pred, z_est_pred}; + } + + /** Perform one EKF update step + * @param x_est_pred Predicted state + * @param z_est_pred Predicted measurement + * @param z_meas Vec_z + * @return MultivarGauss Updated state + */ + Gauss_x update(const Gauss_x& x_est_pred, const Gauss_z& z_est_pred, const Vec_z& z_meas) { + Mat_zx H_mat = sensor_model_.H(x_est_pred.mean()); + Mat_zz R_mat = sensor_model_.R(x_est_pred.mean()); + Mat_xx P_mat = x_est_pred.cov(); + Mat_zz S_mat_inv = z_est_pred.cov_inv(); + Mat_xx I = Mat_xx::Identity(N_DIM_x, N_DIM_x); + + Mat_xz kalman_gain = P_mat * H_mat.transpose() * S_mat_inv; + Vec_z innovation = z_meas - z_est_pred.mean(); + + Vec_x state_upd_mean = x_est_pred.mean() + kalman_gain * innovation; + // Use the Joseph form of the covariance update to ensure positive definiteness + Mat_xx state_upd_cov = (I - kalman_gain * H_mat) * P_mat * (I - kalman_gain * H_mat).transpose() + kalman_gain * R_mat * kalman_gain.transpose(); + + return {state_upd_mean, state_upd_cov}; + } + + /** + * @brief Perform one EKF prediction and update step + * @param x_est_prev Previous state estimate + * @param z_meas Vec_z + * @param dt Time step + * @return std::tuple Updated state, predicted state, predicted measurement + */ + std::tuple step(const Gauss_x& x_est_prev, const Vec_z& z_meas, double dt) { + std::pair pred = predict(x_est_prev, dt); + Gauss_x x_est_pred = pred.first; + Gauss_z z_est_pred = pred.second; + Gauss_x x_est_upd = update(x_est_pred, z_est_pred, z_meas); + return {x_est_upd, x_est_pred, z_est_pred}; + } + +private: + const DynamicModelT dynamic_model_; + const SensorModelT sensor_model_; +}; + +} // namespace filters +} // namespace vortex \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/filters/imm_filter.hpp b/vortex-filtering/include/vortex_filtering/filters/imm_filter.hpp new file mode 100644 index 00000000..08d8e821 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/filters/imm_filter.hpp @@ -0,0 +1,154 @@ +/** + * @file imm_filter.hpp + * @author Eirik Kolås + * @brief IMM filter based on "Fundamentals of Sensor Fusion" by Edmund Brekke + * @version 0.1 + * @date 2023-11-02 + * + * @copyright Copyright (c) 2023 + * + */ +#include +#include +#include +#include +#include + +namespace vortex { +namespace filters { + +template +class ImmFilter { +public: + using ImmModelT::N_DIM_x; + using ImmModelT::N_MODELS; + using ImmModelT::Mat_nn; + using ImmModelT::Vec_n; + using ImmModelT::Vec_x; + using ImmModelT::Mat_xx; + using ImmModelT::Vec_x; + using SensorModelT::N_DIM_z; + using SensorModelT::Mat_zz; + using SensorModelT::Vec_z; + using SensorModelT::Mat_xz; + + + ImmFilter(const ImmModelT& imm_model, const SensorModelT& sensor_model) + : imm_model_(imm_model), sensor_model_(sensor_model) + { + for (int i = 0; i < N_MODELS; i++) { + ekfs_.push_back(std::make_unique>(imm_model_.get_dynamic_models().at(i), sensor_model_)); + } + } + + /** + * @brief Calculate mixing probabilities, following step 1 in (6.4.1) in the book + * + * @param x_est_prev Mixture from previous time step + * @param dt + */ + calculate_mixings(const prob::GaussianMixture& x_est_prev, double dt) + { + Mat_nn pi_mat = imm_model_.get_pi_mat_d(dt); + Vec_nn prev_weights = Eigen::Map(x_est_prev.weights().data(), weight_vec.size()); // Convert to Eigen vector + + // Mat_nn mixing_probs = pi_mat.cwiseProduct(prev_weights.transpose().replicate(N_MODELS, 1)); // Multiply each column with the corresponding weight + for (int i = 0; i < mixing_probs.rows(); i++) { + // TODO: Check if this is correct + mixing_probs.row(i) = pi_mat.row(i).cwiseProduct(prev_weights.transpose()); + // Normalize + mixing_probs.row(i) /= mixing_probs.row(i).sum(); + } + return mixing_probs; + } + + /** + * @brief Calculate moment-based approximation, following step 2 in (6.4.1) in the book + * @param x_est_prev Mixture from previous time step + * @param mixing_probs Mixing probabilities + */ + std::vector> mixing(const prob::GaussianMixture& x_est_prev, Mat_nn mixing_probs) + { + std::vector> moment_based_preds(N_MODELS); + for (int i = 0; i < N_MODELS; i++) { + prob::GaussianMixture mixture(mixing_probs.row(i), x_est_prev.gaussians()); + moment_based_preds.append(mixture.reduce()); + } + return moment_based_preds; + } + + /** + * @brief Calculate the mode-match filter outputs (6.36), following step 3 in (6.4.1) in the book + * + * @param moment_based_preds Moment-based predictions + * @param z_meas Vec_z + * @param dt Time step + */ + std::tuple>, std::vector>, std::vector>>> mode_match_filter(const std::vector>& moment_based_preds, Vec_zz z_meas, double dt) + { + + std::tuple>, std::vector>, std::vector>>> ekf_outs; + + for (int i = 0; i < N_MODELS; i++) { + auto [x_est_upd, x_est_pred, z_est_pred] = ekfs_.at(i).step(moment_based_preds.at(i), z_meas, dt); + ekf_outs<0>.append(x_est_upd); + ekf_outs<1>.append(x_est_pred); + ekf_outs<2>.append(z_est_pred); + } + return ekf_outs; + } + + /** + * @brief Update the mixing probabilites using (6.37) from setp 3 and (6.38) from step 4 in (6.4.1) in the book + * @param ekf_outs Mode-match filter outputs + * @param z_meas Vec_z + * @param dt Time step + * @param weights Weights + */ + Mat_nn update_probabilities(const std::vector>& ekf_outs, Vec_z z_meas, double dt, Vec_n weights) + { + Mat_nn pi_mat = imm_model_.get_pi_mat_d(dt); + Vec_n weights_pred = pi_mat.transpose() * weights + + Vec_n z_probs = Vec_n::Zero(); + for (int i = 0; i < N_MODELS; i++) { + auto [x_est_upd, z_est_pred] = ekf_outs.at(i); + z_probs(i) = z_est_pred.pdf(z_meas); + } + + Vec_n weights_upd = z_probs.cwiseProduct(weights_pred); + weights_upd /= weights_upd.sum(); + + return weights_upd; + + } + + /** + * @brief Perform one IMM filter step + * + * @param x_est_prev Mixture from previous time step + * @param z_meas Vec_z + * @param dt Time step + */ + std::tuple, prob::GaussianMixture, prob::GaussianMixture step(const prob::GaussianMixture& x_est_prev, Vec_z z_meas, double dt) + { + Mat_nn mixing_probs = calculate_mixings(x_est_prev, dt); + std::vector> moment_based_preds = mixing(x_est_prev, mixing_probs); + auto [x_est_upds, x_est_preds, z_est_preds] = mode_match_filter(moment_based_preds, z_meas, dt); + Vec_n weights_upd = update_probabilities(ekf_outs, z_meas, dt, mixing_probs.row(0)); + + prob::GaussianMixture x_est_upd{weights_upd, x_est_upds}; + prob::GaussianMixture x_est_pred(x_est_prev.weights, x_est_preds); + prob::GaussianMixture z_est_pred(x_est_prev.weights, z_est_preds); + + return {x_est_upd, x_est_pred, z_est_pred}; + } + +private: + ImmModel imm_model_; + SensorModelT sensor_model_; + std::vector>> ekfs_; +}; + +} // namespace filters +} // namespace vortex \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/integration_methods/ERK_methods.hpp b/vortex-filtering/include/vortex_filtering/integration_methods/ERK_methods.hpp new file mode 100644 index 00000000..55918fb7 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/integration_methods/ERK_methods.hpp @@ -0,0 +1,227 @@ +#pragma once +#include +#include +#include +#include + +#include + +namespace Integrator { +using namespace Models; + +// Base class RK_method for RK4 and forward_euler to derive from + + +template +class None { +public: + /** + * @brief Does not integrate, just returns f(t_k, x_k). Use if f is a discrete model + */ + None() = default; + DEFINE_MODEL_TYPES(n_x, 0, 0, 0, 0) + static State integrate(State_dot f, Timestep dt, Time t_k, const State &x_k) { (void)dt; return f(t_k, x_k); } +}; +template using None_M = None; + +template +class RK4 { +public: + DEFINE_MODEL_TYPES(n_x, 0, 0, 0, 0) + static State integrate(State_dot f, Timestep dt, Time t_k, const State &x_k) + { + State k1 = f(t_k, x_k); + State k2 = f(t_k + 0.5 * dt, x_k + 0.5 * dt / 1s * k1); + State k3 = f(t_k + 0.5 * dt, x_k + 0.5 * dt / 1s * k2); + State k4 = f(t_k + 1.0 * dt, x_k + 1.0 * dt / 1s * k3); + + return x_k + (dt / 1s / 6.0) * (k1 + 2 * k2 + 2 * k3 + k4); + } +}; +template using RK4_M = RK4; + +template class Forward_Euler { +public: + DEFINE_MODEL_TYPES(n_x, 0, 0, 0, 0) + static State integrate(State_dot f, Timestep dt, Time t_k, const State &x_k) + { + return x_k + dt / 1s * f(t_k, x_k); + } +}; +template using Forward_Euler_M = Forward_Euler; + + + + +template class Butcher { +public: + DEFINE_MODEL_TYPES(n_x, 0, 0, 0, 0) + /** + * @brief Construct an ERK method from a Butcher table. Cannot be passed as a class to a template + * as it needs the non-static members A, b and c to be intitalized in an object. + * @param A + * @param b + * @param c + */ + Butcher(Eigen::Matrix A, Eigen::Vector b, Eigen::Vector c) : _A{A}, _b{b}, _c{c} + { + // Check if Butcher table is valid + if (A.isLowerTriangular() == false) { + throw std::invalid_argument("Butcher table: A is not lower triangular"); + } + + // Check if Butcher table is consistent + if (b.sum() != 1) { + throw std::invalid_argument("Butcher table: b does not sum to one"); + } + for (int i = 0; i < A.rows(); i++) { + if (std::abs(A.row(i).sum() - c(i)) > 1e-6) { + throw std::invalid_argument("Butcher table: row " + std::to_string(i) + " in A does not sum to c(" + std::to_string(i) + ")"); + } + } + } + + State integrate(State_dot f, Timestep dt, Time t_k, const State &x_k) + { + Eigen::Matrix k = Eigen::Matrix::Zero(); + for (size_t i = 0; i < n_stages; i++) { + k.col(i) = f(t_k + _c(i) * dt, x_k + dt / 1s * k * _A.row(i).transpose()); + } + return x_k + dt / 1s * k * _b; + } + +private: + Eigen::Matrix _A; + Eigen::Vector _b; + Eigen::Vector _c; +}; + +template class ODE45 { +public: + DEFINE_MODEL_TYPES(n_x, 0, 0, 0, 0) + /** + * @brief Variable step size Runge-Kutta method + * + * @param abs_error absolute error. Specify a value for all state variables + * @param rel_error relative error. Specify a value for all state variables + * @param max_iterations Maximum number of iterations before giving up + * @param min_step_size Minimum valid value for the step size in the integration + */ + ODE45(double abs_error = 1e-6, double rel_error = 1e-6, size_t max_iterations = 1000, Timestep min_step_size = 1ns) + : ODE45(State::Ones() * abs_error, State::Ones() * rel_error, max_iterations, min_step_size) + { + } + + /** + * @brief Variable step size Runge-Kutta method + * + * @param abs_error_vec absolute error vector. Specify a value for each state variable + * @param rel_error_vec relative error vector. Specify a value for each state variable + * @param max_iterations Maximum number of iterations before giving up + * @param min_step_size Minimum valid value for the step size in the integration + */ + ODE45(State abs_error_vec = State::Ones() * 1e-6, State rel_error_vec = State::Ones() * 1e-6, size_t max_iterations = 1000, Timestep min_step_size = 1ns) + : _Atol{abs_error_vec}, _Rtol{rel_error_vec}, _max_iter{max_iterations}, _min_step_size{min_step_size} + { + // Use the Dormand Prince (RKDP) method + // clang-format off + _A << 0 , 0 , 0 , 0 , 0 , 0 , 0, + 1/5.0 , 0 , 0 , 0 , 0 , 0 , 0, + 3/40.0 , 9/40.0 , 0 , 0 , 0 , 0 , 0, + 44/45.0 , -56/15.0 , 32/9.0 , 0 , 0 , 0 , 0, + 19372/6561.0, -25360/2187.0, 64448/6561.0, -212/729.0, 0 , 0 , 0, + 9017/3168.0 , -355/33.0 , 46732/5247.0, 49/176.0 , -5103/18656.0 , 0 , 0, + 35/384.0 , 0 , 500/1113.0 , 125/192.0, -2187/6784.0 , 11/84.0 , 0; + Eigen::Matrix b_T; + b_T <<35/384.0 , 0 , 500/1113.0 , 125/192.0, -2187/6784.0 , 11/84.0 , 0, // Error of order O(dt^5) + 5179/57600.0, 0 , 7571/16695.0, 393/640.0, -92097/339200.0, 187/2100.0, 1/40.0; // Error of order O(dt^4) + _b = b_T.transpose(); + _c << 0 , 1/5.0 , 3/10.0 , 4/5.0 , 8/9.0 , 1 , 1; + // clang-format on + } + + /** + * @brief Integrate the function f over one step dt + * + * @param f Function to integrate + * @param dt Time step size / Simulation time + * @param t_k Start time + * @param x_k Start state + * @return Integrated state + * @throws std::runtime_error if the maximum number of iterations is reached + * @throws std::runtime_error if the step size becomes too small + */ + State integrate(State_dot f, Timestep dt, Time t_k, const State &x_k) + { + // Copy t and x + const Time t_kp1 = t_k + dt; // Final time t_k+1 + Time t_i = t_k; // Intermediate times + State x_i = x_k; // Intermediate states + Timestep h = dt; // Variable step size + + for (size_t iter = 0; iter < _max_iter; iter++) { + // Compute k_i + Eigen::Matrix k = Eigen::Matrix::Zero(); + for (size_t i = 0; i < n_stages; i++) { + k.col(i) = f(t_i + _c(i) * h, x_i + h / 1s * k * _A.row(i).transpose()); + } + + State x_ip1_hat = x_i + h / 1s * k * _b.col(0); // Higher order solution + State x_ip1 = x_i + h / 1s * k * _b.col(1); // Lower order solution + + // From https://scicomp.stackexchange.com/questions/32563/dormand-prince-54-how-to-update-the-stepsize-and-make-accept-reject-decision + + // Compute max(|x_i|, |x_i+1|) + State abs_x_i = x_i.cwiseAbs(); + State abs_x_ip1 = x_ip1.cwiseAbs(); // Using lower order solution + State max_x = abs_x_i.cwiseMax(abs_x_ip1); + + // Scaling factor + State sc = _Atol + max_x.cwiseProduct(_Rtol); + + // Estimate error + State temp_error = (x_ip1 - x_ip1_hat).cwiseQuotient(sc); + double error = std::sqrt(temp_error.dot(temp_error) / n_x); + + // Accecpt step if error is within tolerance + if (error < 1) { + t_i += h; + x_i = x_ip1_hat; + + if (t_i >= t_kp1) { + return x_i; // Simulation completed successfully + } + } + + // Compute new step size + Timestep h_new; + static constexpr double f_ac = std::pow(0.25, 1.0 / (q + 1)); // safety factor + + h_new = f_ac * h * std::pow(1 / error, 1.0 / (q + 1)); // optimal step size + h_new = std::max(h_new / 1s, 0.2 * h / 1s) * 1s; // limit step size decrease + h_new = std::min(h_new / 1s, 5.0 * h / 1s) * 1s; // limit step size increase + h_new = std::min(h_new / 1s, (t_kp1 - t_i) / 1s) * 1s; // limit step size to not overshoot t_kp1 + h = h_new; + + if (h < _min_step_size) { + throw std::runtime_error("Could not reach tolerance within minimum step size" + std::to_string(_min_step_size / 1s)); + } + } + throw std::runtime_error("Could not reach tolerance within maximum number of iterations " + std::to_string(_max_iter)); + } + +private: + static constexpr int n_stages = 7; + static constexpr size_t q = 5; // Order of the method + + Eigen::Matrix _A; + Eigen::Matrix _b; + Eigen::Vector _c; + + State _Atol; + State _Rtol; + size_t _max_iter; + Timestep _min_step_size; +}; + +} // namespace Integrator \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/integration_methods/README.md b/vortex-filtering/include/vortex_filtering/integration_methods/README.md new file mode 100644 index 00000000..747d174f --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/integration_methods/README.md @@ -0,0 +1,13 @@ +# Integration Methods +A collection of integration methods. +All methods can be used with all of the Kalman filter implementations. + +## Use Cases +| Method | Pros | Cons | Use Case +| ---- | ---- | ---- | ---- +| Forward Euler | Fast | Most inaccurate | If speed is your only concern, use this +| RK4 | Accurate | 4 stages -> Slower | Should be the go-to method for most cases +| RK45 | As accurate as you want | Adaptive step size -> Super slow | If you need a set accuracy. Not meant for real-time applications +| Midpoint | Stable | 2 stages -> Inaccurate | Stable 2-stage method (compared to other 2-stage methods) +| Heun | | | Added just for fun :) +| Butcher | | Slower than a direct implementation | General Explicit Runge-Kutta method. Can be used to implement any explicit ERK method from a Butcher Table diff --git a/vortex-filtering/include/vortex_filtering/models/README.md b/vortex-filtering/include/vortex_filtering/models/README.md new file mode 100644 index 00000000..e3ee0b41 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/models/README.md @@ -0,0 +1,33 @@ +# Models +This folder contains the models used in the Vortex-VKF project. The models are derived from either DynamicModelI or the SensorModelI interface. +They define the dynamics of the system and the sensor models used in the project. + +All classes and functions are under the namespace `vortex::models`. + +## DynamicModelI +This interface defines the dynamics of the system. The methods `f_c`, `A_c` and `Q_c` define the continuous time dynamics of the system. The methods `f_d`, `A_d` and `Q_d` define the discrete time dynamics of the system. The methods `f_c` and `f_d` are the state transition functions. The methods `A_c` and `A_d` are the Jacobians of the state transition functions. The methods `Q_c` and `Q_d` are the process noise covariance matrices. The noise is assumed additive and Gaussian. + +### Usage +In order to define a new dynamic model, the user must create a new class that inherits from the DynamicModelI interface. The user must then implement the methods `f_c`, `A_c` and `Q_c` for the continuous time dynamics. The discrete time dynamics are found using exact discretization. If you want to use this, you must implement the methods `f_c`, `A_c` and `Q_c`. The methods `f_d`, `A_d` and `Q_d` are then automatically generated using [exact discretization](https://en.wikipedia.org/wiki/Discretization). The user can also define the discrete time dynamics themselves by overiting `f_d` etc. + +The interface is a template class with parameter `N_DIM_x`. This is the dimension of the state vector. The user must specify this when creating a new class, or derive a template class from the DynamicModelI interface. Both static and dynamic dimensions are supported but as of now only static dimensions are tested. + +## SensorModelI +This interface defines the sensor models. The methods `h` `H` and `R` define the sensor model. The method `h` is the measurement function, `H` is the Jacobian of the measurement function and `R` is the measurement noise covariance matrix. The sensor model is assumed to be defined in discrete time. The noise is assumed additive and Gaussian. + +### Usage +In order to define a new sensor model, the user must create a new class that inherits from the SensorModelI interface. The user must then implement the methods `h`, `H` and `R` as they are pure virtual. + +The interface is a template class with parameter `N_DIM_x` and `N_DIM_z`. `N_DIM_x` is the dimension of the state vector and `N_DIM_z` is the dimension of the measurement vector. The user must specify these when creating a new class, or derive a template class from the SensorModelI interface. Both static and dynamic dimensions are supported (and tested). + +## Movement Models +This file contains some movement models that can be used in the project. They are all derived from the DynamicModelI interface. +- **CVModel**: Constant Velocity Model. Has four states: x, y, vx and vy. The velocity is assumed to be constant. +- **CTModel**: Coordinated Turn Model. Has five states: x, y, vx, vy and omega. The speed is assumed to be constant and the turn rate is assumed to be constant. +- **CAModel**: Constant Acceleration Model. Has six states: x, y, vx, vy, ax and ay. The acceleration is assumed to be constant. + +## IMM Model +This class is can hold multiple DynamicModelI objects and defines functions to calculate the probability of switching between the models. + +### Usage +To create an instance you need to provide a vector DynamicModelI objects and a matrix defining the switching probabilities. The switching probabilities are defined as the probability of switching from model i to model j. The switching probabilities must be between 0 and 1 and the rows must sum to 1.0. The number of rows and columns must be the same as the number of models. Note that this defines the probability of switching to a specific model *when* a switch occurs. Not the probability of switching itself. The probability of switching is derived from the `hold_times` parameter. The `hold_times` parameter is a vector of the expected time between switches for each model. The switching probabilities are then calculated by modelling the system as a [Continuous Time Markov Chain](https://en.wikipedia.org/wiki/Continuous-time_Markov_chain). The switching probabilities are then used to calculate the probability of switching or staying in a model. diff --git a/vortex-filtering/include/vortex_filtering/models/dynamic_model.hpp b/vortex-filtering/include/vortex_filtering/models/dynamic_model.hpp new file mode 100644 index 00000000..b82f7ce8 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/models/dynamic_model.hpp @@ -0,0 +1,128 @@ +/** + * @file dynamic_model.hpp + * @author Eirik Kolås + * @brief Dynamic model interface. Based on "Fundamentals of Sensor Fusion" by Edmund Brekke + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include +#include // For exp +#include + + +namespace vortex { +namespace models { + +/** + * @brief Interface for dynamic models. + * + */ +template +class DynamicModelI { +public: + static constexpr int N_DIM_x = n_dim_x; // Declare so that children of this class can reference it + using Vec_x = Eigen::Vector; + using Mat_xx = Eigen::Matrix; + using Gauss_x = prob::MultiVarGauss; + + virtual ~DynamicModelI() = default; + + /** Continuos time dynamics + * @param x Vec_x + * @return State_dot + */ + virtual Vec_x f_c(const Vec_x& x) const = 0; + + /** Jacobian of continuous time dynamics + * @param x Vec_x + * @return State_jac + */ + virtual Mat_xx A_c(const Vec_x& x) const = 0; + + /** Continuous time process noise + * @param x Vec_x + * @return Matrix Process noise covariance + */ + virtual Mat_xx Q_c(const Vec_x& x) const = 0; + + /** Discrete time dynamics + * @param x Vec_x + * @param dt Time step + * @return Vec_x + */ + virtual Vec_x f_d(const Vec_x& x, double dt) const + { + return F_d(x, dt) * x; + } + + /** Jacobian of discrete time dynamics + * @param x Vec_x + * @param dt Time step + * @return State_jac + */ + virtual Mat_xx F_d(const Vec_x& x, double dt) const + { + // Use (4.58) from the book + return (A_c(x) * dt).exp(); + } + + /** Discrete time process noise + * @param x Vec_x + * @param dt Time step + * @return Matrix Process noise covariance + */ + virtual Mat_xx Q_d(const Vec_x& x, double dt) const + { + // See https://en.wikipedia.org/wiki/Discretization#Discretization_of_process_noise for more info + + Mat_xx A_c = this->A_c(x); + Mat_xx Q_c = this->Q_c(x); + + Eigen::Matrix v_1; + v_1 << -A_c, Q_c, Mat_xx::Zero(), A_c.transpose(); + v_1 *= dt; + v_1 = v_1.exp(); + Mat_xx F_d = v_1.template block(N_DIM_x, N_DIM_x).transpose(); + Mat_xx F_d_inv_Q_d = v_1.template block(0, N_DIM_x); + Mat_xx Q_d = F_d * F_d_inv_Q_d; + + return Q_d; + } + + + /** Get the predicted state distribution given a state estimate + * @param x_est Vec_x estimate + * @param dt Time step + * @return Vec_x + */ + virtual Gauss_x pred_from_est(const Gauss_x& x_est, double dt) const + { + Mat_xx P = x_est.cov(); + Mat_xx F_d = this->F_d(x_est.mean(), dt); + Mat_xx Q_d = this->Q_d(x_est.mean(), dt); + Gauss_x x_est_pred(this->f_d(x_est.mean(), dt), F_d * P * F_d.transpose() + Q_d); + + return x_est_pred; + } + + /** Get the predicted state distribution given a state + * @param x Vec_x + * @param dt Time step + * @return Vec_x + */ + virtual Gauss_x pred_from_state(const Vec_x& x, double dt) const + { + Mat_xx Q_d = this->Q_d(x, dt); + Gauss_x x_est_pred(this->f_d(x, dt), Q_d); + + return x_est_pred; + } + +}; + +} // namespace models +} // namespace vortex diff --git a/vortex-filtering/include/vortex_filtering/models/imm_model.hpp b/vortex-filtering/include/vortex_filtering/models/imm_model.hpp new file mode 100644 index 00000000..896bb81e --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/models/imm_model.hpp @@ -0,0 +1,117 @@ +/** + * @file imm_model.hpp + * @author Eirik Kolås + * @brief + * @version 0.1 + * @date 2023-11-02 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include +#include +#include + +namespace vortex { +namespace models { + +template +class ImmModel : public DynamicModelI { // TODO: Should NOT inherit from DynamicModelI +public: + static constexpr size_t N_MODELS_ = n_models; + using typename DynamicModelI::Vec_x; + using typename DynamicModelI::Mat_xx; + using Vec_n = Eigen::Vector; + using Mat_nn = Eigen::Matrix; + + /** + * @brief Construct a new Imm Model object + * @param models Models to use + * @param jump_matrix Markov jump chain matrix for the transition probabilities. + * I.e. the probability of switching from model i to model j is jump_matrix(i,j). Diagonal should be 0. + * @param hold_times Holding time for each state. Parameter is the mean of an exponential distribution. + */ + ImmModel(std::vector>> models, Mat_nn jump_matrix, Vec_n hold_times) + : models_(std::move(models)), jump_matrix_(std::move(jump_matrix)), hold_times_(std::move(hold_times)), N_MODELS_(n_models) + { + // Validate input + assert(models_.size() == N_MODELS_); + assert(hold_times_.size() == N_MODELS_); + assert(jump_matrix_.diagonal().isZero()); + + // Normalize jump matrix + for (int i = 0; i < jump_matrix_.rows(); i++) { + jump_matrix_.row(i) /= jump_matrix_.row(i).sum(); + } + } + + /** + * @brief Continuous time dynamics for the first model in the list. + * Use f_c(x, model_idx) to get the dynamics of a specific model. + * @param x Vec_x + * @return The first model in the list. + */ + Vec_x f_c(const Vec_x& x) const override + { + // error if used + assert(false); + return models_.at(0)->f_c(x); + } + + /** + * @brief Continuous time dynamics for a specific model + * + * @param x + * @param model_idx + * @return Vec_x + */ + Vec_x f_c(const Vec_x& x, int model_idx) const + { + return models_.at(model_idx)->f_c(x); + } + + /** + * @brief Compute the continuous-time transition matrix + * See https://en.wikipedia.org/wiki/Continuous-time_Markov_chain + * @return Matrix Continuous-time transition matrix + */ + Mat_nn get_pi_mat_c() const + { + static bool is_cached = false; + static Mat_nn pi_mat_c = Mat_nn::Zero(); + if (is_cached) { return pi_mat_c; } + + Vec_n t_inv = hold_times_.cwiseInverse(); + Mat_nn = - t_inv.asDiagonal() + t_inv*jump_matrix_; + + is_cached = true; + return pi_mat_c; + } + + /** + * @brief Compute the discrete-time transition matrix + * @return Matrix Discrete-time transition matrix + */ + */ + Mat_nn get_pi_mat_d(double dt) const + { + return (get_pi_mat_c() * dt).exp(); + } + + /** + * @brief Get the dynamic models + * @return models + */ + std::vector>> get_models() const + { + return models_; + } +private: + const std::vector>> models_; + const Mat_nn jump_matrix_; + const Vec_n hold_times_; +}; + +} // namespace models +} // namespace vortex \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/models/model_definitions.hpp b/vortex-filtering/include/vortex_filtering/models/model_definitions.hpp new file mode 100644 index 00000000..6a6af7b1 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/models/model_definitions.hpp @@ -0,0 +1,61 @@ +#pragma once +#include +#include + +namespace Models { +using Eigen::Matrix; +using Eigen::Vector; +using namespace std::chrono_literals; +using namespace std::chrono; +using Time = duration; +using Timestep = duration; + +/** + * @brief Define the types used in the models. + * THIS HAS TO BE USED INSIDE THE Models NAMESPACE + * @param n_x State size + * @param n_y Measurement size + * @param n_u Input size + * @param n_v Disturbance size + * @param n_w Noise size + */ +#define DEFINE_MODEL_TYPES(n_x, n_y, n_u, n_v, n_w) \ + using State = Eigen::Vector; \ + using Measurement = Eigen::Vector; \ + using Input = Eigen::Vector; \ + using Disturbance = Eigen::Vector; \ + using Noise = Eigen::Vector; \ + \ + using Mat_xx = Eigen::Matrix; \ + using Mat_xy = Eigen::Matrix; \ + using Mat_xu = Eigen::Matrix; \ + using Mat_xv = Eigen::Matrix; \ + using Mat_xw = Eigen::Matrix; \ + \ + using Mat_yx = Eigen::Matrix; \ + using Mat_yy = Eigen::Matrix; \ + using Mat_yu = Eigen::Matrix; \ + using Mat_yv = Eigen::Matrix; \ + using Mat_yw = Eigen::Matrix; \ + \ + using Mat_ux = Eigen::Matrix; \ + using Mat_uy = Eigen::Matrix; \ + using Mat_uu = Eigen::Matrix; \ + using Mat_uv = Eigen::Matrix; \ + using Mat_uw = Eigen::Matrix; \ + \ + using Mat_vx = Eigen::Matrix; \ + using Mat_vy = Eigen::Matrix; \ + using Mat_vu = Eigen::Matrix; \ + using Mat_vv = Eigen::Matrix; \ + using Mat_vw = Eigen::Matrix; \ + \ + using Mat_wx = Eigen::Matrix; \ + using Mat_wy = Eigen::Matrix; \ + using Mat_wu = Eigen::Matrix; \ + using Mat_wv = Eigen::Matrix; \ + using Mat_ww = Eigen::Matrix; \ + \ + using State_dot = std::function; + +} // namespace Models diff --git a/vortex-filtering/include/vortex_filtering/models/movement_models.hpp b/vortex-filtering/include/vortex_filtering/models/movement_models.hpp new file mode 100644 index 00000000..743d208a --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/models/movement_models.hpp @@ -0,0 +1,160 @@ +#pragma once +#include + +namespace vortex { +namespace models { + +/** @brief Simple dynamic model with constant velocity + * x = [x, y, x_dot, y_dot] + */ +class CVModel : public DynamicModelI<4> { +public: + using typename DynamicModelI<4>::Vec_x; + using typename DynamicModelI<4>::Mat_xx; + + /** + * @brief Constant Velocity Model in 2D + * x = [x, y, x_dot, y_dot] + * @param std_vel Standard deviation of velocity + */ + CVModel(double std_vel) : std_vel_(std_vel) {} + + Vec_x f_c(const Vec_x& x) const override + { + Vec_x x_dot; + x_dot << x(2), x(3), 0, 0; + return x_dot; + } + + Mat_xx A_c(const Vec_x& x) const override + { + (void)x; // unused + Mat_xx A; + A << 0, 0, 1, 0, + 0, 0, 0, 1, + 0, 0, 0, 0, + 0, 0, 0, 0; + return A; + } + + Mat_xx Q_c(const Vec_x& x) const override + { + (void)x; // unused + Mat_xx Q; + Q << 0, 0, 0, 0, + 0, 0, 0, 0, + 0, 0, std_vel_*std_vel_, 0, + 0, 0, 0, std_vel_*std_vel_; + return Q; + } +private: + double std_vel_; +}; + +class CTModel : public DynamicModelI<5> { +public: + using typename DynamicModelI<5>::Vec_x; + using typename DynamicModelI<5>::Mat_xx; + + /** + * @brief Coordinated Turn Model in 2D + * @param std_acc Standard deviation of velocity + * x = [x, y, x_dot, y_dot, omega] + */ + CTModel(double std_acc, double std_turn) : std_acc_(std_acc), std_turn_(std_turn) {} + + Vec_x f_c(const Vec_x& x) const override + { + // x_ddot = -v*omega + // y_ddot = v*omega + Vec_x x_dot; + x_dot << x(2), x(3), -x(3)*x(4), x(2)*x(4), 0; + return x_dot; + } + + Mat_xx A_c(const Vec_x& x) const override + { + Mat_xx A; + // clang-format off + A << 0, 0, 1 , 0 , 0, + 0, 0, 0 , 1 , 0, + 0, 0, 0 ,-x(4), 0, + 0, 0, x(4), 0 , 0, + 0, 0, 0 , 0 , 0; + // clang-format on + return A; + } + + Mat_xx Q_c(const Vec_x& x) const override + { + (void)x; // unused + Eigen::Vector3d D; + D << std_acc_*std_acc_, std_acc_*std_acc_, std_turn_*std_turn_; + Eigen::Matrix G; + // clang-format off + G << 0, 0, 0, + 0, 0, 0, + 1, 0, 0, + 0, 1, 0, + 0, 0, 1; + // clang-format on + Mat_xx Q = G*D.asDiagonal()*G.transpose(); + return Q; + } + +private: + double std_acc_; + double std_turn_; +}; + + +class CAModel : public DynamicModelI<6> { +public: + using typename DynamicModelI<6>::Vec_x; + using typename DynamicModelI<6>::Mat_xx; + + /** + * @brief Constant Acceleration Model in 2D + * @param std_vel Standard deviation of velocity + * @param std_acc Standard deviation of acceleration + */ + CAModel(double std_vel, double std_acc) : std_vel_(std_vel), std_acc_(std_acc) {} + + Vec_x f_c(const Vec_x& x) const override + { + Vec_x x_dot; + x_dot << x(2), x(3), x(4), x(5), 0, 0; + return x_dot; + } + + Mat_xx A_c(const Vec_x& x) const override + { + (void)x; // unused + Mat_xx A; + // clang-format off + A << 0, 0, 1, 0, 0, 0, + 0, 0, 0, 1, 0, 0, + 0, 0, 0, 0, 1, 0, + 0, 0, 0, 0, 0, 1, + 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0; + // clang-format on + return A; + } + + Mat_xx Q_c(const Vec_x& x) const override + { + assert(false); // Not implemented + (void)x; // unused + Mat_xx Q; + // clang-format off + Q << 0; + return Q; + } +private: + double std_vel_; + double std_acc_; +}; + +} // namespace models +} // namespace vortex \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/models/sensor_model.hpp b/vortex-filtering/include/vortex_filtering/models/sensor_model.hpp new file mode 100644 index 00000000..dc50e1af --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/models/sensor_model.hpp @@ -0,0 +1,84 @@ +/** + * @file sensor_model.hpp + * @author Eirik Kolås + * @brief Sensor model interface. Based on "Fundamentals of Sensor Fusion" by Edmund Brekke + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include +#include + +namespace vortex { +namespace models { + + +template +/** + * @brief Interface for sensor models. + * + */ +class SensorModelI { +public: + static constexpr int N_DIM_x = n_dim_x; // Declare so that children of this class can reference it + static constexpr int N_DIM_z = n_dim_z; // Declare so that children of this class can reference it + using Vec_z = Eigen::Vector; + using Vec_x = Eigen::Vector; + using Mat_xx = Eigen::Matrix; + using Mat_zx = Eigen::Matrix; + using Mat_xz = Eigen::Matrix; + using Mat_zz = Eigen::Matrix; + using Gauss_x = prob::MultiVarGauss; + using Gauss_z = prob::MultiVarGauss; + + virtual ~SensorModelI() = default; + /** + * @brief Sensor Model + * @param x State + * @return Vec_z + */ + virtual Vec_z h(const Vec_x& x) const = 0; + /** + * @brief Jacobian of sensor model with respect to state + * @param x State + * @return Mat_zx + */ + virtual Mat_zx H(const Vec_x& x) const = 0; + /** + * @brief Noise covariance matrix + * @param x State + * @return Mat_zz + */ + virtual Mat_zz R(const Vec_x& x) const = 0; + + /** + * @brief Get the predicted measurement distribution given a state estimate. Updates the covariance + * + * @param x_est Vec_x estimate + * @return prob::MultiVarGauss + */ + virtual Gauss_z pred_from_est(const Gauss_x& x_est) const + { + Mat_xx P = x_est.cov(); + Mat_zx H = this->H(x_est.mean()); + Mat_zz R = this->R(x_est.mean()); + + return {this->h(x_est.mean()), H * P * H.transpose() + R}; + } + + /** + * @brief Get the predicted measurement distribution given a state. Does not update the covariance + * @param x Vec_x + * @return prob::MultiVarGauss + */ + virtual Gauss_z pred_from_state(const Vec_x& x) const + { + return {this->h(x), this->R(x)}; + } +}; + +} // namespace models +} // namespace vortex \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/nodes/kf_node.hpp b/vortex-filtering/include/vortex_filtering/nodes/kf_node.hpp new file mode 100644 index 00000000..5f57349a --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/nodes/kf_node.hpp @@ -0,0 +1,68 @@ +#pragma once +#include +#include +#include +using std::placeholders::_1; + +#include +#include + +#include +#include +#include +// #include +namespace Nodes { +using namespace Models; +using Period = Timestep; + +template class KF_node : public rclcpp::Node { +public: + static constexpr int _n_x = Model::_n_x, _n_y = Model::_n_y, _n_u = Model::_n_u, _n_v = Model::_n_v, _n_w = Model::_n_w; + DEFINE_MODEL_TYPES(_n_x, _n_y, _n_u, _n_v, _n_w) + KF_node(std::shared_ptr> filter, Period P = 0.1s) : Node("KF_node"), _filter{filter}, _P{P} + { + _timer = this->create_wall_timer(P, std::bind(&KF_node::timer_callback, this)); + _last_timestamp = this->now(); + _has_new_measurement = false; + + subscription_ = + this->create_subscription("measurement", 10, std::bind(&KF_node::meas_callback, this, _1)); + } + +private: + rclcpp::TimerBase::SharedPtr _timer; + std::shared_ptr> _filter; + const Period _P; + rclcpp::Time _last_timestamp; + Measurement _last_measurement; + bool _has_new_measurement; + rclcpp::Subscription::SharedPtr subscription_; + + void timer_callback() + { + // Get time since last call + rclcpp::Time now = this->now(); + Time Ts = (now - _last_timestamp).seconds() * 1s; + _last_timestamp = now; + // Reset filter if time goes backwards (e.g. when playing a rosbag on loop) + if (Ts < (Time)0) { + _filter->reset(); + RCLCPP_INFO_STREAM(this->get_logger(), "Reset filter due to negative time step"); + return; + } + // Calculate next iterate + State x_next = _filter->iterate(Ts, _last_measurement); + _has_new_measurement = false; + // Publish + RCLCPP_INFO_STREAM(this->get_logger(), '\n' << x_next); + } + + void meas_callback(const geometry_msgs::msg::PoseStamped::SharedPtr msg) + { + RCLCPP_INFO_STREAM(this->get_logger(), "Measurement: " << msg->pose.position.x << ", " << msg->pose.position.y << ", " << msg->pose.position.z); + _last_measurement << msg->pose.position.x, msg->pose.position.y, msg->pose.position.z; + _has_new_measurement = true; + } +}; + +} // namespace Nodes \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/probability/README.md b/vortex-filtering/include/vortex_filtering/probability/README.md new file mode 100644 index 00000000..d3d0d39e --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/probability/README.md @@ -0,0 +1,20 @@ +# Probability +This folder contains the probability distributions used. + +All classes and functions are under the namespace `vortex::prob`. + +## MultiVarGauss +This class represents a multivariate Gaussian distribution. It is a template class with parameter `N_DIM`. This is the dimension of the distribution. + +### Usage +The class contains methods for getting the mean and covariance, sampling from the distribution, calculating the probability density function and the log probability density function. It works with both static and dynamic dimensions. + +To create an instance you need to provide a mean vector and a covariance matrix. The covariance matrix must be symmetric and [positive definite](https://en.wikipedia.org/wiki/Definite_matrix). The mean vector must have the same dimension as the covariance matrix and the MultiVarGauss object. + +## GuassianMixture +This class represents a Gaussian mixture distribution. It is a template class with parameter `N_DIM`. This is the dimension of the distribution. + +### Usage +The class contains methods for sampling from the distribution, calculating the probability density function and the log probability density function. But most importantly the mean and covariance of the distribution can be retrieved. It works with both static and dynamic dimensions. + +To create an instance you need to provide a vector of weights and a vector of MultiVarGauss objects. The weights must sum to 1.0 and the MultiVarGauss objects must have the same dimension as the GaussianMixture object. \ No newline at end of file diff --git a/vortex-filtering/include/vortex_filtering/probability/binomial.hpp b/vortex-filtering/include/vortex_filtering/probability/binomial.hpp new file mode 100644 index 00000000..bcec3887 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/probability/binomial.hpp @@ -0,0 +1,67 @@ +/** + * @file binomial.hpp + * @author Eirik Kolås + * @brief + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include + +namespace vortex { +namespace prob { + +class Binomial { +public: + Binomial(int n, double p) : n_(n), p_(p) {} + + /** Calculate the probability of x given the Binomial distribution + * @param x + * @return double + */ + double pr(int x) const { + return std::pow(p_, x) * std::pow(1 - p_, n_ - x) * factorial(n_) / (factorial(x) * factorial(n_ - x)); + } + + /** Calculate the mean of the Binomial distribution + * @return double mean + */ + double mean() const { return n_ * p_; } + + /** Calculate the variance of the Binomial distribution + * @return double variance + */ + double cov() const { return n_ * p_ * (1 - p_); } + + /** Parameter n of the Binomial distribution + * @return int n + */ + int n() const { return n_; } + + /** Parameter p of the Binomial distribution + * @return double p + */ + double p() const { return p_; } + +private: + int n_; + double p_; + + /** Calculate the factorial of x + * @param x + * @return double factorial + */ + double factorial(int x) const { + double factorial = 1; + for (int i = 1; i <= x; i++) { + factorial *= i; + } + return factorial; + } +}; + +} // namespace vortex +} // namespace probability diff --git a/vortex-filtering/include/vortex_filtering/probability/chi_squared.hpp b/vortex-filtering/include/vortex_filtering/probability/chi_squared.hpp new file mode 100644 index 00000000..50fbd27d --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/probability/chi_squared.hpp @@ -0,0 +1,39 @@ +#pragma once +#include + +namespace vortex { +namespace prob { + + class ChiSquared { + public: + ChiSquared(int n) : n_(n) {} + + /** Calculate the probability density of x given the Chi-Squared distribution + * @param x + * @return double + */ + double pdf(double x) const { + return std::pow(x, n_ / 2 - 1) * std::exp(-x / 2) / (std::pow(2, n_ / 2) * std::tgamma(n_ / 2)); + } + + /** Calculate the mean of the Chi-Squared distribution + * @return double mean + */ + double mean() const { return n_; } + + /** Calculate the variance of the Chi-Squared distribution + * @return double variance + */ + double cov() const { return 2 * n_; } + + /** Parameter n of the Chi-Squared distribution + * @return int n + */ + int n() const { return n_; } + + private: + int n_; + }; + +} // namespace vortex +} // namespace probability diff --git a/vortex-filtering/include/vortex_filtering/probability/gaussian_mixture.hpp b/vortex-filtering/include/vortex_filtering/probability/gaussian_mixture.hpp new file mode 100644 index 00000000..7d82b448 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/probability/gaussian_mixture.hpp @@ -0,0 +1,108 @@ +/** + * @file multi_var_gauss.hpp + * @author Eirik Kolås + * @brief A class for representing a multivariate Gaussian mixture distribution. + * Based on "Fundamentals of SensorFusion" by Edmund Brekke + * @version 0.1 + * @date 2023-10-25 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include +#include +#include + +namespace vortex { +namespace prob { + +/** + * A class for representing a multivariate Gaussian mixture distribution + * @tparam N_DIM_x dimentions of the Gaussian + */ +template +class GaussianMixture { +public: + using Vec = Eigen::Vector; + using Mat = Eigen::Matrix; + + GaussianMixture(std::vector weights, std::vector> gaussians) + : weights_(std::move(weights)), gaussians_(std::move(gaussians)) + { + assert(weights_.size() == gaussians_.size()); + } + + /** Calculate the probability density function of x given the Gaussian mixture + * @param x + * @return double + */ + double pdf(const Vec& x) const { + double pdf = 0; + for (int i = 0; i < gaussians_.size(); i++) { + pdf += weights_[i] * gaussians_[i].pdf(x); + } + return pdf; + } + + /** Find the mean of the Gaussian mixture + * @return Vector + */ + Vec mean() const { + Vec mean = Vec::Zero(); + for (int i = 0; i < gaussians_.size(); i++) { + mean += weights_[i] * gaussians_[i].mean(); + } + return mean; + } + + /** Find the covariance of the Gaussian mixture + * @return Matrix + */ + Mat cov() const { + // Spread of innovations + Mat P_bar = Mat::Zero(); + for (int i = 0; i < gaussians_.size(); i++) { + P_bar += weights_[i] * gaussians_[i].mean() * gaussians_[i].mean().transpose(); + } + P_bar -= mean() * mean().transpose(); + + // Spread of Gaussians + Mat P = Mat::Zero(); + for (int i = 0; i < gaussians_.size(); i++) { + P += weights_[i] * gaussians_[i].cov(); + } + return P + P_bar; + } + + /** Reduce the Gaussian mixture to a single Gaussian + * @return MultiVarGauss + */ + MultiVarGauss reduce() const { + return MultivarGauss(mean(), cov()); + } + + /** dimentions of the Gaussian mixture + * @return int + */ + int n_dims() const { return (N_DIM_x); } + + /** Get the weights of the Gaussian mixture + * @return std::vector + */ + std::vector weights() const { return weights_; } + + /** Get the Gaussians of the Gaussian mixture + * @return std::vector> + */ + std::vector> gaussians() const { return gaussians_; } + +private: + const std::vector weights_; + const std::vector> gaussians_; + + +}; // class GaussianMixture + +} // namespace probability +} // namespace vortex diff --git a/vortex-filtering/include/vortex_filtering/probability/multi_var_gauss.hpp b/vortex-filtering/include/vortex_filtering/probability/multi_var_gauss.hpp new file mode 100644 index 00000000..135576c2 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/probability/multi_var_gauss.hpp @@ -0,0 +1,79 @@ +#pragma once +#include + +namespace vortex { +namespace prob { + +/** + * A class for representing a multivariate Gaussian distribution + * @tparam N_DIMS dimentions of the Gaussian + */ +template +class MultiVarGauss { +public: + using Vector = Eigen::Vector; + using Matrix = Eigen::Matrix; + + MultiVarGauss(const Vector& mean, const Matrix& cov) + : mean_(mean), cov_(cov), actual_n_dims_(cov_.rows()), cov_inv_(cov_.llt().solve(Matrix::Identity(n_dims(), n_dims()))) + { + // Check that the covariance matrix is positive definite and symmetric + if (!cov_.isApprox(cov_.transpose(), 1e-6)) { + throw std::invalid_argument("Covariance matrix is not symmetric"); + } + if (cov_.llt().info() != Eigen::Success) { + throw std::invalid_argument("Covariance matrix is not positive definite"); + } + } + + /** Calculate the probability density function of x given the Gaussian + * @param x + * @return double + */ + double pdf(const Vector& x) const { + const auto diff = x - mean_; + const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; + return std::exp(exponent) / std::sqrt(std::pow(2 * M_PI, n_dims()) * cov_.determinant()); + } + + /** Calculate the log likelihood of x given the Gaussian. + * Assumes that the covariance matrix is positive definite and symmetric + * @param x + * @return double + */ + double logpdf(const Vector& x) const { + const auto diff = x - mean_; + const auto exponent = -0.5 * diff.transpose() * cov_inv_ * diff; + return exponent - 0.5 * std::log(std::pow(2 * M_PI, n_dims()) * cov_.determinant()); + } + + + Vector mean() const { return mean_; } + Matrix cov() const { return cov_; } + Matrix cov_inv() const { return cov_inv_; } + + /** Calculate the Mahalanobis distance of x given the Gaussian + * @param x + * @return double + */ + double mahalanobis_distance(const Vector& x) const { + const auto diff = x - mean_; + return std::sqrt(diff.transpose() * cov_inv_ * diff); + } + + + /** dimentions of the Gaussian + * @return int + */ + int n_dims() const { return actual_n_dims_; } + + private: + Vector mean_; + Matrix cov_; + size_t actual_n_dims_; + Matrix cov_inv_; + +}; + +} // namespace probability +} // namespace vortex diff --git a/vortex-filtering/include/vortex_filtering/probability/poisson.hpp b/vortex-filtering/include/vortex_filtering/probability/poisson.hpp new file mode 100644 index 00000000..5d2a56c5 --- /dev/null +++ b/vortex-filtering/include/vortex_filtering/probability/poisson.hpp @@ -0,0 +1,62 @@ +/** + * @file poisson.hpp + * @author Eirik Kolås + * @brief A class for representing a Poisson distribution. Used for modeling clutter + * @version 0.1 + * @date 2023-10-26 + * + * @copyright Copyright (c) 2023 + * + */ +#pragma once +#include + +namespace vortex { +namespace prob { + +class Poisson { +public: + Poisson(double lambda) : lambda_(lambda) {} + + /** Calculate the probability of x given the Poisson distribution + * @param x + * @return double + */ + double pr(int x) const { + return std::pow(lambda_, x) * std::exp(-lambda_) / factorial(x); + } + + /** Calculate the mean of the Poisson distribution + * @return double mean + */ + double mean() const { return lambda_; } + + /** Calculate the variance of the Poisson distribution + * @return double variance + */ + double cov() const { return lambda_; } + + /** Parameter lambda of the Poisson distribution + * @return double lambda + */ + double lambda() const { return lambda_; } + + +private: + const double lambda_; + + /** Calculate the factorial of x + * @param x + * @return double factorial + */ + double factorial(int x) const { + double factorial = 1; + for (int i = 1; i <= x; i++) { + factorial *= i; + } + return factorial; + } +}; + +} // namespace probability +} // namespace vortex diff --git a/vortex-filtering/launch/vkf_node.launch.yaml b/vortex-filtering/launch/vkf_node.launch.yaml new file mode 100644 index 00000000..29be9186 --- /dev/null +++ b/vortex-filtering/launch/vkf_node.launch.yaml @@ -0,0 +1,7 @@ +launch: + +- node: + pkg: vortex-vkf + exec: vortex-vkf_node + name: vkf_node + diff --git a/vortex-filtering/package.xml b/vortex-filtering/package.xml new file mode 100644 index 00000000..63a7be90 --- /dev/null +++ b/vortex-filtering/package.xml @@ -0,0 +1,25 @@ + + + + vortex_filtering + 0.0.0 + Kalman filter primariliy for pose estimation + Eirik Kolås + MIT + + ament_cmake + + rclcpp + std_msgs + geometry_msgs + eigen + + ament_lint_auto + ament_lint_common + ament_cmake_gtest + gnuplot + gnuplot-iostream + + ament_cmake + + diff --git a/vortex-filtering/src/nodes/kf_node.cpp b/vortex-filtering/src/nodes/kf_node.cpp new file mode 100644 index 00000000..1535d273 --- /dev/null +++ b/vortex-filtering/src/nodes/kf_node.cpp @@ -0,0 +1,4 @@ +int main(int argc, char **argv) +{ + +} \ No newline at end of file diff --git a/vortex-filtering/test/dynamic_model_test.cpp b/vortex-filtering/test/dynamic_model_test.cpp new file mode 100644 index 00000000..38e65965 --- /dev/null +++ b/vortex-filtering/test/dynamic_model_test.cpp @@ -0,0 +1,60 @@ +#include +#include +#include +#include "test_models.hpp" + +namespace simple_dynamic_model_test { + +using Vec_x = typename SimpleDynamicModel::Vec_x; +using Mat_xx = typename SimpleDynamicModel::Mat_xx; + +TEST(DynamicModel, initSimpleModel) +{ + SimpleDynamicModel model; +} + +TEST(DynamicModel, iterateSimpleModel) +{ + SimpleDynamicModel model; + double dt = 1.0; + Vec_x x = Vec_x::Zero(); + + for (size_t i = 0; i < 10; i++) + { + EXPECT_EQ(model.f_d(x, dt), std::exp(-dt) * x); + x = model.f_d(x, dt); + } + +} + +} // namespace simple_model_test + +namespace cv_model_test { + +using Vec_x = typename vortex::models::CVModel::Vec_x; +using Mat_xx = typename vortex::models::CVModel::Mat_xx; + +TEST(DynamicModel, initCVModel) +{ + vortex::models::CVModel model(1.0); +} + +TEST(DynamicModel, iterateCVModel) +{ + vortex::models::CVModel model(1.0); + double dt = 1.0; + Vec_x x; + x << 0, 0, 1, 1; + + for (size_t i = 0; i < 10; i++) + { + Vec_x x_true; + x_true << x(0) + dt, x(1) + dt, 1, 1; + EXPECT_EQ(model.f_d(x, dt), x_true); + x = model.f_d(x, dt); + } + +} + +} // namespace cv_model_test + diff --git a/vortex-filtering/test/ekf_test.cpp b/vortex-filtering/test/ekf_test.cpp new file mode 100644 index 00000000..3e23c2fa --- /dev/null +++ b/vortex-filtering/test/ekf_test.cpp @@ -0,0 +1,144 @@ +#include +#include + +#include +#include +#include +#include "test_models.hpp" +#include +#include + +class EKFTestCVModel : public ::testing::Test { +protected: + using PosMeasModel = FirstStatesMeasuredModel<4>; + using CVModel = vortex::models::CVModel; + using Vec_x = typename CVModel::Vec_x; + using Mat_xx = typename CVModel::Mat_xx; + using Gauss_x = typename CVModel::Gauss_x; + using Gauss_z = typename PosMeasModel::Gauss_z; + using Vec_z = typename PosMeasModel::Vec_z; + + void SetUp() override { + // Create dynamic model + dynamic_model_ = std::make_shared(1.0); + // Create sensor model + sensor_model_ = std::make_shared(2, 1.0); + // Create EKF + ekf_ = std::make_shared>(*dynamic_model_, *sensor_model_); + } + + std::shared_ptr dynamic_model_; + std::shared_ptr sensor_model_; + std::shared_ptr> ekf_; +}; + +TEST_F(EKFTestCVModel, Predict) { + // Initial state + Gauss_x x({0, 0, 1, 0}, Mat_xx::Identity()); + double dt = 0.1; + // Predict + auto pred = ekf_->predict(x, dt); + Gauss_x x_est_pred = pred.first; + Gauss_z z_est_pred = pred.second; + + Vec_x x_true = x.mean() + Vec_x({dt, 0, 0, 0}); + Vec_z z_true = x_true.head(2); + ASSERT_EQ(x_est_pred.mean(), x_true); + ASSERT_EQ(z_est_pred.mean(), z_true); +} + + +TEST_F(EKFTestCVModel, Convergence) +{ + // Random number generator + std::random_device rd; + std::mt19937 gen(rd()); + std::normal_distribution<> d_disturbance{0, 1e-3}; + std::normal_distribution<> d_noise{0, 1e-2}; + + // Initial state + Gauss_x x0({0, 0, 0.5, 0}, Mat_xx::Identity()); + double dt = 0.1; + + std::vector time; + std::vector x_true; + std::vector x_est; + std::vector z_meas; + std::vector z_est; + + + // Simulate + time.push_back(0); + x_true.push_back(x0.mean()); + x_est.push_back(x0); + for (int i = 0; i < 100; i++) + { + // Simulate + Vec_x v; + v << d_disturbance(gen), d_disturbance(gen), d_disturbance(gen), d_disturbance(gen); + Vec_z w = Vec_z::Zero(2); + w << d_noise(gen), d_noise(gen); + Vec_x x_true_i = dynamic_model_->f_d(x_true.back(), dt) + v; + Vec_z z_meas_i = sensor_model_->h(x_true_i) + w; + x_true.push_back(x_true_i); + z_meas.push_back(z_meas_i); + + // Predict and update + auto step = ekf_->step(x_est.back(), z_meas_i, dt); + Gauss_x x_est_upd = std::get<0>(step); + Gauss_z z_est_pred = std::get<2>(step); + + // Save results + time.push_back(time.back() + dt); + x_est.push_back(x_est_upd); + z_est.push_back(z_est_pred); + } + + + // Plot the results + std::vector x_true_x, x_true_y, x_true_u, x_true_v, x_est_x, x_est_y, x_est_u, x_est_v, z_meas_x, z_meas_y; + for (size_t i = 0; i < x_true.size()-1; i++) + { + x_true_x.push_back(x_true.at(i)(0)); + x_true_y.push_back(x_true.at(i)(1)); + x_true_u.push_back(x_true.at(i)(2)); + x_true_v.push_back(x_true.at(i)(3)); + x_est_x.push_back(x_est.at(i).mean()(0)); + x_est_y.push_back(x_est.at(i).mean()(1)); + x_est_u.push_back(x_est.at(i).mean()(2)); + x_est_v.push_back(x_est.at(i).mean()(3)); + z_meas_x.push_back(z_meas.at(i)(0)); + z_meas_y.push_back(z_meas.at(i)(1)); + } + time.pop_back(); + + Gnuplot gp; + gp << "set terminal qt size 1600,1000\n"; // Modified to make plot larger + gp << "set multiplot layout 2,1\n"; + gp << "set title 'Position'\n"; + gp << "set xlabel 'x [m]'\n"; + gp << "set ylabel 'y [m]'\n"; + gp << "plot '-' with lines title 'True', '-' with lines title 'Estimate', '-' with points title 'Measurements' ps 2\n"; // Modified to make dots larger + gp.send1d(boost::make_tuple(x_true_x, x_true_y)); + gp.send1d(boost::make_tuple(x_est_x, x_est_y)); + gp.send1d(boost::make_tuple(z_meas_x, z_meas_y)); + gp << "set title 'Velocity'\n"; + gp << "set xlabel 't [s]'\n"; + gp << "set ylabel 'u,v [m/s]'\n"; + gp << "plot '-' with lines title 'True v', " + << "'-' with lines title 'Estimate v', " + << "'-' with lines title 'True u', " + << "'-' with lines title 'Estimate u'\n"; + gp.send1d(boost::make_tuple(time, x_true_v)); + gp.send1d(boost::make_tuple(time, x_est_v)); + gp.send1d(boost::make_tuple(time, x_true_u)); + gp.send1d(boost::make_tuple(time, x_est_u)); + gp << "unset multiplot\n"; + + // Test that the state converges to the true state + ASSERT_NEAR(x_est.back().mean()(0), x_true.back()(0), 1e-1); + ASSERT_NEAR(x_est.back().mean()(1), x_true.back()(1), 1e-1); + ASSERT_NEAR(x_est.back().mean()(2), x_true.back()(2), 1e-1); + ASSERT_NEAR(x_est.back().mean()(3), x_true.back()(3), 1e-1); + +} \ No newline at end of file diff --git a/vortex-filtering/test/erk_test.cpp b/vortex-filtering/test/erk_test.cpp new file mode 100644 index 00000000..af90ac4e --- /dev/null +++ b/vortex-filtering/test/erk_test.cpp @@ -0,0 +1,231 @@ +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace Models; +using namespace Integrator; + +namespace sin_func_test { +constexpr int n_x = 1, n_y = 1, n_u = 1; +DEFINE_MODEL_TYPES(n_x, n_y, n_u, n_x, n_y) + +// Make functions to test the RK methods +State sin_func(Time t, const State &x) +{ + State x_dot; + x_dot << std::pow(std::sin(t / 1s), 2) * x(0); + return x_dot; +} +double sin_func_exact(double x_0, Time t) +{ + double t_s = t / 1s; + return x_0 * exp(0.5 * (t_s - sin(t_s) * cos(t_s))); +} + +class ERKTest : public ::testing::Test { +protected: + ERKTest() + { + dt = 1ms; + init(0s, State::Zero()); + u.setZero(); + v.setZero(); + } + Timestep dt; + + Input u; + Disturbance v; + + std::vector