From 5e735e10f7c2b731b831c5f1ffec7631f0fc90e6 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 16 Sep 2021 13:03:11 -0400 Subject: [PATCH 01/36] minor improvements to CombinedImuFactor --- examples/CombinedImuFactorsExample.cpp | 15 ++++++++------- gtsam/navigation/CombinedImuFactor.cpp | 5 +++++ 2 files changed, 13 insertions(+), 7 deletions(-) diff --git a/examples/CombinedImuFactorsExample.cpp b/examples/CombinedImuFactorsExample.cpp index 9211a4d5f0..49cdb68354 100644 --- a/examples/CombinedImuFactorsExample.cpp +++ b/examples/CombinedImuFactorsExample.cpp @@ -60,13 +60,14 @@ namespace po = boost::program_options; po::variables_map parseOptions(int argc, char* argv[]) { po::options_description desc; - desc.add_options()("help,h", "produce help message")( - "data_csv_path", po::value()->default_value("imuAndGPSdata.csv"), - "path to the CSV file with the IMU data")( - "output_filename", - po::value()->default_value("imuFactorExampleResults.csv"), - "path to the result file to use")("use_isam", po::bool_switch(), - "use ISAM as the optimizer"); + desc.add_options()("help,h", "produce help message") // help message + ("data_csv_path", po::value()->default_value("imuAndGPSdata.csv"), + "path to the CSV file with the IMU data") // path to the data file + ("output_filename", + po::value()->default_value("imuFactorExampleResults.csv"), + "path to the result file to use") // filename to save results to + ("use_isam", po::bool_switch(), + "use ISAM as the optimizer"); // flag for ISAM optimizer po::variables_map vm; po::store(po::parse_command_line(argc, argv, desc), vm); diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index ca1c5b93a6..12e8ccea89 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -93,6 +93,11 @@ void PreintegratedCombinedMeasurements::resetIntegration() { //------------------------------------------------------------------------------ void PreintegratedCombinedMeasurements::integrateMeasurement( const Vector3& measuredAcc, const Vector3& measuredOmega, double dt) { + if (dt <= 0) { + throw std::runtime_error( + "PreintegratedCombinedMeasurements::integrateMeasurement: dt <=0"); + } + // Update preintegrated measurements. Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx) Matrix93 B, C; From 9dbb431db9562c61cb442da0a89b6a6ab933222e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 16 Sep 2021 19:00:08 -0400 Subject: [PATCH 02/36] account for bias on position in jacobians of CombinedImuFactor --- gtsam/navigation/CombinedImuFactor.cpp | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 12e8ccea89..28d96d343f 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -99,7 +99,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( } // Update preintegrated measurements. - Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx) + Matrix9 A; // Jacobian wrt preintegrated measurements without bias (df/dx) Matrix93 B, C; PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C); @@ -110,8 +110,8 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // and preintegrated measurements // Single Jacobians to propagate covariance - // TODO(frank): should we not also account for bias on position? Matrix3 theta_H_biasOmega = -C.topRows<3>(); + Matrix3 pos_H_biasAcc = -B.middleRows<3>(3); Matrix3 vel_H_biasAcc = -B.bottomRows<3>(); // overall Jacobian wrt preintegrated measurements (df/dx) @@ -119,6 +119,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( F.setZero(); F.block<9, 9>(0, 0) = A; F.block<3, 3>(0, 12) = theta_H_biasOmega; + F.block<3, 3>(3, 9) = pos_H_biasAcc; F.block<3, 3>(6, 9) = vel_H_biasAcc; F.block<6, 6>(9, 9) = I_6x6; @@ -129,15 +130,19 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( const Matrix3& iCov = p().integrationCovariance; // first order uncertainty propagation - // Optimized matrix multiplication (1/dt) * G * measurementCovariance * + // Optimized matrix multiplication: (1/dt) * G * measurementCovariance * // G.transpose() Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); + Matrix3 aCov_updated = (aCov + p().biasAccOmegaInt.block<3, 3>(0, 0)); + // BLOCK DIAGONAL TERMS - D_t_t(&G_measCov_Gt) = dt * iCov; + D_t_t(&G_measCov_Gt) = ((1 / dt) * pos_H_biasAcc + * aCov_updated + * (pos_H_biasAcc.transpose())) + (dt * iCov); D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc - * (aCov + p().biasAccOmegaInt.block<3, 3>(0, 0)) + * aCov_updated * (vel_H_biasAcc.transpose()); D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega * (wCov + p().biasAccOmegaInt.block<3, 3>(3, 3)) @@ -150,6 +155,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( * theta_H_biasOmega.transpose(); D_v_R(&G_measCov_Gt) = temp; D_R_v(&G_measCov_Gt) = temp.transpose(); + preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt; } From 7e48962f99cfa3e1e716a05d59eeb667da34c732 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 17 Sep 2021 13:28:42 -0400 Subject: [PATCH 03/36] Add unit test for checking covariance of CombinedImuFactor --- gtsam/navigation/CombinedImuFactor.cpp | 5 ++- .../tests/testCombinedImuFactor.cpp | 42 +++++++++++++++++++ 2 files changed, 45 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 28d96d343f..216140dbc5 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -130,8 +130,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( const Matrix3& iCov = p().integrationCovariance; // first order uncertainty propagation - // Optimized matrix multiplication: (1/dt) * G * measurementCovariance * - // G.transpose() + // Optimized matrix mult: (1/dt) * G * measurementCovariance * G.transpose() Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); @@ -144,9 +143,11 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc * aCov_updated * (vel_H_biasAcc.transpose()); + D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega * (wCov + p().biasAccOmegaInt.block<3, 3>(3, 3)) * (theta_H_biasOmega.transpose()); + D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance; diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index 2bbc2cc7c7..dc9ae288ae 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -203,6 +203,48 @@ TEST(CombinedImuFactor, PredictRotation) { EXPECT(assert_equal(expectedPose, actual.pose(), tol)); } +/* ************************************************************************* */ +// Testing covariance to check if all the jacobians are accounted for. +TEST(CombinedImuFactor, CheckCovariance) { + auto params = PreintegrationCombinedParams::MakeSharedU(9.81); + + params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); + params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); + params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); + params->setOmegaCoriolis(Vector3::Zero()); + + imuBias::ConstantBias currentBias; + + PreintegratedCombinedMeasurements actual(params, currentBias); + + // Measurements + Vector3 measuredAcc(0.1577, -0.8251, 9.6111); + Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); + double deltaT = 0.01; + + actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + Eigen::Matrix expected; + expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; + + // regression + EXPECT(assert_equal(expected, actual.preintMeasCov())); +} + /* ************************************************************************* */ int main() { TestResult tr; From b0fcd17140cd3a9fb9abde60e4d52d18139a7145 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 17 Sep 2021 14:19:41 -0400 Subject: [PATCH 04/36] additional comments to make understanding the code easier --- gtsam/navigation/CombinedImuFactor.cpp | 2 +- gtsam/navigation/ImuFactor.cpp | 6 ++++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 216140dbc5..1e99db17c5 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -100,7 +100,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // Update preintegrated measurements. Matrix9 A; // Jacobian wrt preintegrated measurements without bias (df/dx) - Matrix93 B, C; + Matrix93 B, C; // Jacobian of state wrpt accel bias and omega bias respectively. PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C); // Update preintegrated measurements covariance: as in [2] we consider a first diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index 28c0461b1d..9b6affaaf8 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -59,7 +59,7 @@ void PreintegratedImuMeasurements::integrateMeasurement( // Update preintegrated measurements (also get Jacobian) Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx) - Matrix93 B, C; + Matrix93 B, C; // Jacobian of state wrpt accel bias and omega bias respectively. PreintegrationType::update(measuredAcc, measuredOmega, dt, &A, &B, &C); // first order covariance propagation: @@ -73,11 +73,13 @@ void PreintegratedImuMeasurements::integrateMeasurement( const Matrix3& iCov = p().integrationCovariance; // (1/dt) allows to pass from continuous time noise to discrete time noise + // Update the uncertainty on the state (matrix A in [4]). preintMeasCov_ = A * preintMeasCov_ * A.transpose(); + // These 2 updates account for uncertainty on the IMU measurement (matrix B in [4]). preintMeasCov_.noalias() += B * (aCov / dt) * B.transpose(); preintMeasCov_.noalias() += C * (wCov / dt) * C.transpose(); - // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3 + // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3 (9x3 matrix) preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov * dt; } From 5656308e9d4ed1af3d3623717b3c19709f51852b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 17 Sep 2021 14:20:10 -0400 Subject: [PATCH 05/36] no need to assign negative to jacobians as they cancel out later --- gtsam/navigation/CombinedImuFactor.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 1e99db17c5..24e2e3016e 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -110,9 +110,9 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // and preintegrated measurements // Single Jacobians to propagate covariance - Matrix3 theta_H_biasOmega = -C.topRows<3>(); - Matrix3 pos_H_biasAcc = -B.middleRows<3>(3); - Matrix3 vel_H_biasAcc = -B.bottomRows<3>(); + Matrix3 theta_H_biasOmega = C.topRows<3>(); + Matrix3 pos_H_biasAcc = B.middleRows<3>(3); + Matrix3 vel_H_biasAcc = B.bottomRows<3>(); // overall Jacobian wrt preintegrated measurements (df/dx) Eigen::Matrix F; From 810f97305fa53be6d24d1945b234c2cbde652fec Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 17 Sep 2021 14:21:39 -0400 Subject: [PATCH 06/36] add details about noise propagation for CombinedImuFactor in ImuFactor.pdf --- doc/ImuFactor.lyx | 155 +++++++++++++++++++++++++++++++++++++++------- doc/ImuFactor.pdf | Bin 198168 -> 225325 bytes 2 files changed, 133 insertions(+), 22 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index 0922a3e9c7..bba8f212a7 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -1,7 +1,9 @@ -#LyX 2.0 created this file. For more info see http://www.lyx.org/ -\lyxformat 413 +#LyX 2.3 created this file. For more info see http://www.lyx.org/ +\lyxformat 544 \begin_document \begin_header +\save_transient_properties true +\origin unavailable \textclass article \use_default_options true \maintain_unincluded_children false @@ -9,16 +11,18 @@ \language_package default \inputencoding auto \fontencoding global -\font_roman default -\font_sans default -\font_typewriter default +\font_roman "default" "default" +\font_sans "default" "default" +\font_typewriter "default" "default" +\font_math "auto" "auto" \font_default_family default \use_non_tex_fonts false \font_sc false \font_osf false -\font_sf_scale 100 -\font_tt_scale 100 - +\font_sf_scale 100 100 +\font_tt_scale 100 100 +\use_microtype false +\use_dash_ligatures true \graphics default \default_output_format default \output_sync 0 @@ -29,16 +33,26 @@ \use_hyperref false \papersize default \use_geometry true -\use_amsmath 1 -\use_esint 1 -\use_mhchem 1 -\use_mathdots 1 +\use_package amsmath 1 +\use_package amssymb 1 +\use_package cancel 1 +\use_package esint 1 +\use_package mathdots 1 +\use_package mathtools 1 +\use_package mhchem 1 +\use_package stackrel 1 +\use_package stmaryrd 1 +\use_package undertilde 1 \cite_engine basic +\cite_engine_type default +\biblio_style plain \use_bibtopic false \use_indices false \paperorientation portrait \suppress_date false +\justification true \use_refstyle 1 +\use_minted 0 \index Index \shortcut idx \color #008000 @@ -51,7 +65,10 @@ \tocdepth 3 \paragraph_separation indent \paragraph_indentation default -\quotes_language english +\is_math_indent 0 +\math_numbering_side default +\quotes_style english +\dynamic_quotes 0 \papercolumns 1 \papersides 1 \paperpagestyle default @@ -69,7 +86,7 @@ The new IMU Factor \end_layout \begin_layout Author -Frank Dellaert +Frank Dellaert & Varun Agrawal \end_layout \begin_layout Standard @@ -244,7 +261,7 @@ X(t)=\left\{ R_{0},P_{0}+V_{0}t,V_{0}\right\} then the differential equation describing the trajectory is \begin_inset Formula \[ -\dot{X}(t)=\left[0_{3x3},V_{0},0_{3x1}\right],\,\,\,\,\, X(0)=\left\{ R_{0},P_{0},V_{0}\right\} +\dot{X}(t)=\left[0_{3x3},V_{0},0_{3x1}\right],\,\,\,\,\,X(0)=\left\{ R_{0},P_{0},V_{0}\right\} \] \end_inset @@ -592,6 +609,7 @@ Lie Group Methods \begin_inset CommandInset citation LatexCommand cite key "Iserles00an" +literal "true" \end_inset @@ -602,7 +620,7 @@ key "Iserles00an" , \begin_inset Formula \begin{equation} -\dot{R}(t)=F(R,t),\,\,\,\, R(0)=R_{0}\label{eq:diffSo3} +\dot{R}(t)=F(R,t),\,\,\,\,R(0)=R_{0}\label{eq:diffSo3} \end{equation} \end_inset @@ -947,8 +965,8 @@ Or, as another way to state this, if we solve the differential equations \begin_inset Formula \begin{eqnarray*} \dot{\theta}(t) & = & H(\theta)^{-1}\,\omega^{b}(t)\\ -\dot{p}(t) & = & R_{0}^{T}\, V_{0}+v(t)\\ -\dot{v}(t) & = & R_{0}^{T}\, g+R_{b}^{0}(t)a^{b}(t) +\dot{p}(t) & = & R_{0}^{T}\,V_{0}+v(t)\\ +\dot{v}(t) & = & R_{0}^{T}\,g+R_{b}^{0}(t)a^{b}(t) \end{eqnarray*} \end_inset @@ -1015,7 +1033,7 @@ v(t)=v_{g}(t)+v_{a}(t) evolving as \begin_inset Formula \begin{eqnarray*} -\dot{v}_{g}(t) & = & R_{i}^{T}\, g\\ +\dot{v}_{g}(t) & = & R_{i}^{T}\,g\\ \dot{v}_{a}(t) & = & R_{b}^{i}(t)a^{b}(t) \end{eqnarray*} @@ -1041,7 +1059,7 @@ p(t)=p_{i}(t)+p_{g}(t)+p_{v}(t) evolving as \begin_inset Formula \begin{eqnarray*} -\dot{p}_{i}(t) & = & R_{i}^{T}\, V_{i}\\ +\dot{p}_{i}(t) & = & R_{i}^{T}\,V_{i}\\ \dot{p}_{g}(t) & = & v_{g}(t)=R_{i}^{T}gt\\ \dot{p}_{v}(t) & = & v_{a}(t) \end{eqnarray*} @@ -1096,7 +1114,7 @@ Predict the NavState from \begin_inset Formula \[ -X_{j}=\mathcal{R}_{X_{i}}(\zeta(t_{ij}))=\left\{ \Phi_{R_{0}}\left(\theta(t_{ij})\right),P_{i}+V_{i}t_{ij}+\frac{gt_{ij}^{2}}{2}+R_{i}\, p_{v}(t_{ij}),V_{i}+gt_{ij}+R_{i}\, v_{a}(t_{ij})\right\} +X_{j}=\mathcal{R}_{X_{i}}(\zeta(t_{ij}))=\left\{ \Phi_{R_{0}}\left(\theta(t_{ij})\right),P_{i}+V_{i}t_{ij}+\frac{gt_{ij}^{2}}{2}+R_{i}\,p_{v}(t_{ij}),V_{i}+gt_{ij}+R_{i}\,v_{a}(t_{ij})\right\} \] \end_inset @@ -1372,7 +1390,7 @@ B_{k}=\left[\begin{array}{c} 0_{3\times3}\\ R_{k}\frac{\Delta_{t}}{2}^{2}\\ R_{k}\Delta_{t} -\end{array}\right],\,\,\,\, C_{k}=\left[\begin{array}{c} +\end{array}\right],\,\,\,\,C_{k}=\left[\begin{array}{c} H(\theta_{k})^{-1}\Delta_{t}\\ 0_{3\times3}\\ 0_{3\times3} @@ -1382,6 +1400,99 @@ H(\theta_{k})^{-1}\Delta_{t}\\ \end_inset +\end_layout + +\begin_layout Subsubsection* +Combined IMU Factor +\end_layout + +\begin_layout Standard +We can similarly account for bias drift over time, as is commonly seen in + commercial grade IMUs. + This is accomplished via the +\emph on +CombinedImuFactor +\emph default + which is a 6-way factor between the previous +\emph on +pose/velocity/bias +\emph default + and the +\emph on +pose/velocity/bias +\emph default + at the next timestep. + +\end_layout + +\begin_layout Standard +We expand the state vector as +\begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k},a_{k}^{b}, \omega_{k}^{b}]$ +\end_inset + +. + For the jacobian +\begin_inset Formula $F_{k}$ +\end_inset + + of +\begin_inset Formula $f$ +\end_inset + + wrpt this new +\begin_inset Formula $\zeta$ +\end_inset + +, we get a +\begin_inset Formula $15\times15$ +\end_inset + + matrix. + The top-left +\begin_inset Formula $9\times9$ +\end_inset + + is the same as +\begin_inset Formula $A_{k}$ +\end_inset + +, thus we only have the jacobians wrpt the biases left to account for. +\end_layout + +\begin_layout Standard +Conveniently, the jacobians of the pose and velocity wrpt the biases are + already computed in the +\emph on +ImuFactor +\emph default +derivation as matrices +\begin_inset Formula $B_{k}$ +\end_inset + + and +\begin_inset Formula $C_{k}$ +\end_inset + +, while they are identity matrices wrpt the biases themselves. + Thus, we can easily plug-in the values from the previous section to give + us the final result +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +F_{k}=\left[\begin{array}{ccccc} +I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & & & & H(\theta_{k})^{-1}\Delta_{t}\\ +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t} & R_{k}\frac{\Delta_{t}}{2}^{2}\\ +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & & I_{3\times3} & R_{k}\Delta_{t}\\ + & & & I_{3\times3}\\ + & & & & I_{3\times3} +\end{array}\right] +\] + +\end_inset + + \end_layout \begin_layout Standard diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index 0b13c1f5948de38aa6454732ca20367cc630c62c..37badae9cc979302341b1dbac23e03b5be7445d9 100644 GIT binary patch delta 155716 zcmZs?Q*b71(6t-ewv8t?C$>59#J2Iowr$(CZQIVo6DRxq{#}3VgKu};Ro%z;(Y1Q5 zPLD>Y*++~ggJ5N0CP`{opaC+*&d5NppakDOV)!OP$jP~X$4&C)?@yeI^NYp6&CUXh zObqshuS>e%EBh+5*!5p_Ri0m#AP+X0sg!A*uE3M^5v@6XlBs8R z!iV=Nv)%48!H2~pVf+Y2xp+&C9buu=BaMGMPov^lC9%M#H1cSSgN`zAHP*`Tp0azD zw$VYn#MtTlFTS!Z_AgMV1#tv8Q#%u97bjCA+y9yD|5(AXu#hm5{LjG8562{DYG>|Z zLBht$!bb96CABP20B`WE?YG4|sJiKOAToI$L*p6-(pUm8M2GITLi zy19p~@o#a^17F{J`YeB8)o;TCH52I{27v?Rz^Aq!l(5W`VYr)n`nc~rdU94>{|pPm{DWx;!1n z!#J?s*Wqs~Lokk|5i839T7QJyAsgsugl{qmhRZ)~YG9GGb%WzBu8p-K!N*c*@cz9p zmN2A805es=UfGk(udJ5xuUY8AvbPJ*@e=XitFFhO&;YJ_9&3~VWExMj6=0xwiQ1DO18Ld_F`Dpcu*C}CKuyBV)a z-AAi>cDj(0!=*TeCw*QE0cL+U@f?cjAHAwbuc3>&!C4|q1#`ZlixbrpXhuE+Yh2`{G`Zm<@9Zc$J zf$p!PEKnb3x;S7PHd~xr-*6EKy=Z?cy>x7SJitR#GA(G2%Flq32?{+8*orpt+(V9c1c>f)Zw$fSoRmsI|;8;Domc4}(!l0+PhheE|RbRp^4? zHh>`MSKF&m6JK!pp+OfjC&`@g*bV45c$>CuKMX2DD=#)$&~(GCTgp%QW1G4_byE0^ zTMuNmE3_IWP3^YHM`0}>OHbtyH%aVrLB&rB4?zAqs)OZ%w!TQ%8GaHyI2{@q7>F$o zf8QyAY56iz3+K49&>XOHwN?1g88nEL2eDS*VUkC{&&l1!O~N3Ti$jalKm_*&zj+5#RE1iwb*^dBx`fgU2*y^T#3#uOM!sQS6L`{c zfNU)C|4v1$CsB+Iz=fbA4T3{^w&VDfX^3+9mN??Uf%LWxqf)Q~Q@4Ew40>c! z7g-Fb@pW`YubzBAPjWz$vkz# z*t_kiCt#ZyPx1izgSqnqGnI;VWR+g}IEU(hp1Qt497feJU=!=k?=hhWv-`{`(N zs)Xt858`EFIy^G9_7!FRku;=lZ)(|^5{R3WA08{gbiUZ0taKo=%nP{}UvZv;<|qaz*aLO6N=1C?>QTi}NUv2?wU zLbQ}_0^!G8M3KLRJU)q>ZuM}}mDxEdi6)gD01Qu@wM((eqD~#HVl@BaU!ZfFW4nLm zEM2tx1iJEi;_TUP?c>^klXGUn#Kx>)cowtAijws#-f&5WE>s(5Y_Ju4YjJE7dV=ic z56`G0>3=RCZ%nFzZMo7)`Vv8!)r**n-~lyf4g*F*{}{V@2}4#nqz7q?c>3lnqG=O* zr4Awper(Xm2b~k=W{hFjqC8Fj*avXq8F*lVB_rLxBrq7Uo0RVB%ncR${#+BUfhFQv z_A3haia4_TyuDdB58E5OV@*CvFQzG26;BZ79d0x3xXsBe=L$!qiCo_n}$ZXIn-oe zKRc-YIH8 zNr3P(xW&ju9yF1$yHNz~EI5u{Sl#?l^B9PG=@uPCHCLrII^9>ukX{>~Q=^_dGA$I) zry{atnlkmykhn3m3s!}s!6sNn?c}hSN3dFuihVx^M&pdAa;F{SRQSX`#*JAePo(rI zR6}oOPc3QfKc2jchw&bQR&`Mz-(ziyX4;4kVSyzqc7_t3SY6kwMwxi+KK5@!+I!Sj z92^wL*sKQt45AU!{R1fBAUt$jrQN~bjUUnRDa)Rv1s8Gs)bfVEx(gy^4l^AH=^Lax z1hjO3(XDr+0nnVzGG@clyif6PEQ7c|6iYJU;%MZOs*11!$ceccPz>@DB2axL9juEA z8(*2q<$XzBLy#<@Aa9E)c)(u0lgQu zZ2P+wiQC*r&pfMOk7%yO{Qlj~c?5C6^jwlHL4FB26vIHxH|m%h8cq>_{5(2mv|U4d z1V3+%d`o>T%vs7UXO0~v$ls1clK>{{Q8&a!mbCOrl!S46bzsS%#2bw|X={aZi0=%v z84a^f;*$qDawSQSrHn&sX7@lIe|GsujpI3 z9V!U}ZwmSgAx|lJZ&3-X{bBch4&$Et{*}((oM0$f(OH^OGzM~^$*zx%nD2~z z1a@}WMV7i-!BrJ$gX%DNx@MXwagr^4gmdJ>zCb8xh%+bN_ar$mkdIoTxfBqLMPh}7{w`vqbd6WUb~dNj zR?oAqK7%z%5ob6NxTLV_0bra0NWOGwp9o&!*~5S_#CqF-G4+JGh`+-m$v)KBQ%{qC z)pkXp32BGfC|ZR1urBRHF3q(MXq)>b%y)%^Xqnby*3$*A;PZN{Cn@KxxsZv0GW6HP zHT`k`O5~YIOiG7->vftyqAohEas)H`gZCLURu$WPdqRKlG(hxsICbgHK-FckAJbo;*>ERwUws?UQ-tkiyilL30j0GVjWQJGB)uZq4-+v#C_Ej;^ z>(~xo0|xeZjCzAv=Tn>0c5 z5_NrLP#q4>H?uiA{Zh%U*&;z&vJD>FA*8D6gk*D-_Dnx!-S^BLevk+9hyx$P;({z+ z(gKTOCW3n|&MX45&mn6Q)dIxj@f-(*FCrS}${Z=j;LGYN)fMs<2$e8IDmwNEP*k1$ zRl|#f`Mw#2FSRe9W?s(rKC#!+w#fgttYPK&-?E04o0H}L$hw{1I&nv>n0|Q%2fY*L znFn8qWXSSa;*C=|JoT{^`=jH(%3qA|Y9pWw0eaZe5u@vwpRw@B>Yzy#e-9jeQ3KQMAHc`?jX>4HY#7zg#=0rnx4dpZ)sD{q;#}sfZEsdnb$1x^p*kq#9_$njk=9NjpR70AH5kJAWgf~c8uU02 zrEH$h3q+S#NcK;}88GirX6h%BGbKLTHc_^%Iz+^D!oGd5z?6k;V$c$IodxkSINg_M zhYJ97C{`%({_!aLg=Gp(?@rG=9GJBaS4~)(G}8|@YC%vE!3-tI;$@kWk7R2`K)^J4 z*^;Nks43QzYmq&sY{#9WR#P>M8i_0?7LotQ1V~CLdDX=BD?3to`ouvQY6%QMMYRO1;`_s1Q0lNU6N6KY?qzh#R)6$lk6xhpSvb8zVLN z0gNcUA33mzlmd8{8d>;d`KC3uQ$k_gF<>I=SF)UY2SqA=yaiewr9HgM8RDAeHK(^J z3+^N-3d@^4@iOmE1N2dGb)B8Ed-$!#UMl3`KEBDE&bFVUGM1gISgtAXft6|7bn8gdD3?|yzj$+C@efhVC(Zp&HHcxcR}Ze^|6U)Vqj0eiuW zD5@`th&yw5M0_8%rv19!&SqYS6p$EJW>2E}h@^y&6ee}{K9cIz;-w9vNf#xIl4el? zuXuV%Mtl7eD8lgmZecRlkP_5M&azfh;#HOpch=-wsFc`{c|xr(pj8h1y%U_u9A`|! z5x+vQcmbhT?O1t&|H8C3fPYE#1mZX2Y_t4@9|!d>duklk;?j=sCy->Uy7~6i8;;cb zJ9u|e%F8)tNU4LiT0?0hfy8oOBl!^P#%+WCH%&bl>h2O0Ks*F`LAq1%B^fT(;ilvl ze#;QI(#m_S{QOO%4Cl^J<*WFBvWDjef9|8L8D@-=ymp4dgSE)y@8r8?1Z>jTbA`Z- z71x#S0mL!gHHP`1FY-KV<&#L+fK%$l;wsCzCUm0kRwYr&z{y{qVX zGK*)y(?Wuh(Pf9|2)8!ZFWR@|14Ystg9#2FWR=3pI5_Bnf*l3@MX9xM1M&`_I#DFr zkJ1_&hj(}MWu~$n5BFmhfg)b54gaby)e;Wlk7z-JEZDoI$BN@Dq{96xie-dWlO*zv zjjA)^%`2ia+7*IPOs;Cb^D11?8tZR?)u(COxYy%2(~M-Hzf1mL`K(+1J0U$aRv7Fh z$>nk6u_I|V+=obGi^lO>IDuHHpQk0F&ah|wX(tMURWm5aRx)LPPnInW% zcX~)Ckk6_#?sgE(Ks0_$@CGGB&_CjLp5txeG)n?_h<@#&9KH%k-s``|>F-GjZ7uVH$hc=!z@Rd4~nq$iY2#AGu1XK}y zh6jr%c;>25$$%A9Hha};+J2r+!LxGJ%&^($DbTa?1}ZBKWP>fAJ|=;Bp`mKW zKfXm@6lOIS#%K;IflT}%T1$##tBahP!C7ah)@>2#;=>PD9Wc2a3L}YaYMEqnBNmvho8R^r26Jy9yWhqEjj)k+EBl_F+GWIo6n6_3MVO{0D{h89mR?J zX2v6Pe?XXwP3>-TIUoa=E!nxAWrGdyx&hw?o=hCWqbR2<7vO8?iOxejv6cncx|f9< zw>FbEtG`zHXz!$Ws%WDLCtH`jv*-=xB$iQr((x6TGi+3T?LV{)GoZHTd43nNtdT<@u7A*8;bhkI*87EKpS0_Teb zw$9x5z z1>+Wqc$x4C4DN>2r=*&1Ae#?}8|lqN`}oXg0J22M)qk48SeH5toi;~283@>)i(t{6Uro=D+2D`;0pRk}UZ{WbQtuN+H&p@pZ9{g&&;&5+Wp>S*p+@ zJi6C{vq*a=6{Nll$^vzt#vb*DiEG4zR@HOttY4h(Z#G}DRa_v~_G%(wKHRJRL!w9T z$#1$DW)T_I!-g3B^BPxr5_Yy+(G@?T9YvxFbI_Di9BGSVq1(CoIT5|A3qllNuyUt_ z1O9~ukTAn$TYjwUmdn#)S0&HSQN11_EOk1@OPzPrmx0u=xhODh1~9eot)D< z#JDhfER~1rGVUFsIA!mmPDQo1DR{$ZZEW(ia6B$YGVOaSf9TbF5+-DFyOzYMnarA~C z$ct}_+N69gV)*}S7I1O=zf^sqtK>&sK>*Tp??sR+pxN8Q}Tv}&))l)|Ue@*-S3W$uUYuQNriMiWU zT$y%4Wgm5V`TYEn=R34~mvdn=t3t;1SN~=Rb$H(EuO}%}Tb5DOJ zLppMEr%y)vUGxI@X{~qDTKiULp_xM1VPlBUlL?=2kUT11k#vif9zh!3r~Nk?EE`3_G>j%eZnNSim@M0bVs5Gvcf3p@>?)#9%4G5oF&;Tz zHEB@MKheA~GgVv$)gdRlxt*#ryA?e;ulbRgb(C{ZndGlN9#`ek#p z6jsCTh0A=C!eH2}DAdBZb6{^+lk!bF>ix~iF0oH{hL+Xz35UHv1&Tg9-5IFCoO8gh zz=?uv6pF8~MBZfvl^g%%b%T;S%Rb?9$u)xzRzw*|&qWvG6agX+0uFt2_f@&IWCPgO zs|d_smu@+`0J_s)kRUTG<->E56_RX|k?364pjl zz`e0^4Sc@$(W_Le%e$;f_?ctHYb}b)4%3?v(FpV}4zPjR{%|`Bt>peco>lV|TWCzv zqBVxM70= zRgND_uXOn`TUx6V?R)%F!n<~m?d(sJi!C*NfB0>i>jHaj*V1umWsz5iGMTV8%O76l zs4HVAcA$pGMx3|R`>+MN+#`W|CS_D7h~a+40ic}bRE6pXfMpwU`X*{4529Sm{zYFA zoyk0S?70<`p_Z*Aw_wb-Easo=7X169W@~}d9xoWj&7FQ*rKL+x+?_Il#iqDDPiisl z#(XZBoUjDuL~;W9AJtaUTvby0h;lx&gj`}!H;~&HTtr+Qi_T=e#~T4_r7#;ccQLMn z_RxjHNr=WkGixhhLkkQ-U#kn%Q=Cd_^!z6n>y^LL0h~T8;xzxS2Qpu-{-9z=N*ryO z70lNUfnJntZX+M3(Z=(ysainWH7jBpnLimuJ6DRgUvwg*3*X2Z8MF|_Rikk=y~MK7 zG;qONf^EGwiOadLJL4!S6}j;|y*p?4<6wb%mw2Ho3jm*tOtb4PIb?}ZtHeDzz*)pl zTH^**$ijJ319Da$&H#z-SkG*%3`cc9K?oKa``cKAgb?C@fp4~uwRosa*;Kx<>3PXA z`!4}=ya0S!-Y!-)tjyezZm1ezQ9|^QR+KOcYy~e2@>>m={n) z%nWdDMapT;Bf)|yN&9eREW75TNr-M53%Z-@?e+Wj!FCN*8{`^51~vo$2{(o?1vpZghDa6(*nsE+`rX$WP0FiCEW`khL0%LaV(!)mC^YK z{zVsn)l9jhb9khbGQ^G~llZ3^LTAI=bbM4@+GVYo691*akDH`hTcXCc0lI^PgB0+{ z9fO_z4KPhN8LG~b7aR;{ZsG(zPcIl&`Z63SkQKiFdWFFsk(2<5$1{O%2SYhNMMnnB z!4rGK*k z_U_cmc2x(=bhoI}_edW*V~=a;8Vz>%{guC{)ZG`+_`51^#fG$-518*?O?Nxj-={bI z)0pq?%=$J_VTVGT0nDlC6m?_9%A0{!-M}Nxx|!?RB+Z|d*V_?~aurs-E83tkexB`k zV?Hz}7v)*aIKfH}#yNVvpA*+P;|y_;Sy_q0q%!iX^j%$S@mZ_AkGV8^lD*$m|D&E| z)B^SG6vpv;z1{<{HekBHhjDcNW3m2ARYy212Dog%m13a$3^dc*Eo}Db&nIH#giJqc z_eHN-sb|8jFkoiKO3^XD?{y_~lXY-?HlA-Ed2fKK`jxEU*J%kaBz{3$AJxdVW9wc6 znf~VWHQ>tY)o+zrLLCkSp47%B&g0lD1DIaGA3MXbB2NDMjGf{v_}Y39HJGkdDFK+Q?200^zfRvnD*ixhkI{6-(m-i{khc)|dEO&r3QOaJM37yGulqQ=n{ zmr({e_!w7zsC0ImXHQ+(GMArLY=O7yT&KQAsM(^9w|UpJ7}cun({kU<^(klv5pXn> zfB0vq@AJZX?fS;wE6RhpfX~mZQM1fF+s|_P3V9VdGLBW>-oG^}|_pTe0ZYw%~!D#QBowc7_bb7NA~%nD!dbun$j7 zTQQ$d{j3ie8m5K3&DARA!)cn0K+xK=Papg6PTd@YH1+45)C8FDcq*uE8v^` zk1gY*_%ul7Rk+a7A(R2)kUmw&rnM0M45G+pwG?60tm(;v%C2u4oLG9slcn)CyOCcB z5G%vy7it_rEQ;O|i<4wgM=PXLh9`avKh}MkW(B=_ipug{ z|NT7293=mU7&t_aEHfjl{E~zSZ*;Wks}Vlq`j#atJGw78zr_6LpZj{w*2AM%5%sjM@{U|17I>g< zt`ZW1U2~I${?AQ&Jx<|M<8xJ{j6kX!#Lq~@JY4mY3qgdM$e6Tn;-lORc;sg@+2xe8 zhC?%;^C6yg=O|*M1v)&crk$ezn-nL_St=Ix_j>ZK2|X)pl#lq-5p@Dmc+k$^1F_u# zw>6NP+3ncxnn;-}eaK_(O!;ivKluth=Mg3S6Ytrcm6G^As}lB$tR-WWX`|Wit?%WZ zg6qH6C0_4OvPZj%1NVnG;P^Cxg9ZVQ&u_j7YJQEJNpd2394?5#fU$R50_85$;bM1_@b9$!{={!ISKrhOEp0VFaOOG=Y?TuAJJ-^jFyHoNAq)m}4+?j_Gg zl$oiczyjjo`J1DxEkZ50pYeY9I?i6EHe$)a`2Y>h@)W)tcza1E;KJK>&h3^5NxWlx z?tG|T9sfJLkKr}UL$P4k=BTG)(CpUI;Tp^%D7Az0HX>*6Q~|awr|RBvgXDv~kP(~H z-hgR(yHP$mDt06}QZ4WKE?hn+`us?^%3-+oRGiu$p=R$Y!Bp=mqVXP6>W;Rja-g>( z#Ak01{j8(I#>l}eP?Rl*P51(m?aa}0!S~L0&~+AJf;He9CA{&as9FT^^PsWfzt~I{ zT^8R<6!c3ClZ(GuL&V8Qd3=B9S;=T)JD$tl1wteP=Ty6>_~NyGYKG+35`f1eH55Nj ztn8qhrZ3zJJMn3DBp51;s^mr8u)G)Cnm8q5K7j|1i}%(*#8(cYVtL|MW!QvSg{rA` z4&~G(MT9B~JAPK?fu>s73_&~#QXh(5WzZmhaWgcRKdgWC-zlag$FB3~Qy>U&#rtMb zw#fe{YgsvX{*PI7qpR(FG>YoCR%f`|AIY8jAvKBIKo8hzaYU#ebY^AZEynk2P1Bi6xBYG4{$73@ww&nl(+TGG zS>$t)$8ZD0PCnb&o%`|~;%l7Nv4a&2#GkvVs&4F&YHVqy&))W=!roZi`#=^AbCSen z=j+Vp;2)hJ1BT&FMcSBpmixbKqk{Q18nj*fopIMP1OtWx(^C()d}{sSNfYy$JX-*Q z?{9~l0tV62#pz%Q1kkt4BSyc)yRw8uF7&7ajE#YgVmvi`>J3IXtoZ?5Mg$wYZ;Lue#MiIpFql@KeE`Io-a z1TGvC3nckG`;@h^qD=2*}o` zfK=dsQU@f=i-7DteqGcPK)1B2L$A5buo|nNB(gD-@Z;d>=bs)9R03{@9y0j9-$Ci| zCW|kTP6I}uOVU-?nSs%c4?}p@q0~wse3t5Lsc8q5=0v(h99ekNrA@iJqe0SZ5U9Hx zZWV2(vsyzdlJtW03nTA<(VBc1dM5^)M;#JpQ3OijJ(j-BZyQ($ z?T@(M_POqvqVvOZluaeH;d;BVB*%a_FP?DPU8JXn4{Cz% zhhR)l9Zfvrk}O5ulC?z~G}{zAs|v`TwO-Q0g}@l1q3l7!z3@V<&&)|7?Hm?micC(J za|kMPd-WERz|{(n7^#ES?Xi%j7yzPn&=sd#j6aW+>t-x|oY0}BSydZuWW-OR0P0Ch z&V<34UnPe>(fYLmy*@sY+54ejIV_*wkNV9I8tdL~ZY{+)qI_$aA~v_HYEf_C)w3Q4 z`nViDRUYu;&wO=rRWgo9HQBhQs}C zUf$^9D^P|!7eNh*E@@Ay?E9!}h-Lu-elA!PujCzyF7;4yLmJqx?qT3}&{7isMYvdn z2k;q2e6}_d9D#GACx>b2Mj%NGu37Ng8~a~~SO-ZO?!Em&O~*$IuJ|UmzN6PqfamTR zIuc?ba`HQj0m=gP9h=_IBPmUZ-yzj7$PdPRBxdN;)7=IWt_CCCfSLs6JFXhFvXO`u6&CR^nw2wDcaf4pfs#ud&aM{QtSVOo zCeTw#sexsG50un_xHph=$d(JHx64wf0Bx9Q6LCKw$nq?WH(&Z**5J1EUxAG*{!yc# znrSB9RL$U?Hz0HGqQI0>iOVw%dCXP~^Tm!{Gq{ ze|xPvy4703NWs*^RTNO)=L89>%TZcM^4A4~4Yw9?i!u9UFYp%ym@uYkxONgI&cU-M zo)#70aK=gPmWaV*c6`RLz+o3#XUxgze8J*8O_^N2I=6$PhO#C_aFon3zrH8l{s=0S zyMN*G#n>l<#WOmnxXoK&tL@&^B)5kcFO2akSD%+QF0kH;Js30W1>#^Bez~d#zM%5z z@1Bv|k<)1B5ikfmGThU35XFdG=|AhSZp#=+Cidbnf5bPlQ4z)@8YLW$6yjWX#dBVM z*u+D-mGKvm>sK^<@pWht`miUnh(X;grzL8(pYx!xqRQ_v`hh*KGy5UE?*YDPk5=8+ zuvBR?>Fy`wB5D>o*z`eDo7b=#WAZ#nu(=&=C5$sA3ShC2=;1T$-7VCEJNR2yz^4zm zG_n=Ra};YlgB8g~x8-6B&d(Xj4f28(&4T|Js0H-&2dST-98E)3S?Lxirl-YC)7a`?Q(tvyuHvT3pZWjOtasd#lhpha8ljVMU?Gn2mytIW6*RyZFM`>rv#}oaR(0vI3yA< z%*77{eoj{^j9-~!K{z6U?V@>cxz#ZU(ck}ce;)0OM;jtk!t@Ed5}th$=+?|tNHnku z+y?8Qbw|owB7mD6a4t$+wNu3s%fQ(zO%%f>EOIF${zqa(3NgoQiZKdyom6Z`H`6eX zJiw#eqZ7Juc>UZ!oy zH_<21AlVB~W>9G#W=dPgYtRNkY%~(HB%;xaL9%~rGMDZSt?pl!4-=)X%COR0KuIDI zOugOo-q}&qKx-`|?o)7GNz)6Y8)`4Dn1B{;u77UEh<#`ynOHy0i8)JXTwm8Xv9voJ zeVaT_^3<&Y9}au|SXjf_n+2w^)YqLGsd z&+}QY1a!X9JOovfqINkw!6qnQCekzUM=R7aFgNRN7=p_crjX__>024+JAcoZvVb#- zSe^Y|Z%Zyz^$NAy3OY&0&|M>bcWZlJHwNE_Srq{{y?k&R1{3c&0?YmFwG@L!IPL9j zqV0=>9b5l~g49pxEgZ^+2PR7EU8|$E3A37^n?lMf0b(($1F*#xMOG}URe35o6W=^` z_9ob@osl&Fjz`-AIu92W*NG<5I3Oq-th!WI4~83kccCL5^TN(?vC`%V?347K)_aVl z_v00{*yJ%lcFHzk2NKH$M!b^3V5Ylcy0X-XaY_S*J!C4M_Ra}UW@r;?qF4Vt$JGt{ zJw=DOi}uSlzEBO&qT2~}hCFpWTN#43zyD}vj)eRuoK$n&6O#t*Wc5gK4g@{EfCGeZ zY(RjHB2KjCXU%R{7|0=}dTL4_#`FbS-J}3h!}eSo>gg-)+@G_Y_j4%lf4(ab)Dt!* zN!YP!>+v&fNT&L{@p(_Gw!?aCs?t34oH8^?AIv@=$BeoapITCQJ7~MDR`tl$H@eUj z)2$&%esq)&5~rJFb%Ln)ft1;a6b2?0J%zIio2i;x@}@a;wvPqhL)FE@9q1?`Xss00}@Z-9J>6;SoMo_2zSdygd>`YWtoB`(E}Ihf1iJeuGPW z3-=gqD32iX=~Z^1!2J|S?9#6|4YKp0_NTJK>QDJAV3n4kN+{_=*UW?QrvbNxzu_Ev zW!^3NdVS2BmSW2OSJ@Z@76P@4dukuC%~W-OTg;% zhi~w&$;wPj2>Dd^l^2i5g{T$|x&K{@IBOvSH#<%>SzyACZv+3$uEQrJU) zja~fefNf-F{Q+>EJbn6qr{&l<|9{eQT-==ha|86uO$q$Z+Kbz2|DV8IK`Rq0T0^%% z>$xcQx_DRB3Jb;1*Lq~est2*K)gW|u)90jFLaz&ItD|M4EUYuM)*x7r|kSNgG z_xbF$LJmd(3O`Y|PqtY&JwpsHg1L0!nZYv!>jk}X$;na3pf}GXdV$?QaaZ>THV zNu43G9BX||uPZzhMHiqR{ZQl=RZVJy$T?jk2Lx?{3=eVekO&(t{O<)(?v14$OQCe2O!dc=#A=gK~NrvLf z;@(AUCo<7h6}io?xUXpv*TKw(qbK?UeMv;6$^3t`sFt#-H0>Q&gKqt#m=F7V6zz`X z!3r{DV2QCOrm75TdtLh(OfbL+^XX90+UK&Y|MEfp>etiep&Pd3cn?~I^S1K~m#{bYM$MY>4~+;4zud~@p7jYXWD=9{jl$v!nH$5I=8gXX)P=ZafiLIH$j+%E1v#`ib)j1>2Cv(T$b4EK_n_Lj z0h1?v%gL9{rLX79kjj@XXCVWnEAM>Doux>u1*yo=V6}&q5-=3-S4&PbM^(FJ_f*4y z3p_R6@}c+^sb}GZIJuJV-E0Sg!{+vFqqD!JPW*1uNyf-rPUbsZr4 zC(gCi6+Q+YyP@X^B|=R;QK5+k7(_xP1~cP@_y&t?!&(`=jb5qtYF%SkA>PU1Ci&SH z{O+i1o-bhIGg0QX;D$s2o(_-J$EcwA!HO1!=BNt6#FK(PwN7(kHaoix7KTR0Qw+Xb z;nRELfw?B*uK8ui(p&P%fG;WfirNy|l769~w}h zP^lwI{?5lIA0^Vk5~bI`Z@*pl&wqEMyrZH4fg?~R_m5Xm!@VX39)+)`f#V&`);fPK zqghw!GGzL%6^QBAwv$O>Y90@%4{;CT4dsfH3;0l&R|}{^B7?!MCP2nv39Q#fL|EAM zsH39}{*4H_!j6xBSrMZM6kgFmPY~`fgQXrVh$Yl+%`a?6EGFo^HD~6euGGCUrteF0 zzddW@*zs&fVK8+CN@p+2xQP&qZyuLd%M1F2!;=RYG+f;MV9W?`_Y1?}@E$=`RIa`~ zR;JICWoZ!pE!!?^`AEZu-z(HTsddu0dB{^{`BNHb!kuXf(Gt;JT14Jq#N5M9?zz=Q z*KH{0Y?|gQp5*5so!W(aJU3kb{dIXh$ynetm`T4j(Fywsgzt?C7d*4`r?aQr3>I^o zw>VmKuy&K^RCc*?JDPy4*0o01n|QCevtTruozND zhR>+V1@JHTK*umElUt=5so7s*Y(vFcZ16~t6(=}qR0MQOLFLge`K)m7^dP&^-jh$l zYNIxo>R^jW;qd}WrAQE_j_b0|FvEcU9O%1)AL#urtTrZS#8AA@YTpTPWlf>gBlAHo zz0QHS`54)QQMR)U(fWoas~MJ8%XwK);N{&vRZCfKVDj&Ei-4>jHG$6O`o{D(AoP7P zNF^fvU=nFp(fF)azTr#LAdy8?v)1ftDo$pnMoRfQPhvWO#4x|au>RSBvsOma(~Vx1 z;$w*b)E>rdK&g7~$=X=gHjrg+I;vKL_5fl$!940)@`(U)i9Zfn4&R!Hr%Z5Swx3QI z1h1(c_?^RKPAG0@lRFr3?pImdM#ow8-j{j;r7l}Juekm+N@QoL_IPA}7fE#?y9KB5 zI=8pO7^(j3!5iT6D5`wseX!{-Pa{#N&{ezBFx+Z6lSk9cy5=ziBVU85EzIA!UKooG*v=Z#G!5RFEdXXy*^N}tvWGn>bl4hyiQKKib= z(^8-JKY2&u9woT76BBh593_GK*riSaV$SBLxa{pxxH}*=6lG=_tHHy%qr7NZr@NbmD$j3_Syx8J{-W62J&E@RmN_9Cv(U%6h>85d{ zu%0QXGj+-%i34hJ#DT$@-S~N!wS&4%BIudxzA**@*=S`yafLChKha3*qeVk0wx`53 z0WOkT8&W*FB0szq4vq(L7B6Wm0C|^BfFwr`Zr}bIm&Y;9C3-Y)gMbx4PRbxT9m7&}HsV>u*3X{fvKh~pY!Y>V%TpnCk>L)cmt z1QKgpPrAFeJrG}7-PR%c%Vv;7OG$sgVvfUPu%D1-_4=O!mXtSx5}7Sxe7k`V50G>O zmxR#V|B^o>Ijp4*!HR_tSTt<#OGQq&Mws#6Hb+#+2%_BK(jVvsK@LFH9Nfnv=G33n zK+`IxC1G2xH#3eOf;4Wo8`81y{2g5j`JM{HTJr|F@$uZi=)O0OXsmM@O@hv*+DHUk zy~Kn2L^(yI7&?|eVmpe;IK@|ah4C#*@5FkCYdHTOCKLbPV|g~7|INv4%bd2%79 zM+U7|^8fxHvd*bF&^GGQv2EM7&5o^(ZFKA>>e#kzb<(jqwr$(iyfsr(-&D=P{SWrR zUUyyV+MM)Q=ZgpTmp$A5JMFLbd_bnNY%=<8)OC;2U&7<6QT3m^{+-B5CLcVz7TICP zcCG8e2gd*WIdvUdU)i$ieS_YfY%5sXohN}&8fQy_ZOfNN-v9b#cm@33>LjQW zr7fWvk2`$fraOT9^9SKOuZEb*XMq4FxQHbYX9E>oVpO%i)vu*rjTUQ=Y`d=lj>}(< zA#L}R=xFT5wSV+?n$Anp&$`kOI%$rlc*G@pYK;1XVk@)VFjD8IH=ea_5C`RuiW^8qsTh@23-B{A^3j$XEuYVq z9^~?<&qi&#RNn4_{Ykd0Lw+z2BX?hZQFhv}+ODBvuU_cxyWYMq%uWD)rvKX>N%IqG zaO{?ixnKHSKb~z`aOo}?52Ad6b3q9`5`+RTK|LgL1KGH;BCKcM`Qk-QmLVy?hI41d zOV&XE8^N@e_GNf9*_wTeqBNuq));DX6kW|hg5k0CEE(N z+vT6(By^jwF_b!ba2p7LnkkOIlKt?Pwr2q_~joB091*nsx;` zsE(XQ(`+S%VyW^cF9WP)EvuMVb~6Y87Sy&k+bq~oVI+e!$4}|MiD`V5NC%$K&h3!A z)UNlPblkeXH|^3w=qNP@9C+!LG;K@xWNfQ{)madI%U6$h7jpiKll&p%0SsRj0>+5d zTTg4^o$Asw9tuG43uy)Jx3=|>zBA}Xd6mr&S8LKF{(C{Sy~?dk;7JgnQ(+Eow~?23 z9~4=%U9D$;|5wU}N`B?Cgrc~xVc)^SivT6-K&C98<6;AIfTe?Zr&D;#+_26y2PFk2 z-iM^wb3B{M&8k5CUI*P znSw=laSOiCUWEu&dE(M3fkz{^ABY00*O>JPJW_+Op-Nbj7g#Pon79cjb^WAAR{Tld z?!?)=j0hm2E0)s6lqf-*=!!4XcZBnp5*$uVymP39%wN%TuqVV4R~L=X5tB|w0?twv=IV6JW7|t0;8x2l~W!WZA5wTJa}dcOI!WsF)aK!{Oy!h#$)0$ZV`!q2tj+LO;UR?jgqKEE z2p_+|FY{GW(^2M#4S(?ESN}LZi3KlN>aHA6muUx>iuMtz#;R`gQUk}?ZoBG;g=+!2 z)-+6W73(g=!E5pHxuJNj$bd@X+3Qo)$SVMw*sf35^7FQ8CL4e-{xq`h}O%ZTZO=@M<;t^jPy)$0Ufa zHRh!;48SvheRE1PTdK7)!@doPYiCq-qtp+(PlHTygB)I8(2n}CpRCfLgWNaJ? z?1ZsK15+b;`49Ew-F#WyJa?sw!>qGM5cEE0afI&LvR zpiDX$UGq|s30ILhC{S#YfzqZ$1^N@<{bxi^!polx0{zB(DiAKOEh$FZ({OvZUbUC%on~1U<}8P0kEpNa+-;MeU5U zu}^WdgwPK(OWxQ3{*={YGFH9p+Y6!M zm_!jgT%_zNsUU?}eHz8%L`j(`SW8yB1d1W-AHhk2fC% zk%mt5HPZ@`gC~uHWEJG4i%ak3h8X6+@0cd1ZA?&&D*I2);Ufj0unEm!l_?EK#d%jX zg9mWAH*GEE-a2F(D_3&=(zsLysBecg+Y6%_mePGftRzJ>iNSd74A~|n3od7*n519d zo%Nr4;kI9m&ma@!_XMqE6=%675=|bsxON^>$y5JVz|S`#33VopG8P*#$zkt`;A>qe zckUjQIGtS+v{(n4F)<2LepPkK9ij+fB*n0w@;Mc2tt6XL-#x)!{moOc9QawiV;3I0 zJRC8N!JI2+7xbHJ8S?7U3iQ1#!c;oq!TiyKB=#*tE>-JlF=KoUhNCtM#wS@FtqE+?ruZi7aD?XX?oHFM8h7o0c>?uybTLjT79shv(@s}_y^vkFs zEBl|~(CRcpl`4@_A7R!JB@QgN1#P=Fv{HhEuVtLrd)wlC${L=O;70m4G@k#WyhOSe?w`Te`JJ;vym4Er5K{ps+P{3a?i1K!Z6XU zyzH*|cnx#`omLRO&D{iE#YjlW9=fHF9fJc<<#ufUQMf$2qx8j%!B=eSq{2rHDsHrW zdW)z>mE=cjV-GRR_#p7fi#(Y~GG`?MY)8!mb=wWSA=Ae~jDaYvJBFnXm@kYks!@2! z-4PEI-c`JTi0lDy`xik*XLSX%#{kP%MhBm?0QUvZtPC5cJqo=mTPCk1U7B?Utw@?v zIq@_+x&W8Z`74TR_~IN#?YI=@O91Lf*Qs_ z*&Q~F0taMc@jswQ00eADxwx4wO^E;j?=!cqBh1mU*1*t(lN<-vZsg*~zZ9~6Vxl+! z#+0u^XUd_;W0A^|ql3QHJ!3k9YV|$u8xw1}4OOSXs*3O1^S*U?8Bj;c*j>#wp+JE5 z{mQXT)p;%$!5ZXZ$aGe#jq?5^Ac`6+Tyu1(Y~r%p0JrV=OCLp5o$BUAysa5~$67|$ zlu*sc%|*RR@5x4WE=0S3UASgfX-{3 zKWBZq)gD+&qer8bb-q7YYcOS-YKo>Qwvq{qy(anS@YD&0aX$w(8EzlCc-rbp-yaB` z=eQ~p1i@80lLzxl#J5#ln(AC;C0l2cl6jB2PnA|S)Dd5{17na=Smy5^Z?zCT*a~BO zH3|P3-#b_M!q}Y0;wDH+{_z@P%Q(wGMQjII(Bm)ZzE{NTkhg&i&ib3 z_GDsvx5icvbL)uAQqXPw^?E|!U`nvlHXnbkQrsqm5NoG?3tq|-&&s7XLPJ1+#N<@j z8wVHi9di_!0JMdRVnC~J2U|rqtv8z$8@Zv#qX$8fB^N`)dGR(DZ1fztkYPfcr<3~* zrniSvvcl%ZS?3;53Pf=z$^45ZB{#Xb=9^ItKXaKf3J=^573-FR1r0YEW;@y;-*IEG zBDku^kE%?`ma3v8xhCyuwE^@x*jYHa%on`0E!XWnk`*&>Lo}Kwq(suUPQ=h zR$0In{n)r^(V+ia&!a??vk8hVb+j~<*#)6z1m1)Ej8nW>5-NdE1raHTQ`*%o6%l)s zs3ima^1OItQeO>zlpSFzpxOnKzn;cNRY7EDizJ;o6-AU+i-rNUtfDQ8@Zm{pUv^V# zc6%KS0}RD}HHnV5tW7Rs$vVnHsgwBidM3?b71k|Ej-A2gHPk|>EJ3ehbC+$<@%^C% zspY;UMJ$9PAAHmEO!}b|6JB~e?-FUsI&?V(>9q|(h=iJ^b0KKtaX6MkUl$h~VzueO z&=?(7Z1{wnT(+FCT{$mb&6e$z_@a)$LG9>C#FnYdN#}>G3 zvyU$l$E*}dq~1xN)No;Jb(EWZl=;U9r{O!+Pv+~f0{aI2TSVd`>MWR>&t0RO%N_{m z1>i!>$NKz^6Ic(>Qb%FJ@jVgVx#9Zol{4%~`58X@u zU5_u;xdm;_(@|%vcy=&^+)=uM&M~u@qH%DoMDZb%EC|x8c9K_?BnA8xHX3U6X9;B2 zU$^LSPypfsiF+XgYml*0O&QnOp0-!+8g^FGD4Om0_2C zs32vhY4GUmi9DBamy&0$XdsDt6X4P3b$73|?9uTrLUBua_Jo=^b7r z^Chk}d+>A4bh5XI`?XE!l4P}~tN)p(nHKwVQ^m}$jGuToq?DR?#J)Og_nnmzBh!HO z2WFt!1W8^f;rb{oojb8*bhOj@aU{tp#*y9082Tu;tZ8B*j5HKRPMl6c2mlFX%zkH& zR(7Ngmu{gSw;zj(T-;MipKEcPV6zstSvs}n)X(c_!q!Vt`>u>Nib6}vob|+n*RN<+ z`r&H<24}^JkCHnf=PzT>SeJ7pO#EB)=N>9|`Jf?`+a1S(=w#9kyeJ6J8;>oT1M#5R z3s-927xqW~9q$;2g)OMJ2&h6km5q{6&5VMJ|L_If!^R-tWE7!IfolBnjEQXsnHrMu zhm#%oQAUya*MGFgSm{ZUhfO6{6gElu`rkNv5^XHU$r~eE60J5r=3E8sR2kKS3Dj8V z6Zd^`Wt85dq~r<3QKBPE`y0LJvu-mu^o$0;a&jgo;xPlC&7T4^i)=l09B@h8f16<%*SCC1m(#`W4p3I564wwaBXIx-JcTeS@Y3d zw+94WKJrTUQO@5Of!FkD$f4D&_U0jtqZ0bNwvb^uh-H6#I1J9caHpr2`xQTm=wCrS4tA3QjLaB__}HE&v8FD3Ir>a z9Bf6KaSejl6Ek|0$w00llJ+$IPCDgT>eWdZdBZ!e^OijMO>p#`TzJklWb;* zPmUm}Aap3$@%&U> z4F4AK;aZx)1TXIMdO)abEkIi9>q*wHodTNKVc=Sz+CdfqSbXB|2V$2*r~{Dx;UNTh zeUn2br3)e)(e;m>o}P|^y1E|+03w$Z>8l{QM(Khg_yS^O{36minEAVK&aVSHkI2wmy?J5a zJ4ZWTj_txl03}$*2NKjzUGZ%FK&CAtZ2kbo6<>bvUo0&*eH52gnKI0*R*1>}<;?+gl~ zTZ8ohSa+>P=GeM0A}?{?#7JktoCDt&p!0d?{Rl6XOl~8=uA(5NJ;@GZgVW}pH-n$w zHP73m-`pABV|U-`Z$0#?H%`uPlNn!5FT_Z$Q2busr?({f$SVUl<)TEPeTUn%Q2D|Z zT8L)gPflOl8lj*7@sQ}+;M8dkG_1Q8h)I&!wutwjRUs~zDQy#9(zvvIQ&oMxp+JyxE z+Y9`nH-I1@=)1z;WH)hBFgpk6d9mxgs#O%Z?&&8|L`Av_5-gu3{LsDV84-51z6ACA z0ssDa;py}~{r0>L0&xeXV>+cEUM(q3AQaN4CI%b_)*8 zn9;^YZiVYjnlTRRGC3wZch^*VH2Hb{SYJ83bo%DUG*8{~JI zX&{RL=dNGD*rUrW{3#-RAob53^NoNTnUr8sAm}<*Fw%gti_%ayOu^B{UIR`5_-HZ< z64YcK;<(wQ@T=80!l1n*$Kj{sga3+HP8y9GXMR~NdS0Nb(`Gd!_;-i(hF5pIC#z{=6^NiyQlCGuD`|UH;>O0w@G|ft=3zq|3snQ4%^-_olpIHl)vCZW0aJRJQ5*f2Q-mhR4ur>5d z3|jNrdJed@MQlF(GG8x`@X58lY5emwdc#k4)&AL$>t_xD!C;9gK3s+qOY zL&9070adQpk4hX0MXSusrF6hlr4V*HUxPJR7jXbmFWSUpIZetsAYR%qLeS;iQnSQ> zT(_*-Qk@D7MSF7`=rlVm$d04V5s0;b=FOMxaFSV#E-U($8LO_;(diQ> zxSc)A`Aq$&1$01ve3s~+AoW0Irvntx|e zY#re#wU-ZF0bvmAXew=cP=$dd&Q!~{d3e1A2fBi=n9@lelSm;Cnf6@|p#9xlcjup) z`HT=5sUasc+^2JS$inb1D>lmg_R&g%Y(;wSRP!8tm;Uh~$+w%+VUP*t`mltcy z!h8{X_0a)C!*y_$i4K;i#_sn-yIKirR8^_I5h!#v_4!{+-udaMu9P3&s5E`EYh;fJem48pyxPxs& z8gL%L0#LKl^CFImbZ)UgI ztA#@u2a2xlD{pXZ9Y?vZa~j1Z<*Y7~z}}79J`T-gADv|I@77%2)(KEj8r%i*OAIF^>?8O0-nB!&~uA*6{@alYBjycRz5o`B@A!%4? z+*mGxk-d_e?$&1X|N6>}nf6U^w_}3z?6OWLm!t*g(r7X9(YQfGFPTpg$fw64Of^-u zCjL?9$4w^!u4j9Z{*`OIG?tvZa`C*TqWM1@q&@cUu`wqq62NcB!|;BPo$7J2Pux&p z$1&$*mOBs`q#5Lz(J(52Q{_n%hZL_@MJsj*G*fVWz#2{XMuVQU#fh zV|X`-v2{d@GwTk zs~ce;YPSqN9sEzl370pYR zKjJ^^dV!Jw4ZNVPfw355XdUg>fBtoZj&7G`{j99KREgWMK_xxb%8k3k0u_a^x@D&7!}lggLD+hO!+zSuxOfJ(RH0HPbB%XOyWR&HZ`Y531;Z zg8s!1tdIkB>A5*B=O#;Na+K#<_)cPL2urMHnT#EeJZ7@gda5ek!#N33cJ2A;950{% zqtuM_Tb<2yhjKAGWa+?yAGnzCEH`D=VB*-OZ#~9lqVkqw#p>AgdUI9T=t#;U==Fqq zPvA=I<9dPwZ-RHYh^I@Z8qK33*1d(IeBf&NznsEy=;%5vGJCla&H3$q%jL1ct7u1h zLZYg1Ulw>K3W435FPLtYoy+dNo#z-J{PiIkD^Mia*JJ3UOvgIg90@V~ec|~y%w|8H zE{)pX62_eLjnD2zHt_crXRLqzJ$sLvcRz2$ZNwjOi%pQ#r^{p+>9r57&V`Wkcw|+E zHE(viU-Mw7_$CLgzWTl=sjLRhe$;~DD5$U2D_V4he^5aA5^fgiBRSZoFH5R{C|8}+ z#A-7s=qA0}tgK^S)bitG>AShjJ;+6JGI1Ncq~2~=O}_!qq(?IP7D-vl9RfL14C}r6 z0H?}d>M5&6qAqe0^@b&si#z2Mq`x>2{448|j(PdP4vnwyi;825Gmkcm45gO>wC>5D z_uOQ?pgZG`(4f*eXJa=_q@UFvVZzhAx8Z{~Jcxw%%0 zbuX5P?uQz)O3BvJFBvAI0eMa3^La1VYJ16VKjm4pC(T#I25GqRe~3^dnactG9mQ(%1aYIH{25N9hudCC;lxN4TwT`)O;{sRM3nmR;}g(WP-0{zjv`3 z1-;z!oX@~=(EmPp4tE@JjuN~z`Ox$=YBNSN2*TNg!(2@95>Wd7OJa1_O-h70`_9CA zaOPn%@FI65c>f$jP?4V~T_qp$nyXagGW*>`pFmf#vHH)Nn%wR;24zkFIT_1fnU+!! z--tvaCTz^ow4-=tH|-J$@J2u;@rH*(e&Up6_po4!Gl#YR`(z3kZSfPO!TMWU0o+D? z94?c$nxHzQs_;aJiEKd0fqQV>GehKPGNQi2sio|i3z7APwZ-867!Yl`*G&6c(IC}@ z1gU^3Z)?+huz- z%Pc~{n<{EDYD2ERw5*wlWdw_vy|E@rwA+*xdSm5eRaSs@LB|nJkhm1MCwmFbNJ|%? zGeG)puj>-9%v~hbgGn~^Rm*R+&_hT+4LQST!%%Yt#?UJ0Q8$O_PHGdqW^mcnZEzk( z*=JnF7WW6oV{qmI?|Kxb-5V=sR{v&3*@b1=(|?#1E#)>U@cgHTzGhRX`#TLut~uMk zeO`hT5ot%1WtC$CtYYMrI7!r7!*@Jg{2=03hw?#_PpW}cb+T>Q(wtxIRB6qq!#|5> zKt~v>OT3l)Y)f+%;6*uDCA-|cmFd@N)tZv8KlKN8{#iT%z0Z$syl)Vz?V!;oy7ig# zqS{EFLh%tK&ykDCF%avEEAr(9UHo+o8}nd^N@acohhM?waV!{<2-S<;nL)rj$bN;_C8dXV|yDjJO{P<3TTToB<7hudI5% zleCs%EAYVX!6MgT#@)=DaeHp^MHx)Wi6JA4Wg8CgKU~J7U-ES~neUjSz&A91%B+of zR#;Ck3on-yf4vN5D|j?k8acRk5ev7Qfb|xXYcGrkj(Xh?rve02n&F8URDX_c3Cgp} zMcM2<4}qw1kSfqg%x@;ROmpK-1Y-2{Km7OQMPYf$Mal;Tnq(H*kjUI`qP^Ut4jmn- zAvM`m^0yA!!>JtfUH+-tn>hE20Njtng-Os%ZKrwFQyiC5My875MZIwxlwSN>a>g7E z`6v|~D3z*7!b}QEn5ie*iaR_L@1~12u!~1R;_HWQGHEzNjtJ3I?aqUSE3QE0btS8Z zwxcv5Axx`$^=kvG$c|dSl-cZpz>~!!Ib95LO8&Y><vg!qLC|^DWQgGcaQg_h6|2KL^CsGfs?px zSDI?4VkJg!FAIieLx1$St2Aa+N>y4|QdgZfH}7yoP*7Y_$Pl+kGbCNl8@;#6@E46G zaMoN;^#H$*#v6UISh-d&wb0e__`?R5?&8*CX{@HDzy)Jo>aymv7PL$c^5Z0umFW7LPM@vSjA3?<1gZ3#8 zcb{cz+UBsXGC5dB5weEOuRm*_w%M~hz>7~#`Y~20coRAPr2V@xvec=$7BULx`HY$z zIR|VjOF$pD_#hT&)_!;um+6MY#gp2eDglc75S8eQptthe;AtGf=Fqhlc-S!3Zh=11 z(d>opel!&mB-54z-q0%<9==CXqW3QuO3-VxHBUbY%>3R(G`(aGW;7ng`uSBYVCbL` zmz3CwhJ&jarwF=ALz<~%%cv{wFn{(Q@BQc-qWF@emRd-a=D0=Uv(t(sOep@U^)nA3ANMs>;@CaI~A)Tsy2lHBfX( zm>ToB=xJa^*Rp=9p|@V*wex2jh(=~Ynna;~C^L{pol~DhC3dOnk`gb(%gj`mW^vfp zH0j;sSQ6simi%u?RWJ+Yua8WQdV-N`ckQXJ{RV^Z>-d>>f)U10^hH4joynNY+pTTh ze2M&s726Vbm9o*)k~c0}@QNyCA0uNG(nyG2i5k5A_88^{`Zd@O-%4!{e3Y+N(3U<5 ztEOjmmRW`GJ4Q_`A3Y^xsBbR{9~~X%xCDf~XRk{uD9c~MU2{=rNZ6Mo!YiWV7>?lS z3yEz+*LbbI=oGn>NQA_clHO{@v8X@cj(2uNm>6LTk{MpaO09U|6WRtopJRZovBKKh zy9=PUgNkdsxfd}Mc7}igZ9lT+oVk)pq=m=n==w45T%Vocz{oE`5o&^mD%W)-;YLXM zKX*qjE(IJG#%N*Z;*fcEN_kW*CpABLCt2pS3IV@ z!^ITAtp++8c+}fsj^H;(kB$O2xW^vTh5Ivp6vHu9lbDS-8k&rN^S#|Iq%BLbdFuuV zEeZW6+T)?>?_3R^(25LS)(yhRI$hO8)Vl%_#iBx^JEV;|6nxyn6oCl}jMITGZv`{- zjZg6rbi`ot`_qU;xwUAzx8su|qpulvxmK7nfHfr4HEv`SM7 z((vc=KwWY$d^WTiGtbRCW7kM`!xS1s*U>L_EYV-ubxdo&amy20GzFPaFVQP6=o6=U zorR5@-mT$&(K|%Wdx$K8%>>hX5`v?n=Ca1*F zFO#|j40|L~)Ae9MOcibue)5{S?qc!;JA!e|L#+?-axeSKxG>%gShuz#D{T;F(q;FIDozmfM!*)Ot zOpWX)A8Y-uw>T>ar8L|c3Q+P~ok~ zG;$QeB)~fS@oNcZFDAK`_no#}*7~aO>P-Mc3R!lk17$kb7lx&P=*rx`nt-1UeL9w6 z(g^dIet)a4A*#LJ3}tKcuqwIjU~)fhoz3l`*0L3_ zDKV?0gWuNNif}>Thda8l;SUc=PY@bV@fc0baep#ZH{Z}ScaO4=SdnnpG~jC;8vp4z z2GlJIghh&o{XE{$-D8|?Q=;a)>Pe4*?nCbIQjCU3q&hYj|UW;kk}RVkYA!JO(`{mOuUWaLea0;Ot)A)}v*ZC@y`z^H7}2 zmkmMlXpZhEZoZYroFmaJi!(kDqP^L zp-^tGJ6Y1jmCPq+*n+Q!a~M6S(A`dM;%pWZ?Zc$;$PthUD^07Bbwfd$ZnFn00o=414-I&gp)I`%%}$r5G^K@(AkJtRp zSA=if7+PH2a&r^NrK-Y4A8K&l8y$pn1Rr{ErWEMlTGOG=5Gl-_ z&b3eLrB%yp-9zl_C^1%2oOlCx8;(uS=-5~`ObkB1WeOVfZCLFdG?3`)fbLQzhEsh~ ztO&Tw#np`SCw?C%An%`f;-TlFp@CY=2Cp+u=!Uf0phqEvea{=MiYEy`A0sUrjKOHn z(Bldu3vuK&jm(5*&}>qibg6nrdWHv|bgKzJ1k>>Hj-GWWjB=qLGfR79DhA)%uXS^I zqnp;k$=aP!Dji5DN7&PFTeBw=^S$=?SlcTGEeZ&PItTPK+()sPdI$%WV zz4r;Bq!tnhQqXF%9ao)`$+#)h@wDbZ#~2U7T!Prk!gIP@FDFKU*UC_g7~YehJ$m>R zZE_Wmo4%{E!Ih`j`Anh8o9Z{?u;KN8k$Z9ty0sNpS5D=j<@Y}T@(;SMEZ%xcde$G7 zJ-Bnfz&i6ly1uR^+9W=R5mp|Cqc#v&ZNV(&ta3J&SO-~)C|FPmGPN508F~@V#{5-M=g) zI_W=$gH;W}tt*iLd~@6T()?06+FM?Q*+vd7H*pL!E!5&Fn`)Z{70`NWx!aZ}cj4T(K_dTp{@`gc(Fx>5F=ldl8;4(qZTa9Tejc(H? zoiN9v#!<|3{>TzE#QZ&9Gs`%6rQr0WlF^uy5dOwmZ*n>T+R;b-rkYCrGAqqZx)!lV zVOLL8$qNYQe@e=0X7MDQg|-T9dzwzO!Qx_b}4&0Q+iT6^wiF_F`B&F9dgtPCa_3c_;MR5 zdZHKs*q?S{Sh!fz?PJkW#t`~!bx&XXNUU+=`f-`Sb+kNlrcm}lWp&;iKZW-soniG_ z!m;RlBIoheErT7j#*tlQiALXYBkvMf?0vgcrK63kkYz4IqJx{RqGgM$zh6rnbexJV z;25wKR@D5l8fIS8c^Bq{Ruas(>ycCKa&Nj2uDL|a(RVQ!~u~tG;v`4Ye#`U%%_8Ljxm$8YI2kYQ+FD%AYT* zZp(6rvC`~*3q^XHZRGWWpYm5Qabr>7)LOL(2`HtIaJ5*l%NqFq@XTBJ?#~th6 z_UQe(E^N#%@7&%OQAy?NU+*kqR#qW(tE+x|GGW6>cM6Hlc%Gym5i>&dCo5JO^HJAK zkOnOTF1X-DaEiFC19gvj3IRCoe6pTJ8lXAt*nD_LMs$%2o|JTbf&~ zL?_FSN{2?im>*{d(~xoq)xegVLFC-a6^0o-sc-*w!rsl-84j^=c|kC7g%Gaf zJ`J4`9-Tm%Jp~4Z}2-%R{s3XVw3yobB8n-s4+k z<;P8R{P+hq;Yjm`hDYGE*)vMBE*ZV86AO0)u1Oo}m~rc(jRpV%6EI|jM(T0|3cb>`TSz|7^aszk zfD|7?7LQ^{A|=!?sgO*iL~6)InnL}5>MV-{znT(8 zJta_AG{EI`xaO+xQltSt5*W-RIt!@q+9xN97WzSRXG$2R`8sj`EAb1etTp$w-+r7J zDaY+l7`W$oz}P|G#XRg@B;K`}XHqr%HB%)z0IKqSiZ$T567So=(^z0-c6UhN^$Lzp zyd>jc*cU6dv80w6F;yvjHi}1AgQ9q;=YqtkxhqIX#oyh$Km}Rpy<$(2SMG=AkCO3Bm@cI7P_G(Rdb_ti4Qb`sC_GGTKmiP8Z zgRs$P&d%g(uRVZeVxVEm_Yd~+WME$(Xq-pt32ndi!v3(&x{~U4hI08(^7;#@FA`tw z0zhawxUR;Ekc?(=$J=2`5 z;VT`vqKR+!8JyRw4wc-Z0j8gA#EVn^HM@wG)0 zIHF&o%Ib^VX{T)u{T@NmfJ7a6Zb=-cK65F8>}o$`3^epuI@T~Y5jFTSz2&OA{}`Ts zP9dEH=Rv^%)VV{KTZ#I(6CTN;ABHlgUcT6JSJXnzq@1YHo^!y-Ry|) zN_lKwiV15b8&@MQEJ0oM&5o=W!lRoG3Uqf|tK_4^D$$g5S=w?LT=w7TQ4f@3!`&3Q zAs-}B9Q!JVxLBX}0w%2%QxK2y4W|Tnd^$yJ6=NW}cEGE<=utdORc49?A^zQSw^<3F zjwtA-L0Nhb-z+ zRWYs_%5|M-dJjjunS(z$sP;_4YE_!#rxkL?4EK{2#_INwlBd@FUO(LHs@0Bvr|~9Q z}I^shH^x?1s&s(tMF!H4Ea-#GLM=~fATfVsR|>O!y^sI2!9yCW z`g58A~lrfN-pjD?{EqE`8224!6qXU zipvF<3R_^=ZRANavK@OJrDg8U%_1%jjY?iOUeaxF91$wso?&guOi3mNv8sRbG(*N$ zeR8eiG72AMAkO3MH;Bq3Pu~C3U7Ofm+xS{JI6--d(i-HzFk6k(L8occH~>%#bXIO| z_Wwc7SXo(k*wTLe2c1E%v9WWd?e2im0L_rf*{5hs(a;{$y*pP}8=IRsprO4+!Qw&U zPSiXQFjsgKe|?;mLHa2B4*x?_IxMHZwKjFt5enNIEu%XA0xOk0m?35 zplJTCg7f?ZA?O4n@CCcL08w;z|N6$^Yli_Tp4b%C1TohP2qMQhiIgWlJvlf8Yi#)4 zS^PRp9k7)M+S@lhJ^T^IFR}r80@la@4W2wn+9DE`7M*(Z1fn13#p> zB&;DNI${#(g*QTOgb30%6xit16v6J5a}Fr&L=#zrh54G-K2-v@=rwEtb*gv%AiQF} z-VPMm5zd}uWF#cap6D|msYmR^Ged?bAERjy6Cj-caj9Q)6nF8_8pZ}(01ub=uC~Fb zKH`)taI=4lphwJzUyHd_CGaD#dt+yCjo+JO>(?yIYN=4VGJJeIAbluW2iuP_fqDU{ z%%;yK?=DS_eX&GFc|8!eC@W)c9_X45igs&8@lE*324~Dk*f6ie6HqXqH}y?T_qQ&f z0aGCPWhIR3*Ec^66nlk}0fL_0G^7vTY=Rt+C1wSXPm!hGG+;!i_UK9kY?yitb_ape*y9uj-uv}_ea*a&?XANbblLUA z`fb`{C%e}UWiuxaxPP=NiuKQ;?+o-$A{p%-7(+XKP~mQmhi&%&1LYaPUv&FDzK4BF zu^?Z^DXX7?oQ-Bo<(vUGV)~K1nF@WB}lH#xEh>IfIPFGFyUt8LH{;>1&|_Y4Ct&MBZ?U^NROD01tb+^>uO712^(94%*Xa8PyO8M}f75+Pdl+6N_ds8qIyVY2XYP^Fz*n^U zV&k#@n-w2_5L;>NgKhjnka`)=OVXpBS>XU~5H3#LnQefKIY0s3Z2u-M_j_=le{kcD z@#e6tIrJmg#K3a20^~qV&6m(y|r%=mUD!oA$88+{YyhFzFFlB6$WnJzqfVcG6(K z5uNVAR{(-cH|a&&9*G0%?K9Yq&=2RH;G zpl_W%s5h@!KiT20(sVq*^}iOrZFf^0n3!Klfb0W!{4etF+g`B1ToJj0L0)OOKBJDc zot7+{Uuejw*ZckR9NTWfZ1pb;?advV1wFDBK=~Mgo<|#+64BX^-fC*;H)V^&*NMwZ z$(M${l>}_HK=#ASd99ji&eNdJYm(|ZUZCGWt)To>Zpro`H%onq?KZzqgF(8Ay z^7i^uz96TW#eN^~T1`~YGo)9)XX9#+#QbnlQ;K;%+0%;6*)S7fA(RoGQZ!MJL9eZV zFQGHgsIsO&Dh@qojCcL6`t#3bJw-9?51@Z`PWk2NHXVS=;kPdSeZ-Xa?tQ#iuEd63?2hsGl#uM0KC&bC(6}d5=Px z*Xt6&ZxUMr=I$QMeIqziRHyX60AfI$zj$(e&tv>58qQR{Zp>iK+k0Re2R#SzsythC zq@JCB6%g5SNt9<&u2Z+snBkXE*w&+TXe=E0Zw6`{Af_ zdsg8QE-@6dsl^wZ_u;FCe@>^XYMQKgB+Tc3>+RVdBnzrzEeUrDho)EzT`l3e?Xk|! z4<5{=@=`Q(g^S94ia&(Hd>4%uqzZe8s{O_AKm2O)=d5j4y`hIf&BR=dp~>7`hNUuX zA8OJ$e~m~FS^ zoh5ch9@{Kj>1tHFhWkq>q)gbTQy-doT}m`u`v7Tj_klM#=bNW&o;rA-j3hmRXa`h9 zGnbT2F+YW@#0f=EW0;+e^>e%MJp)C5ly!(+Afn|yRwN?Sw$Lmc?qF?f%DD!P8kck) zMKFs%4Hg~N#?z!Yx&lTOEBs<_t)#*@lmes_inhmx4Fq^Kf=fZk8nR zGLo%i7+q%G#)DFZCn?tBTr-^7x9T~-QC(u{jR(S$>yHkS(4EhtvjFk z8@06Ta;tK?Qy6BLUdy+9sy?lMt9roe-?fY+W?v^QyHHlRRnF08FCUF{_u*Y9Oqw&g z=>fpF@lWuMkbt>l$gqo%gM|8ZB|%#uj3Vc1D{I0GCTio6*hMkG=kou}o0q_Ih|sPYcG zRv0BpV|H_Vr(Dk2OX$7kmXMYkHp9!9-pcqHt*;xcZ0ec6W4w4>v^QTd3Ez@|aAe|o z)9B152U0;RTCyE8(fjirjG%Ss(Vn>5MxAS=VkFs|Q82!wdNns8R;bJANxuKanL^3x zTje&1t8)t_U$xk(wun$WIEyu zni5KEyF#V-Cp(^QKf|WiaohbBFEem?^U>Sr2O2kO0k5IvHd^8pu6R^5^ zwFu~UOm)v-EX1FG-Yfb#Dx;X<%uT22Vy!>Dj&Dcv+ELzr=JhYjtubl8Hiu-BBZ{eV z9OkiQLCKtxCpB_;kx`{>TVg0H&rizs89c5U!a9^cw|GxP$-GBE!nQBHEu-vK5UB*h zE$B$Z>Po!!+tXo)gIm!YTm}&_=bZ+u6`g8e<2U0MwztZEL=V80wyR~a?zbz!P5FD? zzKp{sqwfG^ z{9DdCh0R5yg@6QClefp8T&-dY#=1i;x{)Wi)`XB_N{{X{(M*EyyuUs7Znt~bwq_|ub# zquMv&Or3C;t-Nt#y>w$b*{JybtMgY4K^wVvw zOM|DLI4)D@sMg-QHH8)Qp1L%yopOqctL<8if1dxyAlj8b44TetyMheu$Yn|QRzM}G z@MzF=`qw~G6S)|Ibr5Q%390UC2rVanw+D8Ky*J7(^$e%(DNe1&YDoW)D!;{Z{&z~% z&p9~5W4b+zGT6qeY@f}%N~6?kkiv(OjMS66Nn{vHS3p|$=h6EnDu631(|l#Kpn_0M z8m&5&7Dc|;DnurYw7DZgm%@yPLH%ESILG?VK)<${h1aNsk=G0QVQP0jk;i3!ptYqx z9bG;}olPqSbzdq#Jj)SvMYlwd6 z)6FcKcQ~CsgAd-}ADbyv0|{luO4lj9@xdmI-B@#hoQ zWZdrl%L}lORwkhyZhN+4gHbtVa*pJfGqX(QJVOa>{ZTp^e8P#VcgQ z8@}%{Ncv)4n#S+WLvmo!DsJr^CFXvVCnAxjWVutY-|ja>$Rq`#uCCvmlt{0e8-@p3 z->7+V`^$yo;`tuD(tW6Z7hIMlo5RJ_$D!ns_{p<)`LKJlDQ84EU1o@I!;vzcc5KO` za>HNhB*Mw3&?@nG+2G0sdlJ!TL;thH6HlEP9U@{_x%Fl&QP#DuIY5A1gPPx%7ne5t z&cUma0n|Vg;Xd@kuKP;2I8v!sL&AhqL&Ds?b z?+0gD7xiDCi!Ffh%3M+~O@AJNR|2{b(Y~raY(vCV;8~Q=z$uZbqVT3`_$HQ3>Y#ATn}Pcw9eHfG&6 z6kf1J3%=4MqC++L@=IU`0;f=8Cw74ASymS$P0ubnEI8hRx2*0A6H_vf^j3@R%UL$2 zV75@4GYNQM$1MP2uO!KlsMibN86!?bc8;I#b^cZuAi5KOIqA(Ismav&I$w>W=N%bv z2u720427#qAw_vXu>#S{`vm|9kOt4v`|wzGb0wRr3+q zeTJ~a;;6iTF^Rt>0>?Fg>Tv(h_LkDCFMx3j)>AuwGTs?xO#@A$pSI;Kp~N)hXj6oq z;oA~U;DGL6s5dwPSu%mIjka}aO1b(j%`3zyyu8}B1%Nx`bvqqA0aoq9DxuBWU0==X5d(A2Eo+YoJn;y*J_V>dQH zA@}uvG*VUW8F6SVhTQbFF;Z|ptakk3ef*X}vwI$TZGiC#6*BeWt5S?*I!Rm60G>3V zU`@hD($?dV>aKIK#0tVJq;&K0dVdz&H1YSA5urcq9d)7WmFX{H5nP~}il~;&<|o1W zK6cAyT)y@&?xdAwEp+nsxsUHRYAC+fKji&?npW!`KJrQWgdkn@@l<%+$$Z}gC1An! zQ1vaWSyt0Y#YUa1|16@L8t0g0D$I z+w*c_D{%qV6G4w}n>APuGk!g~)ANB*wT>>@dp(d7@+IPbLe>8@Cs|j~ z=kTM!q_IlYjmK0rWBFE=@3FwaJcEcl!%`b0@JQ_ zsSUp^HR)Y(AGER9sq(Gag2}fpvWi!NJY@(49s`H1a69rY&ZpwVT-M@&>-tzAw{rjP z)t#P;_NmjOZ`k@Sm_JCReq9N~MlV^Bz0xRzT?HhHL$FW}SxV!WaT&H+%u5S@hFWa5 zCio3!irk(NHTMYl6%&Ypv3j)>OU(7CcRXx{5*t;647XrBBT1YGg7UrK(l#xO_q2`PS~=&rtZzm&+@Q8528gFR*gqsntl5^DxIC* z?LpiHe`HQZf|}>O3%XD;4<^9&vm3778xp(EkNED__udm@_f)qL{#Dv{aF}b%M|LnH zx(|Aly{JKn_hn@AFm|L!^WK|dawit0DcZsOd)QM&GZBDUeKAe9S<0t>lhuwP*HY0I z_mS3q6QhR@j0t#ikLtsl#VQuoAxz6{U)O@O9VwBb7mKu!+PtSOZ4PY4%y(kq-0Ed= zr_zLaaP;oHR+~%9Ct>aw+h7K5uAaF?^*D{Y=lydnTO4&wA2FMJbqrtOuJEos&J3j0($|eCVA^`eapzulM0k?UvC< zX}>Ls?<=4(mF{- z-PO@`&+U5|0xKO^r8#D%J$zTZa@nVX4HLHJ66g9JxS=a(+o(Q_^4nVjvU2ZWsS=17 zD%Uj-J3S+3UwJ`H#EwBo*Vb%Dxh-7edH&PT^Se#p#<7l+!mMv zk>Nbm=aWoQ7oD|$ZX!?P>MsawA`DxnIb99L{`Oh7usn``Uoj2$@+M^jF_~3pi|KGc zB@sq7D(YSG7jiRWKPSmMMYRNu#TH~v3HDT;QC?~4b*-}32$eIm+HUC1Aq2E@TYr&} zYO;-8W?iV$f?+Vxgr8y|3jurhJu;(&8>lo(<4sCJ|E#)3(MO5afCn~sch6j%akYIj zLT+4u96vpO>2LCw#S+N8GtKbqiVlL+&i0L@(@SU=2n&`K!_c0? z5E#-iy@weRnf=VqD9`SPKiyzN>9c@`c*>={hQ@bUSHr_9xW02Kip#YB8))3+Hp+vXNd2)JVoGDc1~435sfOi zcQY%0lKVm(z+s{ z$-^Id6Vz1)9bKAD*)!LhS!c7a^`mWd$HbyUw+|6vnZA~h8W81yP=2$|fEN*!xE*4G zt3u&Y(WCEOC{!3qOW=|!C~hS$Nn*wp9^i+6%wh+C=JhrjvA@6=eT>LdXj4-0 zF5Qdob{%S6(^kpf#JYHSu;whZf;4T|Ex%zdMk?cg(&yx(T{@zi#Z&lmDPUuzv{7e& zGjqS{K%D1SHe|+8Z(t=N>?mnjv6b69;(YOmoL7krBIb40j#nUQk%vK$yy1x|&S>Vq z)#;jzv^CMdt&6k~EKHy^qM1$+{eJJ#lDH|9(23*rM*);wlWOGTkyXN#$U9ywiHQR* znhc%w2dJoFafFg8k9kHk)^Dur8NQK!sqc!s@pz%tmQj)+#q77ICNcD&^oPd_{@$Yy zeDM!bLXk;Khr|${Gj9Q8v|5f-gy@6EBRM$6Rqyoo2?2;=ESH%UORSZV!#AWItCRIt z=UrTIu+Xm2&wT+jG^j@D_tjJu7&fIc9Hj5(UL6-}u&Q{*0cu7SSgOdcpd@^MvE~ft zR(8z%8z#lKioM|8^TJX7%2Bg0t<0K?h^*_$qGx(P?yk$WBQ}5Be>lc?HtS$iw}`x- zEmb5zzsXFlPp>PO`MPP5^QjQK=a*^)^IOv9KK^^aS)lF=#s`dnZ4-Zn>Pn6$1)G~I zW8HLTyptaXn01HxC25{Qm789FUVhpH-$E5W>>TS66XY~My?KA)j~~bY=XE$&om8Xx zMMYuAtt^+`v4^bHCm?-Cdn8TdPG*Zoyts1;6(zL+_RPi|I$xKv2V7$oA%qDPB{Wd| zN}o!SRjis7mla76@y+C>>ykM?VmJJ+{BL>#z8{YXzPa$H*>QhG!7#jkOIr-vmxWx_ zTcF>uk~b_RxlK#cQ^ht~-HotZ5*W{U?0+YvaR?3{SLq!Vn@%x&TJwKZq70>DUq0b2 ziZcj0h3kiL!N! zP9K3-AK-Ewrz@n$dN>X9+tp#%A;Ha|X}_kRy=Gv}b5qau>xao64b*Og80^d%$>v%8 zsO{gj4tU-0D3{9B8v$kn0=TFeAskhSBYX$dEN-$&g`@nH1)nZ|f(e#SyvP-S{q;{gkE#aDN&Q;;FAth z(8anc*&g9CW3oifu0QQADHnpTX+H`EM@fMXMAK z!^HV*)QV?`YD4hCdu$HlgWC5%uU%7OyKG7BxG49HNG1`b4x(J6)t^YPTP zRVD2tK8VL2n&0hVmsQi;mgioTLLGEss+N8+(06UFd51IFmf7`qAgOkm?s6G>5MIyp zQTaje2w7L7aOGOWkI9WP#tC=f%LUS6?(6QLCRZ^^AVzyn&c-l;>;amIy*@a07)y#r zqc@(GpbIj8AV8nS+RMmDIV;KUzvJMkxiWTywxu6j+Q>^E-5PEr)8`!gaih4W^fD`J zheHkjuvVMRN(?9#0XlDWJXVvlSqfW6Nojjyht}Pw*R6-p?_tRkk){H5c<7YT;5;%n z`x>fFo;G^J?RyGjUD$>ap2M=7%bQbLlS~Pg)?A zLnr(wRi&v!a(E7}xcF@@ndYgm-Li7Bq$GmwWTCG7d^~n*7K)Uo5PC%(MT7M>f#QNT zo6RFE*L&->^&~6%5%zoyO>|=A38QT2_kw)5Ik{^4qH6oR3&g~|8&`pjagn!Y*NdSw zGdvW33YgM1di9x#ZagX58gRj^PJkOOg7WVQw~16=3Xk-ktMhoPR*-59o_C zFr#kgM0}c&1T<0cvx;Wd)HDI#`7n_A3*)l#?UjGFtM%fG71jw6fnsb^OGW5JhcoWe zsQrEbA5kW%_IwruK_w(2S2vM;oNc)$o=60LM_cHTYULiRXPw>)*D2({GmUe7)4C1L zGJH3+G~mZIZ04-B+YG^B-_sJfkM{2q_t;y|O!2bJK$_p>$E&b%^Ii*jr{YHU2rcwG6gja(7)H)3+xsIKn&8%&;VWDV9F&f;p_IKk^xGf{M7@0$6=8{ulPj#*dZ_>4vIFIf z19aK#sYUdXLXu@#ssBRj7XDfMEUZmJE zjj-=9VG{-Kl6y!W0}YHG@fXX(N1G$m$xXPUvL8|@>VK?f`u5M1b}@a9qNQvRtnexb zB$M-JQ#cErZh-$A1pJZuaHauMZ+VR(a#*yw6(L2HgRBzaF6A`sn(w(4X0PG}ns@4`#73DPK zEaLZ=pE=+vOfzreMq8o#kG=-K%5aE^pMtvy^6;Ljex4odQsVBh^ylg|WuOYk`GA&T zTGMoMzwgUV8ros9lwzV24CyC`Lp_~;n0)?>Su>g+ zUw2JBm!L^8v+BNMzL)X3H&;g`%UijEDd?1*nqh{0oTn5I4a6)`0Phh`m7_i>mf&T| z`eYpYPI&`~-I<|NMTvW0$??65q2nAw&X6LqW#^=n zYF@S%5ka)O*2&!y`Ma2YnIb2WKR`7l$6Z{npBe1J$y(tX?jy$M`X&t zm#G-u*LPjd?0h_UGE-EM)uq&yMMR0+rx-3NPInAboWt6fL-g~~)(;sceEFEJ27Ojw z{nOI8F!?M@96*YHIU?jI!CO24E~cX;ZV7HV{yUTdXp+R)^rpJg2qTRo8vXn(mu(+= zN<5f5B5v(`*<-wAh#glS6#EsU!dI-=E1PZ{6j1+1hBekOAnCxy+J_1@8UlCe^`sn~ z{cU9z4I+f5bKS1-Q?xO7&}Qz#BJw{9bUlxJbDIsyY5N8w56qxd}V zC6UBdFE&@wjyNk6{Vz46_!71_6*h3trZ*)@ODGG8)8CfDU^l)!{Rpa}MI94- ztI~@yT_T;9flrA4k_XX$p2@%D;(xRva}#`M>(pI3Qv>zEbDiiAij&+ZG~svLNd+PEVaYQ*lAF5c zmwvmDW!=U3{Nu+Y8c3<~a;3$j#^*7$XHHlstv2~dr(Hho29!lf6u7F$OKDmb^GSAN2)zi&q=T2Qp}A=LmD-68ZBtl1g7d;Idu08qVT<^O9+73N znXpoSFj{7ydc#--;*xZ$|=zIRK-ko3i*{0wertz<$aMb=>*4qT4LQSfB;-5{C1r*!9c2I@ynShexK)lM774 zflSmE3+Q%O`()LBjGRRy+bVgw(SoNTBE&#KFj{LBw<6cezd4;hNhw|r=wzie3lgV) zP+hNtE^AsPNJW)9zbX%v;++ zR{;c!B$n@)`ux#;<_tyV?E_TXJn$s^je4!MdT(K8drU@r7b^_w*FHa+?r0Uk7py8K zhFJ3i&OLF$YwYC3bjao;ok?gan4qq*=GEZO2AIe)E)>M>^y=CVhK#9 z`bI?9qV~O-QEGk3R%{eygHR{)lMes@d$I5aT}|dPDqfuNBMdCtm+}srGy3@MMc#Xa z%ElEHqo&mk2oAS$e0)`~$&rH2Zb>#tC5$3i4TpCN?gT$_+K?r?!D!(mls`g$ut&2u z>LviEj!M)taxM@4`Oi4dS?xF}X&PZGDrWY#ry(VK_=}y=xO{PAwGp2t9$PkqeXUU{97^z+k;R-F z%O*V&N%t!1j;)C0j@^j|M>YF@2Sma_t(!RZx66gsCfGJ_sXoNDj<&*By(>+v+t0Rm zpj+RYb3Vf)!7p=@>4YZ6%bV2uA)}w%r%%l>Z{&M8qUCWcW*?Uhx9><=|?;?bO z+(iaC*tUpx9={Y-y}XZxz5Z!6bV^e1BRW~Kr44BE_$D{fDPWBCQ0;numprYm3OAgN zfhc+H6A2^t?m{UiTFjG_#8(hFkCDXna4QO04>W?D_>w3~FJJ-`6#p zCZ-U<-np2;sh0f@JL6jzbDd~AYw%43wwoLuR&aHCfc%VqKi)5 z&K(~xO7u86qwEjz9Bc-E=1<`!#e{tcHYN%PBllw%3+l2=%fc>XP|#suhRyheLq(^& zv-?OYQ2)KkTd3fSo;BTnVvDc<_VK=pCZ@YSOot{$T$z|Nl`i&Ju%nFbE(aA09=_t; zqfatxgEUzkAS@)BjN+s8PJ1O^BR?tGDIk`X7v5b=AT#6g=&784j_`r)*;+LSHyH`B zc?yaLypz)P$R=J9b10|$Me4@rv-OdlX4%7;z6b5=UCWqnwnI|PL;U2(0w+_gndXcx zCxr(U+MVc-rh+k}0F*8S{;HWH8&&*{vB-ku8i0_D04WRiz`0KW&h*3wmvC74?D`t~D8O15$GO=2GvONX6C)Kim zRhN5p{DIz%nVI?phl;`I;B&ouZKkQA1qqNDQ+vGSW5wD<@9ed;#@%P6@7Uvrb>jx( zKR#vWyxNveZjSQ7;>+IXay!9+_WC%(9Y~OBfR%pe1S2!{S5VZA z5G2T-6ehd&^mC+Lw2PN*u7^?7Kq*>3Igxj!A0bvm-A}a@f!dHQU?*X^QUaw@>6gte1;^+qNEw(4SfV0i}U2B$*X<2k<$R{r(7!6h3 zIk|h0N6C<@^`EdAbH+VJJBRTSRway($J$y8S}kQ0Hl*@4)_^hM^K6-BAK2rhA@x4$ zC#J#ClgbX#qxHULZ+{lrdcM&rCyCq>;a(8qo-O5rlW(${)OL*; zpX?8Rh$Gl~yaAtQUsLmzgud~MNwIZ<+&Xp6XuDMp%3#noqlA2J%D#R=YusVLgkiia z+_YeINQf6GPJG>rzG=pXgI00-xzli4K6#{_x42^1vnOV#?8dDSIK^`t%Cv28&gROw zGy~fz(b_9CiVmM`I(2$aPIN1j&aS5lFfCz!P_jpsaWAV1{G<=nedDKOoF(krO~@~0AIY$?gZe~6uT9v{dW-Y& zlP9Kt{!1j6FKg|R)}Aw$xbozR!Q~}-Pg4r8j(PXYs}=xvPmK2qEj(dx`Z8Hn?UaUp zJt7u48k!!cj;uoWDJ_Jj!_TKTzoguW{2T7k=!@sGqsVER>(`BIJ~_TEw@+lAX{_Ze z6LR#`mQphyEhNJFr023Be`okOyTVp)E)JrVU)n~uFEXZz_(B($71nVJ<-McW)S(& zM{+D1%XKw^O7r@+HfWjWb~|DtvMc7H+Wuba0lUVLAqFVovOA3yBt7Hy=dwkAE+MT% zJguEbk68Ep_(dFCN{t`9zm|^RX8Mi2Y_G?p^-Xr@ZhB1Z&w;wS3c^|1Dz1(9NxU0Q zd%Er6IvzO7_}zpqK)v?3(Y2`*5g(0Sa_7)5>e%_40#dT;wwM$H`h&>4h~R@sQc34f zg;1>KsfTJqfh<%9c-RNj()zc5{=vprh@hwiH#nlt(m>UB_qjQe#G_@lJ&Y!@`)^ZT zd!3!)x+>x*@BE1Jve?>>{mEd~ul)U4x$i>DNk03hKHW*YbgynbhiF}IC$S>usuo9o zuLlYv)3JB#>mmGt4CQ`Nv|lDKwdWLA@=!lD(6?P4EDu8Q7S=0%Byzel5H8eH->e@3 zk5?)1D2^pOyL*@9rhK|gnVPO6Ed`TqX(JK;A7QAGB*k@Ol59obZ9alGBq_YlVSN41u`};HaM5z-~lIpY`bHSE?u@Q zT(+^xRZrQrZQHhO+q-sQmu=g&ZQHi-z1@9J-#9nE$Ul=Y#~f>Btjt)kND0O4?Oaqm z9ZVT%8R;0f0Lo%Q8jK8_tN;c&W*AaZVJA~V7fX9P5knVKE`YkJ2|(G@0l>%vU}9ik zgdqh8+dFtVS(;n804R)qDgSK*sM#2rSlU`T0o3em?A;Y{5F`KwL{EzD&K+gZ*15o_KAtk`X)a;*VR~s8SLt9e-g|NM?gR6_F6F}D9 z#MH?SAY^Z20uc3oa51$rF*W(0XhT~|8_)mW`2Q0j>0E9B zH6#rGdj3b!{l8H{LiQfsv`kFw09s~7HUJ|#6ElF5nZfse!8LYuax%4Z`8VzV^zuLY zzsJec)Wg&mW^LKtm^;KOr8%t3PqbjR9GrS~+CY_hnGtwps{2M8*>cdrME~##`(6b* z*BuUTCeVm~clUBf^1g}4FwPY2cw#b!FhX}3`?ZL;+}y8v>s>MLtu8|E8cYq#)>sbg zCi2cDZGA0BfohT^Bm2Bs%CUqOS)4J(ptQXY9BKQ{>cXR)IHfK*O1joJoasJw71FFl zX#TYk|LfiwNO*4WF5C?%mcB)PS)jvVxK{4|qhb4huk#J25NcbX5&I}+&Gxp;sbang zQQ)759hu#=%^XM^rEoGbxwV#n0&>P~|K!YOm^Tb~0())#4 z+*U9Gy;gg?6z#{W?bVj~Q5-Wxk_mL97G$({5s^$A+0DHA9Vthcq^Ed+O&xd*jz`<7 zRyH5F3Fc$?R*W;Y9Bl(}w%4D~9=cp_wiiWz{-;t}L zInrL8KVx}MJa!PbjiOaJ>kJTG?D58PO9~T;^kJ*3Ea%wjkHedjZ{ke`x+!5DVw?}| z^&FS;iNZ(Jqf>ITSU}6=+H!xjcRfj$z!76$C7RtC+F1CUgy=^}XBntKemDp7&Wjg+ zA<0j=NV!0ZpqFCBbA=bXC*gqYsjQm(MGyiy^3~CprU0P{h!Os2coSiUNh-kM)*9(T z!%Jq*5e(8C8V$^I5Mi|t2ngfS=hI(KyJxC?Q?pW8c1CaB_=Om^M6JOo6wv*NS+cR_ z?8>||@#0h;dS_!#kjCKtZ>v_&Pcy%N8FbW|)u@n=??I zZuJdp7}r*fq3Pv6sVc#8*`w-g{kx0FsX0qT@MBOe(F$z&JcFNeQ;RdUwBEmejhzY$ za%6Kkdb^rk*nL*iMI2uaqKc&AsMx4WV1;=dJf8XPv$%AIcf}+};O9P4Qi&6A9=b(& z9$UDr&Vgi~!%b@jRO8aV^)rbPVC`*$kk=+*;$og-*PKMIoZx1IHoX6J9PwR+G87m4 zTo%kv6Vc-L5%QecAO=nHYjf6rz!8wYyY*M9XLmffqn3|=olSbLRRgT(2B<$I{#p4s zONI>x+s(*mzV?AH3$1Q-LQo&@!g+%u*+dG}vbr^pG)8lp(`E8f#&VzoHg_O6kzh-g z(5*){cYu+guX8>L4n@_Z5?7XPQIqPNWz-L*>L)j8m&iwWdzX*z=nPzcl9-5PmgF!rQjIJcXYK@gfE4|JX9^H|1BNoG6R$JD!G_tNjY zfwMR08BOV1a&b9`BVPr}TbEXGd>Dtl-7*1jotaP3y=+d*Hh(;Sy*N)}C31ZMNMCo`*1TK7N>8iF)9zqb$L#o#}@8#Rx%`dWvz~M@5FH#Y{$&D&$B&kPb#s5TrdVB2nd|f2+ zZ%t;f{sUmpe773o-{MP|8p`(PDc+LUT}v3{VuYGV=ya7cYZ{- zd0v606K8diaA3+o$8@Y2dI0q`eo~Bzbcfb|!&nx}Z^GS)Koan|2J54Xo2)%UZ5_-p zAt}LOBkBDV#oVL>v!MRON-;d!_pYr-1WBg=Jq%5}JvIr{pSG3_pG|>6Jt#g%s zMrJ^HS7tOu*AG>83Y33iZfN+uNXH``Dhs+KMb-4m?z1Dp=}6vH8)_NrKJCP@&tKH< z(TTwcyV>U{;@7gJpK>949$yv7Ifq;`Ks??(V1e=r-N5Su{8$v{H$0|_n8Ptre)}Iu z%T{TEg*_r%O$BHL-WxFO!@1wCN^AswGQNkdz_2hD9FBNyFaaph7Hh8rHzAlU)sq%= zkZ~L!E?04Nkr?tnnBaj2_b zY>F!t!=E^Nley3FvH+H+&Xc&uDa$kfn^jnHwz=1W=L`KY}SjU^>atsvha7@`vDuOJBlZ{ZDE`-AMP!#N=f@-b@01#62Q2( z*j{QkYxlxJRz_M&3>5j(`?x95S;HnzduF{Ixi;aNB2H$vzJpo|_=;wKe}v~yGPyq@ zi$~wuB)NwUi8vUXm_hhY`% zk>4}?jF!AXWzk)AMOa$38SFBT+sx)=yv!oqD$3riMd%K|Q$MB@JN1JjZH5rf*EPWh zQg)}STayY|g${!o<-=Ql_0!^jU&oc=Bp1xzFxZPSRC9lh=uvY{$*O1yg49%rN9E4^ zSd|*A{=RJtC_(V`BZ+Lqel*e-uD3)XK$V%(84LnKlDbs8RP_1qDeTEB@R?zgTm1fj z3Q|P@1I1%ap3anic~D($Yhn<`ef?l{AS$qEcN3J}1qO5wDLZa|;*+k+gVq3tjQ?`s z97oH>?&YD-<$CVwV6l^`zP;CgaaL7!T@VnSYBf>|Dw$fX(4xMxr-8Tw!OQnVQz85_ z)e`#5RDq!AXg#jzZ!zL}7@AWa8`#KGBdjQ-I6WpmTE3t&r3*vUeI#O|Wf!7t6Ek%t ze)38huLgs;$ble#-3c5K-XJ;-^x3BmM^UL2p<>*GUxE5^NPd=Z`zFnvb!gSdl=J=t zS59I)Uaf%$jLH-pM3tb0eCatWN<^UYDNM+TRA%yMx9L5Qe2Zrc0au;1F2w#F2I?RF z@os4BO3B?cZW}}VV7SYOh2%a0Eh%l@iPk*{y#gmA? zL0(Gpa*##N4GHvI0vYWgmBkcWFB(ql_>LjAW79I-N+Y(bGfPMPu})5Di%Qk#6|kG} zIbv-laZ|W|0sX4N2lZZzUpr&F`f!RPZg}a`iFbh>^WoqRl^4hgZ+G88IJW8E)R*z5 zj^Vf&<5v3Ek_6Fc2={BuZ)}Xk?CZu(5(>CQ1y8B+`BVZN5)oZrk$VC*4yUL} zdlu45Qav7e@ao$)fTyj_mI38lw;@gzM*@;S$wm0Sa$~(D6;csTjzF-pe)!KX{Ls)< zL+TiRv1liU1gZmbC}Bip@BDQt2@5SC|Jf!g8nl_zx#!ia>m1EIZiN%t)yd$aTX!eTlpr^PqHZu`wdv}OivuEmsNDA-KRO56!$@Tm)6q=yD4a4z9|c-a zc@h(QjO#K7Ly(Mfz|R_NR7E zAsZ+NPMg9bK^j*c3KaKs!*puPBpjUqV8{|Pj$3$=w70N(Pi zF@S7Hzh#6xPS_}i@F6jEx^7w0f2sg~TVhm!hh6&Z_9fxNP!Wvu8*zlStejx(9>)bq z=m8n^x25HY_AO!Er%?G}2>wqGT&u;?5@8eG$@3dfI1Tr~!rON_t#s{iz7`Jhli?le z0GF@+eZi%O$;8+?PS6+DDDL_~1>W-22L0Z6!i-V@|D*JdQAi&J40zpfopVrsQ&;v4 zEOxuVM9&Teg_(3nreA!T3?3e$D3*^8_ks-@=~*Vux(b^-y`!`)qQ`K8@A{qI&PKek ztu<76Bn_h{y?hW_iMn5N0~m-fzhh9>dY(YYuWuQvw!$!)8hW1VEM0E5plQ}uXe(3E zP1Y?*5^-HY+`QhUtYgg36p&7TlMtM-mb&)D`EbIspLjd#Zhb7WhmxjhAlwa5L(z*^ zp7`7<#Ew@x<}-WN@b)7zhhrwXJKVU z)?`J!8WqfZd%`SAOUB2{c^rnoMp7EiJo}pu36EM}ddwzaG~}%(;bRSdsSQQ>f3!YL zgEFtlw;RC*uJs!w^e_i(KjJ{yM_Ddy{y@?#KUiC{HE$9-4M3r}k}?E6vS*1X zUo!~@-+(cjuRImhsB})^&+4w%$zlzoh!k@jho!aCJrJ&x;%?>hhQXE|hLRMazJrap z)z$RCU05oWeCc}jr*FA`il{-GgMgx1(B=>eGpRPe)?jS(kV9DCCXbn+ygoY!TW^S= z12s#q7IVf5+j=`5(FvlJ8&e`8jYXxXedMeE7N+}J#S6?Sk1n(yM>)KF%k9K<--{x_ zQGhqA80b4ErjL=n_%WJiVSqrb;&HFVDU^*^ZPjN+HuKb))SV!Izn($*%4Q^+rTY~M znHaA2H&mT_?N|N;(O_Vh=k)R0P>vn`iV_m%TREq=R1Nc=gO72ogf43E>5OlfkY#(w zXWqa^jMaWzF_nH4^8*PgK(ebQoBPuO}GjK;n(zyhgL{yn&?BP;Ts#<5FdJT zFY93fL4g_~Xz+l4!fBr~qFvoI%wnZ|b^o)72yf%KS+Q-0%f8^@d@Rbp0!QtmuGw)p zQOCwW`mXo5;+o>0lZr!Ce~L^y`2!B)ogn0dLBAZ9>Pg$Yg%C3vu(3b>Ce5KX9oE) zPkLAChckQ=mYA>_J}|0Yy3XSLy(`w}Vo+0 z;v)wLpL#oCXgB);e_P&CvPNW%i|7H-e9p^RTnKPs@J|IWh0C?bR6CU2Sz?U^19F9GF@E0PBoMWLS2q?oTwHj$F zbhe{WgiI!tjSS(GL zQSa6VlH7NO_8%FD?)PhfXJtbed?9&JxIszeZigpIRTvuZ za$ARczc`TKP@>x?Mq`}Yyz+O&;nF6PNtnb-Lv&PZz!F=zj={@>nVqcI7KAWOwXhwV z&O7-pL#N#iR;q%(t1-XNE1>~f4jA`T54PVq9{?+0#ti-#rT2d$;U1;e7QE1b5o=JKt@z;*FB zdr-H7e|pJZWaBQ7`#);HLg?>F25~h>{DLjbBlihtr=NGOd6xYV!OMpPq~~bRb0R_L z2x5M0UW$1uL6>@pg;wBloJkIm4%3eX(^ZQ%XLzhTZXWA-Kr4b3u1W_-e|Lc`I-vBe zX)E;Eizghp{e)ljS`A!{gT5QSze!CTcn0-4e^gt0Aw90VG*bRfq`BKuQ$jfIU8%k{ zmwvk|fD{wj`1yDH;X(u}r?`n~Dv3aV-M#pPNyD>fYeR(va!3Ts!U`{eYXsNb z8M$nWXgTMo{X^|lGH7WY8yN-iIg1M=c)UH zxPC3Ecb`6eGf6|mHPw&7^tjGvokXRfAuMh zg(QvCy-GVQxF*m7QPAsMGSKl6p#J6VW}w8#?x2R>1$M$|Pvs6Hz$ z4%FQD9jI+2Tn1T&)$ILy4VLyIL`hZ6)vR4W?NWE~^HkG>kAow(u9t~s!Wo;*dSs9% zw%+*+&Q+Yu|I2C#j1G1oMGI)%>N6tP=x;# zl#Sguo9wRg7clrhn${G&mZU>JO@5*FtzMAf~L;>A*t;g0@e+y_=1rcme z{ni}wz08UmhU~*`G@VVDkkfT3Rcl)vD^JWs6=!3LxD3`gorE2X-jKvJG1}<#2Wt%X%M9b8gY!G zo{iv|NKI}`Lp}Ld3>#_hf2)D0%r=^2VyiOZHoWV+vloCMyQ8U&*fzb!jW~@&9Hvob z$yehE-8$yqbhiO5`ybeo->9&=v1J+Yxi94{AI_QliQ0aVucG{-EorUD_@sN4>NB?% z%+1I#sqCSzJ0}k~H0_1qRdrlNRq{Gvn!1Oc0l|S=nkwRLyK}O?f6OZ3C7Nk3+UpgNZca^;|v6hOKUEm!771E+e+n^H51f(3w3QrM2 zz_Z>80T+~wsG#O!t&Z3xW z9syW3os79DCo!2>D{oa`%h+DjWjO!XSy2C`c&=AU36a4zSyGA$Y zi!Sb@8LPa_f5i>thL|((X{&T>iuxNb-PiHDCJ;^_Op+yKizuLCZhecOF@VBA_~#_> zB($`68b9#WnTxYU8ymlT!_}n?Klv6`9klm03M`KDy-8jf`KVEcMp*z_v36(LI4Bed zqakGaXa&2myd>sug*Oy>;fKfGGnELnexuCA723$Ue}2MPb*rPj$w~-79drLrj+yJYM7M@97JoEKi9`ETnbb={IB<=L& zE_NEGc|WuT=jLs}uzp8ztqa%pg9+XX107)s;bE?lcU3@cln@Tax*gwWfdE}H2&2~# zCCByi@WMbZ{DE6}TSF%sjtd5b-S1q3`P_VLf6Ztubo?I)gsp8lUL$UzfU0}U6m=Cr z2+fe&4p?eDKI>M{WG$VvhMX6t!n2L(gMf5h%&c%#c(f<3c*hfyMoA62TLFd1+k8o4 zpG?{1uSxWk<&`k-1V;$D16K503bj>JHRXl0N%0Pns-KE9(;k3ZwmE)FoGW7scg$ko ze=wwk*;>lTnIL7$4t%Qf7^)!WK^7-u+FWNv>-RF#?h1!(M^TxYxDDq zQ+yuWy|RCl#oRP|K%joVXK(;ol)bnyx=)|*}B*Q8{t$OCPu zDwf4DM-WwV)P#D=z6?a4f6a3D43dh#o*{6@-N(CGa6m!*;4Ue(;_1lI6A zj1DUkZo#a&5Rsgen6uog_14aHAts?^!Z;a}zEWwxfY^RS!C`a{eMO``+)UMpv(NJi zGgUyfMz7NUxib|KI%r=(F^9`tMk9y*D*H&IZJujA7u`IoHza}^fA{qlC6XH?qi7DO zui1zBYb&fe)R6(sl?TpClFe1B#l&PzD`i$r{a5_feZlTn*ZsRJAURGeB{7(CWZFYw zCKlue*g&ZLdNdo=9tgJ1qrpx`@XcIF6D~YwYX;iH`3V0JC(vU}4CeycINzei3{pI0 za$J5dKZQIQ?;&gNe_D2~D$$d@_K-_^XIh2AwGh6Yd{*GnO(}zI`Yh`5PTnpRFBB&= z;yA?j`Ec?*iw&X@cXO?+j*|64vthSc7gnSX_WB%L?zOGWj+XER-H8KrTYd|(kfh^p zaxV&@G`+b?DS-ly{#Y=Jzu&F?6Oux$qK`%syxu|6Pf%kCe>ZWmAVCuTAWK}j?J5P7 zjJh+@vWwp8bJO3K(%%xn)V)2&8zLWQNeu$(gWRy<$gM+!N<#%VjurF%%I zNB~Q#9QpMle*@T=m3<9O%e3~nKnPJDOZX!vnw0&UyYb{FDPKO5Vh7{O*+?&+R;~+l z<=uNg`12_Q*3CGYC z1I~`fnJY&EB*btQIhr9#2~sG9(_{;R&a)a8{BV{t_z)sr5wi297k9Z`5S=*0>zmw+2}e${yRm{JT&)OlXjyh0Y6E6uQg~-$*=?Nyk(4 zP3#M%MyrpP?|~{~0})s0Rjz*@`s7i%#3A2X)k%c+;8;4u*<6a?j!g#B{rU$v&7d%< zpe0{$o`ds;20#II%{58|VHMQ__{Mfp--;eAfAVS=%B$r~uJ^uTgXa8mCbbxsR#CH6 zX(REQ`p^nPzr`TXFOcfZHhZTiibwE^2O{ z!9>YooB5J{GkVF;MgC{|z{jd-~ojUt3dz1#a8?mTqY~Bo2{^ z)Wt-<3|Kkje%E{hZZcfh3!1Gjc&X%@skLQEUt^)vU1#-_tM8*}gqd22`l5e!MX+MJ zwPTrMSgc@vmSGqw(+xW|H!fzYg(>cVe}%>lu(1I0nXg~cV9juFTN)S~D-ecT0p0D| ziZZEJiK+mIHqf=5lU4i1gcqqNu7hSlf2@6?V{gdz_lGlp2_TYYMp_GBVhb0Y9klml zk9`NFP@1mDP9LD?^xsp8;cw78xoz;T)0U+X}-lr!_ova;#0lh(K`6q>j-467$A(o<~lN{d^W=>c}Z1rP0H=G zPRc~7@_JIjm{seBBc3fkSH55!JwMx{tZN$S2>VLLKJ*2O`3|f2q)G5m)Fm- znmbOra%D}tZ)WFS&L-GTV&w!qY(-1tk&Z!3iDi1W?%=|WP)+{CLSD6k+B5LsrZE^0 zpG;z^c}!bFQu+!PIk_#b6@Ykr(`zsB&zF4pbQH<>Aa~T=8~VEjCT!hW$|Ie?X!$y{ zoTqW-j&IqW;f}GjBt2hle+6tmn4;b}*ciyKMR6$y208$IC7sYJ3VHgV!|$e?q3P({LiA-vM#f zY32H}97tlTJ*R}awx((Bc<+EDD7TaxDY{IF^jH)2To@CTo``z#^&2_WfEqX|r?)4% z)2r=A%l*VF!+rg%b5;j1fW^24`r_47X7xfU)A&%*_*#C|Aitke9u$Qw?|GJ<=}*Ku zd}VWKn-!AGG|4K8e=)G8ksJ>SET((A49Z@FMIEXRsY>Y*@0=5Hl=IR<<@?Ct=L2t5 zdFk%rwA#u?T*NrDmq}3y9kf26nDMPkjlH6E7=`&Lx#XGf0H2f^KX!ZdF<#~?TT6M0 zL5{nJ7hlx8f1s@k_8n%~-9{0F*VF8d-IlkvfU1ap6a8h?hYHVuyQ?~w+9aaIKX1!W zCa0|CMj?21f9yz_T7LWs?9;CBDnT3#n-42pjOmH--q`I%y9o3z5*u}pwCoA*uA$Ib zPh&;(6yb#pxTRB*gsVQwDnj`hpuQP9=0;>PLe-}TRA&brkU#J47o&s>a({u0l z*kE|$s%lEj84Yd<^}D$X#S7Xonr_6YiAv187ASNsD|{)6BqI#D}rFo}o^#z@U{@yr~29L`ceKVMCmNbgl*l9!YkijixgU#3h9( zlezR3-EUEcYdhzv%Kx&Z5`(URsks;_yIbCEWq$}H*%quQ;~}PmGAu?A7tb6KVE;n8 z-OJc;i6v_vZ&aRry=8Sp$rYZQ$a^}~%$)NQf8#^^644w9Ke(=0A;795Jm_U8_d<0$$pdY z+~sZO9MJT`Eg!M{creTj>a$Z+)eT#ayRYnL)&q33FF_>|5w#McZ*I-2$NrqBf)kO( z_DZ}(FH~l~qHpF-C)wdmy|!F8FOptkf2R~r0d+d0tYolwuK(pxb`Kzqe_W(^4jM?K zzP`)a%6<*TgZLH~f>BwZhE^t;c^dAAEo8m15{*f*Eu;0pS`IyMJPkBwPS-KDT`YM?>Xc9a!S~S%emxy*F1iUA}{tk;~vuXe=*sxPEE$+ z0KQn%p>3^jfc5j3kjj!4T*a@g$aNl<67X>X)061yx+sdD_ZA~!kkRkwepz&vnY!nm z6wZB}C$dLvGt*YW$PLjC3>SEztMc>?8NPQrCwa1JP3rL`i7fA=qdVc$+Z5~Dy+=wYM94!;hzE~8P}G%=+3Dhi`gUD1;p z{VVbWIWWpE9B=xNb2VOX)qJD_lvncei!g{cf>m8}N~}kOaUkoZ9Q;8Yy2-~n#bWOg zAbsUvLbe&kqcN9L@3iStqlD)8F-Fw~Wnu!4DCZBXPDJ_qUDvkvf7H`%$1%B?Z`+ex zH!fHvxvkn7pCnT*gJ=;(K_ZCQU{%~Mb=Btb@E;m%cb#xf0axZH0Fg3${K30Fr3SbO zPD-HHl6gF^ILb~0GnegfSq1XQ z;v$adw?h&}=aDFs2Xyo|+fP!z?jeZg>K zJMMV0{Uw8t1>dcx4Hvx2>CJ<#Z=*OJL2cD(O{N^DOR&D}TuCPrv!RE1gwUKp#myA+ z4FR})My%>SD=c-3h+!|Wc-h(#1K@$Izk-a?)7DjAu<7w=4r(|uKN^2cAL`9S9>*(R zLasa}r#Yg|e^x=`xe`o|R%toodJNWJ=d*n3vAs^(D?|0iH;Hene=deV@WlX9?1g|0x_khnLPaB7wrVO;bsGLC@#LA^p+lO~iz zz+qcQL}wc2tY3)%<}bsUtc0Bs0YLfaRDl}jW-!vH=C;>i`0KQLj?Pi=GAsvWD#B6P zV`9T_pnyl#m8~LhR#wA41^&Tp3qF2HY}rhz9znb)90yn zUSz1m84L+Sp3FbeZy5z$?i?4l~2)=YwltwKZ|JxM1ma%T&_mjzDpRo^d&%t&1J~ ztheS5N<*{rN={3XwBR4o^QOn%VovQN_U8)D&HHty?=a~>o=vXX@%y#7mcEc*3|ela ze=PD7IiPmFwM>rK4_ekE@~{u;r(0^I{JboA{UkY%*kAF_YX#nGG!aMgg)(5WfJMJ! z@?=6TTJK=*(H9gt>G-Dt&n_an?@z2_hK%?w6wVGYw$Vq|?<)F(l)f+Qks*q0j&AQ^ zKb{+uZ?bXd?MU`hfC<^Su-*PkTCR?If4xD#UIpM|z#qGB{Sb9Zk0p4T2h;qr)dv1Z zqM6*XXcHZ&SUkH%cxm%NU5IL0{j$JQ35%F@x2}uCCWvb?s^%=3L$2l0L7!i6Si-~< zx?(a6=;COUKZss9)c$m6yfg`CPKIdL$_?A>$Npz96~5pFP2J?sh@E-jB6qYce>en% zBYUD?>m)He*mzMl;9+PfOv)O39)|<@cn%-nJr8eZOXC(<9#LTwR!rnES`)Ja{j;Qm z8lT&ZwU;|VtSqSmEjpX(2>F~~npb!0|FJ_$FUyw~2n~NU?G2B{%+B}|(yI6On))FAlkenC|t3mM;QBc_D%Y_JMHpwMT_#q3~~pRPGIZA`?g! zF>aZQ@R?$s*lAOYH_a(30t&|qSI!VNJ!zve+@K7#gFu;e-9^IWud+`4Ei)oK|%AQGy6uPDEm8+ zA;F4zS(kf}*XFW1m@7D0iy0FZ=HlXci1x7NlzxkA>k>tO^iaLcxMoe{sU(aW)bY;_ zsWdi;)pa(MC~16Gf9hQ7Rcf3juL?Nz|32C!SA)$ZkRsQ`7-N*KKm+#FZh;#?BAt|i5G{}aQobbgZjU66}$_9fox_jW>3thdnlwWcz-)y zsl!3RXsaL6vVjSYJdgErG5%-ECadF^X;T=w?ecCJe~>aNO8g{9wRo!7Bgr2`tra)3 zWQ~7D_;Y%;BV@ExRK`=+wxDCneotBflVANy#I@QS@wS_@`giV-9AJHD--eKQqcIU} z&oF^_(KoD86bx^iD|_b)$9Cp8KlqZt&lzoZ8`HXX@i4EfkM-LU8xWC!w={o8qymya zLwW`we`1xPG~JfuT4N>o!D6uTQPbT*-x_2P7E?HAlp;e=E?e`@2chts_kpbKPD4el zcv>fQg4NJuo$TTt6FgM@Z88?9WN4AMc%JUBjU7@EXlo^a?W?sX#S2yS00Tv#a+Jd_ zDSVgFfz+H3SFM3ftOVKdef8s((}0&-qge5dQL|*&m8?&lKKgiTm3;Om>P&Y2w$dUoYF529g^Wa*3;gG=pb$leD)5p-jalh z=@eTh(Qmx~4v&^_3C(w1{El}~?|tj_UQx$u`z@P0xr^c0**WBp;`kQfbtgmSe}mhw z@BHK4_-i4iS1{YCnYfClDTuk+oth(&lN{(5L!I?{&irN2{7^dL`Ilw|R<5Kb2sSYo zFtIetihaIE!1y?V+=c#I-$6M&e|bgNFr%_b<&iyOxAIYfRF+q}XAfT=T@no7PZwD- ziN6X?;S?8r8Z7=w094Rxt26L+e>$F-hn;B!s6~2whR(opd+j=y?5^R8$Rk;-Oor{WFQt97 zDkw7r#JcQn^({I&iqKF(F zS2!0cP|!hE6&psqY_3BzCfFq5Nk%{qJ2BsS!(PM^vy4lsb~Ohnm3^(L>tXB#h&(>V zPQR?zSc^})Fl`F?V??q=+uh`~W3650n`D{Q?%HLl2}-yTyD~-rTXFh3=k0o|UdR0D z;T_WJOBgAaTQ2!6e?LApyJ*@ND2&9wvDiroc4j4oNPA9nGC13%V*#Wv}fu1&!I9MFe_&i*~+bFoyI<@tLfdJ@};X1C?gcRD)cBR{uKi z-(yXyLqZVP|9w_}Zu0Z+ngLu|N3EOPR~FuxqkX*h%4x$Z_yzyA!m+W^(;w^um!QoB z($mUO-g-tRf3Lxq3Yr^{CsVO-#hiL?fL16|u0-H%zn?k2htoNhlU=aCSPl%TYR&eN zYEl|ghGl0UUE`$GZ(*wV=3Q8raJt)XLQW7sqCm~mj}sGIpaXOV$$zmPar4b|sG|G= zd4NqqAL~9BbMu;J{(V~u)9TDHrGb!_)7LGE-?d~wf4v!S5^&J!c0OIDh=D9(PPN0> zRZ4*hEP9_@^@lJE5AB*sM>MlI&M2+v#VaqyQaC zuN4~_f6fAXT>n_FHuTJNg9~3l|6X5BQ(pGOUF-2|=s~B=U<3w?Ujfwj|IfuG$N%RK zHb;YVZJy>A?#DfW-n??umS}@7+?)USIgn>>1PMx(CJ}mZg9Y(^OVORBu0@aM8|E>Q zApI@ZpBo_zZY6x!%z58+rTxfn&E=q*6Oj#Yf0TXjnYy}i&JxEUDe5Sb ze_#$F84}TBVqkLGCv6p@oS5dW*uxuE$2cpDswmnr+!!w1J?Rgt2-!`wk{QJ_9bNlD zW}{7X2!+3AestVjHh?aY4*mw~167xySu>g#y(Te#9zY6+*>{yf8l^ir)cTbftelun;t#!ZaPu}H(KL67+Axa zaTqE&Km_>j{VyHlOq$;0`@Py@aR<$gW}K1pdw(!Yi0a)IGJ#O@$z+I??A=t4J$q=n zo12VPb*E(#hV+|<^}7Vfb+H#)3XDI@}L?JsK zm0aQ5P2`sb2j3(a*7vTMTMuU|u*1&>?1i&B>=b)4W)Ki)F2k0VaM>^9lt618!z`?d zL8aM3naUixNY;-2`*E|yq|8C0e`EyH++?pd^d2FSgcj+7Kz1$p5=8R!_@G$3gAsOr zT-_j_*m(5!mkV~jRQRNGx|YZ&hmf79;*1=M7LkRV8-XK>DDZZT$MgF{MQJKP>^v=t zR>An4vuu$KsBe5;5db;4u@#P8{EVq+>RlodOhUFi5Mn!^1at66?)|gY7I z53Se|J5+SUu1~~HfeoH7^!X{ouPKXG-@TR|oib;>Y zix*GjAaDLf|0N~ zkwM|%A~i@DgjMw?JvdTp)K8fHLTK1bOAuQHv1|*0K&dNioj2qrjVirpz6KW|cl!~K zF8)-@t0m)#OwuaSA6X@YdmtH#Q9Ch!tWHr8F3~iYVktr;CIo9I^`85B?hLfhSAYN= zR(}D{S^4MJ2~MSuf4-`UQJDUWZLVI6yO3(jVmJk*Y{pAr9NkipFFhNB9Bl*p`o8(d z9h|)z-mtSvMupFe;gFO7;976i^E}xw)G^#TG$x!-)?E~~))}vSF-{JS{7Ij$nHS)s zAs<-hO$j}bNywGlNk#NBWfqo?;!XJ48igaMJm_`*G>Q7%fB(Ekh#+F2O_wUs*;e~6 zp?y0%n-c2fi_b5J?zPntJnhMj=7zMTQ};@R)ts#j=(OTH8S0pVH>0xAqi}!aLXhPZ zP}^DLG9h*oe>R4%p@uv4_BjhiLGpalzR1iJopC)!ZgKHP4!Je|_)12;e5&`R4M}Y1 zT_cl4d{Cf3f0We0&|?wbU)gAY?CD3g1u9Q723%-GjVQ)&%l{k7Mf8f~dPdbAfs|u; zYX=G|J5jm;kn2k$wUc;Zc9S76VSqXkM+C+x0TC=AmdGc@5Qi%*y@qJ0r^?A^JaEMX z$CtC<$O33oTuN!QNMy}mtcRahEw~*%{zI7*w|11nfAgk6OuPste1uj8IN4u4SdDH6 z@#1d|3{(K;t*04u;VQhimEagTS;ycfjO#(fV{?>qSl^tJx7^IG=gaAiE_~3X8`e0y z3?(;!n~f@LNBq66K?xb-9kn27@DW_f5BDt~lLwk6LeC@g2q_Cz^3s&d>5)XwuT=%x zj5_RSf0K7ExzZ)c^FVcQfH{z)W&;XAet7xTp$axxh4d69lxUNKMySGsV zJwjGX$Jwnt=tL|s4kxx2-Zi?XrSEUmi))u&2&m2@EqxPD@1 z-J~Hhb5`xi`?jpYb5}EC0A=!EjJ@H32Cr08e*wDfOI!y``O58W2_%6~cx~f2Iyv20A^4e22> zbPRK`IYfC;H$mQD2^;&DTRfwQYtpdGeso~chvr)?-uBX;h;<7UXgPx~H@=J3^k zXBDv7m1&|;Y561s_OV8sCc46%3U4<9e^rR;QC+v|AUxC~Y7(#w86Oir(uj$!#x*Sx8GcB{kClf&J&9HlymfBc#Z=lyNCWfav zpxY5Pjpxvawr0gn+^UezzRJWS@5@&_($L*a&s^g7c_=W@-EHw{!K`VBVYTT>|TMsRkpYSk;#CAPx|*u}8WCJ$DG=fN@hOjhQ(!bfz)lXk=ObE$t3?oG7Y7IcS!&8Z ztKz4SSZslU&|Ca{QE~T0a~FU{e{)F2zz|QWxmPiE0+-RW6IeqfCm@H>5NlIPaDBL( z5$t{t7tzik0K2}>DKbjolkN$}m-CPePa5uqGjF*yPdrq`G{e? z8PM>N*C~K_e8%&dgI@rysM$D0%_^v&%gx@R4EfG|Ltk?}HY(Y8ktfpC|G(Gd18?iq z93t?&X&AusJ{xEWeMnV37OX5 zQ)?ZSJh1Ka6r~=%J*ZhD(Pig90GYnv6aIv=_tJM+=WbzMipg!y>w_(3-CN|_bcT7Y zR!6vh^WRZXn$O;D9;|zkbD$G?+Hc>{!3PdJk|kOD5~}w;_FfD=e}1NKQI~;mdK|%( z39v}YzPE<)Hnv$Cvu>TC7<-#tN;4B$-6F$J&8wAY(wdmAPO8d+8o_$1K6ta&8+TXA zwNO->+|T-@aXEogvS=4Uw`@qSlw>^C0Mu^Lpv9Z|xt_K23M?3X20^t2QnBawC=^}8 zGpB$1w-~xusMXrHf2eS#`zOu(yGaU2Wj@m7)k-{P<3fPIgq80xkP;Zg;C$a}a5K+E zuQ25Po=G=)*aJk|a7_eIWj4I@Gt~0sWVjo*)6tkOEPpW^lD)q={^Kxv9Ng5`kynbs zPG8=C^f*If;G*`G9)Gte~IWUypaodpBbqPQ%& zg0PDRIUU_(V`?6q=rvXk?@yC{=+9Q}sCv;5XBSRKy(GbeGn{4gTP@YE*=+Py&>T>> z5$fmo0ivX+f7ig_r35JRkg4aqnyJ(k^&gQr0=_plY38}xKAJ&se;}w1c1=4(m}%4v zIj1dnG2s^;?+27~Uf`(s7A%DNPw2m#_)S1?z}s}&V;PqV|GgT3#Sr1~>Au2QPHjs} z?>X94>!s7^&(ap+?Uw5es75yceYF~pt_iQqnFuase@UlaCx@NKC5CAN-<+KrTi#Aq zijVz(8w~sB#S49o%NuE1#Z&Wj zc{x0!)`BIf^lhnI)GiJ|JXiwErpYLh1M3VG(jsT} z!L+z5e^KJ!isn$*vfyzHlUSR_*r9$!fZ9O$=3v!`3ameZM18h1S_?)*M?=64zzW8% z$|(_coqH&BF?)}(J|7kY7HzP`f1_3NpYXMp)(Z8M!BDvA5RAd3pO=IRtfxdwJZo<3 zQ_@=;j&TKSm3?DOueN?63CEUl*j2*RJGM;Qf4sklw9Xa2ZsE4;GqRF_Pt*WI>hS*# zdX{F`^bq!=>jOrk%g|7!Cp4NBFZqMd0qGPX225t^y8wHd4parV2Q=*Pesr$=?tD;c zkt^!7=BJI7V=Fh`aUA<#EjL1Q!TtuJOmGV6Yq~2Yo8syz95G%>>6pvL$#6+5|9t_V zf2Z&O$cfFC*Z=XatHsHaa|xeZ=>V!WD*CO_pgkmIZ6_D}w8dp8Q<5yc_@~h}(^U}?B6K(xExH__=!oN?yKjit!)=0WvX71Hx1PKz2^}7)ZLoS$kGe*p3 z{utf5*B7bx^lZ2=rru2xnyn^>(%DX0f2}&6z%B@`ivB$Udo*?-#~j;P8 zD)15ov4*EWj{aT=YN7&1;W9b3K}S#x$CS44&v{uY9F*?@jU>yMX-~?en5Vn8!SUw5 zRffBPw)I+xfeZ0?jrl8DJHbkeG`+I+h6cLO*;X+JKkcI2qftEMZ$F%%9p#mHk=RI~ zb6o1J3}UNvXO#)`8nAU~u967Me|mJDW0Ju0VaVHmx0H7NcWS%GS4Sv+j|-!T9uG)? z4J@ImjkrXKkMj@rp{ERwn^RorNx|EXW9;J(_vn|IP1Hppl-+HT!1|_MNePgpF=Ln<_*6tx`3VorA;5qdvBesw#)*Mcv=OdCVxO@ao%IKdx zG0@XtpWNQKV@Gj^q56XhcxQiV@pcX2{%Uf64TR8tv+a{-ah|$hSD%06e?#})&9VJ> z32uzIK9hVI;FbhpU-Gege_I|^w87uyW!}NI!Nz2v@Q(kp%s~CdBGCeZzgC)tjO)z9tFJ_+aq47j|L^mc={gdcL)&Vk%2FPM_d&%Ir zh2GMj=5zXkt*+`n=4K~>&uY0R^o7wM?<6Hu3AC_jBjIxX6VAGHOR}CM;~$x2C_O0) z_MxJoyzT30e;QDJIVdq6l$k)dW8)J9pw1fOZTU(FWB-D664=&R=K_9p+Ocg}W=&e?@wWwLB^qy6#C zIrK}12n;aPT?sl#A(50<8*U&S2J&x&)F8{w$NmIs{(aU%;GfDLT?R&sjaTo`E{$bc zV)JRcp-tU$PK^};lnx^WrIoapAJ1A1z#8Db4CON~V)QOEjWgHHlUq}!Tq0|Y52J}O zF@N6VxLdF(?4i{X1%KlMPO% z+lRLr+4(v1$^UMLRj%EoW^Hs3z#6UphYGV7vqb>fGPZ-d4QIp_gQ#k{muy=E^9LHEj?5#H&rLtR1iH z2?}J5fXheye9=LxhERnU`Lda4X+^{if1S=rr})a*_0)%?!C^`9rmBATt_w7%(ObcILkm@OyjBxYcg4u{^e66xI~nREO}20e;u_4me+Hs_g6HC_|ce`EH- z+8!q|!jQO7uq$N2;--RVV-HbInG=HH=)eR&sv2;VR99*f5heQI-Rb&3byP)AF>(dOG<~)uup%zR!u-I!wo}z zJD_;vnBhZ-;`M{X0_G3@M3*DERnH&WYDdcj2w?lsA&j=xc1|ywOLGJdoueH^U8We` zjteuIlP8+7NzC)2K#euUkdT)^S|A?7;3u%O*+l3A$f4ZB`z(ox&#dfle><}NYa|)t z5}%X6HbH`L69XM&0R)zkL*9M|GczMT26SIarYa&+#uSFZGb()erwD`^!#&fA5ehD- zAWqU2*=laH4duE!>$glEv>62l2@{5Yd$*l#2J4fK%uO@ z7po-zbU=&0?AQ1O@|2g?=_A?!|9_4NNcmnl0SIuzel@**+RhMx2Enr7c~U$M%1-if z1k-JwTBmfL-E%`(bqB1f!FrZ4WWrA9*){VMDgRwdu0WU8C7XKUtznQmyy@oOwgwrMg(O(;y}*&zkfV~bJsz? zDK~jW97n$vIcn*UT9HA%Cfc#J^4@yZp~+L7{#%H;HtOJ@d`zy>8e*bW_a-PylY@xPKrHQt*#k>m%v3hunhnZTFWWcBm7k9~IBhRNOJZ_wj9_hS znaV!q;K#jabW&TpilOLs=RpHRo!hQd!?JCr$ygt8#=N zP9wHZZDmOK>7Q&4ugfD3o_~fYM0*^+<8L~6jnbmFz{!hm%2PQ+b!XomTG|+JsQ+tl z{L%tJYF4bKSh^ll?__&Oo%kY#jszHNK*-%I;j{(zQXk%9O`a^OvO|`qv@x-A*?p(i zRfWs9NSdxqDfH7%zke1ZshZQ|p{H$d_KhNwXH2p*GcqN;R4VA1GS|W!j4&W%kWf2t zGupS^aM5$QM`Cm|I2m}|c(5Y2V7R%ElG#*A_`Q5NfD`d8sNlH`gzO(DeiKBvWqln( zHJ+<_mRAxa!FsoWf5WfJGiutCz;LNATV7vBKxo@bGjpYKn|~qJp{KMxB=9Vjm_Poy zU8YN63>}Vwd5T3utDOIF7hChATPPM>0x&rJRBSMyaf(?xyubnGj%8;fOdK8(1*!#x zM*DroO==SSf5%`=rdVH8G2<;P3D;4sDGim)Xr2dpImGiR{w1z^j?2~*B<4ODIg zFRH~D-=KWiT|8KbXpTN^{H(!tLIgptbPKMK){ok>Tn5eEkps4?E@WF+Fa$NO=(Q_; z?cyfSt7hqv@Jf8sPd*c}QGWZgTG#XIM4I5*av&#$!GBQ8vGloNDP+OSIrUXPkO&V5 z-1%bo8C5$0D*qSXli9<*ynJO)K{$j~9ERg&SeExd2k`mci*-N2ZUZ3eBACOc->`e@XO^0&DX%<`aXzI>>`TAC?HR3)_> z7>}gs&VLw&+a3{_(81^*P}BLO!LQ{wL*)>i=3ri|3_Ltmul?z%?AF%92C7R-OB?3S zKLk}Ja<%gUCEXrx?4lT;&p~%8Kv5(}+qD(R4N#v`Nrl5eaas4~r3AE@?M04#h)N~- z0avp;Y5_E_WK#Dj4(+a91c?!Hy6B)67G#l1Wok!tv?kuQAD|n<8g61kb+Ykj-T%j z27f7IXav09Xd*q}ZD$)%0+$CDjr1j7q?RsOS(kc!AzO^A*&2ihKvmlNL2CrzIy~9J zua$mpRSw@La*67A5vOtQi%7=nl~{ZH+b1k0m%aht&X!Q63Z2wqnnu5=SrHvoYHdJ} z1^JuX56NuX&=r56$qMCVI{6uk(@nDI27hmrp&4+{p?vou#Q6~al&1m;^$gy7)PO-! zn?a4L0f;JE@x>z^ib+=a)tfG)R?V)Au~W5ui829PLu|Yglifw7C|h>d@eUZK3)LCN zDbf$8;g(xl=k-4}Le<{w6YetmlyCfr&<1dRTA*mbxr}HE#N)q>HPG;PVDN*zbAM82 zwYa*_t$_QVs1Sr|%)l`ThGQ5H_&3kyQ)19O1YczO=R=?h^zcvCKwB%QTA9OE9Aq{a zACVEJrm$%^NAEsiPcwws6q|p;wuk)0lYqTAd{Y+oof&mT;NtBXNA+LoE(@lnZ_)j0 zYrwE~glT$AjdnX4^rHVcp9!nJgnuQx_F#o8v4=IGl$t=gMUO5jkEIwA>mHO`ppdgp zrnIEi7u8q=_Xm@AI;iQ2Ep(+0OT5?O?RGL36CY*7dsk0MokCy`>zO4TAk)dFBliJ% zMDYAp&GM0bOg_IOfDC{M^rWvSCu12@@wp~u)|M>de!;lIoE0k#8mxkGKYus>nD{^m{tGUT+ zCNU=Du(^anV&CPsaBg8KI)AeeoNe+3Sfq^|P_-NA{}l>&RjR!a!QKG&CC;~m-|M`$ zG8cxf&B2y(fUui5q)3lsRQ2qhxeNdRm zpEs~)v!?W+_Dn&dxOFAp>jQf=onprbF6$EgbMO)}887BMy98v6OMg4Xg3fK|WpYn~ zimIsF4-;kghlJ61me7SLe_pyF3Aj}<3;sxiLHBer(m>Pm47^qZo!Qy`Lmi(<=5apJ4BpeR)jzdDXgOBrfV1M$|bvDC#_3% z4K04$IzWFDPF#CrFk-@0ZmHY1OGnJ2qD^~t#*Hlyx~7=wJPmut5OsT_z-n@bTM)EZ6F z(a*rnR)Y*%&Y_H;>}?mxxUE21set;?^i82rKtlTPXj2G%HIq^VER=TmB_vbA7QF8| z4HH`b^#HxvV22IDD$h?=oSeXY%DvmWW65djp5wY_b`H#2u7or0I7<8Smr%bjmV6&^ zG?dMy|4(>Fy?^3EeSWEWVFsJ}r0OU?GZ(`JGtHMI;a{&jakJDB0pmiwfSt>Ps}1N) zVEz)ujc-ETtc*0?CoaD2I6zPJ)MQeFQY z)H{YsfPZ5XT|AfwKnyAz;TSR10(7rgh#a)`s2=DmS_GWza!8n5ab2-C;gJ2O8Yfb7 zI!NRFoLCvDpd6MHw7+?4LEtq1nU@XcVkb|&ekv9a5e1$2znc8A6C)J~s*~9$vW>L2Ncoq1Q`P#X!x%+W zSE-hP`cA!d6LDGh)VkKDTdOyP@TDuIr-qHbP?P-=wCw{G!&ueQzy+07=`SDdgk2;M zB7YYHsJXd6^5$hA;BS*>(ye^`JKwdEDgYgwZjxm*EQi>B&P=){U^Qc_+VCb{xLv;# z;{lIay59z=T9BA0w)1tn%#VM`T#)37k*So$RY4ksbU|zyH91TbBw@kEE~PYDv33-3 zFsK{J1i^VsQ4)%axc5}!<^}dThizMlrhl59+XMpKQ$c941%q-3P1T=6O&6|BA3QuC z6%m11Um#$SZ{hC4wdv*|Sbr%hM@NE$^0GCi=vU4WW(09(`|rC3x}NABqBs=J4+ULN zY9ssuk=s&=k;u3tZNfREgd2EH|L-|cG2(6fBSc`X&(W_~J08|b%!!um8T_*VOn>on zv+2)IM;UNF-q?&j!bQOeg4N~$_4cl*mP5zH^kdpZ1AkP_`ib3#A&4oFIu$lUYL>*< zQ0A3|U%QA0V5j!(-r+CevQ11xVfB~dG9bVKJEBdys-DoD^OpW=fKIomE4Pi^70cdj zADYjjux&?WS#FQ+E$o;)r@l>gB7ccm@N4u2hg0Sy7us{1IvNd2vK8F8S@qu!E&dO= z&{EYkIWLp!h4?=EBZu*{q4D8AW5-1jFI3#&*4TeH>hH0uyYI}k;Et&$VyuR7_y1lx z`}__u|BE@L%1b@J__F@MA=4Y$AP3%kM{G_V=VD^#s)~d6hOfx}#LF(wQGYo6X~wSa zqAUVHP?{G^e`(5@KaDW3y@{U^(^g%=52C+~t1c?s!Lb z=>}i2NE@@hZ9RfDBW<{Wy(=tpD(6$zq^?=#=fhc^$u^JviXOnkAJy5uZlSjjV}Q( za(ybwsu<*S)FSOski)o=e`=StpW)2wN)|u3wKPp1H$!`c)sffBjMG8V2_J*p(K+_M z81dgv>LrPRp>Sd@kH5gGP6X&>ls1(A9*sG`rL88`VGR%lxR&Z}FMl^zz^8C^IEtAA zns2u$;@VVg>Vs#2M}HG-3*KD_N%r))Fa}(*+Q%GJm(;M9v)_+ND<78O(q;?kH+W`r z!Whjn=W2XQ1Ww>_nIIv1z`+sp4|h&p`wdV$-KNvqIn*;z%R7wEe0G$0?1wFS#XK0G z=-_M)@ZmeDsT;8Me>NE~)B0q6TP=DSv)PDs7|Ex&&8}@?;)@xXgc6?EfUzG(V#8b17oFt7K#>!^3(4avMoDW&NrQI|tU z_{emI)p~unjm@>mD8B_y79 zdM0Mc^S-KpP=EL7Ew|7Am}Y~V7+@H2fl_b3+Puz7=eZ2S)*6K zq<5WzmKHO7_=KP>{KpdiK@QF*0rP3m;m^Mo0!=Wm)QAT)B_>-qt?|eW%ZNCAyRTjm zv!mH_1=p3C1HdQ}u1zdc8AqDHD&B`C@ZWb1qCV2qh$#jTkl5jJy_a!XWSbz(Bsxh- zy-=C{GV2uUxY+@s;RH5jQe73NK7$ZfA68G9WoJI5L-UQ~?wO zIXE^mld;h#e{FbWP+aY@HEzK@=-?1^a0wFJ-Q5OfaCdjt;2PXXa0tO226qnxcb6~c zJ@=ejx9Y3?r)72Z>h<)N+B6iB4q#VxFGmoN8OXxM4^Wd7)dq5MvH{pwI8bP4#GFAU zuGS73T&+L=3u`+NKuk$lM@CT!Krf}J0gwWL zLCz+20A)8*J8Lt5ytNq!>;hr{SU5NX?EdWl%pAbx*8k$pHA(y}W0Q7$~WB{0hEdHY1 z?Ccax>_Gr}F$a4`H&>7|K*7NrgfbG2g zr{UjW{%OamA|;`&CdK&QHTWkj0XB0mw+34R)Lj26YT|7E-@rd6tvvyHY%Kp;61IO`|FI1I7bPm{;OWE64&((ea{##kKyEH}03VRc@Bh#> zb8~hEfnEQR{qHRQ@&8#T5Xci`hO)fiU?vc1lkp?G!e63zx)PpodeT^faRCUuIMIEs zhh^PwWp1>0N_3@8RN#S1Iu&FpxOK8Ae{=Pn(j)s?yTGcKu1E z@UbD%@C;7#qrI6T+(`a#VC7HaoY{FtwX#lSf>=_(SmW~cUU@EBP*`GrOKVqyyr)ezn&-w`{bTxI`uMJG5oO#N2mu=VNfAy-Ctq-iWdjZ;pEw8KZ9GBnsB~>Gw{O|%X^{$h1 zkWWlW&e9Q1WESCxps-R559o_trFzCMP*cv-lQ2Ab$HFPwMzM1xEhT%l>vd$q$k)80 zF2DrgVY?kMN5nAhR_JE;41+Uo5ly0H%Qd6GF zo|kVSGy?u1S6?J5Z?7ys@^>D&&{-3tSe3VD{~{1Dv7p&8*5NNoUP0 z#~)E;RiB_>T)TLY9waiwU|pF97+qX0c@dBgl|y+%C<%O16A|>H>-U2s+bff|-4H@# z4U8_zM9vzZdvm7(+3*M!e@&lDB1+iBUY@Xr-%55RxZ>a;UYV)>QVrQ0+*7PMwreYo z8p!H`FjoGr>m4Gc_nlNBvgj_!vzLjyu(qRi4m>ftk-w}-zwnWxNZ6x#J#cLgZk;bv z-_zk2Rerg+$q=rjq!YZ3NT6dp9BA8oDog7Qu1}%C1P;{*B9-g6f3hr!@RLk?J)_&> zj{36EAQem_0Nwf$&fzBuQhX;JLaEnd9f~;E?mAx@3P?k>vnAD$!!h# zCWUL+;HHd4KkOFzX8Dc&B#TS zOo=^i#YvXS#F7Lx14-5vI+@kKxh+WY@ z7OxoE#@+hDdT%%4&7OJG3;4G^8K3mBR&9{r2sLwxZ_pJJLB^CzuNHI=%UoG=I`0(tO>RZLkE=+TY=Tcf96dY^)iC3Fv^^8p9{M3 zQYjM!-6x+JN3r0RODL#-y1nmBPMz6b%QDD+Rm1SiYqd<=*Hu_x9vz!chZmF&78S0ixu;XntjCbi`je^*uT+J6qJSLy#EMMHIB9Es6SffT2C zB~|GlfvSZO3iIgn%k3PBE>=cx)aZj)ttg4UpvC-D55ElKLi50ZLCrSAEB=@2D<+6s z*f;2v@a3gYdC`*uvLE`LHTG3_#pR1iYbp4-theZ`5*V<3 zazGQI!jOn!{8PvUIHqPO*Iyw1csclCe*y3O6@9TGevHrK@LCFkd#?!IkPz*>O$sN; zWPnymA7~;@8AzSCEquKdUYZA{}Bgc(7QU<_&p zsXdcv@m*UNZO7&e|DrQL6kZh+e}H$-;oVeW+N!LMSCx8%I!Ci5Tlby8P8{^;W;g4n~^%_ zx?%$=Ww1N-=%pu;moGh!z<3I$(TGQ5H&s5)KtJf-B~#A3j^8Hl3pCdp*=&B4iny=D z;TblJjgm!CuJjIuOzE#Y_z8sE$q4to z^xG}1l|g3JPf3R$m7d1nB2#sIy>qwJckXCe+khbcjKW(dz+~RCchcN zUgM@kqR!Z*5BIX$f14nFw3TBFMkpajHoh;bPov$(D3kE6EoN1TpVOOYt>Otd z+HbJY6ysRMf3gY~Qy>k(Ra!HlH^b|_MKWlU(<&p&Md5E%GZC2_F>i}FrZ2W`HVzds zRka?;nL9BvdfKvVeZlEa8&PMRD`S1iwJ;z2Xg+z9B<5QWf=alMP5<&|#$D2ukLwO| zk)gTG#!VV;hb9&H)9BFIer0W&&_e_7T=%{QcxSVNe{TpoZfh2vh~eV?rlfctfF?n9 zWc2a$#NnG${p(|!67nvJ_V6m;YfkeO0g&0YZF3;&}WIm*Jy|gwRZKfXi zThn^3PX~g~tj9+x*o(P|k;MRQQz#esj-+x>8RvK70QyZ;Ora}3TfDJb^OY=$5GF8U%&*m5MYQ~wi$ z>-KKL-*@t0;%k<}wJQ^=F;xx9D>aj=f;fzie_wz9WzNEJ&6uA{*pQs~<)LC^*}PTU zhYZY>U{{?Ff)I4oS5AA7R+nAVxyieLO7s=NvWSvY_7T2%=-P;g3a}ECvUVBx8~fP2 ze+^%6VNhQDM*6T>t@U?R*-v#M{O66$-dZPv@oKyn=LuzHz_)U+hAdNvr!(#|4qo?~ ze=|?PkK75*Ku1^M_8c@q~jg&JyL3%Wl?^1++a zVwpijNzpJYUV9O(n49O~4kC5dH@`PeIjWOb)C9_R-L9r#s&A4-TfOpd%BbG1&Ni&J zXkL4D*TcuUB=bb!B?Y*NSzGMJOB0>4e~Q}EkJLEv3|$yH-Y`i(95i~_f}Joop{igH zhnpzj_etP0`wcK`xfUEx!XQ30$y(NND-7D9%$}w}kI^Mp-Ou!}VGCTx9~h%xK|*|O z6&6v#nvKLYGMyN3u+eK~^0o5-Tx?#SD$;|uab%p0pSTh58~A1jCVI$FR~WmCe|>{v zAN@l5hS1iBi#`M-WzNFY507wp=TO8`)_VhvfYL4%=|g!`jYtUb(j-%P8^s+YV9b{* zDmSOR^iPwS`z*UM2#85{NGyJBRd}?lE4fma*0}{QbBuAM4tp6CGV9v)8z1}er-hM~ zG5A4F#o`Z6gqmqT-8+?cQ>-ooe*?43SG>m7;K3`~R-qF(PgefL2Xp-zuN=>c0VbH% z`W8kK_MFG0J-SxusQr$(BRiLox!BgSq`JTsEptsjIVVu6YwT`;hq?W ziGRqACOxLmEhEq{8i&^0f7Df$gldCxy-rhoIU_wW+!BaS;kETZ%4In?}-a?_U+_w?WLiz zq~LVKV@IC0t@#@Jjoa~u&MvyrKof{kN;MZ%*npjtS?>V;$C0Tle`$&Gn%nUwIs#Hg zX(}N=4!5O6tH+hpFx?*8bO6w{ysyLe0ADrcIT>{2P-jL)+JhF5pFi`Nwd zkC*OoSR}TKmA1!-P_)d-y{)CSTmIh3$cQnD_P1Axox=xz81sctbU?=UGzdwP@7FK1 z7&x5Ux4=vkvi?6Ee~^C6KjxkeU-oPy2}*<@kj=5KDLD>VmE4uP?usQ>)6IV)6c8fNmlnT(MhO(uZ`@8tseJR?;5Ayon_$Tyg(M->CwSDTqT4vT7?)D#_3 zj~?8Sijv(+W5|iTzIF|-f9wpz2tQHA@Ju|WX8_QzqIfOcfAE;#ZEMesruXvlG>ayD zh9};-**pQnV?CXM8!-RTJs&Xh%zjs_nJ7L-yht9JvvMY;-03}2HZ~sad-Id^jU~JV zI(O3M!NQnY0lehJ=Ah8_f8Sz|(N8>-p`p`{mfOs)YwE$iS#0kOg z9p~_CY}DsHW={$Fh1kYLHipllSV3x&MI86Tq%=0%131$c_w9#$(ahdOmUd zIlj@_BD0j(_v0%f0>UYLbnxWfk6(QZy+5*ION?N#_PD4fSohuOi5L=&^a<5uYj${`1mpGj2{jGm zCV0>se;u{|){#mYbLXd`$r~ZbRM{dOCNmVo?T*44zz}m%`ph5QXB!yK?f}h(b?=x8 zA^$vdRrLh(q5i<|YdT|mT(oLsY*0^=#C@8d+@HxnT3af$vnmdfu&3tArzN+ChQ)%i zh{%DfQtrLSyL6je4w`zN%0}5t))yAV)?6xRe;?rW+pj@u5rPIp% ztRbIAkDyXJyy$}d2t{cd20JK)LG~$<731#WxotEKvTGbX5>yL%Kl<=|rto)%+;*bP zbL3fHY%}#pgP@}<;fQE-{NXdrrgPz%%-lN{_}L;Ah~2uzz@n;UXopO)go;vg7>bw+ ze=3cqJtQ+7h~AU}!%9V_)J*WUO(i*wDfC?fCj15QQCb3*^L?DFfsN*$&2w#A; zPkyHTc6Ly9ke4_`ao=Riylt3iir^A!EPLDkMM1+Pqhs# z-1^+Ul(0D85j^F`vA6uWGr#b8qR-C_e~xK!f|DbG^9OVuTjV1I(4?!N2rXpB@TO$Z|Fi@HU7E> zL(l#a83BHUGI%sGvNqA|X>MRfhA%seJq`oht;-CTZ*Ax6%Ex#HTEwEIKt0ITe}2Oc z*KcAzkCUC8GlmA2d$=v*3TKYY1)Fqq%iERAUqNcBF+cd{{OZG9-Ytm7N8MybK41x` zt$ssXE5tonSQ6mD6{uE}nP4xv&nl6?Y$zWZri!}NQ*U&rvp|%}7#~&IE^*r+U4E(Gf7eb<{Wxa~t(4k0eCF#y3-Og6=53~wBx{%b?!@gF z$ltsufm)MU^3teNqoNEqg~v{24|QnP=y!8#QMwipw^!@btAA+oyA|=RFkgPmxjwuk zoVTZ$sTGl!CL#g?p0*1g#5Gje$Js*`gR4Jz)%!HnMVkFBx}@5XY2jFff6ta5lN<)> z!>;d=YmMD(p7h7WA31=fQixYnKCDllVv28p1a%C*Q|zCFA(EQ-ETPMru9u1r z9#R}$5^z1fE?!opJ0~YcwZkW;fZChKiyzjEZvgMP`vq-*5lZp(lq@XcmmU-m?Kj2nkDG?# ztJJW1S8d-I4@RAt@rTwcx>t%tDeIVGZj7=FYE8zog|5NeaUODp!8dwlmctw6=FxrRmXI zrmKhmxR>W_+uqN-7p3F&WLRA=H{L?fnx*S$zj`-lL$M5#yOj4Z)ZW)%M#?NkHcW?k!8sEufiHig?vO3taV$we>Q5N=x=heONgT%;>IBW zE!*r&6lXO}BVeJ6#hCjWm4SZ(e^vdkhq^O++UBI%=nKiu@JoaqN15ek+7wvF%H4un#Wd0JtW6x(?bCHRcZKpmzj`px_6%V=uX{zLDP z3SXYv)iYju-rls&Py#eB?~gMRj73YGYHbGiULg}($Pd{F&h{G4z7gqO1$@Jmq{x*-&v}I{hnw6_h}7KONOa)K$BmxB&8kBYA+$k45IvmbsV1VG;lvkcM33s zo*}td$ilSri=*4Iev&uyKp_z#6dq!t0{*8~e{|u9>?Y`WB2o;Rcx0P5$3wV&9`%Ov z)WDkKiD+pzFML*Y`yDg=#Vw_l`lQkpsJTfjkS^!iZ_i;@U0dh!U8QrsEgiXn(P>n2 zpAqe$@0tU_l!!;?A^-P3;nq)_J}#Z8YDuNL;l99%Jm)F=WE#vNK7xo+!E=RT+`Ho2 ze*vDTJ)g=8^go;~0beHU40Ma9)VCVUMV57!o?+0OdL0GQUvQOBeW{;`CL*LUnyJ?!X%GQ;0sRTOV_&`V1ciC{?j$YQ~6bpp4 z$0`G0d>dcyVzCmHNmf$6mF+oIA_|A zXEangZ1l|C$1*YtnXmoU+?s>Z)g03*mTgzWA4*uA^!FBMD7sd=D12v=6}YD-e~)b7 z%1MO1m9H9(s|N#j_&>5yk<_oR7pr(7FUC0)qXir7@Rd3AnqCHvV+%vQ2S|P7>Nlko zsa{|IS-=w7^D&~MCc2gz@Wa8MVv(R{KKF&yGtmSm0Ufq$l4DXi0!2|6q2THF7%$wK zPI@qb<(QqyHwlnue%W;wul!@(Lh^E@zf0@*L!9suN z@nI!^c1C|6VA%{>&~kO`o!#l0Gh^JYT7_n;%5Mq{0g@yszmD8zZ9kFh$2LKxre~;p zgdykW1l~|PjWj9ur!~c8>(0eZ4)Y&g(+iWyP-auP%PzL&zp@F#oiK$Rrbsckd45#< zDYjzQA?x7{Xft4|KQM6peZzM$Nkhr%MBg(4}E3rVv{twG&VBbW%*-qIVQAr%?@ ztv*DjeVKZ@fkL-Y7U8G%06Hs|5mDdrM>5j!Ds6)@f6YZ9g{){k-5Z>d zP>jRjyAPCzCkQ{DJmgGTw%AG3MIU|O{2zp%@V9iaFCf6UYGc49Qnt;+lJ{`t_8vy0 zscEu&{}`_fUouYg2>C|WvkF6t>G;B&dxUOE>Z;)TwmqN&k}I6jwh>0DO*c2LEVL63 zUts%8@cu@#sZ=wxe_hn)^!ACe)^B#hTK1Qpp=W^O)DFH}bc|bptOtM?@d#YYNMZiP zVe)(~0$yDW7tyWi6vr4e+Njo906&ttp= zR|gHG@X*Ug9AmoQ=vlL^)4kaB)!z&8&8&V1`>nIy*5vZzPhJs1LPx9?#$C~;uim0> zI8S=5UP{HXe_q5m0Gpl`tdfgjb9m2*B8rl-vBBZg-C@Id8M{~a(ys6P8LB0AOK#QW ze5l@P?_=Y#>Q;uuGI=nGa~cmJ^z2=k$vUg~_A^Zcw_^v#%0>s!b=r}9oz}&IYDC{T zlb^9~LD4ydSzDg1?<^8!&qy;MD|SZAUwK(P<#YkTe=fleaLM1-KOn?e|G*GyPQaYV z>BuF;M{t#;@9Q+FRT@cT`w{XX$V(`fJvs|fAFLytk@?hP5PLOyK(JY)dbr-R1&%yt zX?7Rn?iCU!jVQKAgX$D*wJMFL(%`_F-|Y0kNE1*0C`l#o3_8m$@?eq5-Fa7Gf1;K# zpN!oCe?qA3s=T&-4-0HKzw;WX3h5$!7VxfTAoR@?H|qRmJZd+`Ps@_yX;{igtHyW% zz9tg0G8P2m#@Tt3XSJo~vdT#?*l0-i5_HSOvao*2m}=6QNcN)lnu7!8(f6H>I`hw| zuHKr4nUN4c-U?o^E=E#HxEBVuJjh=;wlGwve>}&Ad=A4Hj|7`r#&e7pKJo579Y;)0 z=!3+XGeTJu*}dG~ru3LUi;;EMgb;-cD&r9M+p@iD7yJA;!DiMd12RI|5J53*xHgT$ z%`oyTNJIN>1}z$#FKOQ$`IC?+#ofOyx7%}*rjBY|E{D$Jj#xCGGLWX`tJ)?^<>`(` zf02x8ir_yU+$saDM;7hzb-drMu#cK__0KluZ){;s%%C5QWxfmW|JI`O=p=94^Ebra??tasx#j5;Oa|01Q z>RF(UEf?ien~2l5f~YL-Y*5SS(9by4T#5&VR*EVjenh2skXz+!ha%p@5b;a#of+br ztRL9N!&vw!>s=e?-fejKf~v@{l1tH?6O+0|9=~#D;aj0MYP%O6l7+@Mvt0Y)e}}BV zREAFYmHkM%CCEw5fec`+tXNcp+Z4#+z!zi0m2x-wO`qa;@I&60@Vw}`>dwm%i~TRe zPDD3cs&L~srAF=ZX=T7cA<2NdEMX$#-n(&OVlQgj$DKM$EE~jS#DECao-9`P!PlI0 z)>M78@vZfI2$~=m+Nl@b7P%9re>pC(sAnTAf7YhDB5zVkQ1(EQg-TsLJTJ+sPWw5@ z1!N;1E$D3W1y_|-yoO*VfM1^nk9rp*jVf!)&%jyTJZw*aPEujwQxPElhxf3ox%E)A_+ zlnMrG8_RhtnJ`oov=;dD;VOT^${B2CDgx zsz6b&%&eN2$3ve_=^ClrRN8wTH7VU>O(Nzv90n-Xx zWTXKE<^Bla6(ZcbZAIz=dEY8d4NrG+@|4H0s)}k|B!-tbTtTwb)nB87(}BXZvoN9e zrM`%_{oFueE_+qww9qd$AuFls%cFFboZkC%b`C5UQKMN-*bIfj$v-RjXBnhu02<0x(}XURcet_>9PF0&xy)Qml3#$ zVu8VU4_Jf~=LscdYKgBi^r9%y<23pCZM#xBC)IZy6=NVP#TSiF%5=v26x1d2 zBFXeI`Le4%18H4k+P{Nz{SE8U}kA!3J{i8(3F%D2T+L1sRG1J z?M$5vZ2$_cMmCnl02xbTQ#)r`%6M&4wKjn5V&RqXwn;JXW{!e!_0GIz-HirMTjQ(r= zH|pf^Z;K9wkr7~GY3u?pGBvlfgQ5Q)-X!hJ>;Y{5cAL05{3rAeAm@MZ0Vw|AkP={G zYW7dItBsAEp{*%^LfGEc!PUjo2_S24V(MfEP_nl*w14|gmZ7bsjpzSw-v7yvbTRyg z2SGdYf0$$Vx69I5%+kZuM8VSKAF9m^ZT_L?Uw(Ddf1iu2sfnel?Z4|y|Ka1G6E(57 zv+?{tTmI9=zc!?omXnef6QusH0R9ygwKKLiv9vP>D7*Z_rJ<9_e;xk{D;Qe-TRr~) z^B*+<7=QooTGr6T$z(f$a|N}jrAY}swtN2yo)+1$8ugIamE;fiq3v;#GQn- z#lLpql)B`|Sz6z4rU%ruh;tU9MK?zLulwsD;RV5aaJQsb`W8i%feuIEnvbj$?VP(y z9e=cU5+uo?w8-FGo?v};sM0AB=?Fw{lz9OW#%5+T$Zp8+PU6(B0zn-&qm(Z|e$&Gh z3S$w77v{OuXBenJa;EDX8(BRMIVo96w;piI|>QUgox z?QvsrHXZN3ag+H%+5^%%!-cvTDp1kqCx41n^q~$^r775`Gu!e$g($FyI>f-LI-g!D z+Yi=DSmQY!IOyI~q(gI|V;_V;Wrkd5cKYDAVGPD0k-eMgeM8HrM9yIa)YgAD{cuTo z7*HJQ?jUy47Cd79&>1q;EDxvCFM-Na{(K2AH~{n5(T3oagqf|F7EHDCdR{mQA%F8I zw_^v9V`yD9CfyC~r!8yswUl~}u8Qnv92OS^Euj077szT|?17yfMjHFX(6Z8Wp_=_& zt%UW*D`VzdxmYh_S%WI8%!T!=W}U`AqwZ<)$Ko3J^|vpUwFS zEi&PrA$QM?{zF?w9mv~%$`FTJPh>j1`od%AJ&Lr=24t6bgQqAd6eU?x7W;-zbDxv+ zhG4pJc-{NMGLd$fEcu7*PQOF)_b=rj(7*VKLQ^oF`J(5{KzG8P5rwi-b$`I_3mrLX z?Pk#-lP{JJv6%^m!^=^zkU%doZHJpdt)IkkOl7H5@@lIR8r)eoe(VW797M@%2 zg7b;5xcRnL6J1|>sKu}7Kz|-b=@Y+|Gj;3A%O}uR8Qrk9bZj;sryb$QlKW+4Z>iV) z<&vXQ_(-t&>rd+O)jT>-?ytq|cvHiUw-qwHhR?!@+_Ad*oFy@5=Zc*k5 z9=!O2G-m;gsreB?qNcVdl&n3CK<;Qv5;1AnSSS6n>`tRqQL zw_qU2#}hL+gs+b#k6MG`=&}pO$SCoyc_^IlojFB>3c5~L;Y)Y-nK-jmi|8s~#t#}A z+Rh4bSrjQc&J)#9yj{Gi!W0Wbt-leXf0G!+8=MQ)XvatdU_(C?7SOUk|LL423hu?lV$pZ?e6BBL zShRwwW4Z88hKQfB_ zv^!JYp|F>-M~M|66*`un2>!gLuPii+Z}Do>bTF-qr-?{+k{p9mhXl%7wAIel1XfKM zNpFgHyFIALV1F2I9h-G*NezpkgL+-2FMhwvUo=nhLw_6~@!$io$ilSA=NV}yll+3y zZ2Pe=8^aZm8slXQjzJp*=PXpgzUqieerzTWT~Y(|56SqHzyl%m&|yMI_VbRnQ#$2cH&KG3;O-gw#E zJi^ZG{d&jF9rDicD<>MBXssYm*`_o}dE5uZcFVj^af1*ghmj#uxmP_c_bFL@vXdPZ7RtQW_ywLG(w6y@QB253vAZH zY1BYD@%8W?5t@Dc$@&x&78#rK4nMB6&()kkG`^Gkgv)iw&1kqPZ(9l)nHi zW`FIwr>%4b)Z?h{u>Ee)E9{H-f8q|jyh<+koPQ=x`FFP*MoD#Tt!el>8 zDsP|gtr!bN%D+38zde|fQo0%STxF9;6V-&U>R*2&BrH>LPn1~n;ML+Wm88#ge9Bxv ziBi&+!|jsg`N;rhz_A_ME`4WO*jXGO=;1^Hg{)k0p9~SaZ#I$r}o5 zT1{48zWnY{25m;si7eg>bbA|-SAe6o+SS8=Z+KlVK6xNah1~ti+X|gTsX{qcvAr!v zWD$Qr{JW)@`Y$hA6_t=o3d&ln#iT2_^)3C%mf;=Z?o-2Gu< zv14Pu-f|T(L7)qX-F&Cf^`Ib7>BI~vb=1mgN8?-&*NcjPY#tK7+k(Bmr36Jx_ihDr zC>Uh*B)AWmaMJiVS67o2aEEw%ka^>xEDC=lFE#(W13|rIiNJu4$uO+&52E>-_2hhb zrA+k?K`KdArddD@Gf6FZR|-Pjpd-W<te1o*Fp+Da35{2oMU1?Mrp>K@9x71QM=2ag*PmP}BP4&U z-#KtPaJkaoN+DVS+nJWcZKGR|m(%n&qVMNnf8J|^FJNT@66A5?74dxrrsODa8iWE| zzd$Z5nGfv)put0$rr}Qn{(kFZK~qn3jPu@Hp+x0$(4-L?G}#&*_;;^Df`y~msLf*n z{TvWXaqa$g|{93vG z}6rIeX@!DZ&4g0h1vb?zGh{O+XHGZ%;5vLm)AS8toMjwBm@F-flASDKs z7-$}&Ls)+J0SmtAzr-uo)ubTkLw}RQG)8;*YrzMYfzcgIe~ zQRZC-jI1AuR3|V{N5p^oh)yHQ=ohZ|{OAR0LLfUhN8adma)y0HVUW>M0YY8BJyT&Q z0ZE2)_=oAnA1sQ8Lsa3j7a@JQ=3N$$coXuA-_PF^E>P}(y^>B3N5UOw}>*MKFWqP$o-qKo*d8rf$UUASHjfIeq5$t1GKc^qYxi zuO>g7z_yI|ps(@=x74&gVUJKscN^{hq%`??Umcc$>pCAUNaG1$C@GA{Xks`})1W*G zR$71Kp<7LkLD@x+9IwJ+x+!GBj|+1hRYJiykex9Rd+;F=ytWMxS)?ta4X0KbttYv5 z98A=?h(i*z`&oaZzRW7{hGcd_f6&KyaS8U^nv^d7p(t{AopFHmM%0-bx3{vA$8rA%yvL&v^x>AUqx z2b7kRv|@+KPx#YY4w4_s={2-1NvlNnP)EI(d@8Z|IX>g zsL$0)W;Y$6!V58r6HEw-qSQx)hQF7G;6YidyjmAD{v^5T8TuYPEun@Kc_(xqs9-NQ zb@YF<2;ysS?R1I?4>DXaMb5RuIg4{^PnS)ObK)RTC_(3}#2U{vHJxOW+OoEz2TRb5 z%%Ha1rm1oMXCn;Ccb}Tqm@ZmLta`|5x5n}g?rq#oZn{*;7Ini8o=e>TpmVVR>EDzks3 zo}u_H1wpTR&z`to?nbQ6D<4Yqf}m-h)p;x4I|dbt?OR=xvHJXP@4nyJhWUE80rK_Z zI1JQORrYJyT>>8*f$d{q%-s-Mp@sCZg)@A7woQ#5&SOk z3w-TCXFGrJ`R(sir`+B2N|yR`_N#}x4db~f441Kj2?8d|0ef1KbhesH4nGhi;@TqY>Yh|LrSW>%TpG0{b19D6%Pv&qu+##YE=FNjLrP_0htCghPt$m>~2>e z1D-n|S~vOc#~PX%A0=C)hACGsg!7i3n9Z{?Q{(He493PeSdJgW^pl69lva#zonfzz zFhIm)Y{c20CmA=PYzMniFcyDgz+7YU=cbTz{?Gw7Z7DJ;H2u8#TLN-m8qH zP#k{@#8Wui>jPL!I`i@*z5~i!noT|RT?0bY&6Oee=y6#88lR>K1oD3vy^0GveMb;u z7VK3+p|NiscOC~H|Jn+kqUH3Ez72{}Y>w_sLV$-PQ}srf@YE)*SF729cv@yWTj6^A z6N*WOmTDQ-%BCU>0XLl*#rqlGCD4e*yIs{ZqWAM8j>|y2iG2WcaECO_5WEe^ib<2e z-=UT?Am&R~)_bWCoX&qSIiS)aXUB!e*FH)@zpIG0=;<-E$FNx?G+Ynt-0a8?TS&kA zVZ8SSVn>xm8dW1439dmf%|w>`CcXR{UpBv)&z1o8^6H3EPV#R@_8Fk?$z7LT!o&F% zq&U!#@TRPdhDw1=h;O=0^xTjoUa+SC3I8rWP`C0kaFZd<<4%9K>xyV1vI>8tD?+fF zXiJRSmDgm$XL4gJ`O>U)Idzi>1&*`LlDz2cYNy5H@qFs zsAU{)HX3H`tEPV^Dve%CJ((Vvn`I9z*9Tm2P4Uku#o^l26TRGCPZ+u(je}o5qWlMa zbhzwiAhV8rrAwY+`3;!Y;%bpnsKl!Qoqogvz3IxLTx5uwcBck01GFb8H2oC1@F&xu zgE}Cs2nE(37(d^nyYjW8`$dBelh!g+%@YBA9{!!hU>tu!%a{J_om*BvUA3$tymq+! zn`W6r8wYCyLTUBDlNETYE)GUv%9b9{b$>_-S;}^q*Tb3f1z!rBlg$>aH+PJpDX9?X zyCl1+UM<>HnhXI*4He^7SQOkXcKda~Ja09E-YbIr3G1@}-XBPY@PVTj!WR9WIN=J> z>RfRR_5pvKREY?uzx3K4U!mL9m_TX{+miI{HZgnwJBN3RCAVFv!%~@gHsxBeaHg`3 zLntb%f_BnUi&9c4ie?{nPW(CD`+3J-NQ8|Pm7<=`}FrY(aL{rWnZLc$p1tOJDzKl5jZu@37Z$* z9}{~d8#`N$I^}E0bgr#NgH_}=&8m5n-wu5ffVQAxDQWG->yE=A0h)*rSosEm9Ct;I z-j_M{(n)JQ%bWJ`twxIM6B>yMlpT=|a@;kkS||Ox$ydHag{&>$e8| z&_y4BQ>-+-a9cqwj=P@6*E42xs(h}Ci9PqN+vzhacyH=jhM92DSBHE^f@!HQ5hIh% z-YB&*+Esl?9H<4mFaGh195TU{R!84=?uCDzM0h9~CreKtyd#h2Au0r)QC{4XDQoTW z{i8D?{zG!f=`vs%VH6Ea!17HZCg(NWmOW(}2qJT|LFH032W`CYF(t>D$K8b`nrqB1 zhco^oE*z~JAlSzJf&_~T%Kc7$czTfagRt^e$O$T;Ta*N5Fxl!myQvkSyL}dui#dNO z6J#^gk9k??)-DVy<*DXn7m9a37+EOb3h4`~gt@12uA=P(<=E~y94>?T!P$7nLFe6X zL$#%daYuUNdP~gvf^kYM$se>+z@D3h9dAgxDxjbIc#&{GGx=6wbCpn94hj9bu2}RP03Wcy6+Lpz9v}oU`HU-{;JZhC1MxqnNwI3Bw?; z9V3f3{NyJ%pj$mUfqO~RI{?|uNG%n+bf~Bxi9boe>8%IPp^PR&+owql55j*`icwVh z{RUDBLLZ9#q&}&S-6z`88)Gjx-GQz6AWC*`SW>s1l!FZ-Si?m|SAB4}aBqSks^0&@ zDmp0yVNVmOeisb63t@}g<)iBoWxZJsi31K|T0ow-S+zk{j+SZ^rd1UbUM)?3f8c3s z;uWzVfE_RcVCG-kG1lnm#s`0zWrS4G3tQeP00O%l`w=65`A2PSzF>4NxBxWOCVQhz zg-v2#c-t?=Sy;x7*VP)BP6|s(_C|toY1nW_VRKSRFp{4!1J7DvF?hCC_2?|maziSRpShsV+$59WP}uN>{@@3i7o4Ha=SS^ z=*$$H)cU+Sb!!uz8Db;=wT|4FxGN2fC2>3QKq~7<>g6&?q1FzBw-tJ3Zhfm-UxBmL zYb{)DAXTt>e$`G#iuArSTa!WSyj+oBy$1WxJEsn_vXSV}J>Nr4N1I&@@U$JZzj!>ZB94~Zu^||c2@YF>b9h@#LDvqCO}de5YK*k ztwlEP=$c_X{>Kx=FHpTo`$8?Yn*#aj#7{pJTaSxqzfNu^4@p&j9lX1QV-L+fZx{|* zu)E%aLc;Mx0`HGs{bzOB@DE`aX7xtABDkJ(W;8To3-I3bSL%Ogew;S@1{avBNF|Q@ zE_1BvooNdF?mwCsKGr6U?&IF`8nz7l%dp2vC2n4)GQ3zj_FL4;$a~73#5nH{N?hUO z%2Vq?cS^UH2uqa1ysUFUGiY#}YiTp|Z;D`e#|6x?%Bk(-)ub$p#)T zZ=_u@RdYG{Z9soF5yUV^MrrNAo2JDqPjyHbOSJ_&P4&GD$f#s)Fd*a*f7?;DyS0YkYBv?8=;&fFyoyQbfTHqNPX}#-V-X_j5YvCz=~|KHd$+6}yb zE^)!KMAm=AEoH%6T`Y37c1MY}Nb_PWu#Y3DBtSZWcQ$C^@@!`#MKw%O9lD5XojJl? zFK1m`DT9Ui3{0N&V4G}!zwe31^weuIm|xLIYPZu8aL~_)(&EHZ{cJc9&{JK?z@MhW zKz2AoHq62BP=6v|{Z7*DtB0rsDTutcFXQWYqJV$HdpMHbXjmGjL%s+Oz`h}4qr=O6 z&y*jHQGzi~bJ^{wYH~swDlc>`H5kVkBpqs5tl1A?PyqOmj#R8W_3+~4RyJc!18pKL zkgGV2)0}PN0lP(shH22v~jybz9 zCl;>a04T17py(J#QIS0R2a8xOM4z87I&FU;PAKIHI-OA!P9sc6@|73f)yg!L7f zN*}>zdEeyPes1q3gYXwe+1#6TI~wwbGX|{RvxoYJx%^GjhuM|KY5t*9RCOdnyZ=F50oUwQ@f|i6B zy)>qysKXfr27zak{qi=!uf#9|rM_K0ALoW&M^30;=?8&;wL*4oLq7;41T}wtfp4Bl zw1BD*(U8~yk*#G@j*~1>xP?lG_WI&=aQ#F6 zYq}dvn6wc-=``J5NqcRWW>J5Rqbm(5jq>f0N@wXh-&CpKG;^}mHCFM+?8uzs)DZA* zB{AeiHr47sOScYo>;(p@D>?wxW#gV_7scM}A&;ln`QI5PedFU_Rq^4&kYnuzbaS1y z`;=13rJ-YAy?6`VKBb25o;`ub_twYvV|Fl?r62+efe)x8Y0q%YU<`j1^jw-=&G!Lt zv&9b_ot)d2#Qrm_nGGQ|(;^^Veo-N?!UGiVEY=%8dp~U#+7n8x3HLI|CK5ghWZ1tP zZ%zrom^=EyWmyB3I+y#T->9RQVTzYLRL4Ck`WHBBkuG0BG=0@1z0(*ZenETsjA;H5-oZ=b-Ucy+;2zuhWqzI}33vrvPxhQ^wMwLdl zm<(EXU&*H;j00szJ`kv{b;0#YJG}3dw%t$5U zLup%*_TdM;4#4t?=Nx~2!{vp{?!!z%x$S6Wys&>R#{Tb{A{e?({hxOls&hD}c^72* zUW{Q>N&oNLdLDoQ>dQof?h=|YeUX*oVul&LD);q_wsoPc21RLVUl{qdl$^6vg4b^0 zea!m&pJ|Fx52%Z!0agu2m3XeVt!afoQom^`A z-Fio5Cap`!w4250xWj~?zF;p5O-}lLSQb7!7O~K8c#49R$i;Or147r%>twZ4(ocg4 zz3)dvEPQH6jf=ZQ8&JzYyH{_-q{H|ts4stUlQkNuRSW^$`9EfV)&2+!Mj@)a+L}Fy ziOoNwF_}WpGdeH0kD8pMAtM*DT$A(BeB7lUI-q!Y;hH}*CpggoOb%zgpE1ztGIkz6 zKm2M$Me;Nj`CjEsDIZWf6Gd<0)gY;kr3qz!(Q= zClHQ5Kjzq1mp|@a1?6w+=^=gou3&-y^|uT$o?q&YUZZ{7m=S4cr?%aeoxM<4RL|Y^ zyE+g32hY^GOf&w&GJla0hqWJdD6M}@OJmj@cOCHTdWD=|C>YJ((6P2H+PZNi^wsDk#SgZ3w-`PyGD|9tvG2;UDaG16mX*xTtdv!n!Rf0+&X5eHhOI6QU_g{Mgyk38l7O{NH}K6~$>N!OAGL?e zYOaQPsB+pxFePjn`Vie3M`UyQ)h0I%*0O8%iShhr=v_6U)C*JR5e0u~OHP0Y$@H(`mI*8>bW{V5fDdVi}x7 z)?JY}Mp`8l9M6(-W;da+tcO#3Wd!S;q_2fX_E94$Vp5xMNjb~k%q8}g9ZLKkM zaFw|vI@ND;MN&WU1v{_CI`CCukoGqr6UO*I>hvh3#TNJg)FpquR}ko0?z{nHfL!9% za2U?gE&hmqrj(&g<-*7@4J^!~PggkNb&+aMkh3Aee8E_ZR?#sFh{vDg6bhLIgW>2q zQ|-h&HIcw>qA7P3=%#*40V^=cE$imQ&)JwY?aJK`+^)w28$IazlVu6l91nIyZj%M< zC@X~U%XsE-;}U-uL?2N>ht|zW-brg;q`&OpC{Gfn%$(x`)P$Aia^M-@kA^OuD6bVn zvIqr=-%#AuTkY|#DvVtgVO*@?GxK)MKI}k{UmkIkPYf8^Ph zsTvwRGl9AH8yq6%p4TtJ4}&0eQU)&Z4j#8-O_2QJRNjC2gFXSdG$12+6Ifc_B|4qb z*wAEblZ~sWyKxJo$*FIjFI`CRrca$p4A5RYK#co_}5{JD6c-zfN-rq52*447!vZnUa^ek;^B+Uu|Sxqn`eOZMcb+{bMkAap5A za8pR=&{V2)qQH?gG{A`PgUE}5C*P1gvw5d+~fFqu> zcHUzuMt`sawALKmMFui&``Uea4?hK3kB&;9Yya}KX5?kJCCYkvpgy}385rSn7 z5So8r+@K!L`P4pl5W{ZjKYrPf;Bo$cE_V5=)at5iiVvrIq%(#05w>&D2x(B!`XA!(G7!8m>hLSdQ`Iy>W3haZ+*DY<1DQ>`Aeq`gBO!t5Ov>@1$-qmlr6nETWTG zb<+Hd2=VAVss$IWkVXBbP&OP&t={8%Y1ye%KiZ6B=+4WADLt^@P;l7GAUDQ&=u&?P zmp6j&fSZ0rl`U; zI2`mHnQasDSO)KwHBx~G*-p@C0v3N7Zqe(W3$+LEpjSPITwt$Pat`p3stgcwqaY`q z0HHPfnSQGCf1oOWUWzs{odmy9R>~ajtlhB}QmU2F(izwOCiQ<&ZdqwN zVEa4ikUorXO(7Nb69r3xIod5fJyb1mnM6QP_g+1oFyiUc=WBb(HGL)#yilGu?)hze z*2=;?l*Y)uSQ(w_f(OCgnM3ZnTq;@zD!`cAM)vbeUyyQf0q`!?KqF&QMrWzgkI2JN zQJI?0LRQ0bw=s4hUNvk>lLUV>Tm`)JI;MRMF>&%qe+SiCs@O1iFNH0I7GkhWYD}iMEo=f<1#IWn@F&TYF`Rrch&73Hp)@WI5Xf+EtzUZVDFqKn z#+fxNK1Y8F0@;i}<>KiB z#P4u0UM$`O=TDhH{ET^dEI98$ka{3iUis6Tz2%>yrU&0UNCw$v3oy{lV=ISJp+DQZ zpiMd)bfnRW9r*Dzb;WN0)H(sZqaBjBs<}+XXgYL2t-Z3FBfH`jX43cK=64KA!WFJi zEkSgKjQo_qI!mbV=CywnqX847GjCX5MSZLJ@tpZy)pM}tT3fSAkdl`B09Nxa<2 zTkKgUJ{sdh-lMXFAcmEDqT%TW8;8q5&ffR>q`B}lERaT89Fc!q-l(|`^*?-}&e?fj z`sjgVc_fJ5GuAiST1Vb5(AI*%yvlgOy+Okgs^qxfWH;j44>!mdGCnJ5EZXGTBQ>j_ zc}>TVTi#IciTdWSw@CEaXUipo__SGxS{0Ql+ZBYVP9=FNWlo(a(4d-*Fky?>-Dcr! z2h@Bw7_Cd_LA8HNTBYvg;|G;h!l)|hHQwvn4{@#A4+A6xEPsM0=_Dn$Xlb!`Fpl^G za6HY;g??=h!25zp#9oY$Gv*PT%FO2I1!aSeUDQ}9e}xkm1&@G(M#UG@9j43#3)|&8 zBL1Zh_`QUNYpeJ{kvO7AOsX=X`Z0M~gwGl8)GZyFnw@_(%hbwG_BU5p9{EnL)?YLk zXKbXJ=luC?>lLTsB4&}|5mDR?7NCU4_uy-dHu+?-k=t;0oj|HtnOWaWt^irv%e0>^ z^uNEh5KFEW;k(WfO9gd?K+LUZ(bgbOgMo+0QErVKQE7D*ey{KU%NB_-zOwRx~K=zLKILA!iNn~5tCwBsy4|OVGRVr(Kpqdw+<@7x<|G@*j z-v!m;0!&Ct9a&8hi1ZNIUAu18hnesa_=>X6P0oM9C_p&=1J^nY->d~TLe$`?qtk{0 zZNG5MygFT9!Zsp`9VdyO7(xcDFreRYpaM~D(XAGnv<{?W~KEtM``_{ z30gSCD1|6?+2rXgSBh`tFn*0%wBcmq@j#*Eewa3Nn1ZXhB5NZ^tChIpNSyEjcNo8lEcLl(z z04Y!H$43nbLFPxm!aCrGY(BXPe zPwPO&USu_*&WvDlYU7;#ig-C?0TYStzC01efQNCg6Sf;>KrV+rW*@HH+MwuqU4CDr z-F9kyp}g7U1YSiYSUe-e&#vdA9NQqL6qPfqz1yQRQ>IK*E(*iuc9(&iPmzCZ(h-}x zbA5F>jgwV+CK5|A;+)rfx#+9@5le*FQ*X0Pqr&h{17fI-1@ zL35Z*489CW2zk>vVEKEV^po35dFp?UH+7Z6Owbw~G%0Z>f3sNel$HB{;5Non4v8_H z(=~_q4X|RR*gphgU{i60I0S#-yB3k#wZcPD?}Yp5`o16yGACY+K)wL4R%Zb=xx?Mf zBsv&|-(e2BRe~8q03pVw+||a|GZ2-P?_@=NZbjRiNDQfe>N~A>N;BC)YTGWl!DS}E zTab}IdC-be-r9O3%cmcS$3zP(PU}(1prQ6;RXLE$L?xV1gA{mmWzv5alNe)X1)%Pq zAR)sqr5)Na+2Gdb%l;TC0*e~&N=@c?xst&iY=-UzxcIreJqXo>)JQUU3{_U^WJ~$c z1}NwF$Wl78k>K@gvu_K32#{}cRvCO|@Ab&ic?@JWc7k>Gia9uo++iS8Hf`C#!zji|W1n~h!5ZtC`%JB#%OijyxapkBwu<|^ z(yqMzg=WfN?-t*FKP&wAPLyydV<7sgUYvH4$JJ%{nSXu(kBxt9iYgz>o&uz`58>|MyP{8Q>@Nl(nXV>X#9t9bx%kT?-U&Cku=qiLv4?hD9yEs)$!w20{|GrVscS z>TJu@l4zQ&LJ5Cl${2k)@e5$7(yvW*Ng{E>eKq~ap}nZbss}-krCJ&Q?ff?d6MBef zLKGaLN=|qAwX>qt&1Nt1k}=PvQ1o@m_3mCc_`;vKH907~9x=k%aT}2LPfN4V7nXfw z@*R40-bS93>z8NSn71`P+m8)w;g)AWBKf4~M)EiyaQW!n!1H;z(CXldkff7-O zWQ+IZys!*H+fYoTQ=(H}>ES>#Y4v>}{ zqzk&goZyPPPmW#K_nLL>enCs3un>6(66f^O_)vSmgOOIkJQg#*R?#6@h{a0;=eOvc z8aQMT7%+04uMA?%i^@x7?;#SMxm^?DkR^XZDDvz=u%IFL2w}bCF{Tv#miWOhwFeG1 zC}myKutE}|t}-kr9)0z}M8Ogz`wPg_rSsG#=R9bA!@}i!KsV%tCQbYATVp!-M~&CM zD}V7(D@uo11M$R=sMzLL>0>&wLCzC$2{ik9_&)UhMlawYJ6Siu?<&4g&|tdxC47JQ z8Z6()*&ana@Tva_6*q`|>LZRPgrX+T>$q}^LHAxDdjy;DM7%}_#pV4x7Xi#!p&`2C zdFMY)IfD5#%^e0~GLdBza_W1Re)4nlQooeoo+Okk5B??-R_d|w?bvhDIa1!)Fsi19 zX0-u_0>oAdA#0J)Szs`Ue)I`J1_s z^@8*tZPV@(@$@}c#E&$WUKzxov!$q5SaZ7zDuGtca~5aIX=8qJw7b+rq62@ih4tea zoREKKCf>tIP_B|db2!+}V`o8`NE(X^$S4Lmlub`3q*&S^SFIJ>_}_hd%jg$gum}y+q2!ewYhhP53!4T)b$G7vp+pc_K=`;LOlYsj4YNtKPD6Fpp0kNj;~<*X7I^wxvGwgzu}382`w z$E1&Jd9nw-JMDy!@EvF&(24$r{{8p}a=1L0Jptg@8@|x(PLOdA^Wf z5+=Ma)aS$B(Q8S?e-wXb6QkT;!{S>;f^$`&v9|;fV!c9fCDn%fDecNCPGrJ!tRB=aP3>6`?s5;g$BxFP~U>v>PDV#0+LNBb@ml=8dlg&F%2$MGxk6MsCVg*UItmK^^R zb#6p$E>K#XmN9?sTk;rk_QfA`Br7_}$w?H?DN#h`W&A{z&aQpwQg>p#ay2gJ*BV25 zFhS+qXY&H}Jo}CBZSKbdp8Gwr-PoT|fM}(|^EA&n)UgYva-s2vM4iVA?(Lqb_+6;wkxsFw%z$?zepBwRV4_Gx!%NTBYuf!zXFS-K>H9 zUP3iv`g#Xp^OIHsHk>#(RDQARVE_C}WL!*qR)0CfLu`_;c0q2zq)O(|bK||+=~Hh! zT64gB?FjloxtKo5$H>LnL>QvnvYn`9YQw;F(@LR=R$1}ss1@=}CiG>_s3`@u%zat? zm&p@o7pQ-t+MkCT{t}mjEX{=zkWZ%!P4F5UJ8(Dpx0bAB{?GoYt^#fO| z`LhAg}@9pr!BAOE`j4H!OCh$(r; zN?Lz(eyx~B35-RblAw$9qY-nl+2?WFl#&NUiZUC<#*p_GN74D?y;P)KNxGz$7dn*j zS!juEUG&jSG$3k(r;3Z|@1x-zM_t#!I1f#AW_M=SR>TLJfUB%8K2#@2s-pl%-ePsa>70;<|~)|-B#M98RBlJZZo zgoatveiddOSJa3^V9zvhlA|9U*&7yrC4(>|HK}xBc4q!w<~w_paqE_%&P$Ju`#`hr>( z@MD~cS_JAHUu$MON#T1TxKUdzCEWOB??J>-ou_wJL~~{BbRLB|gJ{sNGzzTv$5b9H zq?qYKxbpX%YYA5_{C@!lC-~Td))@@RczI|#E8j4bxqe%iG$EA5br|jlPfLAuxHG6^ z#5^r(E*Za3(%RTVU|H8v8vn)M!DJ2|FPN!M>#D%aD%VRamfJ>7o2-9q9|r!EcbZaC z!kHfwW%s9DCObaeL ziQ<@F>U%z-AW`?F!7Xs&;f#e{by{iVocjb?m3 zKXD^E#a?Kmp0oN=*rwae&gDnHJQ z0U7<)+Po+m5Cea==8n0*IV=jdlbd4<`XPjz(gd?Q0RS+Bz(F#3=DxHrO^J@>B$q> zL8tVX-cq-Z?3fA{om7b z$+0KzI^32jTZ=T{mX`$ja7qN#j%RTtRySbHqTOGdDFvmL&vz@+v+k7!0fkW}uwd*+ zpIce+xdq@mf}?ag;T6sUe%lrm24-fJ2c+jUajB#)qNDI3N$`;`2ED<`r&`s&cAy~T z*J6J|?EQK@-92hzzGXMMRmy{&JSVgLl=TiOn;}p55(}_RNvK1Wrl!^cFJ+kL7Ny2U zsLHi()zVgtnY0JMMo`9WZWRuzLdC_rfQjQw)}NpfCy9*N!#K z?3Iu+eW0X_ZR?_Bp?O8ZLAYP2-y0v0lK;oVQLs!oK1V+Ur!thT|J)8+)Z_}N1QRq$ zOL{MSr#n+D8w#^J?2u%Rla-?(f`^AY{O{ZTj^s0QAyQ|-(csOh`hm?{SL{J$lmQ;7aC)Jq6PuGsMWy79Q%Jcn$8&`K?=KyH%_;`q5~hFka`yr;SlHJsi_cbn9f!baP}#q^p20s;MmdHGXrBZ3 zehY;l%1Gj0Gc?pvb+9nst=*IWxCpR;qY9<)X;R)`yK7FSzBNWTjgRriAwGDivry!M z)FTmG1A8vFSjDj~+KtGsSGiTKtc>r^jtL6NFS;MjHYHUF%nR~I9!G!B*;BcRCrkV+ zC^9QAk)~2tBcQ>jtqL)-4E)NZj4nk3=)8sf$$tq*wD_7#8D8vyK=|RjPne)nHH-B& z6`OP?=Ovs>$A6s5pc$jDdR;%Wlq0Y~TviN~Hp*E$;ZyE)J48Qlb&bgW(Km++7z;Ro zS{shn9nZpOAbY5xEUtg@%mqapio6W^yC_d+6h-pcTVcux83v2+9vxR4wif9zq=upeKkI({ttFmwuBYn!rSovPK`Yn2yyfJ%m`w+jF~}B zMDLe2Lz`4BRA1p33GjvBKY$grvK)G)f?r}!4Sj_^WHe$V)+_H(JBhkOi>Y((^KVen z<}$yuHlh88K|o+)W$MbBdy?a4b3XQBCMTea>(b8gtq2 zKwB1`z6Q_o#S0gAdkH8H($4_al3H9eb4IrCLo;d{O-HKo(^SV}_R{}DlV3dO_#Wa< z(&fQpa+bSD<9+E|(vL0%1)9M(*(o>=#%ABOm-pv#=TF6?;IoQ<+$;-U?G@m^(dbaW zV!Z7&oX0@5*<(m>zy(Y-!l*phK2LI2rCLUC&+4ZwYOdYXqO8qQ- z=uB}BYx`Ec-Ta_`%FSBbH&qhYsNZ~dp8Xr*Q%(y?iAKc`EE?Is7yV!|Ej=?_BlpF3 zf4!b_Vn{emf{l}pVjB%=b+?Y~$IWYjigQWZ_~R}qvoq6s`3To{Gkkak+D_aqY*@*k z?)NUNt4A$tT{AjpFzhXCA`tiTc(d0@>u_aPQDSJGT8r9$Pk0yNJ7ON(6PdOVd(R~{ zEQXwPPo6g;92ly4pO?}9D`|Hq61)QE0XwRj?WBZ?`7Z56m$*?{ucO*q62__Ux+9^y z8@%I%X9pAM*?Mqse6y;=%HvXmLbQ^So{Yytl3wF4jjE>1%3+RgTa)omm9$6Iyjj}jFMY6R;9Ev@B?lf_)--a7Gx)G;Z<{kmIf;f*_zMobSuuSdl40hs!jD?F=^d(NM zEo&btv?G?tx`7n%`$-l|OxE9=D`=`b_#$eYY|Yp(Fiz`eLwjfK{w795O+vRTT6Gxdndsvsrx# zHogo|f3uHSrll*9W5*);KrjNz^a0c$^&4YE$-}a)uwtILLluL6KttnX?o?F(H9Z42e0y$*EbPHD=S<~k_?TKx zZ@4*(;@;d)&Y0BYIlZU=>t$+|E+E3^^WLX&043hqc1FTjCgy*Dy+&|gbN!BIv6gB3 z#v*T#31vnuyFs;ru|U&|oHt*<*qlDJGGjI5d8Ohb>x6X;Hsf#~;fRu+D^?nRH?&)ZkCM=!7t!yh76(=U+){U@qvPwiMVK~>^JygJv< zf;DfZwx-(p+7`T+)A5^l6^OBQ7rGr|S}K291Y`t99sfE(JvAyrtKU)(;Vn1#Xu~)- z?0b(-kKaMcF7Te-5H~dN<1po$QCUhOg3SUUfZG+U!p*?y`^3r595%dvhHg!w81od> zkg>62*JDy3g(k+<|Aj!4zh0br(Lr$(Q-AMFkxVTR!E86Q>QEE@Nyh}+6QDVt%go&) z>1OlmWAtAaeRD*=WJkn}(Td|IS{-Ie%(JQ0xrb&IrUx|;35}`}yb+G+ewrLr5{FaQ z1f?O|d8$$#vhNW57Lc}otG3W>c||1CkQ_e+*_FCJ-Lq%&`$+pAI+q(lR=0Z7v64vU($Dt?p|kdSlHkb zaW{#KToPMeH~?DZKD~aoz*9LdU@ANS?eQ>YIKiFfka)&CxNb55$5zT1OSKgs>?aX7 zt{N=mjHltgb_?tWkI>FJpY!90N_tzFw#Ab1aXwt&RzBn`7QHB}@pkWKy9w5?&5$Se zxCkwhE6Le=VFCqz=Ln~BL9+)T=&uUAmwUvCtr6=QGq=5bzM;y?94u8>{MB|er&~D8 z?k;x}W*R#TWXl(Wheho6UI6vERqBY~|HgTi$%9D_NxY>Sm~=Z1XCc4+zQCsWM$J~o z82(=!WJojl89A-pv!g8?2j`(w)(sDy3LAU1Uh4baPSyK=$`lDb@OttG-PwgEM4sRy zEmv2<`!2V-dHfttsvFf*#MOyeV37@0?7Os2=17Cjauq92)DAVtreQ4AuC7O-HmJ3o zt`;KiMjmGK3wxVSC$plEU`_5yNxJcW@wlA?Rs_9-CF_GS83459>8j)(P`YhDPVgaA zbba7<`4z%{h$;L2oH)|QCui37eyOObcJs?6!C8N>K@`? zugAf8C?B>g)WJZ;NK^oi-IoEgSk52ranXv@Pnl1DaQa;m22B8h-M1kR;T*#IR{&?e zq4DxN3c=7^Q$Lx960L`z8k)^E#+!1Gbp^YAH@^e>DcDn2`;QS09}2OhUH^0mbBHHwpOEKhhJ;EQiWU9 ze_Q!~Pze~;!hMJ ze~Yym9}TzF(>CBor+c68=JR6l(jLNkUtvUl6~~ihmoJ-F03K*NI#&PTWGiqRjQ1^F zsvBPh9D&_sUJ}{s2pNo8dXfOlA(K_`|C8uP`4!52T3zMES&#OFQn6=6?$L2e8f?g}f8WD{-1RWtB|avFv}sZhm# z@C+8+qEbVwZwSL2VovUQLO2y3!}%aX~55)+#x_e-GEa zxFr?|)1`njHuMmFpBG-4f$CTSiH6qmXVNzTMk3;tF_eI!UvaMfr(xD5d+4ke%r@i2 zBfJg|C=r9h+ZV(pso;eZCXDfOZ1|D*>HIlI%sVk+v&*~bz(Jj8fk}ygs*{m_^QiV@ z(?Uler8OKgXFPvuE_#0zESPlZ9}vN1ELavfJ$HJ4??~M&E`Dw9OoeI9Y0?SOpjPXe zxT$vYuGUL{e#pc`UC<@WhW~DxE=o{c*VUqb(yu8&FjPzzexI9L))-u(=~?|QR$-5v z{0rqt>Jhqpxcf98+={TQxqhI3IGP>gQdkxpcv;*Dk~3jvYt_NmyD#7G_{Rd}3Y`4G z&}tZbH0hw5lBu1!?HXU0ydUCsa;Yg`!r>)a?@`!!ox)Yg@26;2qugpf=OY`+`LSEa z39RT$qZJDF3B1^uk$Q)NV&40{}5zn)6q;TeudM z4*SmAM*wD$~R)_feO0XYMfMm3BcyYRvf|-NwGQH zswtL}&S2GHxFC}64nA--IrLY){a0S*(h7w(JM`%~fVS|^{1Pf?^7}(m`P>N;)TZ#= z48bdWV7b@X=om3Vu6=r)>;~)M(kl}8hKxhQv4V$GpFhZf9Hd9>yzlsh;6fZA40@<+ z#`#EN;CY#)@?QRb*=(KlLD=$6d@bl9K-ly0zsZ-@e(@TRzmujTp1gRbM($Z8{P8$^ zEOMDDo6Qi5lDGQd11LKUVl@dy>e7GM2`zt#qQZagEZpfed9u;9zRHDR(rc6Vf*W(7 z=@5U@Y2*M+^N|~cw&wO9j|0#Iu%XNcTFCQBKu3DzIbYL%!2`RIvBpM`I;()K?8K8jYR4>11Bmmc+(~CvKZY zY4i{7qJvEU_TNhORe-Yxq9NiBD|CG$b`a@yO8qw}pu$Lq1d>u7y}p|agSGpfrG#t} zgAzIsSD+hzRRN3K9F=v2SzAR8{lt&S6!4C#o2_o&>T7~YM3L6safLyS0UsCG>64&~ z|G;=y48<*bft^98RJSe^x@Ko=2gxoD)D49{SrJSN|EH`moZBqX5>Q?mZ!{&5fM|)+ zAUI%I>$m0i2|6>&j>^D(Q>ydsb2184f>q!G6wv%?%j09{CoGPxLf?Jv%jy}Bo0TakE@_Bd zkmE$vUez4Vj5XBejY5ZdM|rLg9n8Zd_Ltf~EzMcuTKqwe;U80L^JCE-exD>QFRMkU zp@SBGacD`!go^LL1<-*5#N|^dU;bUu5C;q*2Vul0vxn$H!G*XNwNjZC0v=}t=g&cv zax9p-no)=N3NOhXdWrcL5!I6H)ND@|Ds2 zb_8N0S*xJ>=kFaL;On2S>1`g>I=XToTc`w{h4_I~<{Yg(JHRi(sz%FMi$>P^FC4IUXC@?6%O$0;9wGju} z-iUyt@L=GGFR6O;5_XCoz|G{HWo1rhGgNSij|N@cFORNhP3j}i3DR(eGjtjT&{RaI zm9hpM8f67~>S|BTh~N|jNoD9$+3k*hyzR2E4q-9ycD}16U5bd|i>8AEIJw9LS8`7w zg{Jqz);Nn6t7iRVf+YD8modpVN>)gChJc<01tPNw`%%7DCv{;hjcZSCNg zdy;5a6~heoqLhpd*1ZmnTJv#uho2E79@+j-JqVH8a3NzixN@5mxLl!j9BRE!6x~bqEd>@YZ6ld_TxWyx0IZXg!5Qk1k}0*8@UC@L*=B z?lG98JW-~Hj?k+@%_ppg{W~wYY@XO+V>nDAuoR|T$1f}}$@98@IDggE(Oa_+ z#RytHxYmFfr1+@@h6ww&d#O8O;6*^4o?)Qond}tyT(Mh!%Y+PF%hxDMyI_qICLZpG zRz+B7+x#9cnfPPlUf0HA{5WYBmXZk`kgrUaIcsgQ7P`z6weyY#Hiza=*36m?$28r% zxJzHO+x&I7Jx7~OcuVeo!(Tm&9)$OV`v~;=n#@^>Htvx?j0@+_Ii+_{Qx{gHXz%ZL zk6On-`jSGM=eZJYP<+TKA_i&$qrVz^>3q0X@fWH^A$d=h-j0ud0hkA}6o+W5RH}DGJH9MeCf3#WC21s7F%fAm zM&VQx6tQ7;t#b;0uu2LzNLM!BoU^ZT=e*@r-o$Y{O(DNKxF|2+18_PPTK14H2xDZ* ze{Y0-)|WE?q~<3IOlbJPO$D3q)R(QDgRTSl=@4cFNnONFC9-aiJjwrkG)J)D~;P!5`T2;2h&ks zwzL*~Sd{W?E25w2DkM02{blI)7S7HdNp7ya*A<3Dq~)+7M5NPEFH{E9A|&pXBI%)d zJq>*^C;&k^jg)5lFv3|^M7g5semm1)A6?r#m|rLsR4J_nDteB^PXhCLpOt~Z_p;8y zVq~;Pp_&$dIql4!pBdR>=+mi!;)b{qo7h<<-@y5cdRyBvItUKMZ=*h=T zIg0mxv$RpW@3Ed32zq{$UACKkWfcOnm9}yRGKg)Pk9RlkFT7 z*HXAUiPF0Dspx|5$QwEvz8(P7rfYpIpZSji8@#C(TsCpY!T6NL&zmn)2Ry4=f1z~8 z=d&;jqRj9B2EGg;*CJk4a>_b*3u)E8`w6Ol0Dx}GfLW1uh3*N4PlkuhB73f(MWfC3 z6&K^5;l#Z=P?1j%-c>y^s7Cy>k&Z#lR$^u2n>B1^4jRrOrT;<~2uBzH&0oYKAU$Bi zsT-JNzUF=0f^?w?*o9G&j2FRL@)C(!0xm?|U4|6Widdnz(%&*mm`Za7Szn_{E&oq{ z`#ejAcT7rndaW0YCwr6BteEdQAsieHHE0Co@sfX`pvUOG^0U8?q$Yj57~y2_g~G)p zfuUIrrq++w--)L>y6=q52rS7>Ugx8TFZLd-hBaC4p~H5nQG%ZWvu>$$${hp&b1lpy zhJTBOmRj?zCk|L^7Gfl9Tc`T7VJ_-_d1Ha3>Zn{fK=(AmakqNTcA9qMZX@gvOQS|H zQdZGHnUyTB!z-F`x=uvyB1R_5Syd^_!QJ;NyU;h|h9=0g<@1 zEWzqf_NSL4H4M!l6Iy@n#XY_lx)9<1@eb>#_>rm#2MxVQfA&=-1RYX7r? z9+oauX_<}%UOG`UWCYtxICh36$hI)|M|7nPUUVh(UP@#j_NT_apjmoeaqT%}>FWA) zsw5k`K8g0xH6kuD*@13$?~F)vbg^Z)G~W%nf;c!sdB?nutWra%oF)b zWatDxEU3^d>k%+0WaO%zgAVgJ0KO_3xlU*%5{|_P@HT6Z#4?eh+>`=;$R@UHx2bGz zT-8+MU!cd40t~t6F9e%RE;xUnKCWxzi_JtdIyZUc7K7}FhPkH!3;!j=1~ITVSKdqG zy(k@l4S4xDYOo9OnbZ>w1d}1I0&j?vmFIdi9_Obj3w^IKxn-{*h`Z`9^86$VzCS5OX$;)F765)zN zpO)}O`r5nGTrc3(@e6rrI8t;%xCOm#TBC1&!HKt7gQhP(F5^jmNvuvH8cPDTOdo;uy$4V~jl z`KEMb5N#Uz#0E2@{kY-s<`Bd?3iEUDpO)?BXRT;L zQ|tAyOvy(`wrHGxgu+JW_1!3{zc@W7+dR-NO5f=~*(PmNWm!U(dVg^T$4LEpL9FdB z4QHSrO^3Y_^8p&e<5tfLQgx!WbgB@M_E#Dqfkx1FXwr31h1=s%H8F#-op|60ztr6o zgT{M994P7R73&03-A7$~)tY2W1qQYm6R6wa-WePU@XtJdd>p-Sb-eW#GAVMQbg1Vp zj9{G1@g-XXh-IEu>^5xvQI6~#wFglm4U?|z&4pknRNHa;fo|;cYJRCB50G@TXwr9I z-kRXbL=(nk##;=LRHVMZiZhPPSa0osa5)lZqA=l)aW^F_$!jBHB&;YI5;gfpRQ6fM zx+E+pWsrS;*U3_`$RC~GPM(LHQ z{puGC(Ex~1t1Mz|mclZH{kwnkfWsuqz$O>`GSEboY;G2I1mC=ZAB?*zfu(1kfRj)2 zN>UjZzRp#k5I88~`>-5!E0=KsSV5-kO*jv|rIzY{SVDX~VA8s%z1JLs3-b-FfBUyw z#5M5w&|j6SaT;CIs3dK%FWjf_Lm;t1i)x=HgAXM7(MC9QEMMr(NY~B{hXags4Qv4U zirltz1M^W+tov+MEVvdNX5tRo@!vRN&R?0xmNw^3Kj&rc+S_s{8pWWNzMkCqL1hN2 zvh$RGp2F7%ff^FyG2`Q(*EKUa6k$03a5>q9xlFH%1_4w{xX7K0`YOeM_m_F@JPyMJ zRW3;`haQP|r)C=iV}pFEDT__N6Njr!pIhe(fEJi|h$KqKsu-+}{$fVrdOAic$uZ{2 ztQ<#~L-RMIdZ4^IfP2iD$C2Z-#MX(dcy7{vSds^YvG{UUjd+l^u^neU6Fx~iX0+bK zHWM=B={Girjky^9@1r^%UnlX4BW-~%<`-2njZ)5A9op`pG z^@kEryY8iCjwtWu-SAY_Zm(12jtN0D&)mvdbO!|9fzm=Eo6CQ3mn<}L_Q3u}kmRBp z^yV!Gw`DiuP>l*@Ze(+Ga%Ev{3T19&Z(?c+IWZtGAa7!73OqatFHB`_XLM*WAU85G z3NK7$ZfA68G9WQCH#RhvaZ~{n1T-@?Gne7u0VjWLxdlvRO%^STTjTCr+#MQscXyWy zT-@EQk;a|I-L-LdcXx-zY210=%)FVGKlxM1$(FTKYp>dsRB|XuB^~Tt)x8{ntcqS*bz~H!05npH8UQJvJO>VDAoecKwH#g|mYlKtV!XL{fiAQ5_&5#;h&|FtIlW$V>lIZtv>C`wtpu z=4|(`?ic{B|FdjO{%4u~&-!21+4DaZ69OwMz#L@e3NQs)g6t8P|D~IZy@dnd`+vgb zZjS#={X@v*AASIue>9{8m;){TLA%-7Dw@~<0W@L`c8+eYKxcr0gE`RI9-!)AXJUW< zUzCX*$kyxs7x#Y=GOi~7=pbTm`Hyle{|SLyBtf1)b7he0KT=zm*#0BYzvEiK|D1~g z&>ZAu_n&&;KYILgqUH|vwqE~t%YWMV_lC@3+8Ux#BJ}?ofPbeY?9Cj^LH3paHP?T% zG;ucnU*O+qWfRbUrsuz8{yR+o*8hL!E10-CgFFFxEKL6z50-ze|5^tB4<#z<;OWE2 z%FPL2WM^XmuyXwK;o)HO`~T22b8~hE+PnT+@PB&wumA5s0s=jOW(aG`4rY9z)@jY* z<^B?dvlYC z1<<5ee;Svy_d%m>$FDBj+e^_JP@`w+ej)<*>8nv^t-=bfOog8J)*yc5h3q0;Q{ov} z6_f`#9{$j|WoKxzx^mz;HD-i7?1W?flq@r zW$GC3XZMsJ2`0KADiuprWccNugml2i`E13&*;+`YfEgy;G=NnAwQGZL! zu2e33vkHK-Z7>3g-ZWiR_Mpbjwoxt-ql?Ih@L7?={*3r+HLfa);pFZN;({|n8Atbr zTM`+RR@lboPhK~^Q)ho$*k>(iqxU7Ausshi|5IMr=f{}k20_t;4t*BW3+90NY4JXe6dT$XH%-@Yz2@~N4hLs4)$=T>F${^((}pg4I4S{^eb0UO#7P?9F8b)s($ zy<>OA-B9+nVjua9%^FOh+5sOGFC^B7#}pVX!N=4Yh)+GRy-I(q67PmY@DzfdPYlao zX(gStexfZbk+TWZJ3;=qKyO4`Uk~u4w2AmT$%-D}86~-ys+1cb=mx=;6xB29T;9}x z(>L-dW<5kGiIu@zUfmYt?b`FnE&D0U9Z-^DU90xyfpnU(bk4YbjPiuo6}fl68-T0p z`HjvHh2FZ5FgAZu>YJ}t(au;ao=H&~k7fNg#3>n4;9f7L+or$SIGpLxP;ltD_2#EF zryR`V(+~E|{46fIH1_WaE~dUz_?SduloVgTUhtj6G2GRB3PR)Ti7qTSll%5|bxM7z zZF4PnLd^(^F9WBXt&@z$F{Q+h5Z3Dx^S~7YdvbHnsr!Fd)lmK#3=)FzL0>{fTMSQg zm;2SOT)R*=>*67!dD?pu$+S?i9_m=_^E-4VAuc-KQvGSignHVWn!9LJnmt!%lfiP5 z<|+-1TkFdpDbF6-vpOTrEMPv%t@S8{{Rqe`aGzmCX7Kxl#MoO`Li-mvf|c3&?xxq8 zziv+_biRL1yt6a#reAJBw02F%BYU#T>;3 zrfr+R86u!6ju%UI`LTH<{5Yg-XejHxH=o@b%k+OSO}>AgadA0&@|HoiNb_kzeYI{f z&}t6fquG z%WRhel5BdYLep_IPKXpiFCdHlwNVROk z?V^9=>5}yQ!T)YLgdiFDh3VD998RH7KC8}*XKC*vgkP7C?5{Ubiz@shiM4AWF9 zm-4sRIy-df>2voDAie0ajPV;4l~_rdNc3*;XruA1@8XkCkdyyt|BP?)CCyHRDA}}@ zgT7li$ZV;TFS_CJfw$jkXW~V^tU}`Yg+YJHoGhI_3GzfvOyY6fjL3iNyO&fmx=*!6 z&BE2Fi*|Q;E==#W8#0*XwPvWr7$nNQLUJwL+Le}%;rvQ8sID>AMn>UaL74EIXt?q-V&R{bONp4_byl)@Pstr zCe#+0Z342p>zQpLazUsIx7dm7wb3#Zeq(2BG@76xy+36q|g|$iqRk zc-m6`#*PXzZSM&FQ5{veFEunr8@vz4wT8U=B13c8505c*k0CQ_R zl`di$iqsh4JIf?A5mR9Jlw67TX=||w@}Jp^*M8eM!xn!&47R{EQCV2%2-^x%*k)v+8W_Hz6@&4<-Y@K3=%aIQwMVY+ zh8CVKZ`j^RPs+`=`Y=8H41kv&hq{KlaLp~>$eN#wNPpDybccCd8PkkNmpl}H+gm=m zWU!-mI{G8Nz?0Y#u+t^EM*4y*%0GvU%ACGMPiI&d`%UTXX^?-IYD8L5@tWJVgI+Dw zc@R7fz598TF^?8%T8XDsi6#jgmf1I9$eE-LIG3`Z(AM=!!?bNF_$Hj1Jd#k8p*!}sneo*s2Ni>Y$qptlF)ywpwp3=gq4JsVszy zO$?IR&u8EiXYBq`yGR||pTTJ2(k|@AYa^Spw$zd~fCsxpIanDOp1|`985lv@n${MC z&(fB(4tF?33n16y_<|pXxY#OL*h6_U+o}nXoU$+Np^iU56TKIhHsd|OeZSukY8drD z3S2(od*Od!6qjDCmLu`eWH_wKtHdha~WiA>=K@$)f^_H)tRp7@kqJSUH)k{Q`Wbof>?8lY6vx( zL-}=q_tZiwn_K&qObR)z>3JLC9O5}?I(tZjqq~3C;g&}kaYRN3i;YAx$W5BmwVgMa z`Pn)J3FT>W{ahHE>g~ISvQLc#C4P%{S-;u8YE}?A+%A?id8O38@E{N{Hz7uu%tBY* z{B88nTsOBN;wP|%jA7_Zg(t`D_6@5&=Wy0%B&IYx#GvC_VY<<2-*8~9?)4zcqPvwE zlt+K@j9lr0TD0LjLPpfJf*@$ce`m<#!4OiTg4HJ=5d-#2V$s9vUHXZ>myPx9)FCFi(GLypFk@QxmMS!7>nj(1`Ili7I61T%xq^ zbZLsRhZ1INNTBrq>tP-1Idbhvb=Svg&PIt&YzF@YVPUM6g3_x}!P({h`-ydoPEM-Q zRLsQQ zg@z5n`4PCxF6CG`v7)(M#0J}IHj&)j3%T~h%7!bbs8)R8ynyGB@y??@2abkx5%#3` zoQq%cD${Q6gnX(9a~+xi9!mIYl@Z!EU>=;te61#FRTeMV(3ui~6;H*hsfd3NLBMo6 z1KHHV!8{4+UM(45)?4BryPLgxZlxfvxNF9&ppL4vRdMImtywGe$}L+G1Cv*2QKULnXf{-Y(_>L z3YG@>B`~D31;omVI;HY>mC%11a(sM`6qoXA5sHkQ2e`P|PSwx94_S6hS0wZsJLz8s}g*=0WveAfp@GFr1tv zxse5A2_WpAeZ^XeW`+#JJEU3?LoXAv1k6Nu1xXT0~9#Jxk*`{I1ge?y}9h6kE1G0w{R^^-?d z(O2Jif!A_m{xt1@eu&WaE3Udq54^ATuzpIneNnImA2*COk=X_ zN;g|wi1F7=3II`UBG0gE@C=DE7azy*`$b)(NxBrE;fB*@A({>wN;|quBO+hA@P%EP z6lLbhgycXI^ESFD%Yj=ZC}?qC5||7$8bYkwc_+UuKffq8=cwh3v*U4-c+L-E>Ec?i z9+CWDhZfj2rC5JF-95TGR`C;Nki4QqUW;gBq20lMx|(H&820p-x;0@1qy$IfTzTH+ z7h?SBJ2z}{6e4&=3mZoOLPOx7EjUQCjIvar?3$KVyDXo{_~i$#nK$7pqv(? z(ryiWi6lQoPNAKwLqp$78AewQEpriQ6u2Q-hSmV@BM_R<^Gq78q~(69qpMM>`nk$> zv6<&yw{m~qVW~dtc`en##0o|$g{@eRmN8HEqBYoQl}DxyMF_!d80P}S zmtBsmEV_E6GwIM{zG~LE$y(-wzVc|SKB0&vB{|tvivRr(ubc-yj*9r520an)K{%39 zZ7*k~HOlo~T2;p$f^$i_(Ty}Yz!wGis#NLnjnaR~8`i|tnhGa5HQ!CY#`3UbGw>`B z(yaUU6-iMW4iBnOG7ce}@c>6aQ32KwtS?3mKhVrxWsay#&rJueEis18`A$R}fV9_C zh_z{R?@J&nfI}aBOxcusdknbuSM6aM`T9`EZWUm2-t;Dc zAOL?&&D(gV-Rx#Uc8k7AWH}tuhX(;ZBdN*G*p2sjcm8gDTD-26-fl}_j7v|^ws`0~ z|LOIDmaxn8+mE249DzDuO5mNp@eOmK9C9W*dF)M`wG6 zm`dEqtD6o_GFAl*4dLX_i@*e=wNfLS=`Mc_wYjtNCHn~f$vgD9?jv;Yj!5MSYNOWD zumyTHw!>+yiI_F!0YZQb`VC;*zTdaY_4(QHNx}suP|`(uxEEEaqD`OAL@p%f?Pl3! z{9_4sOuNxN!TT}Ns5*kUoYbMCKAXTOl#Wh6DUu0{>kf5ymY0{niEjrfzOZGVZ)bmS zrUss!Je_bKiA0uPsl7JCiZMuPjT*m7>UB(Bw?*Y1G zY64mFczKctRlY@SVB3u3<$Z_;z(#*6kp)b~8Vj$KjzmCPji`oqxDv=7P7QoU`5v2s z5cFL|Qyf0|Vmt(r3XB;{N4}YeD@7;$r!6c7s zOicuC7L` zcGr!`+$R7{&n$Mls4X-oS|8X*o5uZKP<$2QvX!}`efo8COLo7KW&0^GA44gvrpAKYiX&-&n}+>f6EC$9u>J75QCwj z#c(D1sd$F>5+T`Z;M?~6o$_6JEBmGv{LVZ3e!qgoctUwUjIl# zi$1p!H}m)Fry~J3X$B9#(N1Sq*PBS_=l+iUE;ek34u0{|mXswT%Zz_fA4`WZ^A17D zP37P?T$oDLlK(FPbtXX2ritO}1<3>N=P{6pnT{EcLobU?JWcMow3l>9OW}smC|Jy{ z(;)LFr-IR+WSjl&p=`^rKv?d%{(Ae1DtUe6huQD1SZ7yV+w*()4vCt3xs-u{_>w$k zGppBds@^1+=@9mkwQqkW6~Cc6Wt5%KrFDLvcOMz_$HhFBhX^r5wD`Y;KBm_R z&{dB(_^3eyZS3}Sx@WEzaR;Ob$Bl)U1Y_teMmD%>!y9N^m3e>9p<3c7N_A26g|eqP zCXRAMq*f{8l9qx=$GBh@vEx}ZE{HRA7b`Dfg_q021o88h_teAi!N6Dcti%lrzDPjG z^NrlaDPi?#y!Io)>*?auo7Azz&Q6ih%PRRb;+(Nj*94P$vyK^9Ng`*HH(q=_@S1Il z2IMf6fwjT8i6ejE7XSS*IJNZ5fM+Fx03X}c)%b0~ooR8PQgC^waa(0zPL|}!c9kyV zEGc)4ie9rPzr=2kKvlP>KA9r36k4Sr8CKPECUn1&tXZsQnaQ$c#po;z80{xf=qzSrG?G>uyQM7WK)9*mjYx9zT@>X8E`z zMKSO#pD=%*jy-EL*t=o6Gm7)Yi-&L0Q^daif(1yX*rh(W=g3>GwiX#VlJst75*507V z`n(G*3sGF+htG~O8)$XdRg8zg1VmA~##(>X-LueoL+dz_6`KJVZC%VLRZZLv`N5V< zU}1Ao(;%)%jzjd`?F+d`xpdj{7AJ1-`WgB|M<9oJR7jC>GKWee%)|=ODVSh77f!unydP`tOZ;CVCl)RAnMLo&|j-x1fG}p zyGvAd3Drw1tcrqiwWK$%ZCGoMsoChtmgCz(mxH1wK8hT{Be?7i5 za@E^X8o~JD0bB3DcT*~>(!_r*-@)DJ$xmyHDJQ!GU|xm$wnQ936Jtok^EX6BE(ngH zb>~Tc9_I~1dmqF}51f#@?~J5N@WxKM3MyaQ%+f$=?*2JaLOk95hCf}zlw5yM8Tm=4 zO&lndVU9M_;#^sfghE`$yUAB6kz$OqN~vMmquJ>DPpJBn$#&P9=-lP8A@*wFg@1ZEz28zCAGjJo>E``%4WEqcPyiSPf#mcO0Mn zvghdBmDLYBG~vbG&P{!Ly+D7(54zZH4R5w-5w9CyBfbn84&QZ?Fj+6X2DK=Lf?nH@ zX6Vr~;VY#Kodi4%@kh6gg7P>eGj9ev?6$VVBBmKjIXwS4~}Hj(eCAe-}q z0}Sjt_r2X{9NLHBQ_x^4S-BM&xNZyaV2c*4c+=*afp@)|{&nYX@?(D=Tyvhm9>kbL zzvs{U<%bcS{KFPXBh=|6Xtnwm#%7Oz2aIH!Wm< z(#|1(Jv|rkg0;USm?(hnlg-7+^QRh7#aVny%r|=+Ul4OLenmESu5Yq+uA5{QZUZ#w zfo^xZiU?<73(feGKdJX&O#7Q4lM`yr*WcWF^^lNqt1|;Kba_Q^(>!&88?p1qa3A|^ zwP1SbeQ|%tgMuq-h)7u)8x2RWn%(y&&(j-AqQL4;Ry%D5@8q4MQaK|LfaicrO=Gvi zfp%XrieVfq)iuUjL|!#^$M8EL=%;HQpUv7kgg4$IE=j?9Y-8bbChE2M(j$w>JSV1x z9|#i}gq>4xU_qEhXOamgwr!h}WMbR4ZRf_eor!JRn%K5&YiDcmv{hSmANu|FLwEn* zcTUdr8kGQQtqPyvOjyRMWH;!=$w1hM7;~OF040^F-iK#l*F5_MlD&8L?7!Q(kfz-^ zl>R7APb(I_X?B_s? zAX72X1e3+B`C^!Qs6?0S@p%)3%@pjeG0|h}-|TC&wwl$a3|usPx6*_+{T%}Ap;)0@ zAm#;G= zq&t3Sm$3W3%=Dwm<~YRy*<;U>HY5H&$~F_snN%M^SbKEv7$HpEipA;6dxcx}-Gt%y z;6l~Y=S=rAHe)1eDmeI1&xVj;d7TxEz>DHdVkn0bXIY(kPFgg(-C7|*!43f?noaxpq}q9 z5zm}}NIXN{ABS8}25%5W$F;_svtOfpJEfVsXgE7?mI`4RJYorY8Uv2G%wO9N>GNqw z-8-WhJK6Hc%`Cr1C?9SaIjoB%4ET)@;Lqg@^V|`=J=?Rr&kTX zomL9UeCHE?k8>)L*Yv*&%0wcRomX_fL<}MBBxisL*9Jwx`C>*r7^X;aD4P!#z6o^ zx78=ay?c7C-5f{12iZ~MOHG|kshj|PC#b!;R>$UM{Pv{emFwdgX|MMi{`V&Y3fg}G zL^yD`r#|dCZ(a|-vf8@>KydCtS*Dvl<}Ts5TDy{pOkypGbtID@*0I?Oz|0n1O7Z=R zOez-SxRd)&hoI~)Re^@&8d@P_qTjvVG*lG{doAKB|~(HhT1FpQe_P5VX_ zUG!n1iqwFYel82gF&JD{9Z`Vgciq%-X+#9G=$uF$og?~XhctTT^C-77!BXd-8SJS#O<$Jc*yqC!%P z4t>$O?#iQ~Yqe{b-$NQJOAqMJG&krxZa>jCza1oOF?Cj-@ED2*aiwLXrS4A3Qqt@w zcpXIS>x;JgpKOo;2y5b*Kw00yT{4llD5UZ6HzXx*KrlqP&>Mh6g>jB;^+rRYaYFxf z%h5H&Foz26*#!*jy@abL^I&_MDA+zVl+)84?}R$pKWj*g4vHzK`6>3Ng^LBdKI$O) zo7rvzklsA1iELxrcvzw#yPDq&&FHt~6a6fCRP4g()Qtordu3EYnfBb+$|~R3UKPyJ z0ue$NBsUAtXzbS{V@0|^(JWd*Y07^MV{r4}kIqW|)&cW5+EWvFCSqu>)22PtOp&0d zrz7JQX#+HcWzq68=jdR;XNq$4s=t=C@@iLb2hqZk5Vpy{>o`J_hPsWC6>`E@CqIty zTeAL1uXunHkID;afVp}Sch>sc7B!&P{<;cT@<=qR{V%84`gSMjcX?L$>3#HYUI~?Y zG!i_5?)O>Ky8x4;996#3cK5bi>CQMhl0^DMhP?THzUHBL!pHqRnTK;oy`ieOVc6pp zdw&9nu73%BsJG{Zy;Baxr=zf%=xW=&w>0Ie@j?Kp1lb@AOy3kT0G0Y|>q;jg)rfRNwggE6i$yVeC--vM*%HR#)S=-Cn!3e| zIU-Y&TTvzPrEo4e8woFM$8Wd{mWMTgdgz|9skGq*BmX9-U3Q1&>3{)NY~yEF!g(EC z*eWpJOhIhbX)pw0lAACdQ$l;!F{?2eZr##tdsM?E3rY2c!S+bWo$z>ut$uZqZ)_+? zk4kF(>@|TX2_-#MUOZ2c3;L3+!}dK_LkqMk@Hl;6F5pGJkCz!2ui%4qr)|#AbUqn( zHTj7MW_D)Sxu(Xo$Qa~!=KIp=iI~pOh#x>Nm;O0z!%?}@ZyWkjY{e^xyY6VdterTz zMGZ^Pb>)O{B%w6c`|Oa7RHUiH=#p}mlst_O*SRSh6F3&hsR$Nvk}t27H{tRA@G?Cu zOYKLVhlbr$Be&AS5%zU<&1NLwjO7il*bXM2%4$|%i&-c8qSwcwTBeFu;6lO`j0bQG zPT3bI&iJ^mhh87xmeq`2za<*G0P{rpO&Cnu&)WBlfvuUb_uHHl{7WW@ja|NFyWA;V zAT6$^Kc=?3$k#|eUmQd}C!*Zd=k`cTpZy3AP!JYMLfPk=qiKDzcyrf^$R4Y3mCvqP<+V`T|er{_F%0 zgKJ36b0Kg|ore~+9R6ku&<|VUy++%~%K2@Bkof*(&=VQ-b;>3V$__b^ZdI^wi~U1K zjMK1U_4y06S9_zr4W4m8E_(UM&zrT^yj^10t-IXU!tK$w{KVL`3J&Z|DWx4pCW zUn(6gS8;&(SDrx|>UXeXwc4CuGgfxtx}+Xk!vq7hbuF!qx|1rST&^G%9=%@&>tg0H z`>Oncj30DCn%EW2TN+p<15iD4@!ZY7fyoM=rt3N)Goaw`^tfh(7te{o+Pv>XMIn#I z3i$5B(kkoL`Jvvut^9Oem_mH0T>1Gtv`fdtC(w{k^yl!m>KXpSmaCG_$ z>eKO=y1zWDgKbWHdg>pAPTAGPMI<2^pMe^+*3nvp=MQ+tOezziE)e=1j-@1WA6@R+ zTDb|~eW?{8DIrH;klOW&VCxCnv?VtVJH!zcC1k+nVXFH~+ir3KMZtTrp7cdI#^vf3Ww8vnGp8Wa4bkfYuc>;M2RQbuR-!3Nb+kJWVI5?3X z`X3_TD7Nx?vR;}fVBS^tcD=b{O?*$Hl$>kHo*y2YDb%z(2Y|m6762P%{bjTi_Q}i( zf&62NX=}d=1`%CT6rLvFH#mOAydb_SDnDHQ6v6Q4Jwl5S?OT09<9-EWg+x6pCxvI5 zzy*@W4`iI`t0`hwPP}F$^!iUpWXEdS;F#|9@*7Neuu%GmSPshl`@`pD?zST0#xPHZLk<0 z$!3;@tbYSM#mvx~Z2U>){G0a~t@OvpRkc^wNB%B{T_EM?xAq^OnUZTMbF=i`B*nVa zHV+-m?ZIR5l$rTm^dU&8d>#$dL$yh|CQbj;3)?&Vbk9a7K2k2y3z56_+oj}6DkLjZBxj0&cV6RhAK9Qu^lV7D;F$y1r_ypey?J52?sdfDv&YiLhsB|(3 zK3LNOn+dmhbtxCM>C)NmkJ3}UUsY<(H_a#W@)~7KYYa4}2xk?+9oUNz1}V?snv$Hze%FsB_VdeMwZCO=)y$ z-B{=BIZuP6%qz(6Ip`-FNxXf-o~_&KAJ!M`W16^hSF2i=IzB^PrqV%ut@|5{1dYOX zErEk^lj|{9@@fQ1u;H23U%JWzax{ngOIJ44KJHim@pTIe?xl`EY2T&;4*x;bRl;#sI-kR5T0{;8D$$oQLms`%&|{;Q~82uW%ZsaM9brwR=xRE#)C6aEW=dbP%@qM8EL z<6hL8GIXTYIAKQc#6oD5-l*DR6_kM^zAj4LQpAmWLrb;z$$DnLw{f5NX6P5C0KE{- z`8o(LpLs@1eK{$+9l0%GY^yYX-a)NNm7zHZr zFI{d3idXJ@00Ruys!CYZ^)YqPE-J*#AjmljDM7dL;EBF2j{|O!1%tcW@$#cl^5b+J z6h#h^@XZ<-m-{E0h-JFw(-x>W0Ga;d&sp};`$Gc#@^;lWq%MAfgvoOA?c(S7`-KvQ-y{D|HKl%eXHS;7@g>8#QLntS-@C!D={l$s?2CBK_<{|gJAN>fcyWU&m@ns7Ed(5;$NOOJQb|7JKm1B8ksI0`-{(rra76aucQK+u!t&ISV& zi;Xh9Wkna7L8gFlmV#X^B#ul1q=*T26dv?!yJsF3lg!mkeHy!z;1yn|fcq$O!Fimk zsl_O^dGZ6(eVlbW_odNwxA?~C)`(ifyzsIWzag4`zEmP2b(LU<-e$ajsvuTN@%!?Y zXNMu{p1NPC+7EFS6IrDUfZcaA@j#A(-TE5jiSlG5sQEBIjd^g6nWplptm3)s)y*)I zk|G!K@=zl)3Pyy%K*B;hBssG(k-wn`BzY=~PuWwTXgk>S65%?l@#Y zc}8G=pcpxAsjzqv;3OA$NtCMBL_m>oc_R-+ljzjAny&4cbApTD@MO%vfNo<{;Tjmt zn@+mht@FN!bLF^IxsUM-p@L)sDo63A$`SP{m*3!xf#}q#*a!=Mi85s=si~7{&Df0I zoAUdvk)waE(1JQ;i%r$*duL;A;Pl#3g#02#))&-M@tH^@u&O^u`aNCyNk=?iV4`}q zeaAHg5mpF`%Y&DhnWTud!onj=i8(A<2}12_Zxt>QCo`pO2A6BfuByMsLg1H`Y=PcHX zPSnHdytv7sCGIixR^BQTDp-sq4k0EInafSw-Znomt~TEfiIHFSuo zuBkYUq!B9t8WTL4#ZfMVQl5)V;{7{YhMeCPJTw0O&=h5weuef-?`M#V0zHfo8qagq5^cNnIJE(QBM4<2Iw_ z&F{Sc)fiO7EmE@>)(dtI=jV#^mp7Z=7*T9p)5N6RC#$-nL|gvcp@cj%rV^@`reg

xkr6Kt$Y4#g5ZCeS;2Mu|r}&e6F8(UU?5m? z+g!QD0k_iwb@8o%iNXTD9Vcobj&!&qSYC)Xz|JEjjMQ}*?99S1^~a=re2y5Djho&@ zPxU05Il8duFF~a78$WInC##brbPuObMj_Z!`zLbg@XKha9Er=?{Z_|C-?34w$`-Ln zWfjR+${cFl3%uvH#`dZ3jzdYnepX0vp~;FEKO8=2yl+f@KOmdC_Ch@2d&ObQRj1Ow z`Id01KrQM1%n#K8JVuSTmI!!_4=`sOlu5FL8T@35X4gs~VmBh?2DToCJB<~{Cq(cR zHxJ<&6XrATov-*!_K)~4(OpgnBfS-6=$eTaMc$6lY6O^!QG&Sp5}r|@$h>-dzb8#7 z!i=H>nfYD`mRR5D9NA&i$7mWm?)=fuC8ePG;taG|bjUwbCQ|!9DY%S{_nfewR8?a3#YDf1z zjdVJ`5%)wchgggDvl(naXx9koBxA+unEAHn4Sjm>!dk>3MU(@Q%S&)B{}~@|3p-@s z=c5sHGRV?LxS|L;EqS>CIwtX&=cZ4u)g7M10! ztay{-3iG@3Yf$kpqeTN@00e_F0~h|bjV64ctP5l>5>^tj9K~lB%cy#3M|J&2@C)XI z=pI9kNuKLOCKtLi{r*F27&P_Q-6JqHD|&OR+v=D? z@a`_md6w=3nT=;a3!)dEZx9;SuM^BG8TXgZ`^PWtYyHJy1@c?7h z)FEKL249Y`H7Ht7g>R11zZfO+LiNuW;Y>N-T~i%kY9!B`5fA)Q?GTN(A8zHmv@wkx zMPtiZ(5B*CcbHmwFERO%0;NvD#N=*w9B3_BGrl+3&ZDr(!(!GKY$>r5tRKqkWBVt( z1oq@J-=i0Jkl#i;J}2y`%g8^bsqXfe*q#tJ78n4te0?r0%Yu^iT-4{_IH>J;MABz3 zhX7aU$0%dbH`MFqzx6M|Vr0^Bi)%$GxoDOaXb8I=2-u9}ve4xk4k6V8d#dQ%Wd7WY zA**z)nxkC#dLXX?whlRY;0L2<}X zUndE%0E(#DTqih!SxSO~gM~BCrRK%vY+!Q5G{^aIWok!HKBQlctm{$_@jD{FK4y>F zhM267f)X?WT8HR(Z?6BhwR{4*)G{7u8qicfeqY9ATm(cgp`ai@IF$1nYD+sk$nLp6 zNDHpJPk?V}1`i}i5WzRa7VPz(yT>3S?(XiC9)vt#h}lnI)ftih(gX(};F$zAdcOyI zrUfK*LAMvD0Z21neZ9a=Y`x=?ZE*V^PK42V7)axw9KDFXYdJsc0{ef*0xX1Jz)xRy zKg1GCeHlm&lxanPSzdvCn*IB{QlOO5H%|=6>4grPkla|NC94`@kk=`f_iz6WsS}@D zBRgBiTU32VvLs?OL?FHd(G)%3&td!!e}3#`pp8SpiM{*rXI}!6Oa8G-uiq{$;oZL> zET5!boE#R}!h?aXQ`wcYlS4;-yWb{Y00GD7&3&xtrtzcz1}2`q4n9(HgX+2;`JoQI zE;6t2A^nv?o_+a)5#}2gWFBpn&_0GHdVo)1co=^-fv@|3>W`LBc?6up!?&%tCChg_ ziu>PNLj5E0S6iUZ+A0B@ef$Wi%zBY+kF$8+U(uhn*&0ILTeG_jK6Q`@Zo9Rn@Pd4w zzp3>3e`SUM*L+vD_s0N@v2jaGw{K_x27#Td5Hvz7IT@5#ggD;|p93xrA|wOM!`k(k z_UB98C_lXY5BkRi6pOR3hGK zNlY_#Ym7ujwujBg8hvtht9;dkJcVp2A(FM~{CqIr$m`>94q4QD7aDPzbbv~U(f{;# zSR-jR86D7fGK(VfoUtuDs}1L&nUc9n@RVdX)}cOv?R!}HCnJQazm!{<@+qa$@ckS- z-Y5WopDlI;PsymwsIZo*r1?pw;Bk5iA~^7I=j2WzDF=Pkks(k2!-0`)(!2Tk+B*md z0&IbD<5-xvi~VAIf&6|agRlP#i-aSdzNB>OV2A6NH;UfPLL>dw^sE_D}-v-dVprf0XSgqp#TLDvexx*5KX+gPtE)-LR%t4(gj>&o1}mS6(E=E@>vFdya)I3NzZtyr78`d7d;BFD#km$pqD#$=p5FR_z}0E9l%OpPmhAe*tiMM zUXGE9@bRWlU21$MS@MWaV6P_odl^tffezC+irqdU?D?okywo4%fopx{3 zflUUluxUl=BVE!;)i{&>t{60+u-*I$+IEnmS@=xVngsV&ku^a3`#HP93liolcjMeN zIn^sikm_*Hh?SOdE)Lnil$KbO;AcHLd+^Q1)X zZn!#r>*sp%c`ijMUgSWbiP@L>Gtx(Gf{zRs54bgwOo3I+2%V7q;yoYGR^xoCekY4rig1-s%KT9_CUhHijRm_P6 z_=Nu%-+pPh~R5w(~No=Av)2f$xF3 zW8LF7s3CIqn)g&-;_Wfe{eH?^;p`q3h6}hS(|GmC@c8+HcLoLk-do^Oghnuf3T_is zoF|S&_XLNAf^t13r~y|{Hz;QQ63NFC+687-p}o?Cq$%TvCRK>+1cG<%o>8~jHEdHV z>Ly^>()<_^n|Lbh5&9lz{VJK3?L8!C;da`}c#bW0ahol1P1i8{=Ehget)05&!wDm0 zVUGBRVrzA`E||B##p7JE2V}(f^tgv(e3`@xD)QCD?ql0b`J(Y*S9N^dti?oQsXOVb zKzv5|xVH5>aR8;7Xl7zW4<_{T3>s6ck&G8zxOq9lHczDZ0ZO406ImKEkRmz@D+vy z8i&_G`E`>QgXhb_e3`mtrMT@WYi4l9}D(##C`)YWO+?0Ik zNs>n3lL1dPWM_VUp+jawv(`;^N>^m3HB$9nuEA(@lR5;=srynY*4QHahv+*KD%x3T zl}Vv2BMS#$%_4Y<7Vn@m&c5_cXBq!Qq+>tLynj1{BEPs^vrkimsW4MY7s}W;ueUUN zqRK9PW?c8u`w$oTK6wy3{#^fr%Lfu#6KLR3)=UTmSEMk^e-z{0Z8Wq5DvXi(HFMl;5{DkuA`V(RI{cKRfXzCiHcXqbTa zPys2<10s?U5~pE4v+YMg@gLvw37w5ke}oH}Bk-WO#wN4A-!D?*MYOoH?|mn5Zmn7Y zQ6j5A>V-WH_FK$YPzR`5!k@;Rzu-xz#_EvV_6MW-wC`3X&XpgD8)L8R>qsM}pnHi8LX-B+e%Fr- zFrXAeiVT%Cw$p=fr#vj}l`KKFS!QUML13hSIL=}eI1>E+Y`NXAu=M^SE}K`lj=3#up&KBruk1a|!JM z>rg134q2rjJ!ub9`MY_g$LPP~T7^32Vvf=0y+(-A&#I+%#ql=Ia;!Hc%zUMqFvS!ydUzVR=< zT4Q)t8AorG(iQj~>H5&z^Iuut51t|=2@n{}(nPl&=NV-0lp1Ux;2Z;#2 zVT<3sxI)|vhtb?$JcnN5yh{4j1x8pnz7Z)bWcfUpnif3Hc*5cnRBnpT47oX-&0?Jd zr>8X+h|o;)4}`e0cCu0EmMX9TztkMzy%vw83?3WFpK!6!7za(kxs4Ypx8L!>(+xS_ zd5L2tHkvmRl;9i^l9pn{z+7D>9<8|!OPtp_+-LZ6%G>r`MwJ_Mjd!s+=#|oP3pO#; zaG9!XakQnSN~zrvTjhj@wcS%TT>CNP&rtYqlRtV!c<-FHKR#3YGJ?SXYisQDf!+Q- zap7-IchDzByJOLwIE}mKUc&CD?-EY&gETF!>_QJiy7by|>+pZv!BH*VaJT4{OsB-`!`c|*u%Z7um-3{1$iY@}I^KFA* zbl%RB8ceKOd(8KI5;@O%t(>vk}Lp$Z?~5BXI8Ylc_BRhBh@Y*6ZI@p z=@KLdW{W3;Xq_~g!YVXHWz~I+FZ1XY z>~^+KV>-GrVmd-TNDsk^R}m=`Xll8I~cD}fnywz6%s8JUy|$URDq@%chGf;^v%U3%J#^=BVQ$kMQzI<$u#nY-Swd7N|4=| z+3WWs*c~9f0aE=!2>$HkI~odUjxqW^uIr?(L*RL>lJ9ZH`aH`JNNVn{*8>h23ir|#s#fThrlL5k3|=~T8Y zZ{493aj3KOGl3Mkh=F*OES6m9gI#nmdkmXFNgKf0pfPJgJ(Nh5;+W0xY1m*!BxORW zIxbkvAI0U+n5GKqwajvf5{xw0aHLN9`Dgrqq!_PJ@?n~m`a5$@xYU<%IoJY4Z@~;N zJ|s|lxrUB!TJjpoL}}9dn?)}@kC`6{hLBh3kB|4=<}-C);4e}1c)AA;neN8gu)6jz z*#lrpW-iUiq|C$^yLjuAn~&pwrhqP-Q~lA_s5OOHsO76>yG5GfR!in`IG zSUAbduEHLn&zy&#&#Em}a?>{bi|DtDdFzFPO76`GN&g=4cS(Bm2*aE?QOBRNb@h>* z8S^xV%T52T&N<3<`b2c}yauYNwe1KxGnIg0<1lZblqq8MIiE-1a6-kJ*4*$*0+OrZ zxka{W;;tW|wu~_hZv%lv#PuI3erQ^w!6*5ob{u=&R2&u@ajyB|K1;YKOQ%-dcBkn9 ze3)vP;Le z$i;N;CqHTD{%&(prgPm1P9zOKM}l%vD6@Pe%6LefO;E2uEF$ej!S1$68)Z#Kiu(;> za>RAf*fug2ql9U075{42g|P~9&XO@*n#pNJsw`!DD8D^p z1@k28raIo!LQO@JXj+5g52Q+9KZe)TKzittzH%8qN&d(=H`tuM{8ksTW44bIOpMCx z!A!Q{opm@0&syV5lfj=x+QjZs^$|Lm^{o&p$3YXF8fZJ;Wqv6v!pOTL@52Kwvc{d_ zAk8($3aik3YP}L7WN|Qv2ZggG;i5=T_V(e_apu=IQW+(@SVP3G{>g55gV|1n`KKNE zK!3bIEa87xKh4mTFXP?>CCOBkSM=bhe$=)H_;tMm%3tfc-=Y+*#2yM3T`O zZmM3TV=Nr8g{R2^@fe1}c^w0|ihK@R!+$^e;BI%-EXF`a><(_Y5GTxc$!+oScw;#m z9&9RfzCjBs|BhusLyaahs}iPHY2|-7qWO-Fs5JH%QrRUZmcP}ZW^;IUT>-tA({BEx zQqFxC5Q2iK?SSDQLw14EVXj8)FRF^k^T)vJ3AT8NtXzq{01dgNZ14r>pfAmFxfaI< zzrSn<^Hx%Y8I|D8;!#MLngC9T$oOAS zGOISje{PN@R;?sXy-MXH4-&fSqTA%)U6A|+Z5LlR=Rh;YF z_WkbvEjbldO;SeF`+KU_UsiVPhqwUIzL~+cmA)yp)wWe%Sha~kWVMk&%v4Y4l$h+) zH*tS@Bh#xLGkufGNLd@98(U(atE|zlHYh5HxT`FyF{?Z%j+3{!yqvnbJmF_${!jXg zEfEPavggS|vgabSMY3lBhg&S9I)mqZgF32b1F|NvXz<17Te{#yG?C|7G!e2U88VdT zBA4jr#V`5msB^0*+E3I3BW!=_1@OkjpgWD@P`Z#34{OLu%@FF@M=CGqvZ)%GQt7i6T@!`{T;FvQNnSYH!V z@P=-S)Kuj1T=B(--M;))eP;Vx2H5K-{~99%>#7Yq(QSxmY^?B$g5qtB&5G)bs1GCV zip;7F%ct!Mtnb|#|3n8&^bGYcZoYoL;|~DaAWbGfX}-Q*QK9K)%toL1eBZ`^+GgJi z{Z0}1A`tf4tUa;MS5ItcV6|g#mm?$fS$FHI6Ln!#$@6Kt-aY#6sl-LfNGc8`U-p&U z+r2^5B;qoJ)@1T5F$rL@+Od3A?`+w)gGPMKBk+EFIX~HE?Eqg+n4qSjKV7|OJyro! zsE_WhuOz2W_uch5OX*Yf%at`P zwIu_CzlwGZ(;iH-s4-aOIUHp|#b04U=B!+fmib$i)JN-#Kn(^9`yzKoUx(_@xNE>r z8Wh9+O6Pi93t&sg63Xnyo1Gd-2Dzj@S9g zJyMypBVg)=WZ8Hyq_f5p`bB~kq`m02$~I?`KYVLVE?cBYSl!E+>hklqo9pSbNSW>n zQjK%yUjRm>dtO~qT)Lf{C4<(ePW7Z=?;92Y?AjTW8FR8lpLUkxfzDruj|_QXE7tLU zN`{b{w3V&}Ps1h<&5-mhn4YrO?{e01)F;l&C~*lv1rqrJO4GP}&)?)BTuOR`tec4J zpB0jL(V%(VVq~PyF~TB*r%6mJWOtJwzot16tpJEZ%ur+y%8%Gh)9_f>75^(ogjTtc zKP2VO*6Crj3hv%l45ybm5;q-wSx1)06%668sTRNvieIgZ-F1# zb{TU=IFwp`#gC3LNb1}_H~Lch@I8+{wyv#U*!O8QK$TJl`%Z>_bjHl3-`iNps1>8^ zH3Fjc@=khsf2#fzyH|v)l~f|%zV#DXN%3XBl=4#5UK~ckOcimFWr}X(E+nsiVp`|2 z=y(5FREuMWKMwMirMeO=?XAb5%gzgcXYx%QsS!P<7-`nYG}cDcMN&>Aie;+Aqx%il z=xf(y0Sirl5iIC7w;hI%^2lJ1i^|9J>j7|OP52jJw##5j-IMrL)&dsCc5O;DFkebC z5dXbhyb#tdzy1$Nw1SA|P>xABSqd!{Rj&n7AVr7Dzu!fh$JcbA= zyn;P`WQ-AUR7HMfd+JBF4Hcf8oidVaj2)aCa$sR?c?D{wck=W)hckt4;QU7-Dm9?1 zO}g(F*q6IgDi$#t99RK`v?pP44Eds9f>;J&%%pl}w>37bpC06nImO)_z0TH&k@NW2 zFr0ytlZ31ipO-&#IW4OYYw}%cmu*!&cIB>w=hr3ok28tRA~@sePn1f81BRN9n}P4@ zTZ_5fAxj#64j{74nTbYr@Yg@T|563e|JwHb@!_XAnOJkg;#l`o&$*GZ-CyK|8#7-r zswEZv88cNS`(sMWBOw7Xh<)|wx0eO=jS1Q`HUo$*tx2@H@3Hz|=bL;IHcuMGe44k? zJQ^L8#yypem4`(x1+9Yh+E}Xwmp$ls%1U^TCp+N|jNL^&uO1315&WYwO!z<7S9WF4 zG!nrwAT>*n{G#mHPcNVGuc$zC@emP_MfCV{DTay;Em~QfO#O1ku-=r!=w5kF{%Mv_hjTdcZ~$Vc%DmQy+kkDIGqetBotCgh+$t(;E#bq5j`26_bISZ zaL|IH=c1VUa{Fi-C#w`9(a*M<)ZniuFi7DT58NE}>Hr@vA;y$1w*UyNwGjF8H1W6sz6B5N+^U~qrT6jv8At|#hv$4=7$)$mbmaETGTSkp z{NgvAUX=iB98|A-Hp-9dxh>z?L@T1UB zq~Go8EJ~9$0c>%=78Y>h?3e^K;ojvzez_k}Xb?@|m;F}vm^ugbAY7!yJE`a3(2^D? z(uF6mU{4Z$7D((UXA{w+V{r-nDlA6_cCpne)U^#4)6L6j1x1RvIf>QT@#(&@ezP|M zT{~_OB8kDG=+Eo?J*;7cIq+dXq-$u9L2-=tY$L~eysA$3>k)`gEQU79hD7Q3N$8xL zXvJqxK%2a@%XJKw0*kHgAJvAH(sMXLqKOjZ4mu?)6UZ;5Y)mvLa82aID!YzOl78C$ zW9s0*q>`eQaSE*f?zX=wn}oPN8$&JE1Kbjs?G{|*MrPBV4b;!BV_Yq0H9*o2MbAou1?~V%sVgd5~g;b2txW=aXwT^r#S?)rS3|A!FXBPpjt zfZg_Wg)P}yrdOcug|*YeePd>+AZ}55LFc7BWs6nYpjca_+ z56TdXrAIJbS_VN!L(7(Y7_Apv)AwCI^TSU4 z(A$y6#uE(FvK^yueNa|`A2lBfRYsUYVa|6K!ZyVnI~j}8BAOH5wnKhFwe)EdCPmvZ zrDFV?_i9#rPIBD^BKLjRAzb4(6-;j-%}IN_>zkQSUJf^SSQunPvEoc*D@UC8pl8h0 zogGjprQXXnSs^y_=U0G3FxcmUml_`WRw`QeY~6kB4isg??JLV950Go9QOt+>26Aj_als@dkzIElGa zv`*YBr=_m~%30PoM5|XGPnAj6iFst0)=L1G1=P7U6~E_v8eXGvgQyJzwum&RmV&OW zOU6h{Z_C{#2-H}&~^0!}XW>TC7W07ia+vas)qi$|Zo*sQ-p4@#PUH?{_r<-wAFR3b zn8~=#RG)8(VExauj33rx^_E0bzpzkgj55#DdP7GS?P8AwT_cH-8P)1)7A)}x5nVIQ zS5!X&dTZR)SHx;%^^LC!gfaL_As&HXEmU3f2y~Q>`1MbSfHk3Jd3o1CeI;4HiLGPG zI1dSJQ~Nx0VU)aS+1B|9AEwWnwEL(i-rQZZEs@}oerej^>$)>#T$^r(LC|qDDcx>p zm&!M(zHhe;x5b{-N$-90YI&@*r8O{wS%~b70 z@NktebxD<7WyKVmF(oOI({zlLB2tLt22!LRoON`+vvl40sT#yrmkAbw+TGiyglZ%P zRr>dMqP=lewo|K@?-mZ%M*;vH#@fX3G}&7gQ~HD2)lbs37dG_fJR1bHv$l4NwJ{nf zV^OW~b+wyIsQVCgWU1m@xIU9tOFa6r%ylcCXJgi8HI!|NA@R)@Y#4EF3Gs6JCp>M9 z9#WO0wn^2$h`QOf9azrOp|NFWtnP{?k0(ds-+~u?J~VEG239U*N<0CkRu~3tuxsnR zO2pey>|$2;WY}3w<%MB-^_j#NI%vs}8e7Gg*5 zN;Q^kq}5hlTfsm5x*=_TE8rfi*#6>G$n-4Hv%@USfwnM{V$OXF91gs1l4&>WfW z|J_o8hiuAoc+^sGI_CzEL)GN7&4GzgF8Bw|9(krw!mp2SLWciZ>Wkhy?`^V%!b`r$ zq$|g(H0~3kGWnY;&!|+ph;+*~l{Ex4I@gJh%C#|HE=#)EBX+r|5_vd&@e;bJd-Ot= zXG=}nO2d*p#tg&YXUzt>4Iumov9fZaqa#)432k2bG4H^DR4N7FP@=vJ7YhX6xkTcJ zz|J`M##d8&PhjH<9iiM`9GKbOEsX2t6(j%o2J&Q59?{r<*!RVx>}K%23cD|jGG+ZZjy(+u}qn(FpM!x1a?*8@fA}Ct(iNO zs$J-B^znp!$&G&Ca>1lu+Q9PO=RAY}5H%zB?M%uIFjnd?RgkAKt7N_yqn6u{ROwpq z)7y~>k&Sq|Vx>rr&=W>gMxT@MK`lZG{4rJ2Pg8%M_knu`DWMZxy!pA*KTe}Pw>Fc^ zVHo=~P*qK)x3GIifDxu2J=N)#fUG#<=q6N*j!%DNd%**k2C5Y@qZPnf=LKm@^Ih5S zsMJXYl!)cSj;Rxew)fMZe(zjh9C>w^$q(eABs8?+p7Mu6aAa{n-c+Mc2p!zQm$wS3 z4X&;y7Wxot>9xI@BrraTsIiRs{@`*%5&$_&-0{mcV801X*Xxd9{ke$qvTiegA{R4F zCFcDWx!wohc;uLwl+&7h^Fzaj5BG0cr+mju2$uv8r66^7${aQKc+UuXF>e_b5>EDU zB6G-NmZ=+H4oMs1B^hLfyd%dacIw{LvS8v%=tdr`RIx#payp4P4;wWNwx2&MVM1pN z(fcY^d45LYlzuwU$ZxYTbjojFj`&Lg)WPUL@g4x@bKj9i^x(OcC-@d0pvyaD1(jhq z5C;F|Eu!u5^-X{foDImqaV$IC|4ioIW`t31`2EbJap47}GVQ~yMROIN;$CiG+Mw$~ zk&pxGR-bfPp%dTc9LdE^72+deR7aik#dsAu`10x2S4{=)n;s0hlqZO)Th7H`|h>R0fZBxMRM*T$NNo)*3n5+2tfz zFSOj>LWxhnTnJ-2S041Y4-XMr~=1PO>zdoMpYDo$}t-R#ihA&uC?nfpDZOK-;m`#-lv}t7gu*f(&0v z?YPyilzl)xA6Uv2=CA-{ZI>boCmcXm=P?7Kd8S@$W^6l5+VST>TTo48N|T%O{_p}W z#tqnvj$bFoRVR01Kl{XOQL}V^BQkB*5#c?gu&zE!7@ITn=T63Q6{pHuf3=fyR*%bJ zXr25?)uwbuRIu*!Hk5JG`Dt=3sUuW%05w!2MJ#0Zf-={vufVX=J2u|R}t{3S_hEjI1X9RUr%P^(Qs zvvk>)x@LRdqztm~@OZp`=zIvN)fokn@iBz(>X>556roPBbg&)SQ)`)DaaMopthe}M zIu@J{KJ(be&+@T0A`}PdKPZl=T=cXwU+2h==cy`%5c{VHE3fRww|@+%43&%UH%r&$ zh%Ogq#RC1?CHR8z%C;B9z*~F(4V)oyUW1cVECc?ej<5(tmk#t5%NEgM(?G6S${X8D zE+WTd{?l0R_Y5OTuPaT&93wFYu0c3S>$s_=q|5=r`Zo|`hRu(%^nY`>T?C_7i&_`C z2NgTd!7S?E;*gn)U`=@U7pZ>(Ft>95DIijl__h}V=Qo2TY|!YCY~_pqD#Vj6CXBzn z`?R^k{{byP(!Y`vC_etEU}1EQ0lx@$K9_tNz;~BU$j9CBdDJ$Z;pVKnqPaP#ncthkG3amNY--4Abp zj;a2wo@rlKgTv&+G10{%4#BwSUs2i(^zLp^t^<&RZWiESGf-D22| z(+azL)iXSOONA4kt(aK4?}fbW?)#kj=Ms;{M-90=^(p+24NTN{io06ZD+z*&vx{gQ z4AM@~_p-ywh$IWJeV&NbHKk`{WY5JJ->^}LOg@?Kc?G$I={|fQF@JtV@rb@1fdT0u z7tx$?p)Rxwh6DRYB@-Up$QrlvqojLAPS11Ul8ER6t%k%1$fykb^P-KRp6a}+H^cNj zsL0yV#6Uu|C%NbR)C6o|LeY0vGS2#ffZd~tT|G;3e*~EP2qc7m;svqYzJ-L;sq`GU z+8aq02tBUJakp-(kAHdM1|D9&6k|QU*Zoyhyuqny{6NSdb;M!^ScZ@4t^p25RA2Z^0$$!jHXs*=D#d;vd^^WX= zFQyY0Mol|qex^M%+#B#@C*9rhS5)fYJAkM+G_y@l0W$EWY;3x2e18BNxNI-jC6E(I zy$UUyjqMWJvgduY7=u>AC{$xu$&lm%$ABP8|F*fIU%!*}8`@<$epg1Wy&IG<=HgM% z5~nKaaf0{V=Z`;mcvlnXNE6S1(P%ObYyO7c)MDXx+Kxo`L=P$~&eUY^OmJE;E5Eac&ow?DyE03X2JJMQbngO9gQ7_P%Zc~c26mDF zb8{mAcYkpR{53IB5dU`>HbinkZq3%p9%No)G)&#xq@rE*P?%^93&LwgEnDrxgmw$W zeT&b=Iyy?8agoUScN`xJ+~}29xsS}9Uc`I@-rS6d#RTF?e%@s}!0V^i*FdTG3d zJb#ao6iNToj+i>vp9l#PSlz0$16kzpJ=BMIky*w$S?HhJ3UWst;W{noq5J?$kpw^gVc?W*MHU7JYnNm(E8qR4~XnL$3ueDKeK83ZKx9 z^SC;BU=-@Mf0rr!ihH%x>>ITsZBt6IIbz?6v7rP$?@;(zij`p2r0KGAaE$S8jDMJ7 zHIn@ZFY;+}Dve%WJL#UvSK>|Pa4U0ghtZU%l=Qk3^v7`m%Cm)rQxJs!QLJ+|fC0=q ziGffLjx1toh)Jzi8Sz*6egAvH(0w5qzKeO2oq1{kb#Bw5W$Ys9Rd_E=kv4oxK+)PA zp{<<5t}FM6QBz`Y#Zn&vc~JUDKYvG-BO1iLnbs{X*~d;%95oe(NIQP6L8K`-X~t}b z*q$<0wS=e;;xG(vz96)%+~qAP^Z78g^7F=?b}}nfNuQMb9VuRgYAjA*hGbEPHoxdu z-UkhI&a63N*2n9iGb4=j^F6TEKr#;y5PL^iw0=5Gq%_wJ(PL6>sw%~NK7TX4R$Tz4%+kOOyyq|F(L4VUAMbR)&QPJ~l%~{a88pV*$RLY~P;r6B4e95@_y z+3tZ80xKImP`xg1SBh18HTXqDYb23Uc+f_V9gaxC55kZ0fAa@F6q#$@Zai6~d<{+- zZ+Z=+-r^X6LD%N23xBeG(g1djBWK^%L%w?)3R#;N57jBXzgHr;FN#X2T{*!YJF~y9 z{@KBoOxRoGH+NepRWM-mdF6rI3PMbV-@ww=DV~Yy%lOiw#J=wd6a&e?VC7jmVw~WPfYI;Qmm}TjlnH_aQrO z`V2jDiXp*1t)5<{(V$ETt9UHJ;Blgtl&p=EkD4;0Z^E62=uYzskjPB5E4LLl1IMUO zye5y6-firn(geJs-nD_tXbHQxDYAs47%!?*i6VrOPCrbQ_Ux^s&ti53k_)pfhTt2r zP9gb}=`te^%ztMnbVP9BODdrtgVHF&bhiSF(A!Z-4KEKzgZnL%j^t`PZBa`IXokLo zgy`UZe)L#L;HedjS#J`D9n?`Mf$jtiH{eX7B*`5hrZ!0e;ZSoX3W@-JE|U=I#tZ^D zIg_8gM4cQu;8qGf2rfBGI{T}l^~lgRzj6LkXe($`@qZ~Ygj9SlF|AYe$4ea<_hv99 zi2NdKX|cxBk+%;VwV&*EhSiFI92rKRonzS0hx8y&RfP;#gb(zgl-LKR7BG>(#kcVV zmO-(xP+vxt9{o_R4x4rUy&hIrv6nvnz;;LOu|0TqMr$-|a!i&FF0W`GILJ~%FQ;if zVY0=CEq_k&KKplEI^dKt%v^Q{d6$Tf)>omWxIc%a?kd^!Z6mx-C^5DaJ7$m4#(=5l z2sp0}bTM5jA&kD;&MYcWlX0&-e9N8tM6_)Mui5IEaTrG&>?TE1-W>QAtU{Xq&54jA z4tB+D-u9(Xsu#u9=pDlv%pl=qW!gBoXHj>HC4Xb%HOyprMj#e@VURCg@^(34)wrr zj;Znuq>8*AwREu%1_ygSk_piB z)qw~bo!C5hVFGkB)dit8KZklqgXdI?GF*M?5CEQkkiE{-85)wD{4gP` zg0^>cic)~mV^9@TD5|yE9SaFl#yWFG!G^c~bfZ_1QK$+GErBY{+UPpcvo_v_%zu6t zk?lMokvCUIT^5xMu_hs$*(ReZ91x6S+!EygZi3otK=KG*{hDxmY3vx*SizP954{uC z3PwtiQ@&uc%996gXQA);0}{O_c;*X;*CpS^RCs%0tE+`OIt*qJQ8CF+;n-F z8gD)%{+AIR$e()zWJgS@pV=+|?SE}z5pibw`^aZKiiuwa5iP2}^Ui|@O>b*vU$j4@ zMQ~W*yKMOzpgxg6l1jJ6Ba|SQZ9D+E7l8u1JKj-Hh3Y!I9=jJp>)XMb!*UO`IY zGt)l?M;)pD)mqSIy+80r7Ch=Q%<>P7Hz}Vo!M<;kc{)8%_PiBhjTA#&KB-SWoxv)F zge(9BcD|6+QEJbb0(@u+0U<|R{(=Zi0rfSpd{c=V)ym+EDH^z-u)W<2bR0~^Y}p*| zK+$*YSm_vJzPE6Y(V~w3!+%Iy$QA}-k!a623L0jqRMvw%u!n~h7T;PUgd zi`78KrU?%Tq&5p1vo0x&^Bglv&Xt2k~7sHE*ZplXf>8e)xVMbtN3OqRZum zSY{1|*eJT+RzCp7iKUzCV|-cFy5u32sV1Fw5;|#t*S;%u33|z+6MxAKP(j4Yn^n@; zeIH*(VK94)DvZ7;(l8#(aorSVBBkj*dr`kpG|PsDV+^LBpderaD-SU6oat2oK32oh zQ=FyD_(j3pX2Y{N4J2_=-9~gA9Y~s?7y(n&$dzNHORs~AZL*w$Gj*y&3K=g3xBosv z3o%i$y}%1Gj3Tnmqkldl?Uee}5<3_75t-q7Vz>urcSXOeTEh{&p)oC;v{n%El{jG^ zav$g5qW47uvyATd=zjy=E`qH*ZLnWfHt899 z821S!`ANd&tuCC~xh_!p9ScB4z*8v0BdVr0x!uXQQqcFEDb^aj>26r%3bZ&!HA4 z@WuE?)pX_L=zl~TSf<`(Yy$%LPg{*G@l{2<)qe)_fl`HV85^ZlIk?h z>Q0*5#EJd*j{%9Zry^vFqF|^H3?cR1`3!*SF&i|cBydd=WgB0ALB>Kh^%gPu>n}dL zECP<^DfZ2jT*B2N=;s^`rA6&LE#GACI*GEF5x>e{$bU9*_}XR}UCCW#(5^y< zx=?dC&-FpV+ctrLORGX7I{6&(v&pSY)qR+TZfI6pvp~<~@G^xGZC$85aFnhyw8_?} zcK9WTFE5#00!#VEn#cU9RcCJ^S%0jn3#4s({Ti z6SA}imOJa$!RH7XKf~^?oKa45bg(`n%9Xg_8px;@ln>d!h$W+M(-2Wre8IQp?|>A)wWBTAT|Yqs6pm{I^4gc0M>(w zCjnYCvfUHh2QX5PvDNKhL>6mup1a=`h}>7qjxzWC+d>fHZ@9Xlx_6#%mN3h~%|a}M z2^}o5*Lo@(AA~};Ac1*!T%nS0Wqs2Pufe8b*D;2(D6bHHxidVP;Rh=^%3^hNhPo-0cQ?C*6lQLX+y;f~bd7 z;4H@zp_J&UzzDZ-l5&ydE~A7rS5?+6=uviy)QB$S%$?<{STfi$K1pXiHo+nbz2+Y( zMFG#C2hZEtiD!n5I800lQ8TVsJQ!tTyMI{2vo!MYknfi*!0Dk8oIl?q)oU0l`JnXVb+Qm3z9I9Fad2$8LD;)HVnifl(J8eU?el)1?p*ziZk#`9a{y z9wQkIPRSef?hny5uOY`dcim5`)|y)TsZthILeN#>7a}a0OF3!xhB+!RN`*C_B7bdl zaW^r_u&S*;Sn4eDZDfa?(QN9%C=Jf9j0II`1=lrPF;hMQq{|fHh#S28u&ri_k>F{? zm;c6{#u>#Hj0X|1NuuUhK3^-PJw_XX!##d}e6;+DIV*Zwx_u#kTZsf7CW z_-g>-p9^298V5xZ%p^e>h&tbQB7%vJ47Ckzlc@=n&2?7dQ5+Rhjm_40G=FJB-gqa+ zehB#b8jwR^Fq%nJVcLGH$U#l?C75zN_x*|Zdh^2i(y z9){%eNg`Kj=0|eX8fl%lAAh9)=(40pqlGL-J#sasik^U~_Uu!^%gt4H2QRO?QaGtI zD#=@X&{P<;H~Gc=AwA>sb1N$1YzsZy_#>f%+s-?*g`|O@25}Zg0RY*}F@%_~xP)q~ z4CwuNTar@6FVMZNADb@_1V;~(5p7oB#seEswqH7p3i8atp-MdQ*?<1jZzj+2NQFPr zW@ME!sGbw(I-CI4nA3M-d>4Cd9R%L!>P{_RWL)@{lRL(bE0)?KR@!`&Y@6pnm_MYO z31acC?3Ts~Cg4+o@2EL+v!uJ3p-@9aVcva!ACIfuirP56^DFNbiaR^>&AHDf$aLs)3JwLF3S9J5h8F|XZdTJ`( zM8EYHfbpPKl5n{0AQ!uPuN-Q5^02BtmOt1cw1iLIs$mFi>_=5l17STwaGRqpW|*#X z+jGxfhzy8(qV1aU^F#lV#YmHKTi`9nvy2>Sl6ieQce~;?{>1rh>AXRTqy1<2NRwujQ6I~FWDdC{F4e772R_E?nbFCg2l z5kJ_1$_R^R;(tePy}#&-T85_{Mc)*&!g3yl<7Am1UXPdYHt2azEbQjhrc=b1Pr^wY zhMwT+tdHfau>_O3O!@IVW&M3YcohxW*`La6^A+#gj#_qT$ty@>) z4<_o^ikjFfd;*l4Jc7O%*g#OLzlbC6j(U^YCUY8V?SCBGPd#_SWl2L-?7Tn?U9Q#V zm~WS|dqERDNcrYHBz;hd1%h^#EXz}2BklOOVqL)NkAufv@!~`NR@xwMby$a`gL7mc zWvUo~_rw0E8Ud1bHPy)L0?S)727z1grbU;&gO<>j^TRk^V8z=mP4&Cl9(Vm@Lu#? z4M4ZcT9XWTH&>;pZmQ}d7?FJ;>dUgGhy`g0<0fO#dF{+h3_XD1ut1l2yBi04ai3PuTtN5~TvDX=cdIhBr-hcg^ z#Wu?m2xno?AQdoUqg%=y`r~Ve%b|KmhYLPx zZi>U_jCrx3pTAA2&saq_9@R z+qdY6KX);-d8ht#z5nWs7P&9ERR~57;*@oeJUV6p`~btEiUMtQ`H`E;UH4In5hLz!ZU2tmGjq(sd%G3o$sQhz6BXUqWqZNpcRUAwJ2rzm#|HQjv#rDBvGji}=Lo;Du^ z|Mzqh3#LVTbkia%j@#^d>sIc3I9v8`iN4bZ6|29a`UVCNKNWphN_>M1{RKgPapWZ* zZM5}`5;1GA1udw$HYt+fMUQ%ch6#*XlFKh53!q$-^l}QVM|C7Nn}2oA?IEKClB&zw ziI517MQw3-82-FTW9W$K{uwYUZ{S6HPH-Ih&VT-5MNq$K%8uA24qTe%b|;Hu;|}0b z;qG6>++Ekr;}5;Wmm)$4igUlPIWzB|G~ubr3vf@iWs(KKWb3ovyVsl=fD|`l;nYk= zjx2)SOMRNnXx4|z6o1}%D63*$({M4GRIlQ~vl(ja;BhcR2BRv6tlfJCI|V{q<<}0E z!nW;XY5^ysr@`kxR6D(^b1B1umswWd>ZV-M(svo{D$dJ&3}+K>yw`vIiEB_l0gLVrkWu1T*OVPZWq+ty_d)*@H@5hWk-bc4(Pczw@({5@-oLZf}%)+p=dL5{(D!?PDV4 zm53wXQ1+L26MuOyy>i%CI8Mv4goaq4_8_-h@4Z)e&IAJS7S%Wi{QFbI!-)eXAcUhu zb!C^G4|?M+b$&Dwxs|{Az|a>q_$g5v*8wyjeCH26(?~7^0+YD?=rVjWNcw9_LF@G9 z(FqzDVk6M0p=2z8xg zq2ddLmTFpXL0@d2h{<+a=$jtUto(uJrFzQt*YpZj`Lx&U-w2VVk0CgR60@_f1AAkB zk)$N=`F{`VdP-R!E}fe1I#~_X1QdDd4}CGi3W0R_A5{x%=`|m*S?gQDcr+fM_CW>6 z7%S_gB?gwrs^3ZUUpFSd6cr(wZNE6Fr}+otxqy`n$35w!A{d-WO0c4`S$8|*;k|PX zMzf;0M2tdLHcSF3Il(`{tjn(mHf=ErY;xcb;eRs&!Ri0=l~pikiynVqm(`b?{e}7k zM~m5O77!Ytm)*`a?f`B700S9|&kZTH_tGD`L1>Q=e}i^jU@fVqV`sq&RUB!Y!E1Rx zkD_ua6dRBq+mK=HkUHq87_C5Q8`W^USf_Nc1<`e@q#G`!k4xaT%uvF$B9o1DX*4X! zr++dyX~`Nj!_lQmu4!_|nQ+~c4GWdPF{Sg?D)pX?_h{~vciP-}mhspvOwUti3w!INRB@@GGpa2Wmdo>X01WwK171MuaC ztM9z5!{oa(b@Et8`W3<)4Z|ypAJ0U{8N78{A99shgT6taWl*x+V zO+MrlJ{Ig?g$zG{p!sbKFa_A%9Ao! zCn~4Yxbm$bg)Rd<ze z^7JMZIIS7O7SV7Oo4m|c9LPcilYbh}h=OvYqiSR>v+UFm=p1qIs9LZ`?Wb1yP06?t zP$Ao!=7~FY)1hJl3)Bg!frwZXM^rZi*gDN=c3k_xJAK zF>O&uQv<23LN|yfM|H%&E z!@AmD5o2=CA1z68n;i)H_XeljFysna57oMna>+A8DFj7Yd9GvutY%8p8TJK47#kIC z0kDpZ$veua2%f;Eo^twFd7gt`nEH{sT&?{6gUEd{OS3TU;2AWfm z;5-?-vDk&oXpcr3g?hVc=155h2FG-p2J;EHR8VdJz+$*poXXL9#4w&LpI^fM=50OB zxqbc2Oef8*9sv4#yrvn8)}C*GQ=6x;|a z#xfp{?NZ-LS2*(lHO_XkodY2xq)_W@L?Of0j_sE|BL1RHp!tpX_;D=TO$50-jKUR( z1qZwVdq1Ag=gg;v3d;M!m#U$k#=aa1hRohU*@8Oik-v}BT7R~6z1kA}Dp2`DHRZ7X zDBM@HI36Uoi1j0p1N(0U%{cTW+0qnrD<=V>#Jx#x+TH7I)Js=;6znVL=P#LYb9qV} z^Fz4uiWFU2Y;q{oC|E0$c%NWZF!nV)9`zVo@Vk9GzzC~NAFduQV;o4F-6y4Q9Db98 z2*y;6fokBH!hhvUL1AD;>FR%8E$4MTZYQ*6(E;>V^ zj&tfj881ha1DL~U70Xz;F3uLRn1r6b%(2T|OH=EQY22>GV}R+0$GK%Zk`QX7Q9f(7 z4438vJ`2%Ov-Gac3AFI-Y{K7K71}6NRI?injjoY&a(}YpsnA+5tD&3u>Ov}@X0>jA zH5%%rsHSVitcVfa?A&x)TIRi9vzIFYMDO!(9NtUa8&hP|WVbc87{zvT28agU$rKCs)t3=-60isGSTO&#CRpo^?~Q}SSQk&e z0U_QlgQtzBqM{dB2kSRDG0W(IGhDsvQXnD3R)4jwYZNH8y_g(MI^9{!-fg`PI{2`E zWhppvq%wD34XoMX#m7~)iwld3;n?ci1t>-v4Fc16!fhtKTq%^c4a>^pmqC+7gLjl#X2*RQrs#$z&kukysx(Gz$q<~v4Wqu#=j@6)3F@{S1 zHKkypV22uwA#5I%3eF&k(4yK+@83>sR_aX;!1F-0Zxjso z=OCB_?dG#=Qvj@!V+bC`!p>Ef(8wXp&G)DnbK29xY_+J}F}8bb?nP03COMtEk$=vV z{9&7<^aecH#`*U>o{)u7fLTfK6#!6$!`L84q%r+>ZA>o!08?eM$XKsjQ2?!;zvBzZ z;9iU4r(*|4<&}HkyhF1+w;KWnTnP3VA6wF7Xk1CXQUDR$DxED}8|F`Cbfk#Q0@EIF z0I11vplYZ6g-<{qsJq$@{5H2)nt!IvF-c4Dz*8%i(I{-P2mNut+wmHVAtHu)Ei|jz zpDCQa`&#D7P>mxDvFq$QOsPH$PAhC2=ryQO+G8U5*p_=qwyo}tW1(3e<335w_taB> zC?`2nwTtW5?wj!1@&@h#e4O?DaWgB!5vVo^aH?Bui*f+YA4L@-4 z{1IKTxg{?&E_D_FyluK@6EkUfOWWP@uC#Y*y$=D%D5>$W0~VaFBS-)@^i`$pp!+w%uV@CEDR=l<@$SECyXiRvv-++|MN7B9!r9n zE@s@Xe5=v(9g}N8Po^3U(++m(icC^fA5nv{ELvMc3>k9?%oO{>@!;aOb|JHYe2~db zmBX@CI@EeygZStEEnImdymFO=m4qMKcuPcis5l<|ZX}d=>r|9)pMSv8TOo>~2{K@P z`2eo@JnTG&nCu?s3ASsdE7lW;RL$*~)JD-!YA!*4XHgA|pBWhdT(%)ooNoi684>b) zQKJ<#Ij7z*!j=ngey~!jd6y+`KuMvL!jV~VwWDj zc2Ym@m{>{G^yK~iQ-6or<_13!1`|_RGDI97oWqNq2j~VZ5GLkU>I~(=8_961H6(z> zgNloeH0NDS4VxYDcS?<62hthH04Z1jI$Lnuq)mB`Ng3O>@st{%)k>^*sTSD9;y~+# zB%W~!mI1ysU6D1JO*`{WfLJ<0WJ}KW<K~V|-8(g+Vlz zfAbX=)a9w)61G-U$_|C)Dp+3H7_pm-PzDYi*!_rf!1&~%N~ykF3+R@rnd7E?QsGq% z7bkAf*>^=FW$)ZS?{nN6ds`2z#!un$Q=(x3{H#8nXhEI5JdW7~;nF>|Ym0;8cNrCH zv9^+q2Stkx?|+VacXG9`-q(+5N3z%t6Zm=|f8`dljVm0}pQ-b{E!3j!`>6}rnSPuOkE9V~j} zldSqElBo>9PbEK-Nur}$wOL+0xK2zI^EDQ^)Z(8kpggk8>oY$_KtE8FUGQI~)2t1W zkoAX2#1BCp_JoO3LTrSY11dl0g|Xtv!9@o$bAM?jlp#;1&%@clQ!#(;Y60b(6v>Qd z#Kpvp2i|GaEFZ0}j90zgR(Sy|Wjpf2KdnI(QFw}!_$E(P#%?){dTtC2Rq9mfQE7Fy z4Y6IG0sq5s8N;yd(EgDa9cM$_iBfJWQK_u4f0-YHwPMea%g0RMHwE{2G-gdcb2GRO zaDQQ2ULk2ruRh(DOEAN84umc!xI6Pf{tJt??iTcCdzVf#q5(CeRQ#laBUhS*&9;fC zVdDPf$6zKz|^(DSjJ&#*s@zGT*tF* zGXaMd81e;+EK9wK;p{N92=<4UUj(MhQUs%#Alo~KcVxb3U zt$K1k!3{OIHW!u!i#q_$2q&UTnQxUZy>`?{&Ml3x&u--46l=c6p5Cb&&i$q9?{YURz)`8*LBe`LP`_~8nZpJ| zP^?OXG``jS#DCP>G*dB}-)apWbe?fTB~`O6z@2>aT-cVut&z|}9Tm~$WPmS>Y&yyh z8~pR?oi3+^jWvpeq`pE)BcYc6LNS+3Ve}t3p+5`$ZJ9{{N~Vj!`O~RX4u8)c#*RjD zbW)sBMzKEM`56BXdbh$ZRuJxAK^C3;y6osYOR=QtPaeL>oOeL(++H){4QZ9xdmwtM z-xEhLiL>{|jeAIgI4kF9iRC-MC%xvg>^0HgT+;1o;Hy8m&@ON#GFJ>&?P_T~RD4us zEnbBfUG(@wF!JSqo(0yP%76Q0qvY?gVxXaNx|+O~8vVF-Ye!!7m4b-Qi0%)fKrf1Q zNTB-O<-BMHoPDg)bF~Y?did)Yq+Awlx-6B4{wi`}nJ&QAE}2eyTc&>sUFq7Q9V6k7 zo1vfIvwF)RJO?kYx9^hfWBhxN8#m#^JtJ`L7NSh*k0t4QT`D|?QGc})!%~GCRLT9? zy!R3`;)UnkPQd~%-c@Knww3;#T=T{3RBNm~CyI!)uWx;g(4t^pA zweViv;z6Nq`@gNHu@-h%*#n9Txsp3FdtjG1C!Q@QG#+aSjd9{w(w2Q zPX=*}>8Vx%IQB*Ia(}q{VoF1b2N6YCIcm)0JgwYF4}j78W5&3NkQvpPP34u|XWX~F z&u8Q38{~P3UoGTS60VVtmM;lI9d>$R5$#f^^QaBR`8Hnh8`a(J?$8z53Aqu_Ud*4y zyGc+7Ix?T3^N{vAo(f;wG<*Qr(#qvobaxw}G>p5FYI(|Mc7M^sc;$d6oOyB%!`Ldb zM+IzSg22G+oEq1;_}xA`#7{c>Pg2#UPVD@K;!a?LX$awvhEvx}+PyC4ZzQI0Wsp{0 z<~Nctl9z#q>NLNQG(m+JV$QnWD?{BSM~!$X`~SUK&}pM3TG;%e25u?rq1@2)$oydl z@Oh8dw!gRMbAPqE&;B{MSpk_->UWfseiSv|+K7gsFb@dP4Gxb2z53ASwx*Q5aC7OGu z?8XA{xx}7Ue@@5`457QF{~Qdf+3Rf+#tfl3PoEJt6| zf>)Nf%aF9og=rXUI+77nxxq&BlB<`mRB^Y$iv56C(87fyJ`0?XPZn~m|0O5CxQ(HK^Td|{X=&DrOr76?P+M?`e zS2V{`1%IHUi?23a6uc$9T^1WSsISo#ZFP5@D=XfBK)Q!2u@qh|4Es9I?Q{@jVY3vC zkI_R(R7+rj%MsmxL@%&RQ7{8aXNNshscQD;r*B%I9S%6%MeN3F1g06rNLW2D)i4vn zvYMa}a?3y{@l&m9Rxg4y$&$ewi2XFmt0alb&VNP}ii8>1@U5XaURz$z8VVfR?(_ow z08RFX?=G*&QiHf-n;8OlVziEHo)$)u54TadetFJY3+T893by|MZ zSnDzAw($S2yI7YGPz*TOmLmQ&*rSpVK#HG^(dchT{LU#&#M z)-68Q8pFx9d&WAaQ{VdK?yowUBc2a;1b==f+QucjHI=Cv6Qg0qmgD1NklSAXM25wan-wD9^<1#3%dwV&ixQx!$Hgt zADM3pl*{_0xMvL#C>@BMw`D-+#_% z_DCL1z`I^Snx6j(QJs`X0{<*~q})>L{|W468A*bCc7K8)m`7WchK0GbXjk|S%q@>5 zqNBnR55Y|I2-3Mmhs8J7R{C;(vb`5JEJ>e}8M_J!L8wLf_YF-M8VYnf-&#S@a^M*u zb;@2YpWz%4{Dvnh`q~~8C9*NW)_;#H9C)^@P^q0&TU%~=myY1g3Xa6B{kKO&Z8kSr zP@8(?0+LJ@`F9?7956s1_j`5}Y9V;oA|@PnNWBTo20rVU3Vkmd0iLAb_LcOH;s-RO zR$S|EP>D3Qw3GVn=YJuEBdOX{mIueG_jU?%6$)l-6a8z~8ET)9&|=mo8?+0E`m`9?2nqDJ zz1k_GyQVyG5S792o-y0U00e%sI+>KP?3Ag4V;M=2!Qjm$H=Jg5C$tcVpq^ic`k^!h zBi`Sp^XCqiHT9Ug4Jq|Y&B{w(PSY9_=b@By}m%aov93C*XevZnoh z(9|>Uh-a#|#9(!4?Rq>~9B(|)Fg1_d;KEE`AdF8Qc}o3jMOmoLFBTPfA_8f=Z$!Ar zcXzxa{O?(4x(WSag*B5$0SUvVy0x(kE!gzhvAt z8TFzQsw%C+VdT{SbAR?v3^>_c0V&M}hIH*iJ)weYX{WarXB#(=!2&nT-yR*%IhqvD zt+U}LcT#yMzP@uZ$6e#>fv0VN048w+A4&A>djEf9ixQcAMk8Q;>xwJ>Wb;(-Km?oB z&UCLp^$dFH&;4QlI}I%*bG~9CAU<0DInGDa(~KV?+bcRyOG$x9o=T|#1u+RrS_tGErhM%lQ4q9DYFvG^V-R_?J{_~=vYMRx z!WC4Eh%&ISF@H*gW~JrL%o?Lq(a=$Mtb*i?Tn?qX&yL_uVlF|gQya0Ea>pB1#7nB9on~)T2(}O2hU|B_e@)ux&O8P}2p)4u$A3Cs@bCYSsuIo@i&MEaUJdyC zffyLMT4{Ji9TyGmtx((r8a2QUm5@gP)ed?VtO-q`76eJy1BNad5x=K{&Y1o*=vOiQ z%W3VQ%7Fg2`i8IzBAZVznZUe+J6$F%ecxjaqqqthu(kDq?@^VaBLw0)UNAMfzlQ$ zyt4=}9r=WFbQ|Dlk)mLi;Dn7Q@X!fNr&89TnTfbt3J^(q+$+@Xd`0{XrjDOM0aNOC zjK43M6*MH+HZM_&sBywyHS`|6=sz$}-|^>V5KN%_ z&wpZ;UD=dNAGwVNLc5Z%z=$Lp!3N4YxC7@G>F!L7k)3&ZO3eclSV`)7v+6A!B@WFX zMgjuv!dO4ZSpPP6y@JdA%9z-j?br@QQCV&r9OJBf{->7~8~?BZ>>=?_)UU>zs^>xt z)#d<~HZo407~+SqZ}l3o*o#&-x*+%OQ-4r0V7*~zFN&u3XPpu+24LMK&lA%#r4+0K55|_PaVxK z*pX$imJWwt5@qpT+0KqByoHCoe1UhcnC%KE5CB>U~jH*U_0@4yFaA6 zeniDT@FzU<>EE$}*S?QrRtIt0cy2pIbQS+_%Td{U55>!vC#3r?YkENSs`4oInsSg5 zW)hVCL~@4D!;Du8loD5*JL?Wq*U za}CQ2U8<%wo1hRHeI?RVelMGIZt*UyOK|ZDcs$Wp-VQoI_exUVlGuUBCFA zs*{%kJt;u+{c<>j)OF6{QVR@pkbJC43>zPJ&KQ+q7-`c1WvE`46{x`13qs_Oqt*VU zkZYRq7$~Gp&{xw;>e23m9@zJgZ=L#j880&j*xeVu%SS#9+pF_@{STmawvD1&J$=2w z(bt`GuiS&mTy4b|dMz)gT7Rr;#sf4QFy@47w-Pt0@WT>XC!K3JcYhN>GmU(YyWE7f zT0{0@AaC4fYKR~Wj<2tLROZhIvTPh9I-kFUd{@mM21df_+ULb+ zT4iAGC)qF@!<9-*a<O1;Z%)g_8ij3cE<+bRLGl&G5nH1?pK4#LASSey+7z_oIK|?lI^vmuRYw?C{Dl+1DvR<4WW=*7+{!aq~(gB7= zFOyaUU9tI}D@@7I{`c+ z_QXT0Ig)Zo97HftX4)^KmXfGlg3|)jS%Sob-JR8`n}6&6t{x2&p*zMbHUouf=bjjb z5*o7Tu{_V7YlB=&5d<6)JSdlNNTGBf!D5pc!o0=#BO)li5oKIIOQ=|ry!;JceZ@5N zu0Ph&r6zBuC20mAJo?Ggf88y50_CvkcZ zWE8*i))qrR=mq4xFy`%82Z$+8_5eG3DkwNU?lWz=q4gIY<9Ftkb7s~~@{B(P$<~(P z6Vk@Z%>$GTU}7b&j+K2-ZkH&(1&emSFylv$2Y=#V(9&eb4`?xJm&H;lcx@3k9G$N5AKeD4K9Zmob*7yo~;A7h7x&Nk_gEow%h-`SrqMru8<|> z{=2`XXZ9nY!1gLK)xRael1LoXAcjGaKTO=OI!S>dp2pnBqTqg5j8nTy7lp^+L7Srb z=`r%^ZkR~~MJE9ut>bfpMS-LL73=NA%=VF2jBh$s=>^K-pY}80VN^h1uKa1)W%OlU zehV$)w|P5T`McsZKXnQzp3fFh9>OBsTNUe}Re59X9kXAAsyRzvQr(`fj5`c9_ip`h z@D1!fM7z+OBdKn{aMd|?c|963Oub7iqBA$Pf|pF7YLlIR8L30O&J6V{-UU#nB-)+P z|H+0BSWIZPxTdBT{w{87h7NowSb4dd5q#dU3pQCnvo588p{N~7*V;ABMfl8a&>(gN z#ne&2c`OqvB&rf#0^B?+j{uoT&fC+J$+Bsn<&mC2Q^~D@)4d8DI)s+9A<(_A?BrK| zOt2Qaj_gvINzvA+=xjcdul0i;3&ZJHOnW)jaof0U%yNSbVc@Sn$ndwvUa^wms5~Bxiir(r>;VDCgbCLXP z?J!Vt%7%Wi*94R`hxz_!H2E2{=Zn6~#eQSM`!R9|rmsXmxm1+zN-^OxzYFx>-AW+> zIIf{BELNfu2|>bp4wZ&TuJrb13!LLk>gFH7d{fNM;i8xO!y6wCn>L&qzm6mjSqai{ zO5D_b&fI?&9-Ua&j_f7$r!K3v<&nncOo(^YC>4E_Cc6mDIoElGktsUqslw;oR=5l^*@lv=A+7UWZr82=A3cXb1P3h|0uE z-6U-*+rd~Bt?@y$AviC1uJlVZYm>o6X}A!AMR{P&la0!>H#_yBi-bf}|0fDYTJw?f z{NJ%4n`g)tBlZFN(_bMOdVPFig5+OBGQi$z*!b4+zt|-ChvPZ@bv{Ho-ww3&{tz@z zLPOTjl%|lv=CJS#<<@H4;zpJJq3M~soR~BCnvslRZ_WIGt)K2I+}+I-d=}aif{avo zRZdD{X>rwgmQMk@P98fu9>kiO(jjHsSrZJR+N}cI<@b6zv8HZ6(Cqp!#G~fjGwz9;{X+KhX<>2_xZ4AQxWDwB=<@X5t;|``(jl5s*kKCZ zSN8-8Jf$xvIiuspVGQ(K`y#s_3q}eabpKHFHT^>nep}dXHTB=5AlaIeN{(G!he_~i z;d>1#2i;EvC`dv-19SoaLeVpdg9kR6Fa;)n>9L^l4X`feW}0)J=F0SXtawf!Cfo1} ze3;~*`yhTMLxHRvb?X++qYk!edFe{EMpU7Bh}NqCvVCE**;3^^Dc;UmAIG~8CIf4P zguc})yzw^HE7eMbq)_%`rIYtjY$V1SQUp<}V-2amPlEKwhTzPp%sY1azIO$yur@^d z5QlDt;*I?5LY@KYFRO}^x=&shR;YEdKQV~q`#21ag$E7H6PO;Ai02AsD`ZHqayd2B zyu05Rx#-g(!pg9HIHwAZM*Vui?aGXQg`mrT9EKOg5L%da4U5wP`5A7c0z8pIa&gA? zOH?4qee=j5{as>RCt9DUjfzVun1HDOyY_8j1+tHd24M2hPwi%CZQC49`VizbU}&_HS_hldM~Hkh6g|sFANU5> z$gmdPf(F{Fy~J~WY5FvcGw^c{85%b?m2Ight*UXKl*pd7{z=#+hgJR6SIYMtXf?)3 ze$cv62#qN1|G~7!^WVyJDu5Hh+1lV^A!5Xi>L!vaqHa70&Em2e>1XHWBb%U&+A z?2+1JQw-0R`*uDY@pw!3Uic$^4I=t`6Wa{K_9R0M*%@p9C}R^)S8h>p6_BAkZlOvp zhhQal+43Js*+9fa8C#iCd|=&$1}6<@qNg{P=3rV&v|*4-W6Hvfa2B-av8FX=c_d=0 zn$tQO5h11oJL<*o3D0-(&j@~>g|`FQ3eK*~atfLE>>7GX0`aqjPk=bUoRznMQW)Nf zjHa1b7)Ut>3s@nk1f-UsTo3d2Vo+~uKjfwh7wgSx3^l9=q91=<%8>F0M(+ayBIrTn zzlj2K0WOZ>xt4^e6c>?<)}vV=RD?(tA(*Hw$b?a_->xcc(*CyCBeWu18W^~J0Ji+M zVRjb2NIuStnMhrrOA^w8#H5LN>5de;|8cksq074yqOTq3Rk9_5vOneaaw8Ut%URRdi7XGzG!-2Q(E zd0Sv;Ay&~r{>N&f49b=G2QJEw6;Vh61R}#NX4#APH**oUH+Nx9Q*8vqk)Xwsg9lrv zV6!zN&(e!T^S8ES14EKu<^5Nz7Z4~1zMXtKCn=8n2VRTe-Kmdu?YZ7P(UmV3pV3#z zO-9PwxlYj1rY-=V2T+@g$qGHB?oWz`4mMz&9<$Kg9R3BX#knnq>RnaI!(MjlR%rhl z30ZUk*6!qlWwJnaI8#bJAp@6@aF8dmkGa=iBD`>cz3n^@Trv+HoUc3pjC3$NevZRy zFTpf@HBXzan&Uk{;VJ% z1=Qa`cSj2JqD26GdROp@wsEwy&K$ZA9$Y-q^pHOxR@32eN6drD@!Bs27MI~Io99Lc z1E`C+P!p8XY0t@6#j2%i(=SuhVAG8)Nkdw@F?T6t^`Y6oyb=E>&CqE1KeHcjouxRY(`r)=rh5Bq6K$@4DBzdwV$Juk(>P?`tET8NGRX7g7$*-%bmcXL z|Cv@IqyRU4F2^#1)U5CwpC|2qw9o<;b^KJ}AjB>g@795gVkwq$cA_U%!c_V5v!{V7 z{Vl@mKSXGNNTk|AMR1@-F*NkBo|WnABuBFt0p!3+TJjUrt!AN8_<571rj#?WCTNL4 zq350Ecil(l&dMJjR;vbnCnN#Io33)9^c-jJPv=T!iL3^da7@Nlnw*BSQmf1d_)WtBu@f^}GGFTocE!6|lx znxp1uwtiEI_?fd#X+DDSQR^(5E2NgocN$P7kEldQR0E}o@Td5#!~a5Q1HoPcsKQ6` zb@&-tj(Pg#bbQdajzCl{r>m2*Vj-;;_-flf9{U@;sF;kiX1vrgYwR>W657q2rzUC7 zt@m^I5PNh()`V(4^(((26>VC3tUjET}=OdGVDOu*eu zBTpCHPZ^gxXQxZ2LfGrO3%}M(@5QtKdpM2z^w~=>U5iUgl-(luGAF^8W5A~m_;AN4hBM$|!Iy%riis=Q4 zDdI>okDV0EC@JgVmE_@m9UcnvTi7XEabOvk^k*5g1PQKz<|1;*SDN?-t zEw)T4EqdH&Esas@Y?iPd+LOhT6&rcjBW!Nf3R8^_{;SEF=-8hC2>ta1ANvd$dlj3T z?H!05xAqGhx+8B zFy^GS)wWeEuEIde6eJ$eo|w!}X1i%QZw$R97@x~gwNP6L)z?KB(CXtPkw@D^UMz$$ z#3PX#lrS@<|7smuDl_qvB9rJd^K=$t8K7dIE=Mgp*|gM{wC?~G5q{M`93-7bjTPQWs`0&L8Aua%quhH|@ezE+xlpcK2IsWJtGfvq* zRX35AASlQ99lE=Ywg;2d$!DDPcGl(+J`UoG@;lW@;qi^3_I7jH+|uYYsG0> zA2010FOF8Vb%^7np%l8r3*##aggxyJ;Ow90Q(NSV#_0fp*Cubsc^O$ve+-x{lkU${ zXjXuS*=9)lEcduY^fTA5HJs{_7risbG3fNH`*}bv?4!Rq{C8h|*Q53mTdqqLh1X`nONp6glM|@rR(LtlCWGFqfNPdChW- zkDT`QMr=waAOEuXs)omHG~vw^GX{r$0M2Fc^(VQ05uOqvlKSZI-))hhRi3qm;Fsw<#|AEP-!mEF-f^74Rob8T1GY2Kopv=MJ=8o2?z)r zA`Ji+Sa3rse6$rAjG`;1V1)&D1fgF7l}gn49_Xd+zF zt_^bsxww?|s_{J?ral+g9CTK(@Tt}aO;ju$#p*2_36&+Qh;Iz#U3r0MxGG5-4)yz( ze$hB9VCKOv(w4Se1xyyoA7H0FPd(%sLVag5L%Ji8sJkzVf0kRjVads+aM7;MPr_t# zjrj%e|2Y>%ZJe&r?B>E=nk|h&$539@Gvyxxaw3vSw;K0;Q}~RTTOtlBrO`t7x5M$E zw-SMli65*#N+URUVBNtXsVAOLHGwA~ZN_PtWRf;~}d1zqi^WUa_WBE3A zSa4DQ&&q8=;6_1N;Eq=CGmUv`AA&1C<^%EzDdI}u1?!%RtG63hvV8uYWK40`)WqFw z`9=N0{nI|ox-0a>p>k!^--X2X`4z`!8vtv0IT=~?f&?UtX*BwAZUZg@hzwSk_{q&Q zn?-o!! zV6JpM)rT)Zr;kCGelB6$Djhe=OEpD;&L1 zZ;OPDU-9Ez%0y)d4QtZI+!{gTPW8a)2I-ccB@?EuZXF?>9^SV*u~q#W*ReFe@~bDv zuN?YL?#GTMtoUBsJa~C++T~sd>i1%4((5=C^XU=AUyn5=Aa8%vn7~WN$%q zin$J5)tZ}YTVH=YTYW2WEKsQCT|%5-%qfM99}C6S0=L8N9B$p}wPJCij79gTlm&w6 z*p@q`dwMGNiH~`dI&~UP7pl`NyvC#v5YIGcksCezA;LEHBu^qpxltLipY<$Ccrd$t=7O7(35W5&c;7ut8K$=_cs5S1hNKB@wx=uI zW!n_Y2_QW`JFo~%)svO z%cu?(=$w`L)_x-J>b=K?RQC$0-ElSPJddH?dqC8PGdiwefZmt+Y1i6%);%)60jEwJ z{=VonyWhfOZ>Ghinfb5jfV`&VDln-DvVBU=bw#TmI@KQ(H*Hiwq`*tFNb z;xE@&l@2#QpN`DhSC%SU$Ju#X=)%LA?J|CYKcjc%uusm;>_1tq21H1|rVZvbwJ;_p zA%I*x#PGRT~V%3{%GZRjDSFn2bD30h?g^1%!7H~NUIV@B0_uF$}vs{2} zPG%3W8F4J*f=&OCaA%Nvyi|#m_(H+IKRi@g?5NL$kr*%p@{YP*RR8an#HN#n9d}Vo+vq}jkwJfXjaZao zF{#<(oi3U_>e7ts$))prv0JNfS?V=!g6|{?Pyen^BKf6V7iRaZ!{0s~86e#f#lcd- zG6s+3n9I$N$x#tD!<6w=N7^Ua(uhVB%I-D0K;NJ3S`yZTnP3-aLoKx@Y>LRcR^Gd^ zXHM}R1wWSa`}l@En;Qhr^6HtrSCvt>-8da`zCd0-oaH5u%C?O7-qFwcc+Wm3yq8Ty zOy9NEbVfF9&R}yZPcYmhvX9|WV@T6F2mBUe_R&P`|Q7ks_U0`^+dP)EJC~iH_BeJ{rCow!$vQ< zN~9<7`|f*%QaqM-g)-@Pvi2U?9qAwWG3TG>_)&JLFUqC7k)Chzu$njd(?aRB#UuJZ z?eB`!+avF7JX^a`TK^%v?NB*Bu~}C%gp_yHygvm7Yxes4ZMAiG(d|WbS6ADe=dm>Lu%z$mGDZ1v6oow-L;3Pn_KFq z9T;5F^Z@XGX71QnS^rz=PR-L1Ova+60yYP*NZXr%Jz!+ItYmDgZ2ABeRjcpd|8xN? znq<0cWb9=BnN)Fba3SO2esiJn9}9B_GM@jW0{=4*Bh%#<78dzWV-o>!h;j4qh=_3u z14THw*~Nh(!fX;eKtZzqj|#?{&f79_V0#M}OEMschwQ(ya@6BI3VzDie=odNX*WM` zBailzDFnag&dvx;M%M-C`ym8q^lHr)F*qX3CM)5)8=01@_%d;QF&eFW*nyqNuF9q- zX-_2~2&0%|m_C>#9Cz^9SZh*{II(WmEYTF_3UT!lEKqrE`k0Uz5gA`I*~FTRUQ&8RG0BbRrS+RBv}smygRY|mClx>Tli^b+ zV^VgT`G-fd0TpQasY)POpv{US_ZjRGw;Y)cL7O6~l8Zkwa0@Kz1a!D+QymYlXXd_- z3^OR_u_`0*EbT=+>o<~|pA*j2ksWuk>5=cCg*yI^LTG;=juD?{FnK8Y&J~V6mJ`%| iYssM7`k&!-b}@#yctGCb2?TP0cz^(EYH>vg!2bfd{B5@Y delta 128423 zcmb5VRa9Nux~7f0yEBpC?(XjHZV3c;A2$m!8Y@#IjfJY1lpYE2q|F-8%whXqaI`~}-bp{sIDk;|^K z02*3(Ajz|Y0R8z3*7Flp-zZBsw*yXo=G|_9o&^Tt7J@Av|4|n_1wZT-1T40_>Ozs} zP2`5!{E8oKyL~&s#Ej4E;CI;uoQTON#|C`aIT7+HG+f;(eyyF07HaTD8+_6@vRL(8 z@zW`Qeb#nLPW!^}S>du2(`(vogl9iT-CpaqLY8y)?Hpn@&p}|%Ba0*3)eJu-WxG&8 zt6b#;%r=Ja9Kq7w!o}6u($wycm4lfL0vm`0^vAD&00Ogym!l=_ZBWzHV`*2n<2vQdFS7Q zAnrfsgoOV35bNJQB=!5{AOQgovlJ^Ah~tlqe=NB{oPRAjL0o?>e~&Y(I6IiDTe^bu ze;-Xk3dF2oN#*GZGDP^>tN%E_Uw=Zu(*C{c2M{|eXVP~~T3}93ziOue-Tz0Gfa+1gv!Zt{3aGqCMSD!CsxBb_GN0|6aJ9gH>A`<|JTW{$0|-p5JK;3C!Y#HPgdqTu&MM<-SHtkq)7@~2p}0&F+E9_D+c zto{+UpCvC`cx{9)x^M&e+5;S@RBwm}GTDKQ28QZ~^5DOE<_AZZV zN$b?3{J~Cgd1nQDTtf^GzM3x&7dTSt3f;x$H^?Vx)x)R>8C?Y_)d{6gGuu}hsql;x z>g^HAmYW-c>awXL99(k}Rk2R&xj%&(WJ`3{KH|KP?LgAxqYH(EyDR6abI>P>TKAji z7heF?_9KH#4Ytr)=3!oC>68%T4u>_gWi8ho+1AXVZ_;#BHNoh7oJg6ZAb#wKVtGc4 zuGvKk6kANB{qJX3-@%Ocr_KqbhhmH&`x*Izob>xtmt-UNDgBa2*5AC6H=vwy+ zumB2*+T8~X@}xMpyuyZ6LHkkG522dvmwA9x4wvE!Pf1-kTL%2TE!Wye&2sWFdEa;a zo3Y&hWV}eTwd8DQCR?&OmVHuuB#e0iDS+s7$UL*TBFN!fdg=! z+NA#Kq@MQ))=kCZ3e8jd{!rE7PVgfOR&SoNk}&n8BC&7qMjn*{3_4O{8e%lpFOTQX z#4pO!D~YeO)1ODmj72Gn-j^ds>(+xbV_T;Ami9Egv>giPnIsU3sJzvmgpSHS#Mnd= zgrSo8iMy=c63n*8auCo%9hcd=KQsW`8XMrzUr#gJ1XS=oR6r_x@!gKWAh)-%>NcVK z4DI7i@qWtpgdvkl;y9`rYoVWVGeo;2S7J6pYO|dnc|NP>xTb}=v*ZN@g%FvsX{tNP z8&*<#q?k{EB9v^7PYqH@1r9*9|>SLnv+#jurU2Xje)IGUE0df6FA0T#EH1 z%I#s5(MRM-ddC@uoXVCl0*++fDR2DmsCu&8WF3 z341*3PmHlu> zrUA_iw#R(|*6x2T=Z^~$g}@LBedSQOz_$F6@4HBs1YVaT_u5vg5F~11@pTDGRoDdq zU#hrP=b94S9NbhsspA1)H^tnq_#zi(iy1FPlekM38>$6C4sJeoMYP@u2QX{&&d2v_5+5MG}4CnUG;KM?wBOkE574^ zQob4qj!WcS%j+^WLiewbRjtzgl7%`WfvPlqMsxFtUO~!?9o9F`o>=M0S8_Je#cJ6q{U9Rc1x3WE z8O{&J^|8n{zz-AxM&4eWpm^)gJgDK+lAPxAxF3l$Nb)lcXzG8#N(BoZJ5|P$GdzvJ z>Bw7EGDI6_<2EDQ%)a}mtvj~*vLH{gL?F9(&^VxA_5ihJa@LDJx-!J`-3^wma6&)& zQ;xw{j1dBF!ch=K2D<`}B@;0be-RX4pQj#iL=z=DG4M=aoFZQf*=P(u;k9c2#Y{;N zDco3u_h&%DPipbzyVdM+l?elAeo{+`+lp+bSychc478cW8whjf4n}Sb^1_i`)#0(U zB`+~cKRUzig|_S;gP(-mKb9N@{;=Z_)Q60CQ0J1B^oe?h2E-%h^r%9RPE_<(*^uYN zt)-eZz602J`C>_&0(KG+D#Weuu`@1BX~Z|<+L{^pv3R8``chl{>We6_-!S31{NIQk z3w7=%AIx2oR?k`|FVMn}Fb+Z8ESkd8yDYhxBSr(S5_yY#GA+tv`=MCTh%0DNN3smy zRCNx%M9m^01=)kKKZ-xowRRx9y8yqQ7zFR%ItGG}wvCriuclCp~b+lGjp3hmut>8B-1zZ#_Wd|aaT~5XO zhEM9ALxM(nWt9;a=z}@1lq=jy(x01vldVx>p_*_TI01F&kk(xxFk{Kn-n9T-bYnSB z5@3y0hxX@>?5~|9c^o7`8|RI$>4p@Zw4$5Pf@p1<^e9Fw-&um!p2@_bK$nirzQem* z6TVPdpQYAv*-EeJ3iWlkN{?*ZHdGvmp_>bPnR;Eh(zQB_a90ZOCxqgT=)1ChN3UEp*PvT7lOg5dW6Ir6$f@Hm^SU8mY=c37!m?MJ%=2u<)4?^G&O^F zs%-Kj{dz5f;qXPRPGAyf`o+TF+kwz(4wK53YBIoVAgoVp`Be_`OH}RPtta})_d-`J z5-ppj?n{F<`W`_VOESN#&y%}ky|pYXEu8PUTJdC8-4b@$K}(^9jviXUq>e@|F~LAb z^o9i?_L>rS6drEI58l}?6)zSj*wgG8N__+vR{T|kKM=7+UZ%0wheQWiS+RHIveB*&clF@}nOY50Aq2g=6R(C15wJlbMO$KGKo%^)vbIpU zXRXb~sk`Jt@<*GEy^H5mzN(L#Yh=JvDfpHohSC$K^RLBfyUa(z`tw3z1(7fC=ulEc zkM(Kq;L0)M%{ot?6U1qe1fC%7KF+4? z?rqB%o#kSc3I*Z%+Zes(x*h~u^Af|h%Ga$b&H{<4Kw{lt>4)a)3Rkg_oqY@Wg-VKj ze&$G3XrI~hH`<`1WAc*MRrJ~HPWw=9$7%Mx4s)RPa{-;xJA~EGps!~p=-Nah0_a}8 z1T?%khrX)ik8mcFL>0f z^N$IF{xhuo8>_MXae%*$|6i=e#?76Sk53D%>FGL945IrlRGF+xMJ%2@Ic|pYT=p38 zuwWdMb)CWBB^1t?$i|Ar-d$dCPKW70ybyycPq~K}E@y ztyV=x2y=_zaw}b>Emzc0M-2Z4Opw|@)1HJ5N{CmG7DaB8+xK4UTp|jEQhQiu-n22S zDkf3#aV{c5KcDFdX6~dh^T7yC=Pr*~B+t_5E~BPK7by

j8XaMbUj z0=c#52?&cU6YAE6BT-p_EHP6}3ca#8+N?IQ7eNfi_|yZEMr|SN+dGkXA7KTZNVGFt z`AaPtX)5D6R3Re*A_W-(z>xqXm{%w#x*F=M5O(lHBF2wdphgVRnnjJ9C;r)?m^9{l zSo*V|irx)No%JUh8%7PZ{JmNvJTBvaVkh;wxrWHWl$Cwc+A-pvB2Z{|6Sc}NseYLg zLhTQ%5hVt}s*bW)^~Bw}^ggN-NfN>JanVR$lQ9D+4I;$}yejkGhgaB%_hK%Zj!PXFN;N{;}2)INkzf5jG2WKL;}U{RXy>AU8@x zQ7)tFRT1(!x;cR_fp*x@(=NeE>gPRCXnTGfHjOt27hjE`=T~hDG{slj5k}V+$YgDM zI=Sy}Z~?BN2$tB~5qRJnVjs}-mK71E65y1_Im6egVLp&3i2EeE%ur)GxFY5|JsnPK zFQIeyBf3#_=qUb6GbpV8RLH^>`#It+VV|E5JqF1aV$(bX58eH;_oly-ndM28BNx6K zPEvUu8XfsdBp9S%+iOG%hiv*MYP!uquyY%#hDqi(W`&IxeUbhfM zu(p81Xr|lQpbKmW*O7_Jh5%cqWlL_dh%$yrLm5;khcckCdf4twI+D?JIP0x9$+1Q_ zYqA$|HpqYs>1Yj%?m1dUimpS&{M7-MW5ZhehC2^9E8H#3mA>~sw+e-MzQ>#^Le)n# zES>fA)Z{?a_=1k#sZtbpR7M@k(?`jiR7N7zd)%BMSOV{1DKmnRFsAExrLEfE@6J$C zM3#1Q9zX>6+m|4j~`?7=2?w!Pm^N7@##B2+o&=aK5eOwqFAo^Y|oy| z$@?N2!{!>6t93j&DFszARgtPn!;NZ3$+?*q8)$fHhB4ahBn47w<1*1g5PXKgg@^{4n?5s4}97D@PuMa^%)d zSM5U!1{T=w3x9rYCXKTmlwD&q2x>gmuoK?Bd<-1v=ugcVNX>yA^xT}R>1D^Hp+D(Z zyvEalm?a>kqVl#6Dg%%6>bj%q{EQk{S`NIy*T%s-<+}O~3EO<|ZX3P%*#*w&^HV4% zS5ATJ=Zsfd1O#)i#lqf;U%S`FO$o@$T+d%E?uZW(?48s0aec`Zf!1cf@<&y}_t~gq z72X6Ym&ABos~}k+s54;iPy}7nONjJamYKr@wpL)XI|d0&9@G4Lk|Ao8RR{VwfiU2% zfycVCm5yJ4Y;4Jia>y?EP+Nh6;5Owr*bC{*5bx(>dutw49~_wf{+Q?3okTSeG9~^l zHX{F!K9A>7nFMcwQw*3#%@>zh_Acr9tqec9qs6Lr@a~LiSzt_`B0}yHN3%+FqJ~>; zqMT%x7*+MBK?!EFN@otd0;K(K31Gkqd>UBymPC+#T-MAqPY;Fe;X~79Jny6p#L|^3 zf)j&XaNpFF9~i+}wIUSW-oD?QoA5;xtCaXqP0rB!SRHqJTRt2k><==g*Dw zU=LQ1$%JBUV3)AhSczF@+em2=kl%^3fNu>qgYwAf^`XU^rUH1~W!U*HVWhw`c;hOm zW4I(h$hJ58ogYWwMMj4OHzsZd0(Q}y1HKAIC%C=V6RYh!v1Y@B{Eh8|#C+q?vPfbv zsQRGD=eZX&y-J5{P<0L z-m`zzsHBT}n(jIlR(0jU=^)^1<|;=_HISC%y?~lM{?0^i-$HGxVn?7s@AS6d-H4J% z#R+vi*;o4(r5iK-Z{`NaqZAvagPv*Hb@&vb>DrkjdT~h+75)YxO(?E?xA2@WdAn1U;s0 z^Cqm|es+T-Y`A>X^*_0>Vfq@A`q;^zIj50Mx2MmAFZ1B#n)m>HJNREuzTgkLjLEd6 z<6pXr(d3km)u${c6^8-v6<{Zk#Klgt?H$Kw+`r)2Q*H0olCi==Ds;|TI!w7K?5-GT z`k$L#psww+UGk`!j*82C#%Cm(%VXE%oV(h52fnqG*J+GzEaNe$hITVEdFk})Yx*@Z zrQ%+C!{2FhB_W)g&{O)II;WhEZyVrY4})kA(^%$@ zAc~B13buSq=(M_ag~iQo_=gGO2)vs|A&axzNtQ)Z6fyFU9~2Zc`RzwZ=o)gGof&%< zvBF|^q*Uq2R$#m?6JDE~t6JS#;hXObwY`!*5x0LMS6|5+`*jH@4Xo%e++$Cah~ZzQ~4g+pQaPbUd!4ZOlyl z`e{3%M*i&=``dSWF3B8b6C}|j?lcAJ^B2F?v6peG6@!Tk*{fyYH@W8fYDZ?>tF)Gu zmHXSzSMIvaxl#MdE0@uvaqomVybOCXSEJf)VsvGh4#YBcvHf09eW%7`OxlVKyVoZ}Y1IkLCO!x!PRjT? z30-947H0qEZ26>TqC(1)K7@6*XU-JbaMH&yMO&Wy#GVt{DX#1*z-(sR)N8pbAC0m8 z{Em$)i_GBXmPK_p0A>0TxxC1dtz**RkB0zTqzCer&&oT65td!EhplLF5K&HVNswFF=I&0;dkkeEQtnN)TJ6AH?Y+ zJNA`eHl1i72`s=kMSmJ2e-F`_yfGrKN~OXqsJT92FS96cDgQV?wk~&N=Lsn@n>iVcO8V}YSwrOhbDt!0mU@^Uqt z$AEn1h8?Hhg@i|c10&-@cM>cL2+&krApv6L>DO~>__<6Ueu<72x9!!Enmjb&J4k{_ zmIQ>I=GV~ZVkKY|OTIpHJdzIeq!-^IiGJpt0zUjq`YJ2bQ=r^Px|4KS(J6jr&m%bh zP3Rjl`Cc^&`C!kSqjpr=OmXhLp59@6RzGJF3=S%gxx1w zd@mgZh*=@`Y4GNYnGzIG|Ew?tz*O+&I!|=-sS9AE6f=dZa6Wyzph`kjurk8EOH-rT z1RT~-pR?f)Me*JG_zSGSd6vj-MToN=1AX2jtX6T`X?dCprjamAG=qXjV?;iX2C{tC zg@U*zGO$zh)LAqeF$&iDo-LTz9j1i4VQBd5A2|LK>3$%{3S1mHEZnj5{X%(^cGb)h zgi+8P;xDb*#>!)a>aWu!pphkJ+_$Ft0RS4xg9|s*0o4mqBycIHlN9hGskFm2r;!vJLWdMzN z(IJAA*Ifz{UB1P`Z59%O--gPIaURf1vN(kI(c3n(tDQJZ{X{n5q0Zx?x{P2^Fetu7 z&ANbJF~Sxxpj0M<0s>87!(=e=u2*d8hmXJ;=rYmLBP0V0(T2h~T4)A%m~ul^u6YPK zunF0+;R;C@OuR|lKKn3)gWFlv%L8lpvcfKkzBax)>YiNu*+c7NioIHD^HK>acp_rn!alY>px)Es4#1)}Od=@+Y%drz74#4c~H^&p;4nT7QTQ-lnSN@~no z%6;L>6!iDCazb>&fvR+yv-(Ew5diyMspO~7wp$0D=05|h2 z(@}lxq-}V^YoKC27z6*#YVXLWqKc*GSOww2i}{AMV;M~BV^8r`OJz@F8MmcVRa@ zIOGksD@~2mrqt?!R73oQ07sbi+`(FTDF^H)WkK+@^_qqi1ATyl`@D6(;Bq<9+z=Z( zw=D1=5SJi6!K~HAl=x+92Fob*ofWMh?dn6%@y2{g(l58ewZ7d18xdQp*6GLZAUXMx zHFv3wS|lXGd4^g4)Mvwn<>c2qYC#0VMt1|_Tf^Dp()MLGVZ?~V`*`mDDE8 zLU79H+LfH3a*y{cM@V(Fq&jt~bpk5~*?Uca;(;Y==0F3mZd}pE)Ff#^o$?3YW(y@N zMU)MRtpt41_l*2+t#id+JEigPq}UVtc|7k{X?cW$ji_gJ6y`D`OS%-&_a=|Q zj&%x31cv}#6Mhjb7B~ThiECA!qFcE+gB@~*O7!em9rwop@$!HSwv9rDc`vP}BE@+o zzw$vpI{3pnS}_R}zQ8C*^OOfTJecCKMlXj6uTr?f-p4XU?sOOb^yQ$I37#{P21}!` zZJ%aCg4O&|SBfsbJ<+T)`DM#S%2Mhs&JOTj5jQ~friGDP4*1Agn93IiJaZnwz^x{< zzF*z7wJfWZW-1D(tl7-$?paykGG!+wE*)@=5R-A$6dGKrzEMA&EqztlQwpKhQC9J& zE{ZA&yhX}AJB)ZOu=}@&Sa(3J-zm#z7r}gJjG<&0-Dq6-jG-j3S0PShp1RHoVxW7{ zoj(Ct;!ET=tg>HzLa_?7@_S2_4VlK2aE6~XZO1XsNY4$2Pow3aF#0>#ZX;}bH%~XM z%Oqht+0RvDe_Rk@k**dD;+RJHMC7s}mDTonq-14^gheI4i?|kLIFiYN2i=zrC+D&C z%$Y%`fRl#yW&+XO9p#*d4?B_nvYQN~$yc`H%A=5h0A%4?Na(EjqB33fHe@i#hOx8W6LhLq~ zPf0Zm#w2#nOI0Y&Lp}+g5o`JGj9>KeQW=2>KFZ}W#r+LI?2C3?zytzrf{nY@(T>(w zu~mIsbH^RB?oMm;h0(RZkpMl9epvwk>}2%7lZ`x8l|Y)M`1T1;E6BvoTIsPKTK8X| zouzw;cqqJX5EGgrxFt3dx0;($zePt!XT0R3_q=aTvh69JEfqLXpT=^JD3v~5#amE! z{r&(jJdp`AQPSP<+yf7+%~1Kp%Q znt`8<$vU0r=<#5k-tC1iVyB(fEPN8wEw*V-*_O*jKTV)fpH;ZsC?*7Zmk5c%d$&BC zB=a4fi@?tpnd8^P(r~dc8?Sk?j?L1^iLVu9e$Pa*W{8>)zy8EJmGPdY|Kr(7mU1Un znc}E=K}LqE@(ugmton^NWh6inA;h2KVwc!heWoL4K}R^EtaKpu?#5W@K%sQE%&j=7 zBG!-QYsl9EuQy^}*`Y6s4;x5;hS`C3@has*0aLm5B&DUZ;Viwf`d%xeLGxf}aqBah z(T2eZbL~F1vgTQ23k`QM1N``s)z8u`L*(<{-5U$lSx-Vfz2xJITPk2ZaWd2EoBy>=WpGu-eFNlXiEmV{NGT$CkuHcs_z5fMPw%h%7sk1Ns%HDd< zsMg0&jYyq$36WDPP0GM0hy>??Z#K!A(|B*RzA16mb(Ct2vqo%`d=D#2!w%F)nLne) zd9*{|h1Av1nHFuUg}k0(CsHpivhd&0`ra%jRI1ux8yHOZ3p@-CAACsgqld)5a4k|} zkwr^Lvu0l_5-*F$`x%XRZ;I^0;Pxo_-UT}H>-M-ahMPkq)CWjFA%O~OYyy2A9U3!a zr0_)=8X=Y0#6Pc}Mrca4B=^d-176ReuSqTVEr{1fRZ+4*_>Ui(hUTP@rkQo)YK~sjszJpf#8F7KRkQ7;-VWaSKf>?^&Zb;&8gak5N(*d) zD#+%8iqWusQIy01E_oAcUY%({X|xNL^@iB3^}y9S{~^KJM*Vf*Ce9kS`tlsQBSu9r zg~{?DtBqM#By@FNPVCUY3kl}XUIJ1^G_*KO?(HVu1o=M1KEAhGo{~Mvfh?j12rG;ABYd6~lV;Q-?t>Of0b1o4WJ@cKvyRT)S^QB{T#l9kxJw-PN%bAaxL$PE05;`EL6l>W3 z09fdlvGo6WE=bCz=q}Bbzf`^C-^KvyK@_w^AiIx$;r73v;V z1R<6t8WT~zplR|n?LSX!+7J~<-ZY%XKrDb!3te|pLx)%(pUZi!#(<3qOgN9sP@8yF zq-{bqsCG(yLi0vYH;bkv@IGY)% zL;e{czN}mGp#qM1nJVTkY9PCP?{VOoPCtCqwpPSNKX5@eER`?U0+MImh9Q)FeWzSD zkXMH+E)H3iCXqNTx^#p9xS0^6$`*39oBT1dP3 z^G0erA$9lVXPt_W4iG)@L{k>=6}1bwV56SHNfD~kzeGfh*XVfWxCJ@NfuDjB4N2<6 z@W|7D+DK}J&PDcAX*4Z{mc$vvWyI)6c_DcVIcJNT9YaZARg zrVd4I)$sp(sh2;*GZ5=MOYcrSBsh-n~)UuYYCJG z{@YeassgZ+fjy2`Z?S}6-^(w61ChHEgE)#Ysqq$QdNFb2tL>P(P!Xoj6D;adqSR@U1#+`ubzBlIwn}CcG;npk%e!wVwl1j3)aF`U}_^GfF@}P^m07aFB<#;xRlepG!1ef z%*HdFaW;ek8g=AW@;14;`t89g*Yy-Klh2PU7Cjdkp(DDtn5>rU&=HQoSVXL?r9knX zS92MawhX(-P4qMn=A&era03p|ok<8vgIe6j3SgBiv{pSuD3EJv?|ZTmv$o_gE0(u> zsT2@ImPlX;kcUAS@FG8f1~bfuc!K0Dv!q{Pi_7aQ&^KDj4)ikmT%d~)ZJ==_^BgJ`5*(qf|RUSw*6kcV6Lx0=YWK zE_)Jp&pS)=o5*^_u0eQCoVepTZa~q5-F_N4$|eZ9#&eZ&>QoUUsqQkMJd)>ZHC<^A zhHINd5v$da9NTIhEu`+gGx(X*Ek4c=x4$@kl5^s3>o;kz~`R)tev2mppZA(5B zoq2L|ui8WH(cIx=O@!V<& zeg;o6v1o9)Ti`|x^MtEnxf$*w%>-(d*J?=eU?P<=F_Rgvm$bN^tPJB0gJT$i72^CP z778{+K?K@Py;alY)ZH3m!ZAbLEPTFpx1trr6 zfp%p@^!<>B<$mg?`xe|GgJE3g;r7WL{-b+JISM>EbZeCS5MaX z|CwwS$5Ct+2lHkYLwdfNI@T`qOkkY0DARU&44V(?=6ic{eyxE?vz65&D(`#&CgtAh7ERZ{}al()buEzBTu{f<=bdktSp z2Cjk~5W_hx*q*t;+~*!00w%-xjd9BLgX=wGzB4>efnDKZV6+KU z9NTOFVwVi!STZ~CsE5sW#*hx%m__4B*#ns+jpBhmJ-k!qZlV4aN0Iy_HL>CI#glLM z%?gF^lCt%2malHD?R~w(CK!NFj{HCmppeetm1F#rlx_^%DFc^#rJ(}Lr>xPW1J48= zhzzKos_j|=Q?D7G*QDh1!|gV^2Z+a9nNxt*9J>@|#76w7vr?CMHY+C#?Jv_tYZm7h z5^vG7%#g<;a;}jU7oKWqS^XV0iGFXp^}_CKLnPv^h35l?=-Sp_`EC};)CUYHSEp0k z)%E%gBadRiru0w;WXIWvZmJ(HakiThShl7WTQ4m@^p`RO$dP zo?j_XS;pL7F@Fqf;A}Nkq&AHt2hnm?5x?%f+c@c2GLG#;A89o zH}Dj=;AXoYk_7YZ4s8nJ}foJgH_2XqMWx@SUg>WhDc+1%&LpV{-Y_R=5K6*f~W&0?)tVtlQ zP@*S#;H2j2vd#2dYI49kA{sJ^x8MbJ|Ey3~zKr-#P#T)6!R8t4w`M9FRqOE0pX0W$ zJc>3Sr?4Kngm_wHNyGOAH&jOcI>{5C6!;51|G}Q@|K%zF`vMu;pWVU#IeY#w_P?{| z@8;rv^%a4ClpX)hoBv?Rzn38YZZ7}Ep8t2={B17(SKsn4_T>EMEwz7V&p#CDU&sHe z_{hP|^_Q)5*crg~zpFAy!bND!9($S2Lq(34BmjvLw2B6@)7zuP+UdNM+|yW4TkIf0W8vi}O>*#FoB0l+UEtx(0;h|A*F)F#f4R8krweD)2Vce zPMT6F>npUhf$f+2=!Dv0#+}x$iuw$U4t|eim4SDffN8(V zy+i6lncg68P0P&bi_++Vii^I~TIk1}HOcz1G9Q{?NBjx`_7Qct8Ew@oYz#RfDgU^} z&)L39(jE2*KqtkZnIGkqpN2LJZ5JtipmIIrTs3l85`k*g`yL`RX?!g7+wD^atmJNw zd_HHmvZr^>VIl0Eoe^x%Jvdt7z`TKXy_r#qKJu&_DhyuC^Ne`_wSLMV*f%{>YM3E7 zDidU9nPHZpj2}c31Dsj8koi zi8a@qk*6hk^a1KXg=BUKm>1XXulrT6b$X~+dK#7HJ!kBHuTPA3Wj*JsU&+n7ee2eG zq`R@Ux=UYj*HjMEEW-@`qL`^3)KsH0zS(s(U+K<(%0EIk5}vFnJwmzBFaMFEPgLU6TsgW2Fj}D{@lcr| z1g&X;1j+{$Y>hrkpDpR1+Juy$EpQ80XnYL!%11Z_c*5&i^i~(CQ(ud97(s^4k_NSt z{<@4uKdy=v=Z^aT1$UZ{pL!7MLc!ng&A~VrBqJtl)JQ7rRMC>)1*U_S$6&Ltswa~Z zFNs6t5n>@oDH;9sJ7VnR(YeiJj&`L#GItCmGT$1|4XXs^d#J**OD z)t7LJusAOLiU~E3np3pI+RIgzSHf%lbu5+YdiW}|nGO6kDt%oUN+ zxTJ^iv{1;=#r30}M_N5M5mE6oLT+=oJ9F)e24j>{T_`l}>#kxx3wG;-%!+!45y722 zRE&E#c%EVl$VZ~0B|Eu7k8W!VoLxq^kh;AEiLl=Ey-J3YoSesd4fz!JlR*Xb;%h~K zTdgi^#mnH=HujPQI*()6JNj| z`+dO}L)tk>U6GJjaPa3TW^crs<*%MlOa#3zvQ%(pz&OL8a=Dq7Qn^yr>ENna{nO}3 zP-BTscR0z+-bSH!Uxnd=RP!tvhTeEYTfU{VQ*YhzDiWsS#xRw@(wxB*ow1BW1cbs! zz(?MQ_ss_u5dtBhnRaX)M_q2BeI0NPBA4r$b=H`Y-4!wAt>4b^e`-xlJS#OW#@~u9 zBGG#50$}ew$gkN8yH8tH)@a#TC}at#;fc7h_Q)kZ(soZ36==15jn}g?`H(M`ZY=3& z=QU;iZhLw_!E#q-&EOS+10!w<$wTx}xtc-Zd0c(tG*^Tm3Q}GC$8#^d7NK94oQjgV5YGLC52f*E`)$ zO}4l{JDINdxMNheG)#^QH)}H(dOPZlJwF*~(AKdFKih`9YrW;AKhi&5Sz5-#B*ny8 z)dKQh(OGP}`X*Ria$mi*y{4K(H}n*~cD6DJRbItZ2(9hi#JFqXTs{~pt>)ZjR5}?C zX2CSz3n~p)#ByL=wcrnOon2MVHBLCZ=l5<3G|VlJJRx?kww$ruqHkJ}3_XfjQLSRjhZCEp_BBljsLa!D=x^Wy= zLc)Vm2)@11L)7vtP7jC}N%m5U5DwT0E!kp`PTQvV!D7zILIho3^l6h=u)^M+L;z9v zJP77WdWI(lBW$E>dmj-Mw*BZ?!c&cu-<6JcOCm62_YfMEE)<5VZkP)Uk$skYQA;s2Xe|h5y z{YY12U1QB_hp*!%N}vcS?4>!Xy#t~#iBSa$Z`bFV>{fnI@SNtL5(=}O_Dh7zo#^Hs zQ0X;}IMxnce{aqH;I(dglHGHiOSYMQz$zK$xjx#$;x(099Q%b<9|@@Y&_g($ChAy&gNy_s?wnRDGUkkDFIh^wCJk%_K4|e0R=y8G{ecZWTZeCDihm#eSt}NXf zMU34oGN@2df9&z&o_Tn1Z#;L+M(pV(;M%%+2-nb!O0rIej`6&%k4rfWFr&`3w7lG$ zoo_sYTm^J4qH9&pq+b$U&S1BIoMD8dR#rOmdjZo7)&bP#@i;Rs0?p0g7r9#RhU`!$ z#z!hIt8^ko*MW*(;%~|1F_#K19m@JXTq&|l9>E&9nF!hO1tfKfwyGA;Iw{L$?^y?= zr$7~h9ZJ)&qUkIZ_sJGzb^QlcHl(Jha5MK`32(^i^ZJsAB@0n5b4j;=c7e1T%naNe zXI}Zph9QpqA^ogF+mxqo{uAsxGCI9$H3vutg1?ZAx7KJ8mQ?;NGBTq3@xuPNa* zNGcyYO02-PVTFeDDPH*3XE+>`TYAB$>TugvqL|)h~oU&=I62mn^dQ z{;_s0kqXD`xk;~;nwO~L@ml?;qx5O{+Z&JZ z^mn@(d&8vQv~nNe{@bn8m|lXn()sdX8^Q8<|FK>h)@x<|4(s}o9-`8nAxRkgGSn{$ zasgABv67)V9c~6g(wLA-JnjPV^TL!)RN!2mC;b=Jf#xIW1a;NK9vTU7lu=K6y941(P zU=|m$Te>OY%TL9kBe+VczmSQx2U?q7dK)pAK0p;Y)eOg;Mw)B4e3aEM$HI?^8{gpK zBuw%uGR@?NiLWNE1zOA;IE3H?;7lk4yWstCGK7(t4Hzzpn+MJUYYG^P)3QrO5LWnp zfX}{V>r4cBClquDs%j5EBD4N~oV^D;mGApFZWfWuWUo{rdz>SivO^+!j|fG|2#+lZ z$>ZMk8M0@#_}$Mr-tW9WpU?O6{r>-6uXCUKxt{yJ?)%!;b)Rz{@|7YT z#0yG0luAqTPfr_mb1|zY@zNk`&%8648F7Q0HV*wO<;3b%1g_n?spGn(%GNsO$ic=;#cyJ%7+RVcmTMQrOG29KLY1TL$Bxs_G~IELB4Qcq8bWri>Q3ROqQL%#@vEx(WY?^%yqYFN)W4UeJPW-` zmyDIp|6^4o$D<`yPZRUL%N=|~sevs^&6bwkw~f#_GRxTJX>H4He5i%yqvi|fIk&qB>ocYRKejq6XvGJYHidl@xRUKzfy?JZv1gyRUv7)hPj%(^?zy9duTkAZndDB8O_KDHv;m2Qv#8@R~ z+$ac}cnmoXdZp#Z-0^DZKe7EznzlxIt-HrW+nI%A%o2)!zbeZ44cc%(p8X*-yt(1H zUzvAB%v7xJvsv%D3)xNQ=|*X~h<6M*gS4{CV^8puQtT02wu6sXcW{XMxERU+xg8B0GlBE@$1 zFsLaq&P4Otfo0RZ*DTPpm-}nCAbSbDoVC=Uz5GNW4@cXe-Ym)@R$&wOL?iF|s!pL2 z`GwZ>4JJ#SZ=yoO7Kb0qhLlMYeppHkZ2UZUnMh`|pvNUadY|OS`%;7Odg03-^9=eo zY*&-UsttwZ!+2#>!^czH6-?DHOL)^Fd4=QR8~J9+M`C-v+ZqtQ$A{{+qgo6@VEC) zgwMCzl+ z^lmBdTK|ug`nTzA!>Azhu2Q8pZF(t=ZYCw>k8gctk0!{e;cCIgi#mI&SKiY^xfy4G zoz0gnml%?lvQRjafv51Mc+q8e;S0{w7;gHunUNYsyf0^~Livp(B)0X1W4PyA;{!|8 zJ5zs8<>pA*S`*Ng)+9O_b6#?$Tpg-C*uC!{o5}67LniV)kT8`4s-{nBWVO(0&md^F zn5qr7BO_Y5dK$NyO)IiVd)6b60V~U~?W)>rz4F`MZfTN!p?8~@y1@g3osJjqvD;{{ zb$8|xTQ~a~aDEwUGD($bSQENwHxd8xc$^f)JSWvrD!a^?5`9{l0rd zGQoKEya{o}CCI0YCQZhws&r=;uHQ8>669tz4o%0?x?h`1w8{oy-WT=p3EmaL^<~n2 zKRAgvFdff3+k)*{^4(W9Pbr@ z)lX*lFBF-|SdZMULu%z*QjcSD5N{6qIL|yxHdkv7>ux+Ns!Be7DLnfgC9bf;)n{%> zncNWx<-tB7q|P)~VjZk)xJiHOzGBMk7W-yp?GrAwt;dfX51q3r9*oURci@}8&P8N# zz_y%rJ22Zm-SS)L+#RH^Z&F{2qe#YM>iNZMJRe?k4YFDkP}oC{Y?A$HDylq-)N$Hu zGi&QH*Yk)QuJettuXs~(o9HW*E43^%?QToVj5gDv9QPRcqp(*z?0UlbQ#FB)F&r}= zEaI@^Rps^;zE1PrZMUx#`%n0c!Juik8^VY>LdV6yx`-h;(V z>nAN4GSV;7Q^qGeeas}oT?I5qD@v5CuBK%zGU}T*MMSz&wF;9I3=^LWTw zzxf5js@JjOQaBPCwVz2!-t3$nJuV9I zem=KFIg_PypLECT7~Az&noBRAfi9 zLAQFJ`F7mJ+`#z5PTwcidiHzM;6X^Yiuv?;k(kBtbB}OKAr^I93ywwNSZ|dA&c}mX z>Nh5`@$(t)I8Pl#XMcNjbzVe`r+X)Le|N%$DTuH~ctYg8K%DCyLz2)}j*)M8F%nA? zcdD$-1gLBuWvUEqb$uXA8ID`_i*Ael^_ax5cp5xwPDt z=|TER;!89i^fT~dkZ$9fu{RUfA)c#P?8-EDXUqaM)snlCTbQQVd+oAjv!o=Z`y$Ja za&x8~=QFN}MFu_A=&ZwiUsmm4*!S?lP51J)n?EhGipqs8Ax7&ZhZdEtVOw=}HhuNC zKN>3S$aO#Eyd?~O8(Eepd2sQe_2v`Z&hVzYo>$8B=eN~-bX16@z00rphS3$^U&q+L z-4_+}O^nc@yrr%+@s?q^l-~{o##H<>-K`tn!~C}|VXF|8+g1bx)mkYgk9eI1SUNjQh zowncUZl5h2j;3Ua4fM*D%eLHo{+0NmvqJ69k}xAf)nNlHw$;|m~h>x)_ozv@e;UUw%<-pM89t;Rx8Owrj3uFCjN&2`ta zY}Quat`B8S^}Q{URW-tRdtcPv^g;f7>hu0<1uVhm_b4KIpS*gA#8Dhb&?jM2&FuMT z<8AJ!9y~96qgRL?8n?W69*f&nm^>{vXW6U-b7SGH8z1C`^-LMdO-_=D)`3D#KTVX| z<$mp@q8rj)_b z5Cd30;|-tLWkqz}^cxU}iJwxKJL2Ik2y%>j#rO2FuX9mv;Rqyi*}{9$!90Y0+2e62 zC!TrbvgPj96O$B|tj4>ykrv{ioJ%Ec_GK9DwZVsmzmH@(7o_DeW8|M^E4s$}VknAw zXFbm7QfN`Z>ACb!dDNdw&4gGj9|XM)x{yRWqw{-aPTI3dw_D{%Ta44QY{wzYUmCUD zf4-6!?khm?KYR*=ejMP5#|VPYPyR2zUjyYVJPdrsa{RzT)V%*vGDH8jXI}iHWd6GZ z{^t+U{&V^K*T+34%j6SP@@e#Q75Twe4asnLkpk!^M%unqR>9&S_Fp-8PCr~9HRrT& zmMk!-emqfv=q#ZWR?r;hrAG0UWzFEzD#~LnW3etX+0?;r8cD2t1#g8}D|%BTv)F&Z z_q;Xuk~QJSdA|PpHUrt^G%6Xaq%yu&_Hl^w$}4{ha!o(CCy==85_-MyG2XAzTDO`R zZ+q-lqv_=k+g>Up;x6({$z^Ey<=C5FrcV!@Ew8G!+wzE0Y%Jmyx123q8dvB48h1N3 zg7Xdaxqv(AH?kKlUT_+p{Y<}mUo2tF6^}XLS>nSizY_B`meLBcA0y4mEN9+^L6XYE z3QlD{PwR5i7fO>%u@e$PW40FzXvkG4FbqEjg?*xLQ6^2xn7FUI&owdBQ z*dwCTu~nI0Yu!%a3eL;S^D14h1o`+yNV zvGPAWqVnH$>py?Q$PXS;`PVa4{v6HR{PU=k|3xM2%ph1{`Tu(Ki7tW<$;rbg2!8A+ zgy7}mXG93{a|$vd_>r8jCJOQ%chLYrgb)Dp@$iCH0KxNDPY}LFLyzzA3vwb+NCmh7 zu>iRM4<9EVBOgB>Cj_3YiJAa|k0${zfFj`*4MFn33!x_dJr;eRUjW`2KbV2g|64GB zeV(a{> z$(Dx~-~vyVLB9#`Am9xN@dLU9_)#;!MgZgZ(YyfEa&rSbg52;uAzlH{^79LTMFn_x zKr1N74QBF#bs?}1ZWO6Pf=GAB?uIl4@d`Y|9J=c$1Gk10v0lg%s=e>>s(P+00;~L)Z%|{d3gi@ z%h4@2N&{gtyD5(G{iJ0tnbwpj&<+ z*a*=rA0G-XfU+vEeSj3*B89*h0aPo*2a5sS3IO)Nn?SXH;{^JDaseR$SXzHxfLr{4 z-^Xu4NFG1|x;;5d5O@{9$A4=P-0JW>f5ly0A=v-_4F@XnmwKYuf@aSD*Orf45CT#LZ-2M2sQ{mU0x23I1VS7iqYyAP zB(Ppst%L;N2!sGoLEsq>j6yr`~^@=p!LAskudIKOlZv#f?x#4 zOMs{dmfNQe88Up%Lg_OAYis2NM86s59S#^%#lCh zgEKRfcY%aZrifNRbRSMq{Chvc0QCLyU$q|2` z@M7@m59Gw)KR~pRquW1F9&YIGz48L@fVy+S4*ua>Q1JlmZc#0I9Ew;}ZiKRsf6#$m zP6%iYP*sqH!R}WOjt4?;!i6$K2&ftY)_5eGOCf;$f^dUs1<`B)Ij10q58y$7ydY+P zA-r(p5CWH(7xs0+hYOz(JeUAqjU>_is9%~297~s13*u~(qP-5FDL|<03F{(U7YL- zf)EY(g+wI)sP-5g3Mo3J<3rJKG9&u;K6n; z;O~NlALP&=o&nbe(hWhNXCTah3<7Kf_+3CQ1k?*?2ymh(ehY&72e=TR&wQxif;{ka zSf7Blfn**|K6qdi1yey92DS?H45a=*lYj!lVH-}_`GLFu9G#hgI_fVBe5g<@h=jAi zA^{=53k0AVgbomH0Hq)a zgR^!a*cw3}0Xtg&7XW!5fFnT=0{nv$RA8zAfC?E15GDYtQ85a^2Xh|*%$b)F5(LE| zECV>Jgk1q_v2Y7q5o#GQ1H>;7j)290pIV+&Gj#u-oa5(%Lm0~Mqq1grYe1l25m+p| z0G9v|DHwxt6oNbuENMPLR1g750;mu`<+>o`@Gv5QHh}#A=>s^>ZyY+a>IrW3mC4a0Z$M>{=mzkn2XLTVWt4Np^ymz+Z6<|MI{#} z+CLoPN5viiRHX$w8Q>p))x&WPRo@80@d;Epa4Q6h2_}FK72fzkiU-C)V4xsyjBr(l z5CS4VSp`4X9T*O%0KN<8E|52nAwUj77c49|6Bhuc2jmHl{NwljoCp9u0Bk2p64=M{ zF``>O;Ot=i0`?C~0R;YkeIZZ^c${pZN+|>o5{R|H%b{n0k_a{$a3}<$Lc{+;3sNtj zs37X1mV|MmdnZTngLn-H0*|8rZ}5P)aBOD-JK5N+Y@9n1uui3cd^vGaN-b66F;IQI#M#xq*2A4?&=^ zOjtt!LR24tasX%v0AB}}`(P}3WgZ@M(IyD$U%)&R3x!ZDLsNie-yix<(j_49SE-2> z4|)YSnF5tG%FZ-~|I;;uo^rB9FL|WVQ?k@yd*bVs>5*r76C}qkI%T^WCMME2+ur5j*2TFas3N7zyf0e zp$iE7_yS}nu>XNKiYED=y+2nl9)6Iu!P&)MJzj7~_}4rbiXs;U698%k+Z2e^;EC<1 z87L;gJ@h?35MB`=u%hyB)Wsj6{C)5TJ3;uY9!^*U0h>TT0D^}jDV%}BN0@LV0x=2b zCHg)L0}KSw7(T&3^}#|Qx`C7rI89Jvfvg;b3Ed(EK>h`M7lXp=x{ox%l8uLCTIVqB#`wSQQ8?fLs8=TE>M>7>;lH>4zk|dhs2BRQmPeI|d2TSozXT3>FpwQ5F_H4&=vd*5<}v;tpC4kJT?* zDn7lwEY2YluM{k?!mGy8T>+)Uf1;BZYB*I>k7Z=?(_(Vm!VHI-kJsUMQ}<{f4Wspx zwH4OOw9|6K!?D7jUj+?ZcSdNx*7Y3yaqyEw0zVy#+uq*3`_P@1(d_=b89sjzb~BY1 zhm!3W3s$fV#?>teMfI0WM`g)VB^X|`WmFfwfB!xkY?Cmzl+eDLbq~`Hiee=2EXsPH z6`qrYKc4>zbNyy%<`HKweH3l7wej2mm*4YGRLvdDE##}51%)`Thmh3__Jw>rkFhFc zPrsFG!6K(sS~@i6*yqC5si}^`HcGYJ%ddcv4%@;qM#chyJtdy%o@TjzPVxF9&)AG$ zHVH|+DEcX)RNM=Lu?Ob&%%C4OM;@ciUz>Xxn|DUWSNei6CZ!ZG(zeeW=_m1ZxAb66 zDXrL8ZQKnegg&}FcpsAx`0UfWcUg4JR9pE6GS?E6yjI+|jdr%Db%qBk23>v!v~w&e zwI5#nT;Jd&+0oharQwdkuQ9^1Gmqk2qe=uxR=f_BD+_79ksqQz_LlN6bVRKF#9w_(sIP1IjQ6O^#TJZesZChy$y5xfd{i zNmz8$U7_+3njLv_00nN01Wk(96B?-=28_CAA4un}U>~0QWchCE+@~h>BQE<-O?-O+ zqd%yQq*nwmjudTHgp)sYJY6_q*4}0u~@R8Tb zJM7t+GLk;Ik5KGUqQpQyV?Q zN%qM#p}0@lue6c9MD%I(1vmA?q5D4i@%6MZR}duG3zt1>->6f3-}ZR?OY>a8;Q-bs zt8(Ix*}A~DF#%iS{g)>Uz8RMCQu9{7DK>22#NNIws0>kNoX?_B6;VvQACC-BUdNY_ z#ZV63YooK;+Oj((@N`lr?3WO=R#NYkC@HQb<(b(gWLL=<4U3<4w7j&oHr}Bh-lnOO z8`K5J_h=Cqu-*uxaU;;CHRkbYlXSO##5<3;SoM71mSl#b+uUK1{ynpiLAx5q%QTP2 zeMLMc`PAs3;=9}~fxg;qtaGY?l9#G7#(uD~c`3wSD#KTnJ!iZ<_fdzk#7U1(P)NP6 zw(Qyj9mCKQ%S^8QwjY=M9n#qFwVP%53Lf{EyWqCZ@kHt|@JuuPe7lFmm2f!r@z;%Q zM@@!zQlEk(O3N3%yFXlx*Lwb=tMU0}z#64xzMp>Kd1*-a?AO^37reroPbKIXI$e@% zf55R8OdBm(e7jw%?wRFuY`jko8_kPHv!$Io)(rfYA`_MPRRY)E?BNny8t`53YQ@ov z=u}hD?ox_mxtKQo%c5>ho$i3}Qqw9fFV+)e*ZZ=i(6YF`hx%t^ev~}6QQxFG6-;fR zx&3=aJ3NKP2C~yS{bPoETcW74id=@;s+Pj8=%(Jx+vnY)A?I}!4y}G5V@5RdBGvEI zQo42ugtT7F57!X)kvB9^?yA6lP0C=%RAPQW&I-9dB31eMi88!1$Nkoi+Tr-r=xtH9 z&AUliPkf^yGkIdXOJ8S=`Gemper)BKCV3n)UoP>c_3$?2@M1jd0@(J>l z-o+RugNv6xSU@)SYa)YnkeqiOy}UCT>=~lFd;0s58Y7|KmX|S4=N+pjKV1bX-v_2= zIjgN(wp&>L{4MP}*MgxzmZxo;*5Qpe#Z}uT{3Y$?So5p)`>{g??JtuZ&yl5E2sJ`< z;sr-s{-t)M*TAeWS5;2-ne9k_?6BPM;?4Nd=1LY1m8{f6s6~pkenHta^8R_6Ll2Xs zH_>vA()V)*^w%`qjLwS*8oqO?5G-9jpWo^2L+~>His1XnKtU45;1Z@3WASU3X9bQ5 z7=COz2TA=d^YDmz!G{}gGbgn;s9CQsYFkfo?PLA&^^iQ{cZs)UR2jFKCbx7Hxhl?v z(53O*efG{^KVK0VBJ-bqC8d9j_lX|eYYc(Hhdo|1av$~l)D?UKbzHwhUmMI`;X`7m;(ktH(mkq|M$@(TY5Glq>?(Qsh&<$qGiB(W2Za>g zl6>-33WsWRjsgG3`AoxTV$PRH!d20JDZVmxy1*Rhv!};RZ0MB}%kJ$|GOo`G6`Tkb z=H2vzDTjEc;iT`shFXlzNxq|Xq7Rh~BT(>jNmfnWpIDt9e{|u7b2jabYqFvW1PY{b zPk&HJeG9DVio2$kR~8$bzD)4glHxXH?c6%ggU3_OsrMYs=xpN_OJXUM>pt{ObcW=S ztX70CrYMm*HI6=o2zo-NX*h+w+r)GO6fbUg6-ZyYJy!qL_#URF{=Vz}@4R24jN9k$ zy|^6{gt%Wwe=V*uo0%b8)m2#Cs?4W6=>v0NpsL3WH<=9H>oI3j@id=k+`dRZ`#QxL z{L`o4(R1WW9}S`JIvWf+7Ny&q3CunzX&>*(CSLeZ_Up_zg`X1iwf-#DJ$0@=-FQCH z3NphjUr#&_TRc)q3Tbvpqu%dndF<;!(rknTr@t*4~@$ z7bz7D^4_xgfKvr4BOv!7Hn#jltl1bahg$fZw_{{0x- zQV(+78-8@V6Wzr9ZIYwcU>vA0&hq?_XEfyfz!@(M@4o9R@6w?7QjO1D=NT#d&fkfe z>vJSn39(VLnvkqCeJ7U6tJOks6?Z$?n&)0RH56230r8SQWFS}8#?LpN%)PW(wR}Ti^^vxR*Pk7gp3_Ywr9XR=G0awGL;sK*$#l(#fcTN4o&sL^ zgxS}mBytDNDlg0Z1bL6+WpH6-XSa9 z_4|}i)?*$KN}O{{>{xbUXWMKoInHiu%9oaO@thKxc+=}e5$D11t%=vgd{fve-Dib1 z^FrL+!Y3tDZ*`!q*YT4VjIk5_^d8TBAn)z&NV}-Ea$Yg6n|PLhWjzPt?sU?1VeBkOIKT4s z`NfwORs~Xx!e=A{&$4rvYF#a8x1PGeG1a3LIZvB)hArUY)%1|++NFCPn;-4k;s}Eh zHxY?C4;!_OaQoLM7JRX_KG`3Y=8-9pQ>Lo!hAP{R%HDllG@+tV#9Uz;_=BGnhdrLb zq&s|-L6muRb{&nT5!Ya>Sr3>T#?5S&XV?2nhtg*j14k2+t-59p5JcvpxP9Sd78$M z-5mHxKzQ`dpyJGgDhor&%x)PA0T+jjGf@%esu#(^h_vj*S;a;4-InrOP){&T=p-k7P5W@qRw{p*aOSb<^&92L5Kauqd)z`a( zCy8weSH2N4N{38M$Uw-m#=ow7ELc)wp=-J*ViBc4z0q(VZ_~V5t4`&qtW;uN{v%s5 z!u=~>-Yqr>v#u63Z~ScD>JW8S&R)Hn)1C2g(ip$wz-_5HIw-!H`g4oP`y%Bn<|}ek zftia8q!OIMn|unUXdbDqPf>+#Mx)J|>HyGIJ`l z{s}_FU;HMtxM?4*_*udjW5b&*{_Sd)Wx5cj@@OG*|7hU(so*OEvO5mjGjlu-_!Kwy zBh$|ptS@L@qO>)+T<}!6qu)b#lh!rxBL?9P(_lcW_@kdSd>-KtO#o%a%;Dq{R=I;P zyh}}0+jk*G2dn<&6km>4O$GD3O%(Y9tqohcA53HX^X1$})83u$6d3cGBl?8DOLic} za<+i253HoBExqP$<@Eewlw;EZ|LIuCipe*2A8FRI+mv-w53HJLa+Fd&Pwv!{Z!` znR$hi+8#McUHS4&J7L9;yE|X`>K%rF1YI2`o?x5#EB$q$zfu&nO9^M%;;P$I8DqC! zy=~m?dlpM`>c(!l%3gRNN8bzH4;7fQ?)f>`%6G*07}zsHr`qMA%$9*f1lL*NjBsUE=UViJaMOIyu_gS1Nk2lPFd+0;duElEIx`AO83vN zV=#7QyKmk#e6mTfuWiWVKY(vR`ZgDj{CQL`H-`I7yuB^@e6>B~bT7HyJ(?Ed58bE5 z+gditon1ys6?bxRNufsZyh?3+%`2`ybjOVM3TJ|<6Z{eTs`sl7wIbMxuHO1|N_cj6 zH`8JL3BhvxR(b*djBd#ykEOo{lM2qy$(IaAH)iH&a>jQ zcdMC=|3b|@ulZh_upxrTE1zlxL@w-yErSLQU#g)-+{(_%}F%F?ZDrEbX9D?pMOkdKc z)CjPGF3x;QGOEq!;rRf4VxU0MPm;>Z;+aNRz4o%!oyN(|)*X+~z9SRNWx~66iG6Bw zH{x%;ZAEgaRv3o?Cj|iGm(Kd^lH&$Q&m=N?pu(WqEq`mw$lSf=j*t;Af zQ~fu%7Y%WPwchR-JsPi>MiONp=btfJe276PY|og_i)J-A7YNY@KurZ|gi9?6_+R`Z zaIZA;6pFYOR7F`?Uu?_b(%63%5h6+&9BlU5i7x83S~t-=XQ!dwgY|jdUkQ8pefMXK z-6)Mh-zOoC3R#U;OP7;2cpvPuCywW3F5MaRk8!YISIvGdv=Xnrh4`Px3cigyB!{vRsEir z5&4tK`zH%?sJVK-rm4BI!qN7m0!Pr}mvYqX5NkXqb-erN_nOT)Y$$iJ$~{F(V?!b_ zpIqY;Ay3fEbeZnytF$q>J-_L*zqzZNx%Zvli++U&k*s)HpCjU0M9&7*iyK5%cpXpQ zJ+bU4PVSq?Y^1_gPEz-0n;!HTif5Wg%{Plpo7BR^=(-=6XDSebvH0}s!$>yYS}MKW z<-9DU#GYiUSPTmmXZb#4M`3P9kS9Z3)*&jBCN)4YuoX!9(rwo0P9>(KgYaywY?xk2 z(Yt74clZ9B+gwj4?91&|EjGDdrB-$~KP|*AqqdFpd17+!>PoGGP{6$QCgXs1bjzED zXGv~c=4d2#`R%32`{y8pTu(p~RS4_+#eeiZ<0HP<>*>jWe>0+Cm zNJ)2?^8)g2qxPG$gA(;i6H0|cdAgc*)=fzaJz%G2<^qcDALz$x7_IE~9 zKG&Pt`YBVhmDH?NSFze~7sIi3wMtVFI$XJ70BPglk$iqrco`P1Yl?XTOC9V?Db!hRUAN=@83*IFpX~ z3-7txip=A3sVM8hRBiFMIPj;)rQ}o$#ZrrDue-LFJ+@^LA!hBw-lq)Kt zdLvgZodEBG{E_P28$*!mMz^@$?qNlX$XLGD0;D4`jYs>GZ zV2pn0^mU-KV*SjrnLXEO;MlHOqNH>2l*y(JZ=d?$z0H}QgkF=1OZN|@u-5DB2MYEj z{GS;O>zY-@e@5irQX>E1E76iOr;>PXD7y)KsiZceRoJEf+{|w>s6nmz3lG+t0@4?Z zJ{5AUv?QDNU;KnLoa{Kx)~T*k?o3oB2#+Lj>bu@`cqGJ>Bi-6`hW*!D7iOY&3e-ou zuilbI%H#^Om|ix;Z7CIEyem)RBUDqWn9!zZ9Mo=!5WMiEEj_iH$SvUKHf7+3XNkP; z%uc-d{qyH!)gFkq_fp zm(!GEuLt?PdDhr-w)4UHQUY78C#DNqi);3UsZZW3a*fJHkqmwDP;{MGyv(?1F=s*+ z@YqRNUq%a&d}nKX(EUZrU~(~5!0l)kXW6G8)Z;uXC^V(UJ#1;X#-RanA-;sX5vih zpvPW5I+JEM=p_XnV<`ecIQBs}#A zdR9N;vt>WYB0iE0nRec^y*kt(?0pn+k5iG+DyJagwn3EXi)P$+7vg#Y3BDdEnT_r9 z*`E=#zlXec8*{|LTp~L?luuDxIinsseAhXkk@Go1EU|Lk;`i0MaZ4rPhV#!a<^LcI zQ)ypdzbB_wcF4_K!oKxp0-}|jpmR1B*B=Vt=G$dHf5QFFoZ; ziC;mi92tEsotbaO=C4bOihhb_vOIcOL2Nfkg}z>{G$5?!ESG%7>&zE$QJluW+H&d( z=G-0^!g9%lD#4=cQJ;jY3@$@ugV7j6@LN}Y<(s_E&&L<%T}r(eIgkYnKA>g0V*Gog z6n~%LB9F#4f;p|*?W44K&WpTh1IpcXU{DU8L-Vpo*b+ zcS72amrZ)C-)aliyl|C|uT!pUH7&pL7~jiGW}DpmNtvVzhrfmL>@8)N#_S1#$B9^E zMvjjg4qL0YB8PhC)uX#H2_Oe=i8aa+8Eb|ggh!um?2&{%787Nw0bf2J2`$x5oSG(Q@|vBP=f-0ES;a4xrqXdr`BT;ARJNOof5fHt3fN^*NxhDsGX zMf}!7c8844N9P`OD&UtW%jd*n_s~5+L`@i5DE&TXJZggX1Ejs~9yHYY>E;ITd z+NpHEli25iFAIse8RC7g3XOB$WQT>2cuDRqqC<9z8ka9a>{h|iDmg(LlauOvbWQwu zzc-&!k}>GjuQbxp6}VU-3!^aOFC3*nF-u zW-+1r+T=x1NQ+R{+^IK|P?A{egwFD(?k6`cg}$&gTKMuoMk37ka);5>-E)Ynyq21T z*mB#_?$4)wlZPwnre!`WWbpO-PM?@$j&mhBaTrlZ;*(m@SmuN^zPqjsm1?ep89k$! zu+~v+Oth(|ZtHv1m|w!E$C;hYPFJCgL6($sDjYLmmEmTORlY6QNYv=%_ii0I`sbO=&d2hrdG)zX7g>d z3N4kNRq*vwRSn)K~XQ z!Z1}tN1s&UYTtw8%ykTSUudSX4vsI{@m`rDWn>T-*dU5M6S+`zo5(b@A+>}w{KE2? z?Vw+|^en9rFKvsM`T0<6d^W%DxLt~~?Pb&(KDixoqrFRq&&mPskIo*8J?Kx)s zon*$GsmHMS&E)dWC&e5(!Bd1mxjVNtih1!jf_IW~>bf0?Py1yI7k392;FQk6#>lw9T z65%{!e9KbrUUKC{9@+NfE!@c$zsA9M&i&;Z!Q0&;WGL}>?iE1LV+0SSwQpv1W()eBX zgLU)c?w%ndrB@L(i&K#El9?*E;+Uxry-{ME`r6JX@GAj*Z^Mg*ZXa9)3-8h$xx{PL zE3$fa>>26X^3?Et;wQ9v#x)Tyv!&>Qp@4!stj`?a{?{3ORG5Ur1T4UrvW#;beJ*C$ff@dK9%M|@QpXuHc z{I+X6Xd+tjEC^pPtvWyH?sVr3yO|!LK95=OfIUGmMRiAKE}7{*Rpi5WAOhjoZ9;o7uv*ylDc;vHQYc_G==PJc6b zP<8vs#&Ay9W8=VjR$g;i2!Hhjad_#cVOeo%&NddEFbndh6ITt-l(VNtkvJ(V@rSLI zzKV`JiV~w!PLC30%DQz_VMF-h0r~utqbL{09BUwDox4}#h1f3k=yNe2jKMj=_+`fS z=}Tkc`pt2LF^gV%BKl0%!>0BE(+IRLNLvzs|FKvhYQ)<*DMobuvNNPWEB-+E3G`lG zJ7;>3N;|1H9s5idjaA*HmsJ`8CUaOMeowj!JUf#yU(F9#T%Wb!us4=;c<$PDAao-u z@gsZx>PH*NrRZAeEAaWXB#a)%nEnqN(1(?wQo#c&tE zV7PQO;{^SZ^>5l z1H5rcmo%w>>C{r^2`)8XKCGeXFArF(4XIK`?PlXCD8p;bM4Pu?wvQye&R*&Miu-u= zT*$s*TV77NL?6G>XnQ+^F-fM{g}eYUaKfh2-dNN7TAlsx*$M zM{jn#-C*Y8cez#XWQ=_m8J5^0@WT9_L_!&B7hfV>(oWUX=MYzd)7@WF#>-sl{6()( z_+3gq`Wc@-p2(g0yI|mMJAI(!~7!L+tz~y)2`VY0;jV4Dw$e7+v*IKS{db;^z?9Q6e;rfqC zr#i0M+lz|nm>CmFX%2fA;{C)0sNW*$X@}yvU)-SL%VMUmW&FzUL;9WKdj}c|m1>FE z0ABS^Ee$&(s-i=j`wvN$3M2(uBrUu`bawd?#V#A(i8H$G*vodO5h{41Nu22Ic7~oB zcRs1M=`>;SEgRa6u4ea}%PniC5bUH4fqXTYx`gEUVbnufDW&3TiFR*KIi}5A?^sKT zsGlizSdzc-N{hJG^<2f&y8RdaZ`5&Lq-&{Z-Rdj*zD-ORhr1}=WG&ru4&@i!tv~CK zTu<%D9PyqvL{coMS+p2BrCGqfFW@__^fl+4mCe1HkT1}hSh(by@M{-cu=qFvRk#Mq zgzX(!tE9WdCYW&o7O}WaXu|;jUKK;%AQCdX64boA#mb1=STfz>*MvYV2@yFFpE$oTZ*Rz??x1aWc^ zOAB$T8!sLT7-F}4Eb4!KP9-8C?EZ&XZMp5w51|;&UozAZ?l)eY(aUCu`N%`~Barx0 zQEI)sD<6XWtQ(ELp3ir!Hm{x5?^&nCRCg}r)U5^y%+hG2S;(EX5`jqS-8QETvS(+; zKgkY#;MzKD)_Jz>bz!M9Uq~dKSt-H@E3s8-qp-?=aW?d;*F$-cUVgoR?`bM`N~v@t z1!Fm$kzA89UULqyQTE~}yY(tsYRjem=ChYX=|(+Obx-lB3L6!o%Gs%KGc~~D)618c z^2~JQ-!CJ1Qs4KF3%F50X{5FRN#Te`Js3fajja0l`c$LgJX5x7_f*LVv-;1SNy~8W zS+jJk;;Zu00RP;h+8hga6%Qid6}xG;ozG$-ZSc17;WM*B8@h!dc_qOo{znpTyK`{u z?+)n1Pw8IPQj&h5;QT^WbmGZY&0JsP{6g*f_H8wYNsm6B`P0`KD(JgrB5vqoru%(N z-ovTO=FBhB#GXsaiPd>+#1j0xme;;JY}&n0v=vm%AKU6*E}p~ z&JQGVmfK0IB$9hpTmAu3$|}Xl?RpVhO^p++QYVu;MDiWmyN~U2yXEhtJEwl03oymy z*exO1=EB=0e(+THf?!IL>dVDP)z7lsTKlB_C-!+I7{DD$5vg1=g5}zL2}>S zL_^hVY{cs)H)h7XzXuFEQinv+$Bml5yvjugmy|~@P3jRq_2-49w5YpZAd;4ye`d1tVAP5sy2DQ(H&4L?yQpv_g4-hV#NW#wMHc#C)3{bNc)8N?$(SH+ZpXU@~k zlM_MgdTNX$n6&jvDt1YtS=#H;4&sATMysGL@`zpk zX70**&l)4#wxdaq?s;QHg@K?|hCmn_&>{D5#RuR-@-fg7=2l zRI{}s4{k&0IR8!48J0%PhGCHS&M1uDI2kBRpw20pcNma zF7}FPVtI&9EkN$`${%!sbX5g3Zn26CkM|Z+Ys@Xw%z~b(j#XT8@1fw?@Yjk7g8Ky&59g`dlAO-7^oB|j(c z#o!)>AbyuUx>kgp3SOHR1tLOXp;_ycS%~udTWXZ|B0w(7w@|bDI!8YE<+v}xHA%j{wiEJE-{ZWmL&#Z<;yn$jkoGleb&9BO$MrATf8#UwLI-;r|YnGRbQob(?u zG(I5ncr?iXavZhFg}><@zQUPbWAPfAYaZ!ITfIzI#Z>fmb2P3d(U%`ehz`#0Dnr3CO{So!Az@~o@4yxT2ShUBR=J;2 zxlEZKVR}Hn>baUk!azgdw($?e#`=9k(4{CVi>U7*>Ti^R;1$lGv#;Z8RVwuU2S@4 zq>th4S}NdJX}|qDry_e5R*1ZobrObvsMqVmWD1*IxvcPSxm@wDjO#x0KOEet-{;09 z*R!{&G%<7w{4vzRFse2_6Ic^J?ZJ#ImX+cB zVfny{AsI;9#dL)vO5sG7k?_Oj``^u(1ZH-M8!cDN!E8?!Td)<@d8{Z1QLU_K$;r>N ziHQMDxse;}v0=w~A=Nw?Dl>WE4#otjvmz@`mw#Yl_vs&j!f!2!6G1yar}7H@m{;B# z5ksk5*}P3olD7bg=C1Fl)m)9_cUYDe7HdaZq9@7Gs;vu#J&3k1a}>{UMzq{-icW<+ zTn`tf_>J0$NBGS1Pf&Y;W2XEm-tWyBoQG<>IOzESnJp^;PSKM08(h3n<+~Y2`Ug^X za?8bEobgOhefY~4S?mnH^b?^WsPUt7F7rVvV=<8~)olajlLY~n+d4GD*LF)(>qu43 zgve=MUOLqBA<<{Akx~&|Z*#R0F*#C)X?%B3u@7AFt`ly`hF2Ve*4WQXygSpnB?=`2 z4Xv%%I1+MK91C<8d2+H6JrK+%sB!xhCpoPb{DzV~S}A7pp`@2rz8V!roMlv#g!F#% z^Q2Dgk&Fk-vLHT&LQWb)J^N1gScI_%S6wwNQef$MtyoM7Ba1h%)*}er*Rf5(?ZSnK ziSokv50WoOnWx1U9~YC-qQDg;1Pe`7_a!c3uCe|(IkjH15&z_Rtkz~r$ISFnsBA?$$-9jk9M$P7{1^nH1o9yWE^1)EzCE3H;7p(rS9+4! zT03dd-ITT_9p4RHD}C{Km^3j~kL%ZOmR>H!L{D=gQdLg9{qZ-d2`din?T;D#DOH>> z#|chKDbwTF`pZzoi798pUc+xS)j3Q3bH=s!YGk2*S_DhlV5L(lL~kKxhx8y8ZDv z41)eci9d1EM)lStNwb{?PB9LYzcl&p0RJa0wsR+H;uqd>*18RWL&9w*LE^lK1!;$x zmjxotzaYZC@Mo$AR=(ABvkp=@S?<{i1l0~xkd04B=QU5%fk>iYZKc4Q_JXg5d`B8^ z-ko2E*fr`9tZynsOOwWgBRtQkxPVLWJ#FPe;`uDOZ~QV4syuts2Wo$W1};~w9|3vWh?qKTC% zrS_%Z_KDHA@Z4CtlZeHm=@3DQQ5jfiqhdH>`d|Ihg{%DOLlJ6u@`F^h*k#?ukm%9j z?e`qQ#E0rve6*-oO){(3Kbb|-VphD|srXp~p@kVIz4>Ht7c>a(ieK#g%g|B{LVNbFXx1+zjg359?Ijq=u?6|`-@Kw zv3W3pd`|evvT^+fWNC-ZN_>zXx9Vd=u3{m^#Q&rrtZ<3ncjP@ATuh9r5G%kdoI zjT_+{NOM)7CQ|SBM*Lk2^CEk<;Vshy)gwfa*;XQ+>64fE^5WGw4mIl^!uQlq@s#SN zY^mEK>`0R`^RG+u^@w;7FfpY)&N&bzq;b6Z3EP`IuID*=Z?(&=WeECLqF5n(oG)hf zF+^X2e#1pDCZctKb*%)ifS6~1CK%L`tVcyyk><#Vz-IAu#*Gw+pJ?t4<%0QI_5oe4 zYhWj%z1w5f5CVB!z~Yv$i0%lvMd#GcdB1q4k{9hqbLBRsMMs?nOu-25w4X}CLYGxx zR6a7Dr+zx(SNq*Z#R5GF*!lDSEci)+(wuE?9|=6U_d3yTf-JDt_Shz`L1&rAq?(-R z2sO@yjAu@EnPRu)bSTMKTBGeO?u2T_GM7YxoMw-qaYIT;wGq00*Jl@J`|%S6vz`=s zLB2j(zphyfEGfbOqUM`jQaLBHfS2#BiI`d35Oh8EHnw>mK{n8+?GA;FazjCxrW!Hd z3Cn3ai5>N$xZxFL4NN&tacmQ~*?n=AtvE~o%ox^L# z0kB(rTnr}slk6oz;0Pxyw;^iT-ay)|_~OlVmfgwK^-U3v#VWZ^>R>+RSCCA%8*9>> zN~{ykvZ>|kt%p@m#WkwcVEh>bldW^?*`3ciM(TIw7{=5DWH9~0mxyzIsMh8vSD)TC zJXJo!RiDlyfEp_wJy~T6bP;s;-S?fW&z(Uap zo}@Mx3^C7A)U&vZ!j>BL@J=U^L=IL8J2ejpT})9c3-iM3M{uoq7P5zg?4Q0MbW-R?S3|$C*=b;iS1Tu=UZBm5Ve{Mr9FsXK zd9PfFyEj+X$qN*de3gmdX%2!p19I=cxW%L-va*7O1J4}4$nz>67{3tKLQJC~hcGH_ z+ITW3m2Z1^#fJ zm-~*PD-tdekDr$N?^a?P8<#^aodG+*lMBPW15s44J7+)sj_-?63 z+Z&2D>PZyb|CI3H?`=Gu=MH&zK*C#LTfE@C+_Kmx6%}8q<9;aed+dI)8(M{DUx`OD zc8G$YeM+ZC+GD77n0wZhDOmfS;+zD{fZn8MrA-^0i0V6D?e0Sardm7-M5Is~J|I7~ z@gQsWXbLWd$(M$S@5oSoP_M$IzOvPszmn_%Io zA@*+M^=TXjWGyJ^ia+@~%<9J8ug#VrK~!Z54a||z)Edap6Hm>QOnIjXV6OEF(2H`W zC2%PGYA?oo;d7k}V?3y1-#avZ8=N`%N^!dy{SrmjnTjgWvL44}f#ms?r-0U5U|%_g6gWmw=S&`WPtwE(fEGdLPFt&I0d?@H zRDE8YKAD*HCcI#Dh5EfWG(oWkF0Q6#W&aqBOpkK48jcO5A_AU(WfPlmqi_11IjTz% zwpMt59;nXCf$J+N|Hw+yd=ls9(=9(2zK(@^)r6I_8o8YMvqHx&(E+Y*={1t@VY(Ln z^F_XW2f>ts=if^KEyDr0kHS2U_4r#}3{?p_*=rk3{5BxX0Pk5p@7jA?Z5;8eb0(^L zsk*1Ug%b{i52QMf7g?VMx2Z`-m$I(9_|VziG5qJCK`JIhkv+M>fBm4=mqzqSw=1`v zwP@?sGp#Xqh>)~gH9s}<(Uc3-v$uDP*+g?(0`kQwVfz~(iyC1X|A0N%upp{lMQ7rL zshJ>^Vi8n5OJ>0FPU1x&;!0VNq#O;uW986kD1 zPgQ}KwSk!v3G07P5fZX03)HQsbDQsXb zVPaus{&~pBjsW`4_xxv!p6Ne>lFkO!7Dj@$X4WPopVKQjo7kv+PV_mV{@;s$|5#!^ zCowm0{EsZ18YBo328n<~L1G|D&`*#INERdyQUoc1ltC&WRgeM55M%^0va`0c1sQ`( zK&Bwm&yNMj3}g z=uc@gJJbJ=HK2bwBL26mfrE+t|8_NSe#%Tg%Vjh`BeZg&6%PAPi4td)M8CZ$5>ong z(jSa0jQvPR!fw)V)B%M-WQ0;2VTsP6VXV|MI@fuFH`x#EA6*L%Rc2L(9`_rI8xI=~ zJ~|w*5!K*1yk89v6$HB#yajv(Y5ek&18C&oNT{jDK-APhlRXA-!d$}d_q$GCg=5bd zp|p>IF0^n7I5?LRC5Sv*e@!?}f%QIIFiaS*zlDA~iU9#&q=JIOUH))|m;&&7@Q{#= zkKo5}oc)A3!sy$_fkDeWxweZ>FF4&MgUDb~QsFo6vamyK0?LR<0u8 zkhzZD{6r#$Him2Lh4{G64VOz+0}Hk;`)J1J#zQ`awLfuz;`Gi|&|SmayjqC_OG~D$ zO=6$O^Ir3ws4o$=e%AQ{_sXSB#o3E^{?H5^+|x6qXXN)o8#;1}kpnd>eTI0f3h{$D z=LZxt8WtudCQbsBz#15u9S^L(9^zNv`HzqBAI1cEK#oD%{ey*qd-r_5 zG4mK@WP~_By+M6_Ku0|Kdi?L}(9J9E6TcudbPz{(jGXe*OdvA9zN4rBXvi5d|avuzYaMdAD7@L52PE4i|)fd7-%yrgb0$ru~7oE+nr!b$$>1 z3KYLwB!2KGf0SPX6we>7g*)4)uRIfXI9nfIU|YH~ecnlI(@y+bRs6AcR1q&fg3|@w zy?0KLbQ$~VB{(_N^W9$Wj+@&c<6%_o4FIA)U z!yfFgA)y|(;pS`*wp{;!fnoahf4Jmh2!VmW=~Ztg7m^EfpYvm1CIb!-u^-HKbyL94 zToM7WcfDdb0k9{%Vrqfzx8|oB-!tCWA+7m$)44N7V703T4z3^HFqEGsxYi5p{E@Hy zsZud}Bf`!`!Zg!poIELG(hhrh$3ZYMVN53u_ZiEBENAV(-`Q6*?c{Nr;O6(HsxX_Z zvQfP5Y|%&39n0JFZ-DYO4ZZw)n?vhbMJLi7$vXsf@vUb4HA*;>5r1lRj>~b4mpshn zW@xgVuiR731q&bw%ha6JszIA2`SYD<*UJ*q3|*12C(bH^O|maMYR9O*L$2vihS|ZJ zSvL8HcVFduBrN~dpwhNCe}ib=auWLKIiD|tiM zq%0L5=nQ7ol$jrHiuGF)*{EwAm%@2K1>MbhH=rocQEK2u{j8nUI*>nlIk1jhml94^ zqR?e@MQ-$sx~N`kb&%P|*J6+Rg_LmODr9qlAX?Op{mYK~x1P;%@bI{XWK9k~dB1w5D~t9G zTn;!+hOpS~EMd_c&z9RW8-vkO5YqMcaXo7n6Pl&?VE{SNGB1>@cQZl_GeE#jG5?11 z-*Lfd41%l+Zc#|Nc*H<9nm42xwO`IlOgUD}sR(cVwP(JlqAoL%fs*11v}qDt26=~V z%mMLNE^DR35{wLn9Q{ODw!-=2mmbY;_|b*i`SkNBXL;U9LVpMbl1a794wf8tVi(o= z5-e|LD}WtS0Q#dm{fEPEC*x(qVUY|yrkqjtF+(*kpDfanec_Hv9m7g^j}}NXE5(Os zvMP!7)>*@V1$W|7f4S`$<&3kP^&VM#NmQ}L$MY}i`y2gIHmG};&Bc+S!V0g(N9r{* zQ`WXdq30r%DuQ4#IzL!cydf#8!l_;6fpDP2v%?dFAc z?O>r8Ip+*5nxjL+odluqxp6-I%6N!vVNNr8SVlOclR`nJcu$;;r2$C{2jH<3ai44J zj|DpA*$`7CY#N6I+*cwltX6}lxEcen8yDqedXe_B(#m*-$4R+~?I0WuJCSS$%@Thn zF4qIuAn$>SF4+ho}@4JGbD>JEpMUqCncsuVh}W&R94+BZ8YoId|tJ1~%`ihpy^I zPAmty8&}a+>WM_;GYCFy$pQwBZu@Zj-mz?=t6JR5l5n4G`NvJ zR1DXY){wO4tFP)>I4CtgzsUi0bqK%LTkTWqP55nMf|PLl`%tYaZLAL|N02=@ZGjy% z`DaZT^Yve@UZ~R|8FRX}{vLQQ`t0hKP^RKsNeAv#?qw8>mMkRUbc;VZ6Fp@bH1CQZ z4C^Xg811i0bWoNXlaY0|4OzJmm1i_nAG}1tsz);N6PPtB)9#e7_g0iM*|g&dO~v5# z;6l(DVz|fI7r3fsbu@)6G&aQj_W@Okjw7*pEPuCQY>1W%3B{69(;Ef#&>JK<5rZyF zZYx=5$XfRnDWNV~6RkiOXc1<&%tUXjLP_yMwU11 za^I;#|7^ikRc0?;E8yD5bqDKp%!|$NC_ILA+?Zm>n#0FA9X}}75+qS?X!QlcI&pw| zOzR#j1I19+_nO>wh8b}`8ypvsywyDXNzY;MeDJYtRIck4eE#Tw>pNt9P~s1I31+{X zu78^F#$I^FJ`cWy6uT98h)YC>`z_BTbTJj(ve%xmn$xE@A#FnfV72$;+d1peE+wDMfz8(g@g77B{$7S zAgO}QrQbSFCPp6dWG|;swRa+2WBCQ11Yi2{tk()}T5u3i8MeBPMp(EQMMKq?r((J| zFH!YD@mlVTI@?gQVJS)wM`4o1beit9)S4GP3fVDC1MuPfM3L5wK%p;$&AiL9hCO#5 zR}A)0t6Zon*B9fZYKlhRD^i9_w;Gfi=$*qdYM&)j92k5fC_!}0x7c1Ma|!xk;PlrJ z%WBqLs&cr}YUN{oG5OJ^NuzLm$)a0kh@AuW_dz6#vUu2@w8zjjnV+;*{t9(nKn>WWH)aAZD-gZK zw$hCV^>50L%{-REEZbaTn`h*DiDNE5m>aUf8Q2c)6u?v58(%oUPFfH(K$s`j9B2$z zlfPgPN&H-&ASqp`)NzX){*Cj)*R%DWzFw$WjRPHXL!7xVt$#RFax<9UTHK?V)Ae0h zosDD@Ez32K#fO0dd}Ct4iXtM8F`4CWT3?C+K;=&AuDf43FD*UDSSK{B^W(Q(OlRF^ zoa);cD(nSw;a~f_-{%sgYpM4dEln?rb&sQv@wuuf!L?kWe?E8ZBh9u;ht@BjD11JI z+2Mf>)rn1z)zIW(_rQ*&gF-MR5TjuJa?Ni#%%8I}-5W;|B`$-z%y*JAWL@(d9?9hL z+?UyNn&KR*?n1hyd)ov*k8Gwvfy}S|m;-ac9L^5{9vX+xL6CYtrMtaHJXtms$%X>u zY|Pf`)FE87hF(w!V=3(%GjC8$!DiSnqVLPrlx$uNnMRror|412P?8(SCFada#4uL* zBTg89{olAlz(SPK3yiD*`!>=WYP1LzlI8AYMhjK>Xh*h7-jX9bjADeA;xU@q8*uKw z!WZ9=Ycd>((fB9x9W)aoH@@8gvKo!{#Ae)Swx=1u(Ml=qCGTv|YpkmivKKcVqRjdV z|Mejcaq4m{G3d{!Z-8Tc{*d+fhd#R=G$6L=3Tem{8Rt>o zyCCiBAv2Y-b{Ho|XqBM`ioI3&U1gb#d@1oTmp{}y;A&wK{{}@fJMx1%h59o2T$x#y z8&a@ZU*y@xO0_+cU%b&gSS-&~R1Y~;H3_Qm-~z= zZ=8DKQS)^~NTA#Ge>mEW7hA=CVSqsX^2S`Kzr1KXz4`d%TV-WyEyR%BNsM z-faPAu%`z9f@cBI)ccWaR(>9U^j_IX9pI_lu0$J0g^5Vqi@n4t4HHA#cWulj2Ighi59sa*&9j}$ zGD4|hWyQ)t+bW5ujmQs2?qO@a33`|l^i~t1l{0?ify}-rE}RnqJ)?{v{@3C%3f*-DS1MMst@}HM6~}pT}?kB1h(xz!c`i^#v+l ze6|af(^eT5D)MbjHRhV)t4mB|TBS~uM!I9+0IhZ@0&qJ%b?cPSEHF##q<~y7|C|@YaQw5no-C%|8IDvsn>}(tpV!rc}vHw%KqB*{_&#^+&4J9 zJjqqI>JELink`!SKSeo?Ob8f%4+;sc6tY}IaArf)C71Bl`QO}UJL30{8LI4%#>i$X z*wnr9Rsz#}t>^Y*S_|j~bk=#PHoxB-8}5s@X}G_u?ROvQcUYdee{585=A~qF#b`u6 z-|#kjdS{0eg+jH_GT3j_L~Gicl;Y(f3g&fwHwvE4sy`m=$HE|C$`x9@q zNrAW8k_ZUDz8-kkV4zy{RbKq-))YGM;(4eev1_b4$8s-yBF+iDS^Ei(Jzt9EJHmkbDACt z|84J6X;ikm7r^)RCLnN{eu=o9UXKKN^CuGk z+Lt`=>?G&oqN=e@y}|CYV&P~GO=4G`X2lGzOX6woH*9ozhZSqgxEK%i41b+ChFw^A zi>|ErYG^xrmN{>|G2xQQU8CKK5tr&wqZt^ihjtg$#>yXu+3Lp2vGOD zuyqVZUwU}g+c;T`%TjI~`ukevM9BjwU37R3p&RVG5@kBu{}>A8(!|_(T2}C79GACW zi6@#w&OoG={!WLslVWs#@(mkQtDNipF}$}3B{)uI?0ELgSMv>H@4U33HpqGwii z^9gTfaML!NzIu}-a~90DI=I(y8ZeXJPFO}C(4l87sr@#5K>(Ybz{UUG(s}RSq>jH< zJ29ery}Ft?MH5zLyQTMFOGD10a~B}vhG9h=y^H@d336(~#8zCSQuyakdL>6gR@Pnk z(BJAhgRtJq*u(ELD!-h2zgVaNrm6g0bXHFC^hX9-9>~+)@DXRXqkl@Yv8j>{$stL8 zy^D3_OytTxR?Cj_^W*aK*gG;5K$I&$IbBb{lAk`h{+XMDgc}G3nN~pPG-X}h>D}zZ z&R3CS5Ou6N%B4kQw=vVI)6ySw89g=h#dFK07bVa5dx1^;%K>KtL^MtTUSgV8uDyh( zMe0r49R_eP*B;xY-IIV~%ng}K^TfXf8DDoSj$Qxu|9mlp%({k!XPuXHnqhJ@GL(KW=Y=9Jm7X#nj4I-Rnk$vDX}7YWt8 z6grXCo{4a|UnL3%+zffLc!i^hMX~7U2G^w z{_3C8P?D-$#e33Ii_j;^AS{Ho>^yQ4n6_==#5Dde_e7{|0yOedUVe(zes4>fa&|d``{ib|y zuk4pK3y~w#b@^Sdj1N^tZ;7|iRfN)kb`8Jp)J-u+lU=$6)U@98&or%ldCE1BWPLtb zcPy|IBJ_qsWD)QELK zGYa}YTSuhCY4>Q2wA^57&O~5n$+%H@+eqWZ@l3F~cN!fmVN$chCanfij$FBH54SCxiDB#a-nQND z(WFFxJy~Q-*#KN~&_LqxiegruUmMUS*DWM7GeM zlPwJ&RF=im)c$+ywmYNOKJ3%@Twu}VE&6_%peuFrH*PCK3r1Y4y|i$1{$DC)2hSA!8|ITgUqT+$4b9!4x;{Xo;#+(Xv;o_ zip-u^`*-#?uZ}yzAhH6p{1D)r`o()uyoJPXhfhPD&t`+u*&6o9z!WT8b}s*gPwk+r zosUgJ*J3T_M~!z#w+FQ!jTtXWM(mQQ*!RWs%=oU6N*Q(kJaTm?O~V@nGf@EHXA<*? zYEh{Eh)7O#!0q2_i&t&D(E}rvq!cno+z_190o1u#rtjDGr4LGyG|AE(gxd#(=6~J; z$-Ze}VS@QO?pdzo<5F^|naTTRrFhQvrMO+#Y3^0~U$f6XbVhdRSB&%wdy|;P(xFub z6%ErUZXB6b<=pP`i2W{^ z?6Y`u%v~~|UkKmnEz}7>;n`TZkM=?p5*;Mb5|dm$7#uzxX+Rk_(tlaT3};Q{ioWI3 z>tpSUHjfJ9R6mk7CE5H^&Qib3<-@;qDI1Y@wM#C2N)~Fbihuq-OV0DHA!-k9mp-Pt zY&;ZlPUX~1uvF5)g!$=8V9v|*yWDonPUjxrTbecR9dE%; zL)3woz@&;iP?OSsv1MekTSQujQScR!F%L`S>gP5S*BS`NVgBy6xl(cY)wDAc7xO1o zMAAL}Y52SZc}NNv9zOnltu_Av4yM!oe-!Qi7kKeMbA$h1zzaEL1vw?b|8f`1|1aDH z%YV3w|Ab!uQy^hu1pfbn7mQs03%vM$auD|r zZ!Q>{91fWL=VCH8YauTwnwwrl2kwj~^wf05S};*H$fc_nP-M8mxH# z8{fwhyngdO7}(!_kw3nnkbBxa_F?pJ2vbm`1U=OcJSzd(V9$(Na9_7yVlYqRqv3)w zI6*bd%^avh^MSB1Zm|bj5P-WdS~S>?TG+4W&`pr9mbkglj?f>=c&I3d-QDOrSFlr| z%ir1s?HRW=wjk=Dg@2q2^X9qgb8h*%`E{1V2&^I_z4dAAqQWwC=Y&FnU4wmOoKGI< z{UVv#>><(8O0B?$J4W>920JBX(D!Sqhe7Ry?STdpJoDuW(B{>DxB^H(X#LQ}P8XML z&S(M}vN&L^7nhUoyw=-j96_)#u>JdLG3{M5Ys3v0bF$zE#|R;x5*gq55;*@rn~TZy zl!wVtmyq7}y!Q`{W#L@c`>vJR8|PiNAfdG%J>}uR^IC@edp(yQIv6P*lP|h~0oW2D z*nOSL-rH|~{~G*94gl(%dGi77=mN$Ga%r;}93^Ne@S@B9^@o72J{ZI~Jj(3{&*LEi zEF9F5pfx%eek~+a_>J1V7t7Ln%-!2tA1NQ0Q>WJxIJkEg-^ZJYM-3y-*SWtBpodMh zv5Nd^lS=)OC$rIy;OlEfVn2S4E)u^Cy`QP5V3?Q~P+?)0kO0JI^Z*v>sUfxtx1a9dg6Ah)C-^rrqya*Ad_M^xdk&l#b^@YFt!>;24<*94{76$k8(!c?s*X%8VgKyirZN_I zD={orY2YY;3SjKyAzgv5{u4lJiUz0;P}{a^G@Seedbk-;hiVp~yOH;HUvS!p8MO{y zaQb(3le^F#eSP0siZJG|O&_eL9)p9xNjM4iBAkHn2U=1;{!3r7vu?hwV5F^m|6a5Q zQoomb2=IGG&WRcx=#7ftMHrNN=r+GI^lP+Gy+;mo;1%aFBJ3S`>6ISB9dyn=bYb-& zUjNBb$1ZIS^Uqwtzx!wQgaJ5Im;6VdfyoC{(;GL+{tvm3$B0)Jgzfug?x6RG_Yx-m z4-=pQ>QU}-QW5GM`a^ZJYv)}zlF@JR?0r4t{YAu&3<&t3QMi5Y14%!VX?Eb55j2%gYn zGqZh2X&$}BYm!HPefg6@Eq`Fw)SKhX^{-jor2Ar8^zTm-G06x|scVbKc|BiRrL!KO z@nf{UC>}n9+^d-f3-^X4P(G-^j3EOpm^~W>%$?VILh0LwAfJ&O(Lf4cKz1Nwj1j-d{@t%dN>hmEenK@TrhIa`KsSj7IICL0n4x4L$59ZF0d} z{urUmd8LXWMPEWKR$M^L?^FJ$4{jen_EIZsmByx%EJv-*qq7ZJFMFgE*N9 zWw!3d|s@&6*+bqzst6bN;-R5MG|Lq*lyL%&$UdS$| z=y$|5N=2#tfjy>VejvvDWt0t|2n~_7LFN}7)5>tH_#rh)SBk#aKk1~He(6ee1AjeO zLxmSf#x|R2EixMNJJ2iut;F;ie{vbrL{edL-?C5arS0yT9mA46E@y_xalZo%9AqBf^ij&uu3oo3=5eRz#nnCsiaivt~ zizNS=H5De$BHrlTPBzc|ca7~o?2Ob3-XbruD&K0iqIhK1S4KVXb1eSduxQE!bl)f9 zE!bSe>CoVeO15^G88KcR91I*~DHfGn&Bs1n``j3}P^IPAOWyCc~(sYVsO!}$&({-vb$Vujp-TLyz!~Q z9sPFd&MpVyb=3Nw(Wy@d2K19YCDQiv2~x!;;QTtoGsahE7d1sm%U0bRMShGXujl-@0CvT@lJ0?! zT+G)tXZh=A+Qc7{GEYI^{2ha{VDiSHJe8#->cYpmcJJ7uWj{ks_lZrZI@R_T@2yR*E$emc5_1O73vZmV}ZI6Gi{=>4;^M9CV}k6iujQATK7znAyGJ2GG$6 zw`prxKp3cZM%Q4f^Nc`}{{T(vD$*fEZh%Ga#mxn6Wqlyn3?A42(puGFDeKgO`9vHO zYtGDFw+0Oal8YeVV}c8n#tkr2KObJGmq0V?M$`LnEG{i|Rr2z9_8#QeSM?d(mNAt| zWYfY9nVCvj*(Y(9b<4pd$Hu>r)kD2$&_;d{P_gHhZ0;@+A<$g9W%c2ce65{f_$TmXnNn+3 z+3X0j+~{E`uQ7!{ai`DoVaaRQT5Tn-uHEjDNenlbAy$`GH_|{@2vg0~_9@MM=I!(@LN47b_gxCo|-M~1Ivp(H#30`*u3OHg>AlB1aPDV2ZFv+ehciJ_D& znQS@YZpY=51K)TId0PLT5i6&oS-FBv(J_PT5)xra83VjAo||N?^&C~z`I}^P9>|Qw z_6bBymYg5cgQQM`L}+?;+Sz6TCNYyQ*Q{dDc~0p^+Yc&;SX)@P%c$u;wuT<)s&JEm zUy0#rHB}VsMJjHqc;xN(d)PEb!cC^04F>lGfhedu+SEV(8bAbhrZt9$NBo@? z$IgXt4!4EB{n1oHTX&ySU%@rmZn{vuV>@nZnPvZbPfsf(C64gwu`@Um5Ajyl0P$&% zyxq)Hge)m{Bb&XWsq$w%gRvi2*Na{kP|Xoh8i)b&Do`HIICFSij-`9_e^K_%QIb8` z`ghrOb-B81+qP}nc9yHlwr$(Cx@@znx@^Ba-#asR=B_*I{oVi0b0SVe?j8H&%C+)| zPv{?DgS9h3`j`@BCgbDiZ=5hdshz&3aPCcMBv1*+KcYWsJ;vwkv8c}{IZSnsuqGPB z5~jEY#_sni5-`c=Si&&MpVVR#O_AVdqpRL+&cAIaeOkr@>WKP5WG0%%FD@l_7{I+k zUj!uR)B;p2KYl!m%U(eL?BghnABViFrMGFru+$Z7jMdtwSO^UnZkXCXqY0DRX&w%S zT+~{C_e~)x{2}h)tG-S3n1dZ~=L{D$KR-GzdsE{K5M6q#z!bV5zf5_6_d_QjgQ&AH z{njm~ES2mEFnz5^-AT%@dlf(RHeQ`qi#*o(i+OwN1H&)MfnxuNP# z1A^u8{PFsoHl;96S1V8oQ0b_ax#r{DMl#KXOB$8_&7?N<)}`+1sa&kpTTQT0~+?)h}r3K%^RS`ja~7Ewe0U5gfEa6IO;UZe);l zClpYMXjY$gwOcfq5Dit4#qk50sjSuEiy0dN5O63fZ1&B=;nP!N%)zGN%t@=8a~;e1Xtva|pC*T6itlRShXibjidvF}qnM zH*p<6mP4&^tsl+Q54j>eKpxr_N4x@U3X`N_?c@_{cnnEgWNR8@_qK=O;&2IkZ4VV#9w1{O{9&lOlNlw(=Khd(5XowKAF{YZpQ?d8C(=eV<1{6`QnNRl>_IWkQHeoWZDs1dLT zF(7ZJ(B)_|b z8bYWcrEffv7c+btsD8jaP-L38zuMK%(p~~6cQJt~7)6}@ zB+|Bt&GIlmaSEOfj;#NIj>7*OZ;Y8wkIN%ynm~bymE8Bjs(%plOS*Yh-p4c`RahJB z-e1>E95A?oSS#LNTdqU>)Sl#dvD|2RKxTnW5XqDD%W+_m6$Xxb@^Ey`rGL)OrQT4T z4INL7=(Am?mtJFZAr=v^Ox`EtW&5Jk@ag(3J-X_v6tURpevIdp@tNRvF{**C`8QHf z(E-h_$Q`Z)?>EV2f))QGHR-}R2zjxzA4Ay)Y!2T<9VR=1GodVHRyxIUPd(=ba9T}& z;t*Kq%3w!V#!SBgXX-ukj4#A*;HP(KBUG$+jj7KTia&`I{n{x8Xk~`fmYr%YV4HA2 z{pP*I(3#FO!vU>4-_us73FbO+WK*Y8tfoUo<_527`9agCw#~ad-|s*kE=#25j5Ume zi@3d`M|sn0BJ&(t5b}WMta#yI7i#|YhUl`Gn5^i9p7xSXU#{*;6>F8_hhsjGhlSj} z@WZe$6wh2{LD_p2aNiPZ>MK~&A^Py>(v45G!zykg#_4u1^P>J%WbN~EVO0EcJ2Y0I zo0(+lIYtd^dndb{&rT2}I>DFZMWV#gH*t@JGsJwhwNGi3@mIj|qQwzb+` zYBHN)=V00$0&@Y&`^*(uGMK^pCj9&cB~5F0gl!q`kZ)7~-beJ~Tb*cihWl#bFS(RcnZE7p}T3 z&-q@_@yu&BfG%}r9=K4x!coCs1731U;qrJU(Whyz2h2&!s+Sz24RwpbOU~~R3Hy`& zCF>shs_>a^_yH|f?)}Iu=dGtS&U`7!3-u@#tV>(IWgg;)>+Aw=_6-j{g)rAA)5k;P zsNT9tiCi-|!FocaA3vb5_-+Sk;ZgPSWO_J|4o}?|0d{f=LyJx4IAm69GO#__0~_El zIc&EXI>T(<{$~^~ScpFlsoX0wAmsb6%`5HabrKYgnxPJ0_P`4~jU!!4b^>>MjBa9X zKA5;$Vj5r4;rPFw+B%NO%=M6pSdk+&&we%0l5*-oxsd-x5~3fQX!5vYPV8QCPY57> zIUY`I2CV6-xJBQxw+RphXp+}j^rDWoIcAL8)?XaoXS7YzSjAH+H7bKIFvA^24~531 z$ggivqwnj$OHWkWorEy66=9U!)4e;&YdTxl#rm3ea1Vf_ z=+f3a`vE({yF=}g^;L*@3M{bm%+nfgf?ip#juE&+UqP>hw zPFI*X8&OodE6tgPJfTp0x6u|1@JULO)y}daJ`_efQP%5$mooZ%qZPOsLE?Au%ZyD-Q8{> zFU4I!>hf;rI20)3yp{6{_M<3Q9U$5@LPm$SzA+BQnzHptpRMH3ady$jWK?Ce1v1a> zRy5V*46%mDNo`lsXu)E~z~v3vr{#6fCwsUX{^tL*4KmlPA_x^8E@KN6nfe z3}jt4Sr|?23Sx0dhHG_f1qI|xu(oE zn&bEyj&pRhj($0AC(!?SH#QChJs(ak!E?%`Ta#kg-N(#xJ#!x)Ozswhs@eizcF;SX zypogmyCFcuGav-|%b_8s2MD4h#N1};C|kaXf5kp*drVGCF z=Gi#i)?TabZOY_8f6 zO*(ALvm~L^T!V9)!6UU6c6>3w&WY;}djZ~>O?JG@uXc4i5~1Sy?pJSfIIk8;MX8y; zTqjy)N%0EY7RgpBqAB(;$BhqCVosbZCx4hC;srRTxxT>XI{?NL1elnf#6-D2ML~J> z-=-Aq6Mh(Ej#M8TF2kT-$KMw!h$fTe$Bl}R9aMqh+bdIc@9@9+#j7SQ-#O|AdYNwp zb#ui_iu<*I?m{hy)eV)C_MQ)47T@CvbA8v?NACUfOTcC(z>fip!hCk@37#lcs&Lg2 z0lg;OoUT>R$N^&1UkjPcrD^h+NrtKSrbW`Ja%BV1zdTcp=d_9m=rak$+;v0ToOY6Vz@|_I6 z7ddC2Ob;inO0p8|9+L<+m(le30BR!p3JWZ!N+ zGVbspSGF~k%qNi7u+hOMw1`Y@u_I@y%p(tq;)CMgWvhf!xg|Bqo6tOnksbXoayxOy zS;g5;UGfEmX^ahg7p zCh(}KDuAM$czg4WC~-JO20p>H8!rB4m42_YnaE2lWhhc0O7YrO`eVXqw~lp3sL@a7 zYw{NquCOBYh&LUjKrKsphN`_#H4Kml2~ST;aRd-cONd~WKujvMk?}h~NN2NR$8$#F ztSkf{y)G6$oY;5<&qdr`f7i!1o!YeRoJ`WqBr4BdJrSJh^Jmo+88JJ(n z$?4redK8avT5r7jw$h4QEvtv#^u25GKs}>hnHp@V+~pg_H@t9>LM6O3vTR5WG< zRA+H*ZG%@ek{b|O?s~q_Frn;0o;+rq)A0e0Rzsf(=knZDi=_$Th7Q~i9YlgjZoo8K zt$j*t(d=qnv`fodbFS#N%JqH&*c_>?$yG7LT&7-po0{EPC8f{@;C;+9<`QO{?`Dig zN(N{vF9rFXr?pR>P+9V4OBkW}RvC_Yr%LUVQ;ttH*?P2&luaR)Lz3ON5a~}gks$yP zWh2F=9z*G9?LNu<;7F+75wne*s0W|sP>P4CcLbZLhQM)$acLL z;m~=WQYRdZzs84w#zt7Y2_RNZ*+EtE3(cz{_ zN9541R%GO23m$sz$BcatYeh+kZc-igE8pyyhw~x4v4Ye-q?WJtRI`q5MS9;`>$;4I zEb1(3@d_2xI78CQ<@Xs~U}ZQAmZC**$;Jj^j3xVRHC0+}Bik z_Q4rH)v?i=imLGg*?ny2A0!rp;7{0+jTU7l1EGB#X1+gU3Fy*>98`z(PR540e=IPj zDR+|kwCms!cLR-L&5B;!G!>7;187cE%Y9@XfPdLn53*~meWAyO>cPUeb@v*~Nv?E&GIT|7@F1(K1&SignA+*{Sw2Q&F=v2@;* zo@jJiv`~{);7-RBmGlZc(~kzaqa2hlI+@gNJa?V%CY5@Je!blpV5Uh7w?M|^)ri=h zetLE5R>4UpKV}~)3MWqT#%`k0yH%;;8MU0ZlMR`Lu(9f^$@P^s^-wU;Y^sH4sc)!KJ>~FLA+N;p5&i=wYgswjj%FnIq$rb; z5mujCBJxcZFN>`Wpp)WWsbIM%P2*JDLm^o|)5^gZR!SK&N}Y;-MNJ1E5l`{fV^vu= zl5x+~n2}mYR_vRNaCYN47@qtU7*iadpLsD}N=f(Dv@!Y6&OEOhwBX*{lb%TVVY;;3BWsqD&rb-4QH%!bAb8 ztOk$FpNC6pCn)TtvGb-!l`R&-&3j^rrm*WH0v{;>@EIX-eMfV*R~o^Mi%V~E(Pjf$ zf#2iX+YD&}R_#u(7_Cy9k@p+3zfjvgb30WWv!s?}9eCcv{3aX|s=4v>KELBOFmZF* zhzDJTib+`sKtB<*4D`MRL(!RJ5zQkU6m$}SIWAz@r+Ew}nK+ z70W6TxhwqvY==|z!3r^CH)#9k=)o@gqu8U!h8f6QwNZsUOLq0EwT!wx1FIM`OD!<7 zN)selXWno$l}Uq(LB5Y7TI>-a&7Rb~T<5j`crXwI0Kc8~O?%O;Mp8fb9Sy#OOe+6a zqq0Kv4hVj>hHfCGC~~=jq;lJI(o^__i@l+u1hbnn7}*efxfz4Z>e1%@BX^{qT9#u&PeTI`Z+^4xkUg`nSk=d9xVkQV!_zHf zuY5$8SUeJy<_U3U4nCKq%n&zbVFrBu{s2Lg18&$;yuoc8-Y{GiNUFhPn-JS}ESxfQ zR6gVCK^e#!gfo4Q5QB*-ykF@HZN*#%V-9IT1Jp$&y1wYRX$UV6Z|45rq;VQ1dqK~4|ms|{( z11+ba@KN67G50;R)N4@ZU{?m7J9OD9DkS@mYoTbhRKzE9Su~{YlKQj5H>uf_jD)(d z1aPKpq{?&y2hD`qd*e6OiNk0h5iipv9J}j%2eSUG(snjN=k$J0XqK-XR)PN~ybp$pB&Pa{aB5QjJ8kOq=$#(<6UquC85O-XLF_C2VM*b~b&` z@7jlr4XaynV8Q*lM#3czoGT+e8pQlA0$^+D?X4+*6t;4{{t>kk7#26V(D54L8{OxrHx#9Paky{?BlyXGieqcpjVIE}N8 zyT(xBb30W1*~TeKb{BrVdwKHl;dc@i$-T9vU%SQKVRql`_!dpVrF1^v2qrN z*CYL#_a>;m>D=q0urOuf@c!F}d*>c;5O|qtdd<>sD`14@y5vK24t#ulaWBkUEv+cc zT)YR>UFpK5+@mYun5~ttDk#{}8<_3vyZ0pOpe)<)^CxUQ9C;>aIo+y1^{?Sa$3d!D z)Gx&%%59Uv6ez+&_Z~NwVV`6Zlzq>n1hbLI;^I<7t0IC;Uo98;!rh2^$ctA2^=0X| zC5(}ebnxn0S7`F!DFVbyrz}-&yYwlaV(dB7YEUiYG0prEt3Th2wtp}yY2zMeQb`N$ zD^98o4pjsCLv#3DO&tQa9pDa*0wjkZ8RH(lyiA!CWcRb_3)FJIpY3lZwg15hV);LC zg2bie)P*(w*wsY;BPNK6<&Rwr!1)J1#K^+>2NcB4^xu9pmOt#D|KI1AL{Q9{w4p> z)!NkMUq}6K`Cpy?uK)D@ckS}mq<^&n%v@X?{vrP{)&JE0eEJ`g|BoC09Ph98KjS$V zI+@!2tF5h}i>1AtiKVlHjUk;Uy_>0r%ik8;@^8?ke>3ti|10?DZ`>o+ zzqm(@2i}=n0Ji@_H7Ke`tIGYY8e}E^6EupM>F>}e1{RM0A7~Ww-^u~-pQur^e}hH+ z7dMLik5TgP*eF7lf3FBZdZ9nusJ~I8B>r%tWa;JqNsUsY*Z41Ll>MJX{b5F#nA*4) z{_#1Q)0-Rq?T+$lrv@x;#!+3{w1dztp72mN`Hu2F8>xO``;sNtXaIE1pHq(V^T_5nhHvP#rB7>^}obM z``6dUUz9OMhX1GF0RI6q_AkM)|C#GQ6pYdzpxA#E#y?8pZwqYxCuFO?O2UQypG*F4 zDfn-A7?hof{hybJ{V#YJDk>8j$G_0Sn3&jE8UJRDMF(SHVrTwCivT7EL_LEmWZBL` zz#R0`TGaJ#ZEf+kodX4Rc1k;h?IQGN0}1}Q))pcZaNth#b!T6@`l_5MFE`4md^qdr zyfTN8QbK1HQ*?$@&PxjFrv6Ti3QHiMbHhsw>mL%59Uc+_AD^IvcW4Fs-ij5kgnIfL z#HsG&ZBk$p+hQLkMKTT07I=Y%_Z!&Bt_4WV4Tu_(fSR2E7S=yHB;<)d6k)~(2pZKr zj#D5Wn()K`(M7Nb&E4VN2|`n=J#gXu1X;jX4A$W2=*a9jm0MsD;S`RExgL@tqfHC= zq7Qpo#s=65!Hh7ka^)*H54q0C)%DQW?D6{AfT`Zu(8-|%t-urjNTdX^SS>*JHMWFHqr)qc6#!J%hhYNIk{5SIsBn_@AKk=8)@uQe}>G=48bji>`{-In3f*_P>VBP-Jn@nvKO5{IG+p5_nx?(RuvHbW?`j!A|YcX5T1 z4hREw*PP$h+3cS|u(&!4e9p`T8^gAMuaAkR#Fyt4;b>c$QD`t#2qMiBM&oui8b zn1+8O&}#sV|1P}<0Vb+DVc*gk{OQSE>plRPn3}o|*W?(60bDEaH}aPVWMlxwm%;TO zcMuP-7tQXPF?ikk=ljz*5Rcw5!efgbVCu`YXNrl5s=}$@{!8UuKRYcgh`cW>J_x*T zY-Ak7;DZ-nvbhV{`vqTU1oFxr-Rom|L5mC2^;HMn`innm>x&nN$q7iF z7D?dFeC$D!LvyMRpz*~Y``WAX`6c^&Me$`X{0V@TY+qadl$O1t|M-esA3`uWf3OF= z{@KwUh$%1!+y(LYwW0$1JUdSXGA(H5_N7jJZUq9+15@;t-uP-kJ|qUe16mP8N{a+)e=i zi5=jt`QG~jy^jXC$(8k`@EDvy`V-T!5h$(rld!J&o?r+9f0X|RULVaHq$5z;(I+7T z@C*MB*uJW3$berIpMpFj}SpXseckc$<;oVLNNeou78wAKu(E& zAcEY@JqPtIX8@4WVwVZP;My6Vg1d6*T$yQWK>hT%uq*sd zk6#mCni*eIeZ?6cnDqgu>FFFnkjK4V4!~xF=FIHeu-ey_U*c2HGgik2Z>dD1_QKcM zFJWs}@y2XlsL(oH?LpMfXAt_80PFy4(61rzC$MLJFwM2T#r{IeeWQoc>0aNg%{~C^ z2Lbe({dak0ZPdJ{(H!~cLgaA)iBi&+G>>MP~*3d+$R))8!{ z1pzRV0lJAJuFam>yB|a<2QUN9njW9-N4K!EdgG^D<@}`hWQRS!LVc_JsM@vr44-|$ z0p9wuVkckS1iv>o;_Q=s?PU!L|B?jq12A-Iae{tvIXhtL@Zx?t0gXDm!2$x`PCqfh zTGtM013K>}GaDJ3r59p|=CSb^#y9z#zN< zW0CGfoY*xP%d&c#=~z5wQ)#wl(-ruxl?jx4ikm4|mkaUjEyps<%j5qxvAeOQBR z@-~Qi#}tpb+i&tJ(0aP>u;LzVaI1815cPQ!c&m;Q#JwuAOrw^b^9WSfIMSW>!&#N9J#Fa7$x4-&aDr2&Y1;5~Hs$oH(r z&v41HtBx7CmkIKo2|Q?__pV|tCB`kkwSK-~y)A!wJ>4YREq}bL2vD&0 zue836KcH7@h|QQxtTyLH8*O(iH*Nrh$8^#Tv2oe6c+*xbK&yM2jUNz6pqKin)AvwM>RaghAEvs+*V8`XyRhdt-`PJgC+oC-7haY+C;l zTWw3(Gsi%70L&+leh7cN{t~0H?)0|rQ8)%Q$MN`0Z|Fsp{Y&L+J7-j*;h~QO$`gK1 z$&2+P;SWxcu?M}g=w{R*BhY4iyDV_p!%FoN!r;zFg7j|o!U}*(77jy?5>li)a}-Gw zfr6m<>ocf0Bi`b}fd1Tjo4AB|+A4Y$I!m;o=&h773Uzc^aL|az5VVW^c(jvURn;hT zl^h}CiNBJUcvx)TZLwV#wxDAN^7x^R!dxnHL?C(llJ@?4TEdqCrZai7b+q_`5~j~; z<|(D`twC8*avq?FPE!##i68mLwJxJZ3dOI{T3EFH@D4k86YEo@p27fu&mTR=;x9K2 z@EMzB)CTL|7*^#XtOBZ` z;O0rNIVqB|y-1q*2aF9;+k;oTCRXpG6o`c+zecbnGdugS>v;@C(tnx_ zCB16Podmq%;f3K&;9eGat%LX4YZP(i%tLjosY*8Qos`L34>;AO2 zJ|L|LSnNHA6yQAJj5dj{KY-m9Dm^TlJsV@Lo;>iy$-gk|OU6%rVhl%HK~J2y5F#PF z)hZN>PANsWGFLWBUy!NYOHj?vtMldYd|n($i|VXi33~Fy=U_x}X1_gT z!>q}}Sh7kBa?a?E zg!9;uSd}5SdhNTz^JVXB#rV6ShKxed=gJ_WQc96tHVEXEcLc%HLaT5<66lh?nOGe! zz>Up)6%Lo`trdt>Y<8eQ&Dg?j6x_(oT*;x$XS%BFdeZXv8hubtr?sEAG82fHGU--< z2i#k(SsJkdX5`A*wYhzM+x@6(=Nc@mJn_+TB$wMXw<-xg1H<<*nGv`QyXq&*r5UW- zYF*y(Jbr~C)9`}58z^zL7VO@V$MBLH;JhS>h8nxh1#v`kX9o_A#GaH{Tj%Ly)lIQN zq5=IH**aprBAk+e07hj$%dw{#Z5Ew&y<@umsP+c?T(E%XN@F>+IWt;eLK21>z0vIyFEfkiaIxi|1L;oSc`Z8SYw@;~35q~=kr-^L zuPVo04}-1z874D~ZnTVo{lqhxpc&4s2CWHwLIdyerW@{_(l~56NOg0Ijl%M%J5`+0 zVmi?b%s_ar45V(N?#Y^2zcV_70c!lpk5>xHD!cSL!wz@8gNS1%;OeXGgm6G=kn%T? zcJAqr1p6_Rv_5!30$^3Tb!8Y(>idq20OXCuM*DmR(Y1^LwkoOY0S~IJ5y@#aP5=sw zMmD{8zp+I|hO8a)LML3JGOc916Ak4=Kzp7uu@eG1c%xXlB&R#h(9iKffO4}0uG2aJ zzF9hX8GReA5LxpFA-!v!?n@)RN3qwioosa!M z{zQZ}`z2!8{+8=JjU_b>Jupc-*7`ez3uEkLi}-`w?+}2pu8Yc4t3+Acd9*!J*iGX+ zHf2Xq9n+AmWC6FBVn${vKu8VvUMQKS!$z{s*naW|9GfT%iN1K#hmtVX;ab8g zk$ncf5{$~Elf|`nfa5Dh-|a9RW6PTI!g+@$x-nVUl>g=i0e$z>+(!c@X&40$n`2Y^Eq-~eFY?RYk zSB2|rX_Ar?*Ka0w-lTacVi0rW!1uX03G44s5z&L7jRVU#zv7H?WY6DigGR+xSCmcl z7FG&CnU3bW0Ih|nS|2V-X%IM5#Upyj1S;pq#NtZ#s>*LrMW<9Nf@d6<^`oIu{y5Hs z#G(gr`wpy94`Rg#o|n&B9WUq-*knTq{BLfKv|O53ci6=y+)(yHrz$YFXO}E}QzIS@-8h%+YJ9Fk4Fb5BY)>Vicb8HV(-s#2Rd#L^XfA z$zPl|M6fly^DX7ZX~mIJp`73cQJ=CGhdyk{f&K@WSW|2)8?9qK7oTggJfny*-$5;D z?=cdExAl%LiAcD`;ElFf3z0qddRK$DPPq5>0C_#Su6p#M_twH0Xz{nZ^k^GICDo$4 znqF0LJ%Yi#2YhitKap>gn6G=GCW9ubdRkqPw0T~Vq689B4&)}B0Gr=vlTo6&>K`1` zh}umHFtKeMOZUf-DNs{lFWxSqmz7b!GFWbiF*;_nncV92v#8bO!`!)0RV z<@>GsLPXJD3{F&qVXa1D-3U1AFFWU`VimDG=*=YV^`?d%C*5bo3g1byaeE--h8wif zss|fctL{$O?GO0W3t3UYlK7dlF~e*T0X1lGueRSxvwTzY=855OYc};&mh4LX6W6G? zg>c-HX=^S;ps@4|wC0GqkThFHYnENuJ z!i_D^TFkKHy^6PYX$&39)9ngKUvWv=8sQWuOw?ass*Vm_1Kd?Z zfSsFo_h>nvrb$z$>fh}bugl}%H)>xVbqx>CszrMYJ=Iu4CFbiSVsGW$3~I}{1cz1O zidV~&Tfe46PiE029Ej`mx7}f#npKg^WtZ`R9OSyB#a*OyzBy#jLZfWQrazjYs~27o z(I^>SJds1h2$a{$64tAa7gN^6076UF=XIu7mHSZLfy7l1(=Kq6IgZ+insWl?dYV40 zCo{?Bm@JnzIxd`>aqa5A`RPMI#=HWO2MsNO%p^wVU6kZ|1ve9CgeL}O&vBDxkM<^& z@iUVpmRqt>_|0G=s-q^qA%Ru&*KdQ2)gE&(R4I%;s0^Z4QMqCv27WAM0rb0MIDjLl zxaQGe7v6`u80v!|7|@y9xR5v)4T-Y?ByqHvS+0<-_{d<0j_$*nVkE{i#L)__+6}mk zA-!u#iSU^opsVHRmzObQ){0iD))B6ii9+ zMHWrU=E3v~xf5p${4XDo06g|VPDO#x4^J%T)N7EnG8Lkd-CbNy&veJ9^-j|gkvxEb z67Wnp${rfA3kL1ydi!Ei00A}L`uD^diNP|yf))jrbWdjag6iU%-%l25VYcCBUn;z9A=QJ zO%JU{q!%8!_?E3le)qH}T#B%c;4L<^yvzb`JQP97%7d>sQ~4H_@==C3Bs6261SZCi zjfP4HPO9xB+vY_(1GHuvo^Y@5<0?HjyOt@l=oi>(l(vv)->0%(e{p(uzf0z_!(lk# zLtT2wDY9Z!5OwO_St1JhFr~h1O&Ee&v#^Q@9Oa=BQ%+xEmRfS)=F8iSZh%J3`^0l& zf^HMF8?G^R{PDqkvo=IJpye-H^A&5lz3 zQRUoCv8};t;XZG(sziM;Vo8$yaa`jW(tM9Ro%}M$Ge7C}`}tCS$Tp_TYuV~eqEH-~ zh+mxJRX9>g8lXoFQxJA5C;=MpJnVg7I=JR$`GVs&L)B&!n}3yS_-LA)JtI1~Mk^B3 z>cSvkmkaX7_V`BMX*MHo&ghyoC;x+_#{PNVSbaKtr;9#d8;B&b!-x=IUL|ADSFm-# zP)>vYt8P7ee<_pR**ip?d*C2hegJV8OChzEVXkEL2~dYCX{U%Vw-It1Mda`ehVnKr zzF5-xqDkyTg`zU)g3^T?ssemckvpbI!SZ^yK8GoH!U#Jch2I%48`$qg~?r+GRG!cB)IB?e@+&n8*0ltZz z1_XO3sr^RsVP`>F*3?znd%oz2ToKsc7u|;Lf`;N14MVNkPLW@Awl$y(HdW--%(K)y zT5e2-ij~?1eShDn3xAYSbddZWHeZ^{b|O`dWB|N2&s0gtn7adSOln`LJ&$=we%^;+GZX{pl(Muf5&n1ZCZbeNXC;G-)D>W=5}ThW#kV zO$mhejnB;Dz3o=KhgMQ5;~0ah_(RJlnbJ5n4t7aVk9I=VZT~y+r=EZM^n<3O!|6)* zq#(d@w-COz>amvO4|y_{`DbUX@@(wAy}DF0sr=;p&#?5Ki?~Obr^LDO>T<`z$Eq`= zl>t=z!5r<{d?dx`njiR+L<{P8Vt$riaIx(Xlpfh7Dh>kuN85Ria=MV;BYfa%#fUzV zjT?Udmf*lKig-P~Z~5XAfLYN|)-sF__=EzCg1;r+OW(8*IctX~EAvl{!51xs2{y?; zJ#`G_b_tVG>4?Uy*$1R)u6d3|OcDz%H-TuWjl4x<#|za;hkUR7LYY)5b(yUh#O z`8Go?jM^O}wm&O!dh_v!Pnge-6h(Z%Hv3S)^~{qkm|Zx*XESjnxs4${;3rzZHluE7 z8*yVC-7u|6cLU$}(<0#Zd`+C#e0n;M&qqF}!>vt@XnpIhYuhYHU?a=hLN3hCrMocD zlG4uwg0#ZvtTivf;=_w{NpDR${Uscrzd*t}aOT4=l2Sb57@MRQzg=eeWLLKc>r?Py z(_GyQg}FFvI7df1XNBH7(zIEIAZlF(!96H}Yj(BwH06(0Ub#pX&P$8%Qu&A>2}$|L zOH;SjY5#dl?tN0lXEfPx9-E4pjVE{Dp+gBMw3*#rMY4$2*}<~9C_2vnpW{DPc zq0=PsO_=&w_<)m7-h(V#C|-t~AEKnkrHR3x)o$j?lxu49?Cch;dR2@0-R@0^fHrSb zJz}s%wPixwk`$HL^Jic#ixeN9$Is>WCLbK$&j#=)gAHxSZxh- z=G=~g-OBfOh1V{+l96#7Kg{_JC~WO?>E&LI>-xD{jgKN{!{B2W&{bHujjg~o$~6Pw8eCaTTuw&o#z zm&ax?ESw@S22ym?RJexF;R3fi3I-xLx>X8rl?_Dq55)XxIQJhR~=p z(s;aPLg9o0hG9=DDCbgUrM1F6Kk`5giaGM0b=*%fCo6{J#E4-*CU z$#@aD%}MQ4=~KOzD!r&gyjoKH7_2_(LEa>>Dvfm86Y{@0_WpKe~xV8qKm_N=po zH1K5nj^{Nsu!ROa83Y2k=7VsYiX zttP#`Q`e*fdU(DxDU0WMrIx}u2U3u1p%iVzxHO0RLPRS8uIUoe-frBN1L1t{$W(~u zm~hg*iW~Y0)%k{{Y`#)?xeq~4AIl|*^E_b``RhTX_mKlpW8TKPI#q^N^tffykTSDVWQ&tTr_4Cgs%OlK! zk~%1d?je`!>u84EZsCOl3v-!`Ie8zb6>UZ36yb~(2s)@4qb>7YMVIx$?8Kt5(IBQE zNpZzpIoJxsZ)`Cg=#TLUve+c~_sCUGtSi_r`t*N=+)TdmePZ$>zaXATE_yu_nI+QyrGpCPgp>GMx%!Pzb&_ZeIUcbnmb;c2G*ui^~9!}x;0Iu<|+K;|A>rCz(> zY16>4LaL!QE;4biyws;j!Mwkugwfj2NYTG#FGf1$LlUw84?h~BWv7wF zq3ey$T>VJ=T(R`_SE`B`ysk|R?KjZxI^?P|E*S^mo=_Rx}&RSjJC-UisEd+X>bJoAPc63Q*x3j_L|^$kDH&O@Nxs_oBBR6FGG`HYwM-jj+9zz`@>X=$3F!z^@Fz4(SSBOv`M#*oUyW_2Q4 zXOmcFhao=7iO_@Btjx_ZegCZP%@5?2JA!f@yERG7(G)T!6?`gv_wegg6t>WI7etPW z`lVbXkXJ>Is5!icSMYnUI&}3x)9SlhL1N!04M7x_zgG1&Mue@*@As;lN|i7xz$%7o z0FP&y6+bDJUAa9O+A0<`t)&VohGyAq2^UZ;*}S|XB1J^gLT`X3nj!(HGNC6#U8Psx_i9K7rTs@JNex@dDqTud7&HVi#$2T8rsv z+6=YE>%9%~M~|Xnpona~*WBXRxK@I=VdwR*JREw`WleNK1d3RzM>aktK*qbG-tH$8 z=;-qssQzM!QljQgRRZ%B4_SC3zICkBJ^lsulF&(?2VV+_E4t-MD)-NCMy(B>EV7nL zK@K|KRkM7;@rG1na=C2KAz~I&KIbv!*U(_F_yg=HRqfZtdU6jsSQfdIEYry7t4!vh zi}~GdqU9$Q(mobnL^($y04gC0&O!T;0uSk5VJgn9gzGEG3+g3SXP3{ih@ev}eHce-Q2)`q zcs~&jQ-bhCXHs0^q{aYA5s^4ue*f8du8WcITH*dC$HMq=l{$9NVQ3MFRJc?$c+z9w zjRS`zk)?7XalYz76LL%hbxR!#XU0;528SEdObZyU4f#GAmR^6}lw_Gct$@WDJ?)_e zkYFvxgAr%ScUphL-?yVv9(7n(kE=D%GEKgQ1A4V=QcE<_qGeMgZ%SCm?Ty9#+swPsr%!chHpMh~b z{|H^Se~lt6FSaV}lC(v>F*pPZt$x37ux>IdgwywdfcXW!$S9v9xottlPr&4)QyrtV{um#4uqc-lXUNSnL2+@5&i!tyUWjjncZ2f=Eq95C0o`x(y^uU=lkBrBR41Scf;o#inm6%M(vS^4W{iy zlFOfQt)$<9v*WB3x9lRK9CXv$^|qBy`0jZ&y7*n^xKAg3k%%1tec!*_?o0;6M}t5$EGW~L6Khu;F)ltWbr3O_Tt#cT?0T)|M6EaF$t0<6S9pNGHtEY zQTm#?tsnlR5(Ie_h96z@^fTD^a1)zc1=4AHo$=tn0gUQ*cae6@62C}+{;BLtvRE$@ zvm-G18bmlm#X%0h7(%obED6ON7xM)%Or+;WVPy6aiD5hLC)3LnTvDp}77~mBG~7p+ zD8I?bexqh}nCd23K&Z|#tAhP7?B-xNnQe!J-ZPe~{B_QqeZiaQPjqv`NY~QFYN_d` zIt%~>n{eu;%79)+sB`I+9*0!Qe5`Hr7SA!@W8Y1zsreotWLvf zieTHSe8rR;(bsMDErRz&%{~&eLz?9p?}&Z|pDW}&Yl9!XLzR%63w<>5V^Bn!0?MC* zsO{g5U@qW5JA7m$Dep8*N*#5hS(DQco;~M>B~7gy&s;ye_~jcoth5fQX_XCQR_DpW zMt2!L>zK)-+BX#>X|kltowwmP`0BSsgEk%}%WR}_^STD%B5e%vU*8!%#@pA^))Dc& z&Ky&T#nJ@mpxo=*!CdPy!emu(y;%`ij_x>;k*g5_D||fZS$<5oAT_xbza#wjFrLB~ zgqMy^}NdHb}ow=2W(-mRJMLkPeX+6yGQG;r{6A7lA&UA2uUcOjD|3u=!mMl z3zzGbT(gwt?W9kQ$Ej}1beH*l@(UI04>1*Z(E0-qve~D=EbEKH(p+00ruFdf?1nT`m3n*L6ezs zDxMlA=s^+Eoc3Hl!!zCr=XJ+UhnSJ?WGrk7eERX&m2cJ%3QN)P_ zAR}SBg)wb=c#2jQL%NcX@%U}(49FFU#z|CZ5FldZ-E60mX2(PioM7w4VJUs>u3vBn zq4P_!@sZ~J?iVA^bF_&pJ1)jU#LlXn(Hw^LAjub*=i8mx?z}(IRZMQQctKYD)#i!3 z`NJGtdJr!llXBek^w9IEqk2y@B&Zt?;I6Ek=%g0=lnrwCl3>$wB(O>Bk+4UOxo?36mG+sZdADrd(C5RbDL>pY^>$U*wjp9K9_oh-$E-C?c1VW-Y^nqf>huNJq5a zgdObx6uqFx2(~_gqP2=-+Vp2xOBn9k?#7F(-Kv(=MH}5N{7WXZB>owYDJ|)I_;V}t z1`}hViThsI3u(ZFz%I8!8Rq@`#uV;sL$1>H-G%z5XFA-}&hf|dEL|kVtgJZ$$ZMGp531%2a3lomH5H~GNJgM!Hau$eFr0zN2`VeHxooXDWQkhEDuJR^>@nyCU6m~y0=~8S@ zRuJRS-^t`9i+F|M*Pw zA6MRXC7ZS5Vcm5OahUMmewK3P_G8|HD!NvG&^wc91&{a`gWYSw=KIF@M7{L2#z)c8 zap~8T+fQ%%jyn7*xvc_B+dw_ZG=zfyNJRJ?hK7`%G zNq8oelfO9Y8d#DN6*m)4gWr$QOyJB2v$`M(ZEahnr~PJ>IH)Kld_HVy=An`sHdlqf z_)WmwdV{n6nw{P`hT{wLJUIu|uz_b^Kj#=9fyVd)# zluo4$cZ7sAbTAk)0^0&({kD?c4lOG3K;Bszf_Zy|>jwJ3j_Tw|Nw%Z|WV+~JY8eBk zk9>Ha%Vau8I(VG*_X_RRgNCN2*`a>2> zS&Ub?%JVLO%A;4cJBt|?PfYmJA!MK^FDW)jFgFO@I_jb8$Hp|Ygz{JPU!rTB1t+~l zt>V~8pP1+Sf=wJ-oIKZtj8!%@MwqlQJKf^=c(jWW5R9U)Ujvv%ykI2z4_+cn!c(f3 zKE!l)vhl7sJaY2Mf1CaHJ_#OVb?c^PD1MTz*Hc>ng~x`(@EJqi8W$OelKg^da3quG zeg7%xR8t%?m8_Rf~ae<}s6* z_ZEB&b&LS|8=Fr)6a=~ZG?8g?_`DUQe)ycXE;|w}^n*2EF7> zuaq{IjJjCb2Q%!~hLW_yDIan8H?DFlCamHIx*GFXr&nT6zAK4(uRjEjU1Y4H@GPii zp_`3e`VuNewf;C5@dkxuTnm%Y$4XZZK2ek=w37-AF(%=9(e?)cmtV)mI6pnWBd7)f zX2q^FFWaqx<-0wM4<<`Su<oL><1gdE;Sac{48NJY1^vL`xG~C*?eoTK?(k zf36LClxXJ-{%UUh0PuCNn2&e%{`JOQ7x>(kKuw!nGrb^L)luG=JXaan%N(yxfAwpA zq6G~5_|4hzOX=a~V9GyCWGd2GCrpg%Ue+I&NpaLsYCE|d`}zyxcqeEc`%@CUefnfA zx+Fs}(JasKam$5={biuMK~>#2k5MXU^E7L+w%T|6hlcgLg@z*2U5EZXOUVWP(5l2) zBBOtsz5-H%zc)_VkgC_DtEe`7;Trp=oaUN8%mg z&YUL!;!7?g~M-~1?aiB(^08uFR&BrcZ@BTP;`o#TI2>EFdS zO63(WWH3ue7IHX#!#XRH4k2z?egGx;axMHQisfwZB$`iqWhE32NkIL<*hsV1)UYUh z&%J%_C>t8*;V2;QiCc;ajOI9)Hh99(n~0cGe)@uO2$2J7VkVuD&kM2LJ6=dq~mv`Z=bh!KcSTi8g5JuNk5qdHX&43j=R6Td<)x9 z;I12n2-~z3ep|5+Pk4I7OG=VITyziX=(SP()7AJFL;t0s_$TeiBCkhiTPAVG78aRm zOeEP6LL$busI!SI3_|sT%;m9h{y#6X$1(P*Ze}dVx@;|)ypVv^H-=DvFS6aphGr}g#`zs|a3rBEYTBw8*)Cxb&uSBEX# za~$kl*->-@Jq?bVG}7Eq?4A+#NSTP~N>o@JcbmRw-SGicy&z;^ z&m!_%x97?*0G?nNc^D#%WH^K6L7mAdKyB?n0cXtUkM)rsWVMIuC2{$s?MEGq4L4=o z)G*%o{`c4h$%W`n`H}rkM1e7W`^h$OSE(h}dBes*g!xp-+}8`VYjlEd%bq^pHBFTM zU?2?wc%dbV3jXtey9akvA$85pF@vNbp(bK~q|{O*&@n12ZcsNR_9adH!vN}pq1da4 zAd2EWCsBiyQV= zcUqk1!8@J|_~{?h{AKQ25y;jd+AA2;_(V;s!uT2sdJi68Q}{NADo)1R#VE1NL$wUG zjk$yjczaf>V@<5d;i#3Z43;#sR4}H?L3C`L&99@Ije2S2wclP7U_d;agxzn})Rv3c zo5cuvhcNP~H!N$mABJjln||1UCU0x$hzSn7kc+ppf~%#7nAd~a`AAf!tA~_u68Yku zOdbW`N(ng+pRx^VBv`<3gr zGzz^S@wT0Z5jdzuBy0Umf?|uzyC|ts`la(pB@Hfpk0@|VRKCW0XF1VL@NX-!7G(q~ zAQCHPyNo=zgcpucbgOO6L(J|d6oYT=DoZ9P(=}QHVbwv)gcOK|C zmvFe!_bRgAUthCicv`0lU{853=Egpq<8Jiz54ur0DCNyd86D4gD6OAmp^fbIX{GE4 zt~rI}W)UQkS5lee8{7frhGy8t?5$J)o`<>_N7GB8ATckLZyf#+yB)<#(P$cJ0pcgU zQi*h#!hExWYYx?PHLvNABvoms{k`dHGrthivR0IFaEP}ZzD%C9kO@z>^cce)Zp36X zrOm}Ws@vFEMftX4C@Crb+|W?!t!rklB2t4z1-!F*n288HOl+KaQ?hn3saHb-FQJe( z1b0zIif$JWh?isyL_t$sdxV-@u{^=}>l=!NhQk;zUV^a~5w7Bs=lmDXblliZ9^B!tOt0~_eS;TsFu_d0thWU%Gy6kEjHhL| zvnBdaKa}HgRd=b=A%h}_F{WJ~cs^Vplepr3gKSZjQOGn`ECAF%eUf#~1ayD}aT6#av^6k)x#0d7We~yCU!YQ$~NwQ+D1*@xhU^%5d z@D9|(TJO%kO4)6jcOTP`T03;<`!B`(sS{AOm9Cd7LYthO9r3G9k9WN)z$GS?Exr*0 z{a?+$`By?I9)k5f>62+yVX(ZzP|cLk8a;127Gz&-wyVh$#svc;wHT+oz^mfc%8(ZI z%r748f;UG10prQJ(!L8lAaRapO&s;hU86QtPvPBxT<@QQbzT=IL#o4G;5h*L;l!=v z5ixodu43uYfTTP6U8lWh+GA6q1LUFkxUm68WgN*+roqr*lOb;7jxhxSbXHpKT!~Nm z032x`_FtErW$ifK$C1~IhB6sm80RZE6RGJ)x>!XA=Rph$Si+Jzkl#m_VZ~Dc+DUG+ zHTF|Nfy`up`WDnwC1-8{QfGW246L!d)n&cjE+9cySn(wb65q`42rh{xh)ieZp|(={ zXK6|N`<&)v!BsS2+-vR1jDYt*q=eIOVSdaH*5pmR9BLboD;CtfOn$^M+4^;oWhGwt zXtzeZml)D|;=>=QKz+KF6Ila=8X=6(d};(I0Sv^Gk{i$%m=BOC*bpp_^4gQI?VN-$;8m42i_9 zsgOf?C5EIP_ePLTkz9MoMwsZ+aZL0J@O7Y&I1t!+&5POgfO1YpSZkySwBL%^p1dk_ zH+%Y*9;ZEP#NRQABl*DP+Xe zueHNQ+e_TE=;<934HLdtThfMTKCgekf)WGeS2W|I-^4(sWwB*(nLNvyf!xKO`MKx*kWQ`;?FeXP2#LYARiK`Qb|#IGgv zXN!hGCvB*^C-PV|NQkovZ%O2~yOI1kh_#r@;vP$b5AZEVBDJg9lqSuKmU21YmVq zM+W^-jyi2GP5~bRZt`?QArq<_>QmWNDu^336_&yI)CF zjIJiJbh$R+`3Jg8?YUOA`aq61VngxoAep5y5o^<##h-z)>6Au^#qpXfCFP*C=`FXW zpunBRAAtdfcb2TaRfo5lUbi!jc-MgFj0BEgF-D^C%#-#7)1RWvvSrdm5w``Ezlzxy zX{bW(wkoaoU54SutD*TFV&OZ%6LlK;7Rmh7O(tVcX5tF#z*}jDt{50+6%<7WKWVzW zk5GP0hmY!Xdu9g6dNNGxS6IozmVmM2r32c1FXClcAaL!Wr+xY!j0UH;hQ=2j8$JSu z+f#uLKWpgPE~G6?9m@QIol#@9gwrr%j9asxrokQ3%653E!D(-KSXGbHV!m&`J<6g> zSJrJYaM{U7?gjGYt8eCAvwh3bbxJL;z|wn&CzFtkX71Vu`!0wI^-&3?3h$EAA6wyqR*pjqN3T&M1 zjj^ZA5RFYC(4D{$)~c-~UF8h~2;qy^&i>$fAAN0!C1exJV)1W=&vnk246F2v^dUqf zj~6&DqWE$*9DCB#yzObN(EK}+%roCpCh{P zkBj(UssyahO|ZAqZ8yV)c{o6~l4oj{rLsz88qj8pQPe4gA*J~Z=b|(Khd4dd$jAJf zNj`b)M%QoabnTvaW32>ZduHc_nQ>x8%|%`axDuZ(ACH8#tS2E|Vk^o7O(i~%l~0&r|5$;wajbCXjL7bV)!9KG(Z=4K~(TJE|1;g+Jc$C0$b zV`6>ZNPp+j&o#;SpRqn35G!ZzPZi}$9}h4?l4w{39izqHm&YYn<4gUFQgfMesX3ly9_W4h$U02-{o-cxZy8e~TBTYSAT@ zzAv-zambM~yaOq!l2YxHalj!mjA#=0r546JY%fDvXS%`pQ zYT-kQ+ZFG9<`=2?auLb~qAJ@<6Kpw(vbrq3k3b_$qq^=VbpFffC@c1_1=nR|LT5$? zK0S+i=(BXFPv)Y;1Tm=wP$WyF0T93K&#>EN9nV++Sm3^{b!hq-M6rrU= zyAIcIT3=TxLpcfx9tejZlV&3(4+RvU_rY?PHtLlE^`=*L6ix^d*3;gi44h3IO_{U0 zeIZ!jRwW_2>P%87W;0gIf}tj((fdEdX@$##gKIURkMO}s9B3Q|@=qo;x}&;bBM2*} z!|Ubt159zq4CZ~lLpKY2VuLd3?Jmj}X7EGSoDdT@5Qnr&sE)>2J9G)_d1eQ!6!9^H zc+7Rqdl&nM0(Q({w9mw3M%z`e)`Un;n z05OiRPbv_i1&v)otfc5|sqGB6tpF`LetjUL%CjdJyX-#kk+l9vdX8N0I|>ysvUT)? zDFg2G8C<5MN}ytyh@RoLnnD&H;Pccd_3`N^-?oi^5nG((94GkvU+wmZU2=+r0mTD0&xKM5DV?G=Mv^4 zId86Q{gqVVV=$)9rC$yucuf-lw6%-`xkJ1d9Yaf3x^L_g`I;(EoxQ`+1a0rEAzyT1 z_wC(h8o8Ry@Q}P&?gtV+?y+?{5J9MsJR-Y*_&4~g#~IIDHv7`WUg-(F! zaRZN{xc(fmw#pSng9&(|*E4K)Vlx4uIRgxuu}%96efpneUEX3V^6L1)`m5D8wmnfo zNf6D?P#8$Z8Z0Yl@*;gJ4;j^HD%ibKXdj^Njxzf%{L3P^6wd=?52ttG{_uq;eH8gD zkE${}(d?^DMQQ`Mk?41KGMM84EnN(B=$k1b!#H8AvWt_iS}jNF>~A5wwlemzN*72+ z>I{tYpf^ltB2Hsl>!Q?DFf4-jqPp@_?>2e2lK%GFh5mhB2uu3AxH+b(Z^|2>%|Dlw z!$ITM8J-BfBKF>@TQ#T9s*bi)qks4K5_LY=Z_q;xYulc*k)fRsFNRG3YsK3NoDg=d z7fN$0#>J#lzrb6X9jL>TNPZ^B2uoe-amWQH4OFhgGcZs}sCIezH`}`s$MWl(x*lZK z=Hr!tWntyAn{7w=&3u^FSk# zzKtQ?w7lQGxe3|1wcmIHtMpgV&GjM7vRF^99X4697yP{pN{Y(V4Y%gt@7$w%3&dUt zjQd#9cXUUz&q-q!&4GW;WOR(@xY!Q&@k&B&k>EB4U@T!OO48R#o;8a^fkvYt%>`hzKLgvl0dizhts z+AUJQ&cZV?a~JS64v-AU6l95qSm~`Jj)mfpG3!M$Yjz7X`w`Q3GJu;ws%Hy4(H@KF zXOPi7M}uz%M1CPKu>^nJwCMN_bQCjW@67)`}!T7>PTtsF_22I*9dFN_Wsc7QFjRIF56O&)M(& zGbLso=aTt?L%SZqc8wWj4y?RBqeYUcnlDw%m;4L609qOe)GpL=)&Jpajj);me4{Ob zvr5du1|1$)g3#{hng3WZ0&48NCOKk+#yOv`1e>+uX*$B!EYMaD)iU|W}{W7y?%{#s;w>LAiLur zqNiORxElGK+X=o|VW^Gh5aJZeI}f)*gi!QOxFL)kOpow8a|h2Iu9F0M!Ol^ZYk*nY zoQbT_pdq@Mu$WW&F~lnnS`Ki2CvH7j_%W_+^e@ndI0?HmDj4Kfq=kF?Y+ZocGHG>5QXSV30n_kUlyRG&Y?V@nM!C!HCZ2^A(T37IfWD>9m6$u& z;LcXeY+8LFVv{QLAOnRL=^%@v}Pj3>GDiuv9Af^XGhtvXuM|iI_v!LsXg}jNB*heF_ z%x9^Q1u>zN`A0l56-_mJuz@5pMgL)DAuWaZL=8k%HJC* znj^w0fy?29J<1l&Rq_7}rXcUpv% z-~gd6yOmTUV#8Nm$Ay*l0IwwaHLK@|mcQtrCZxVv+`1AZBbk57x?a9q)t1!ECyC#= z(QfL<#@}UW(OrL*E+XnvURqhfaRpI>yxn|<^M#7(+&U!)PgBeluTis7rjx-WL(uZ| z_AJGB5GXqPepJ;hQU+%ajHM_gR`RLCn8qC_J{o?W3*g1u%d%YId>d<9d}(NDbt+qpdvm+?=d6%9HJUcE&ofVUXfJ;z|+?`n`=7r=DEz< z=KX6Mg%^(fW+?3!-mJO6lK;%y7AF`nz(DiVkxp8?0YP)_Xcb|N!;jO=j&Yrl zs$alV_B7oo6f0}V+Y=VC(@?ObR45?EA021b>>e}arBxR)a>8~r`bSOKaK}#BT=)e{ zOzd8v?axCOgNH{pfP@WqNg;_5O$-Ga1mbt}_|o*Ks_|lhI5;!3w$PsKhXj_(K0>Fb z$(w~$nF^7q@1jMWV!e`dGDDDK7z=@P+RfZ_2AK_zWhtjb7QmR!UsWNk2Cn^6ChCV( zSFDr|>GA*Vo+#QZ-#uF20*neoAWi=6acRvoH6SmEqxaVX4%#pXa|8>`J|Q24J1P{l zf;hieQOZ~FHU*KLDv2Ci0~4HUjB7R%YEfTUudLZp1~eR97i2*PPQ;E=h; zo`a1B{Cbc6gD+V8ijsMKN~bJYTFMh(=JDOMaxsM9_81`t>>U;-@ICY7UyjURED#3nI8zR()$!^XAY7UP}j5Z@r({*Er_pyq3>%$%|RH2 z7XEzm9Tv4#LUzdE&m(lWAIvvT_cJS8+WJ{fUD&1e5uj+-@Kcmgpj1*^D0nMqk3;UD z0Q9#)AGheY;KDapwbhk7q4fS3S^Eq9tPKgMW`n2?03(UGL~L@5l^^rR!TEbc4qjLW zsD~Y%pPHJ!)%w5@a=b+-<&yShf~P!#*4rELW6G{`BTY*8Cv>EPdKC^?YtP9LRxXN^h=jZPRI3M#pMojfEXlNF{ ze`f_RXBI3c{QQ&0%nALpLHwO`+eA)LG+apa6b%%2kXC!cch zeR(pc5T_;#ppAF=ee20fF0)GO?mS1Vhp3BFDh6ZUmW5Q>HMrS+FV8c(ugtA#pj;mvq~@V z%ILiT;+%48(eFvnCPMo1fk3vbM|c%1c&}I?V<<+mSmh(I>Sj(FHR|K4NEQCI+U8n* zCES^(65NiN~>*r z@cG7E(mlS8D|$3=tGB2~I)@+brnx&Pu^XxsZw?iJVOyyu`Lg`s)4PLdo}G701at&~ zaV6gLneGH=ke3IcNGkK3k~*WBD>0t5Ur7WIF&xfBnn~=6|4_$?B3_RZZqvc?Ie}Q* z2t{nU!5#LWS?rllT?iWFz=<{MMEFK_;DJTz_6i+*N3eLg)#{2ji9KYjGuvgCu`rQ8 zFqOs!Ub(~;Nct$%(zC7Ug;V{*8?ae*F@G|w6}VF!dj~n!IAjjoiGs@NO4(}blCpoM zDIs}uV*Qub!Ly@g0|R0VsZ#R2T^o)1V)WMftwADEHyz+(vlbi7)tYvu>HQ8?dIs=> zY5u(J1HIHGGvJ-f`m$Q1#!ILpK}E@dfiNC}Pa+GA)=@kfc!wR6+n|v42c)F<^y?AZ zaMO@A9m%iVCiBUo-uT{eJC&WV~p5fHIymd014#^f@HNG%wbyRmW<-hWW; zK%_F#7Jk$mK{tatq(6_4)x}zpliz_iVIRvg5AAQ*q%r<$r68&v*q z_PFifYyJzJL<;8wejW}bZ5l1_L24~Zp!0Ur%F7E|IGQDLIFXgBV5PQ{mOZ_O75n+u zT#;7CPj?KHCEG8lA1J$EYazOchCh~cKSnjFyFYx}y>#^;Dc>bD#HZV1)S{$*$ZY}p z202D!7I6np8+=dw4op;$7`kax9VCf66o6wUp;vEokQIAG)ED! zWpy+9w0R;eVw6BDH*!0a%BWy3qB;6lnQU@gZZZ8=A_`q>1n68vVr2RGm|ptS$vnXQ zaGDUQFiSpr!S{GO(5Yi6QNZ720c_dFpMtdz;p}{d&-`oIbb&})(O9>5c)exAf_$;G zX3D9qixM@#1B}1J!D2;J@r-T=5Dg%whR3f}(*4v?0*{J!ka#S|<8Syxl4mweYu#fG ze_Fp!7*N4p{`pY_;ohuuUCpj)cwn^ixpTAY!poYef6pO6+g?UM$6@yKG-i8vJ)WsR zy(8j<0C9|ZJmjYmv1ERHtqo80{^Pi(--hl(gn*B)H$c{KpiDxL7N=LbEwS3xO@ar# z!lEu3VG#csKf=XiOEO$_GUGV3ck#5H$TC;4G=xEO6w?~THCJIt#Vb#+v&)J+P!{xW zn`sJg2J=h^e!}^URgM=>Mc~amCBuhb(-ec&ClTSvwP;qel@exu=oYr)MGq^Bb@2ch zl1#jg1;m$uAW*b9i9-S?ob%Y71vl6@4~@jI>d305gHGbdMEvpNd3IsJ?PnoofFzY_ zP;|-9=5e5E0Yz+v?%9m#n)E7FF+Q=^M{DU8nuk_!0+$k(V!vl~xxKPT7hJVf(z-=- zabg6cD3Wx2cz-^Xjo-M(K^AlQ3>t*G3}S8^Ao`o4HSyz;!9T3p@Q;xnR?V2_O$G0d zw5AKAj{Nut`P|moXB7cOnv8J<4&r&tbY*R%;wYEaV0XpG*=1k(&35z=^);}p+p7=V zO!JnWMI=-SlAFtL*X0@PZGo~G&#%e4z;T!xp=U3!W+OpUrI%Ay1$4ElV%-OZp#}YT z;Mc#xnl`a%PYO#%br6d!{b5Yi`m@8+pJaUDSv&Fe8A})46d64rLL4$)&ItsW7;-}v zF2?Qo9U(YP6-Y*P zagQk=N(*Yb)-utECW((_N?6p)-3TY!bhg@SL7&>-P zL^58}Xht*>fmI5}Y*D3NU{u`)XgGed7-hf@RF@?Dy>eb00ouIyLCU+1YPlg|_g&Y* z*;$c_1-nf6tVLBK8Wb1I?yj^P*TS(3!4wM|`>lph+c7rm0BPD5r0ap*f7P9Tgke?}8QV<BMn%yzDxMqi3tsa|63kkS0Q^s4xnA#xbIb{r6g-Qe#>cZ`3T0#^bt$8aQ7C0zclF&I* z2ZZ6-rHe^NRQFwgiOpl8`jlyol%Ek)+UlRX1q_G}J#+=tiZCJK>zoxso7HP;)A>UM zKIf^PA*Y@f5X>ZQhydxHNf?DFE#}k95XMS>U0afLa!~{Z;Z(wteIpEM zCZ8aF2lgZ+eARFFiIAVES?)0LJvWE~Jl@?zhP!Z0^>+He`|QGie&0x``EXA5EE3?E^iQ?6bcHcunxq;$vp0;+y0fPjxv*B*jN<+&QhDQBbM&$hn!-Q;&SgPxW;+-F z_ialxH~$5I1Smprkicl1Z2kSQsbg222v2;$X?>h5Pxx_P*Z`}KipE?5b>U!psK)Zo zUW_nL6w!<_I4Z%GZt`lkysikg0ojIseeVCpY~QIol%o-r)mm6QB}2M3-|=f(w4qM& zh}G33LzJ6&jE$K>Ox;6mreVBeTb%1$`;cE1_e2=zj||VSqK*n(8gI{C&ViO@_v4nc zE`x9qY=Ce8mHQY>S*9g%(VQ8xs)R;?VGC4G2?;h_(m+dyqx~jT$C(}3Xa_f-z$&lF zr~FePg}KSOaezX~4Pyy&Qv<8f>k;_^(Jd4V-|K-{P432&!u(9|G52g`mhBgZYM(#i&}}>1gWM0bE$$VP`XAe&Z%6Skf&x6?I8~?2V2m z^gd!^dIlCV2$Q!_ThHn94V4Uo=)=Vy=@d%95kKxdGw%Bf%`E2}hn~*O+RCn#+MnWl zc9{ZXgxjFqE2yVD_+K&#=F?`Pih8YiX4+b7cpkr>iz)0+(yMKSoA}6n7Ur!rj^%NK z4LOQFOZjGeUf~W#VqSE|Mtj!@%_v--N4{&;59+ml1NpE-m&)qT9>aXvNjN=T+q|p* z9;jgIRSLRkQ6A`nKj-uwe^H7y@)Rpg=u6{UVKkQ3sgm0Ipdb4)E>_%`G%-8x0^(`e zMd!uL`MD^<{&pUb9uT#`51*tQNMXoZVwE*}1lRT7Op-cNX_zRXr#n)#E#t%mlkc~3 zaCMVeHabH#~kK%I^ru&K<$1~DwSGo^kW@4YNj{w0H)^2 z;GHBT{Y|eoY`67suS(qtN^VmVYp(ta`_t46AqGAY9W8D8g+DUpH%~a;x5os^75wVTdN z8fx(!xzzH&U?NBZP;WiC>lyAyh2fali84aq>nh=A;gxVanD_5v!9EZbh;)ZuW%{Z! zsMy$N;2w2l{|tXaKlp43a0rsO24=2z$v~FIx8kKwCu;`rhCfUs60?93g5=^!7VzJj zV56(VRqFVH6Z10cA8H>ntJfaqX1xv+mK26w(TpY%RaD$W_A`u<@4|{>_!IAqpa_aY z1VA@HjK`bPS@Ha6LOAf?`zeh&( zlRQ8kU51jYK}#zW#G?RdbI*CU_h9FU(qxn#!vC*`!o~XkLu-(dQc{)?{wEr!{GSL6 zcIN*@U@(9Gk7xk=KOPF__kXCx{{y0Ma{t%B_&*UC|AdtP0bp=`|37*L!vFXSvH#K* z|3NS$|I1*=Fv&8>{lhR6{>xz~0an&bs!XcZmjBcXH70c?4JOTh1cJ_gb&UTYD*ux= z`G098Or}hx#x9NyOs3W@rtbC@cIIA8rjB<1dGNnH4M#U))BjKmOy*4H|B+Uh{^29W zu2xLu&hEx`Oy*vucE)Wd1y%d_g6mnevU9q-49HReB&@T zkncNrR;G}k$9;CaB*iO0iBX!15ZNCzKR+TOqE3zJnofW@vJy$73|aa@*oAuMzy}dz`r0}9H2G412>%prX{ZnSK2V)+U{ucEi-Z6Q+LT*K));h#@vnSMCv{5?(121Z59svBc*Ae$-M6w^9#n+14=ltrmg2p6^vYn^U3sS@9oYaC!ZO)e8%wK6wS?VTcOqX*)t$;9?swu zv>%u*j{P4a7RVxCp+Q3V)h8L3P9}@B=pCh{V)6OtKJ!Cq!94)%Pf$W zpbMcV!8U;!jY|>`v_DX{cQ37fdr%n#1$(jVLLjt4&ij-$frgzdVGm&MZ9+1TA9N<@ zY5gxW2mpKru=b>-F(AO*yi&c#za6ltDRD6?@4q(w?eT|$V^$1Aj?YI4loU!QCSm*r z1)yL;fxUn7#t(&rb%C-20U{NFF#S#&O#ePpgT;?J-6jd5Irn^(GBgGPr@-w)f~ z%T|!ro&t${K~D{EGk6czPs3W;`O^SoV87rop=Sif!yoJsV$CKbkrN4sK2YrFyP^yU zEFiH@r+a?Vh3p+bhWL!X3TU*;zT6?Gd5V4?fNVF+{t{5ZwE=JZ=rRWDCj+5_=pTp2 z_F|#{H8u`J{`#O@59a%tWe$wTh7;XZ1$nx70X;W@+1%lxC4<^keYJlDj{*Y){1iVW zOoBlKx_T1Zr~_wCiQQ%zKk;E!-Oo!1&X*`L6E^^6HoHyJ(MO&C{>@cwLCzi1!hH0BaunQStU| zyi+(*5b=w{2A>OJ@6-Hlgmn|x833+{9XU}((al0SxRDzZ5uB@#PdY1qmObpQPi#$WJDJ#=*tTuk$-ya~jRn=R!aokB6Q6(YxbZ%7s`NgaWzt z*w@UgTw&VBPFp~`|Lf0gQ1Ym=jShIu#n!wR#AWp{pzCd)E1%md|B#npr>h$@@-M&0 z*E|x0=yDa+zRInnl}lOA$_6QUwa`R$M7`rM)0J;MobS|*ZdWi+7;YfzoA7&$a=9>? zBC>Q!trGGo+*R5mVEze7OxpplFc`&D3?Ve$^)^sn&;0Cn{pS1+_ zpZE~FQqlfTL*y}jK=~;T9>@#iYOMSBd*UvA^O6#A?@~|)C17GPLXAItBod>z@rT_x z)fa`rZDkhP+|wG`dTty~&Zop*MR$Rh4wffemq+9jS=OIv4C1+>@J5)`K5! zp`UMgzq9l$-`(Qpb&IbW7~}q6XS|pvvbedx=WMs%zx#WJG?w~0^q~%bcq%djuXn)%(WU-Q`xF#5^6Y9@=GwHIxQ%gju-`|X`tHeZJ% zMGtLzELf6B4F>8e86Uj z4HRmGQo0`C?7;eDRT_w$uqGWj7c(DcAkyP&178ukIkL?8RqmBQIhC@wv?j$rR{c)? z(uto|3o)cim}P;pvpD>YhE!3g^ro$~VK3q^SCT;({2P!kvlwMn#hB1UdkFVNvp)w> z*BAasp{hF}emn4>gsDY;kgV>2wVR03+wrz-T(y1NY?+$P_KeyI$&*7FEA#H`Ms*R| zJfOGey)1qyj9^O*>cAPBSm{Nn<2UBIz+SBK-aBF_S-wk}Qt=FJJ7D6umduq+W9)nq z2$fa{gw#x7`KZXST$w?<<-%VW{y73TMj(AF0vUP|3;@x)a{apbY!@b& zpEo_F2DuT=tr;mIkqxDHG^Xe(u*jsdg~~Tayc}aNfSdZDcjKwt$j@sFKf=)hILQrN z;Y8uU2fyzcViFEfgN6r*e!OXmn=FhTrJsK0vwaz+u_NRlq!spi(gA3zR+^B-{d~-v zESCB)hIw*Y8yI^wFI}f>6uQAu;3*A*w%+}OOy)&NEE9D{Jx;am*cO?$8eH1LmIP{= z>+p{r?-(*rP0Qjv2~~D>kMqXHHgFG6sI-<6+-KjCH2u=@VI+!4KvTwQRf2J8OL5Su zY29t5ISk(xQ2W~NEK{xiC5o#@w2}Lc{o8-=d`3BVo>M`5;fi(HUwH?d%;H-aD?eW4 zFqxgS`t{Z9zDV%({-r#17fdY`-|2pm*asB0SF7ex9Z~C~c+6=CgKqBpcB-Se3! z8&Ice5I?}bO6Yxl#q+e02Kh^@+iJGVb+3o7m%d?9MD{!G!Y;dk@xK(5a3PtP+hrc9 zxg6HDbRF7M6HLVenlX9^Kz5Gu8jXKMfA1XB`$v4=DSh{y7BgKC?E{{DIb za>=rpug??b3nqsvA0ni^ZScS;ua%?Wg0-CEpu9JG*KC0d2a2K2BDD^<(9Vko=SFqEje6A_W|XIM(_9qC6e0u|_$Pa_hk z2$s*S@?c?0YEZZp2Gla7DTvC@#GA3F!;xC_E%L_|PKHTcZh0HhGzA0s9l{fvNdq>y z=UJZh!%UU!>smWz&D}-@HVKI)-(^nyd~U$fDWHKzwJp2#BPy@CDN3i!y|fze zLB^8KDd$-Gt-ZP5&9Ush96HH*Bop)10`(8k(k6B`LTHi}u~N`Gevlw+g&Z5%kMD97 z%8@ONnl+-!i;<-ql#;|RhzJI0EhKIR>6&_k49s4ddD~HzCuaOi>xZBdeLDkXD@$gd zGn0;xIh9d!-Mx>Sgmv-FL%%vJIPaZ4iA2fl7IKOQu^p_ifs(a16^2Ja3O4Wiu#I@) zUEa4FT$|)VwQN7BHO37Z-t5-;TYj4^q~ho%xx<64^yR9WPy%vvQdkn>EN^)w_z3YqiVEzX6q!y1yM*fYU8#?L7xPk=-6ZH`qba? zW&c+{OXeLZG>=EYrjLFY-$n!=l6N|8-4bB7KwiVd-TFKv2_7Wro2W7IfW;p3#2AEm zviZsj7^&E?tjkKNtJFvr=5}q&;d+8#yjS9(<2fJvNNR$d+tH7*NseLc8;947FzL z02SQW0?WRRpg?srk@2>zp*N8HxlX2kF%_D??R8>cg;F^XDb_BUL? zDQAI8!~n_|UlwP=eBEtAHUs1|^{cA9mU9kME7hL~ zs@$9y7;%R90x>KG_~l|!@z*l*$~xgA<-{-Rw&F?M_n_bBm1K1}7g?zgL|zS+O;Wm( zsO*@d<_Qw>Oi(WFxc|2{x~P@<%-Vp z;!++{2o)ed&4;O7H2uBcuJ-&~R+apUJOSRYeS)03_XNf~JN6x$>b&yJnY z#Sge(N{D}&Y(a59Z$6Q6Ee^A!4l9|DweA|9$Y|&u!5Y6sYgF~Ir20ZfC_(|{&Eha~ zssc3lGdiS0RwnYiYM9#a*c2fO^o(SK0q`4HM{az9^?1^k>&>s@OZyvE&!7%h(t=E4 zE((kP$vrG#_r&Gkj$BVBb%j`g5*$l%0hD4}yp7}uaO{2XkEiUKcP7JI7YMNVEQH*_ zuZF0F(&T%8^q}i|oJfzq8;EcEoco(gX9$vw{5P_UFkbh(+Q3u$2OOy0EY7H8p82N7 zP1x<5@Vp)VM%G6HCcIz22dQgl4PZ}rAIn>In#(Q4ufuK|4)fR|P;^i|=gvoAzCc_i7oqi(1YN6w*wgfu^C^Oq{MHEB|TqP&UdP_VVcZv<^E z+4JCDKy?+*>y*2q**KGM9=A9;hir$4n!p?~`EnOyij#+U7lniGoug^BA%-z8!t)nf z)bvnyvNK6^FW@G5pEPSr%}Y6&(4wKT3Ek-@+S47R`}K5v(6dwi?BB*b)V&A%42>-G zmkb@y^4xYP1BWZmP=*gq537m<>dv;(Y*U}&U+9S~EnwW-YIRAD| z`y=CiKhSvG8< z3h%5Klm@udPs>aZ@p`)lL%*(luZV2nnoH6eQ|G?`u3xPU$JP55TNjp4O{!Iakg8Vj zZ-4K?fHO4XOv&Oe#@Px=dqSf5)kp)I&G;b@^TDzE@I0NF3C{~jMf>1p<#EoyvZSGw zvfi|s`8hT#_8#KOy{yM+?Gn&ynR?20!-c5ojpM=v%^hDm_D*53`S-tB=FxIV5rk8^ zj*PIS2I715anF0<#00X6GBw#lO4RFeWk~K}K6el6XNF^=RZN_@_t71>mA58z)eQe8 zWJykO4_)1N30)3jYSvcUhwrfN44`)}AyUzPDyv6`TZ#UBBOPsCi80}kv zhka|q1X3Ry>aXs&Wp+Xh6{i7ovD@`19?6?CeBH||TO#he;)DwJCgi(aCGoG6!SAWm zRcW=$JWWsvK2j;|yXgyzKKpQ_HfMyIN3FyUd4&=a@hgZAtV; z@OrQGKT7eWC|a8|V^9~z^zEC2PfMA0CZy!`@()i*2?llaO+}LFO#H$E-5Fv{J(w#J z^Sp+nwS#H4t4^ml9nVXAxD*q+rmfht9S)6)6tBR`6ccM_Qmv(V?r8)*A`DLMJGTOF9#iWtzXr#_Nuxze;Hn z_RWc~Y`py?b2^$5s@t?R3@d^DA;T@z#7u0zvb_jDb$khp=({B#{|ID%pup>k#aQ#* z_qT3w+`&bRgYnC-wgYH+J;aKU*#2i5Zy`zo!2Q0h%u_26b9oWxk@u=#<$0KqZuv*w zt;TtpQ#**n7RT-P=iMZrGGM@?B95#{P~`kye?1x2qDp(yXFsyo!nVn8m(M1qs2-VO z1!fW_9+9L#{&{Gq)jbx$``A4{L%JjYoz!9qjBCb#l|j1o((GMXE;y z9$LT~>oMTtB9^1;-%?OntK-dvYjv@?s-^7|$q3N7`T8@`;r&`S5b@den>{T^7n;i? z)P-TwU;=7&u248J90?e&sp)kj-105|W9O(z8gcN)EhmK$2h{DmHAV-!rxiFNt2{=J zD>>Ei-cSWw&1GF}iF(GnZaIr`EbEF)3Mn$}60M4dX&^OIJu+`6W9p*At?IvzcRRmb z6=6a7#U3~7+FNe=qll@OowkK2Ma{H2csW77P(`9Td9c~8qaBm)Y(MV6Sn>Kgu>eeN z1H^hvU*uLjWxuCZ&kdcbH+5VN-X?h(FoE|#f?1W>dOGEzwiQM*{>&N&jUsaZc?Aesb|k;ZEZB~XKo3jLu#!Bn_EC(hMJKn$ zb!My}gqJb~DI(3JH5{Xvd2Y~5(ZEb|faqP@_v0>~#(EFzPDhT>c;5bv6 zp}6o5*sAJn(c-pa-;`XzEE;2SX@=pmO0r`Y|3lQPwa|QPwH`m8&JEH6TXqRi6&5I3 zWu{_TKIe?oA1{c3;S#p4hh-`2=0>$r7}+l6Vb*df<7i_?bIGi!qtRFs3}P37i=x8; zHEt?##ncDgTA{m6{LdLLg^f6BYfi6&$rW{XeE%Vi?Vns5T9tYYV`hRe-ad)>oFl&G ziw?h%!BqJn8Wo+P617N`G^wXPgXUf{m&D3Iy=ey1TsCU%qS`*%%tn*WSwJNOJWgwYa&nr=b(4> zbt%-$euLToeqH^w=B;ivDzR6*Jv~u&)U&wpl@9x$;7cIF=8YobXWoMbx3ZC^0=WX9ALt-vpvGa7xqry&ON67ayY)!9I+t#`{6D2#y|=gH#(? zcP&L&4|WAO{EM~Kd)q`EtM@qX6oWeC3zMe%N({5Uf+AQbU-d56Omkf3Ia$GV6kyf& zxnnum)ue+0!^B)yo&!SG^ zW9ky&o9CrLn#n^6;#Z-Fc6uDKvakfz*}B4Fus%G+x~1@abx??|F8jJasyv$Kb9F9U z6M}0D@xAV(__RqZYt?SSQ*o}M_5jnMa1u_AlU&TQ*chf#Z%MlqHe;ndiY>{MDw>1> z{Ng2`r&ovsf%Sph-w9@}aFr%&HI83<29~qG9GTWY;JPNE1Y5yVZ`2xfh=qA0HkkhX zB2IPKt4PlG?MmM?DINIDZH+4>se`99Exas$3J)R& z$k1arVGpxCFEH=OHr_{dG`=T@@xi3~eJ@6vM$ z4}pRe?%d8w^(2o;PfPwi&w>`I&BggHwc2SuK8eIOf9jTx+_(j$$9r=MWm*xJW##1x zSAFKYCM#m_*!^Zjx_lPiasr81IHa zk#Y@v0SVvg2Mz)m*cs-w;8i+0nV2-z4H#_+A2Q+HA;d1iwP??CR209YB4TqiVMpDci(`?5TSUFc%p2K0USSK^km+>2>JeCqfx&BGC2y zoRGBqN&2V~9Mm0R-wwCU7FD6r%4&=R@|%bPj6c|xjdfQhdSGb&6oKbxgWU(;yi4YZ zF98D-oKvm;!6Qy-Q*M*3fy#r`p>OA&n3gGN5ux~qn_eAeJy#J}l)!?H0tqyQQ~Xty z##a>9G#{)(y|pMAskD@LbC_j2&I;_!aCsAMV(E=$LCP=8hDuAhn{>m7dM%993Dt!RfEGzXHa(J$eVD`gZp%A&^oOreXSnQ0U_S=7Fs98> zIPTV(Dd5;{83oVa}~PHOo5&|M0s+9+Km@wv>{E0l%?IkmFp{FA$B z#2$XjO>LCVQ>?iFIjwSHnWR}26eJkMF>;7&IR#D7oz;SZ=)@}!Zn+%J(wZ+vk}Y`n z+cGhWo`t{0>kymJxFO9MOoQ%tCSyscDur2dVGLNU|Ic8Zz zwUA0D-8h7S1HfHJ0JOJXt~U@sDtjx%P;C&eY{AncKxehzQ;*$bx{=@pdCs%9aQu8m z@p=fo*o3oHme=N6>5oj$4-zYjSCTXL>-#KCZd7U<;4VDu2p;{A&VVFXY?&7omLHvc z+Q)$`GA|a%S6mO->=+)r8XR|z<`37Kx1jtLsHn8>`r>V-kF%>Ne#ut>Q0dX*p8}1H zsof#LLpA0_wJkWXoxj0=`iWFQ&R(b;y!sB6MZc*@QY+^Icr8axP|cogT9iGmL%b(n zmo+<4+|kaA$T{(m=PkBmi^M&qdnFdeZh^9p{yUyMZxxVbs_;SRZ_QIZHER*!Ob?Hf zl(-aarQ{grt(k+`CAviiA=V+Gl6vD~W)Fko|9VRuND6Cj>78GobHQOb{9yKvK%v2v z5WslIr3d{?U>h)3hEu>bU|DUp5-Ba`{{2nfbM)V%5C*5Cv_k4tz7;zxXq9PKGa`U* zFSFVp6k`uT7lz1^mCTb2#j-}TdavUwif=3@Wj892sFoLBpI+-Wo)r4~MLBNrcDD`0 zr2fEjJAhDp4G{*pTB<76TAFv!f3GP`+|Dz5w4V6<=bjN= z_moxwsErLGmFmJ7A(psyJ+*pmXU^G%a5SYyGTMnCPjNeaRJpKfF3NIcXRA+OoOh$? zH_5DI+^y4(tuseqJRcu%)Hbs+zgFMED1H60-Q-@s%lQwM(xc8sPO}YDoy%AAx#!8k?-k~VN z=c~5ZIq@S{^&qSdD#*F(q+i!)sN|&Q$|C^_^REFkZFZ-vt*~{n&Ez%Lc~J;15#X~M z58@#99;kM96^)ka$ah(JlBPvKOzNSo(I48*DKf{6sx4}imp_weR$E2sr$y^Xl!&s6JWo%=`P6(EV5bIJHBSnH z*Def(O|^WI@bJ!g8Jm31ijtkI$f1rjU!Osurj=Vfe+S`MqoNopy}HRtM{BjsYY!RS z=xnnTL@ScKiSJ&AzXDj3qDg#TB%x?~rRPZ#IhL;{3Xdd=%0F>tzO@Q%8e$Z?A*#hX zC9XQW2Iiuve4l*co+ySy0;CUkneD<}H>!4v?gAc@#}e*C$X-)IlA=lsC6oBjpIbo9 z7cjBUh@!9(FPTT)9hCpplJochGGj__(hRF4o9Xbn^!Q-FB9;4k)l?5Er?K$~PRjUi zv2NjOxV`)CU6s6idJoEnvLzWS`cZk}oiU!%v#mJDVeAa1H9oBho+p|^KFm}Y8|7`} zgu;~{;d1aCjDA7zoH8~(>N|I;-3fsvUe6i!EFSh8SLHo_3E$4M>CtF7XBY$*ZA^bE zB}*$jF>WdvAr)QB-(?^Eh|S+Ga`R-21!}Dn7GTgO(HzV?3h4-FG7~Y9msK&YBSBN| zxk6LMAC%YE?k#up%9v%KL{7HdOMaeeZOtc{DyqpX69OwsB_A1|c*;Wt#3n(IutJ#Q z5$)NCC(?EkOoRgJT)G^k!(H?p>MZf+4rc^DomL0)v={^#)IB9oB^yz+XzowMrdQ?P zAIe7O;Z^Jb$eHn8o6@l^gSUg6Y&@ z4C^%%kKhNa?wr1r0Q^<$u0BD0iU*ti8iqxk19oOBce#sE(PlaEz6vSDp4}@WKVCb0 zWpcX}I<&Hk zlG6^zQhROrgJ2)M{MFG-xX1CG60e3#rFRnwveZ1!X=7cdh4Xv6p@Ey-HP_?WZ#L1y zzKHEn1}rOM&=IdP({hD`rb@4f)**ZolzBU*&gYWJt1(qywdh^0jpVt2`|LqmY#?@4 zWv}xa*h7En3hBbB3KhtVHdzt*Lgc!cp?8zS=uF;};JyOq`4yE$p4`9O3?@p>3UI4Qxz^8C8X3R5XPDi;uGWJ8o@Y=0yC@ zg#PCQAt5_=Vl8?A>wowtGcgw@=YRC*{}&zwS(_05FFnfk|J0)*|IDb;e?idy$vRCK ztr-7ziun&>+B5z$l>g}DKQ#G|Oa3<^3HU#WB-?-PMhZ|09OVZaGaRFgiLIHlISVl- z3m5Z$DM<(}05e-ctqKjO2~ru|8jW2h&{>kErqEf+&5c8X0iKSo-Px_#&$)zn0}(Yq z!p*I$a2EA8kMHUZc=h&m>A-DoF*9DUO^bo%*Ph1FsxQ&EMzMHT4WqmC->Z>wb z9?BB`Edc)p6_7g_i&7;o9f!7kWAB$7z#=dK4)GzZ`YEgr{vRJng?IGNM@D=m!61AP zSR+C7o)e7cW$Tx+{e}DIBj=5iRR^ZRV|pS^VF1uM^XB>lJ_2*IJNbLnIzBON z9yk-o`nvit(_dB}8q18`jA>sj^1OQ%D60WwNdsBm3@xaWIRjdtLUjEGPBe5m@_A%> zk;~*(`lR>o5{(V73qeH{-`kPU&yV30<31yA&4s>(Oc5QyukG#auVJsj1Y*GApr=DV z)I4qEph44iR7Z?=M$lcGNKDXv3r1+fdNmlwH}D&4E9;05_70AaFP>j(H(M}S326GT zP;Fpz0*m_8uly@S6T}t#&o{SOe+j|JV#F^TzH$2ce14j|Q!`3qqwl^Te>{EENe^Qm zTS>8eojlv+6q1jB-<}wqK-53j-2sE?*ayGvL0$m}#}4W_T-$>Yec6BV(|))Of93oInY?scyo2E5 zU4jLC+i`r~zW8mOyqNm$7<&s$b#w?Hs=s-ye>?tCd=LP+szMsWx;B34RR=`A>=8-` z`~i`GVo}cN;2*&>$^&)$*g^fbLsfTHBgFdD5(I|`|5mersdI60ehxjgXb7|qrS!ch z{O;Dt9U6GKA~VSqNIj@V+}quOOy%K9^U8Mu!i7hMLT^vJv_vEm$8O<5)zk|bFvODh z4Ly2;t1?mD>v4<@f$OJyn7jtIfS<#C5rg=^+DEs-z9{^3-iZ3Y>o2|F!2($(z68I4 zxo&TT-6=Gl=Yo2Mfb3ralSAKfzXD>7m%F#gR!;Qdu>M}&GCsSepdYreL(!lLoVl#5bm0nSS zZZlQ1yr+&fXT&+Ck!mqMJ4to23uyV9Ji&V!-=Mi-Uq9;(e%G|>M0Z;1Qbe`a(JZQG zrK zPF!vYv+=m`ab&vNu`;t>(!P=kz~RpDH{0Q^MFrmuDb`39{4hI9uq=s>X2@nut8eg=?_pyR!$5vk?k}51 zo{J9>4t3;#FxDu3Y`rs$i?|q1^E636vIOOqm`dn2QwA11k4RV^)Dc6OiwQ1XH0m*zJI~J;<%U@z^ER z^mqojH&OT1rgP;ZGR0qyAr07MUCh0x7s3%w+fu@*k4OP`Byl(81K3`q_}optai}}h z^$)mUxJP2I#m!SPt0Y}p>UV7J`l|g^O-uRA6Y2UvS2Q5bTF=%*0`kQ!|300}3I1{M$Et#-4k{)EXxyM%LY3wAhB>V{6sgr% zE`(JBXdd5+2h-F*0D0E8=(G9TI}=dy8a2Rabu|WhaI2gLLBbF$c`fG9a4#UA7)LQAM{6%rlGRF7_q7VrCxwsj# z4a=|vT2@Ll$+F-ttq|YtQ+RGZLAqTxd%$^A#z!JBkS=7~gYMvQq$?7xk4wLq#h+`O zu(5tycTlyHOE8XR?=7@>JK{_Pzr1l=X8FWR4am}~oADWjX#b^}tvl?Q_Os;(kzO4# zZ0phn;#qBT2DYSYu_F0`6-lWShyM!n7>H%Z;yJ#OWeJqbhR}{~CBfQt6rH^H?iWA$>CZg}{zG@4xiHtp+$d-P!e?v_m zeRlP>`&4#nyMa?G!krVfg=KZx7qZBs+p|enMn>t+cZGD|e&8cL5`AHsTOv}^>Fkg# zmB-?itZjCLaQfg06hqpZ$WGXE=)_R$POv?kd}p}a1CbI%$gn?n_YR~^SBZ-QsY0hB z)^?I2?wN5PTM&w70(E}KYS35gq<;7(0!y9&8f*#(QGg4q!N!RpC48DbY3b;1=}r)- zTE%y~GqClJs97mP%bc*m139Y+(i_tE2n}9KPyx-~V{}SoeM|?fq0$u6)G4p9AnfmL zfF7eCApdpe0e5yB@u|gUYmIqeabE_b>TH7!nPzfZ;wvj_ypLYy3GFd@U#IIe8N&da zM5gqmhZ{fB0+dy^vpNo_xQ^&J*%_W*3n!I#9v->*+@9Q0z%(noOr3PI*Wm%-B~@dG z|J{_@FPN0ISUE4`y`@cUQ5NP-Dk0O%Rqq)?It0=D2(0WIY*65c@W=T2VS9FZu14A~bHsqY66k{NqVWs`zXN>q=#k5zEIJ zR9LV$J7!jpCKj9eiq-ufQ|7hocJL2dp7U=+9TJ%>5zSKij4qYokd9nRg`N2RnZj^C zDB&o?(}6dKXK$_h4Rw{ne%}FYqF@Q1gzH1If1aPZkt~0#_>*#a`(4*5vH{b0rpn8o z6Zm~`9cY37e4@q)tP8{@yB4_H#Tl&t#UHwHElXn~8NFe^MgV~aY}AXoVcs|Xi;lNR zD0_+s{tl6I&C-Z@)|D@}y?BM@1%;fy-!En(tRh1&;U7L70fhaQ_ZLH9f_XWwh)_+U z?AK72hZK*sKn1Prz+{(S#usX&qHwXo)ZguFs}u~SSkA?k8RTr;indtn6XPpEUFb_# zu&Mh{*-iYFw@Zi|=lLrNPr6!TlLw98VPV%hxiz#1-QJ3q%$ zf}SCg(6CIfstZJYF`IM`TbfQmvEk;ulcwWR^8D2%YA2tm6twIG6#7^XmUY`&S=13b0&!CDh1?}p(>)>+P7gy@6Y5DmTMMG*pXc&SK4qAcd zX}&^UBTS*cg{&3E<@u2KQw&|8NWMr|$YvDP9B&v(9PAKe*TJ~5*gXLBR#oZ#R*rT^ zWl~}6)Nq=znaqaKZ6J5fM9x#;Yg^3yqg$QKUl}EA$a@%vSRu?O_JoRg8xvt@lfNo{ z^_v70GrIvanZlU@rf)qjtzam{2^~F*(&RTcq)1%Qae|v;9lV~KC+o%TF~5Y#ep4xa z=ozh@l3Qe#wAO^UaS9|T7J)slyyY$xR|bj;lfp&u6RbCEX)||)O{@fUzb;8x9_eVK>8yQq4Kj#*`d3^kIWABRzu7P2l^o1 zG;oqJsUzA$wgW{F$_!bt+HJ{0S}Le#m9I_Rl@2bYNCVz!XUOXoQO4xVZ@gpfJsYv? zR||Vdq|6?ekAJ}vP)Mmz&LE&db?dBj z8nKPc^$D0f`EivylL>kBpoJ7A|!-Xx%wZ`=U$sTseZ~`f00*2JYL6)lkt9C39eI`AN5& z4?|hOUHg1MXapuB-8Kik;PU-v4A*Xi5Mm`;zvElz&w?u8cc2OW{3!W+4&NDRS_|~! zF%m7-;*<`Vt?SVUh{48Iu90Y#{9Tc<{louiV#m*xOPV%Ykbr7Zy3IOI!Qo`O+1HW9BwLx7m)U+F!%$RtDLnL}vQ@XR%}3Zv;tq0tc^;oi@O1Tx ze%(U86PF&UzZ7!eJVU%a88s8TEuT(9AZLp>qmf-L+d68!{_TvV|}D6%J~zq zf;6rZ^v=l?vKLf_sr_Znq;3m;g88&oE+E){GLow;?q2J!gw)bhu{wEAx-m%k1doRW zmhnSjo5W&6{-&{2a_q+{u;;ZDia(j`X#Th+U9L7of~LNaNH6Qf{l++eRf2`43Le>?ch+6iRCS%# zx&_7icD+gYpsmkoPj*tImTx9%2zlKvTw;2-2ei@U{JNLSD!$pqvDAScd9~Tq-y)~YnVn^*r7T0)J06p9E zEJkOk3_buENLOGL551v8@XPm3iLm0oGiM8*sxY74Ahb9r4Gt zQ39obm{IG)h*n`r{(UmRV|@Bx-cK`0xwaynj=5l=b<{$EzpTUX*Z=mo2zr)pCI6yxxj*V}dumgW>Jh8w<^~C2nVfcH$~9@h z7f5XI*&(oX%Lo;nJLbBo7zzZhxK-WHWYi++b|s&*2sSGvxziM7

Z+qu6@DiEkYER~-aivG+1* zK`TixP-yqcHofEr&@|9UL8C6|&2b}*>LbbIt=H`{X~Lw*b+-^xgqQ7I1t6`7qlq=M z0en24+dAa}ZM(&!9BK^{{Hz^PJ~w60{OFyAq`@!!b;yhUy?@q6D$0ftc!GDcIjS=` zc3u#aPxt#gIeuH%&4S(CdH$xI81z#1+KpL9TyLuvnJo2?HwhM1xo)ttMQzYwKW_}U z`^Y~2Z6!(%ri(L!%U#J)!XVmEe%h3+1L1HJl!8vK5DcQXg_aCXM(FBQx{c5x@CCbOOuH?d8miD(vcjaZ1haaVbNcEsIOpg#FycKz9j7$)i&jd|&lOA`KwGh(*Qd$f` z;%Fsd-{X2TW&!?meowZwFKVs{F}Bh%G#_<*Gr>~yMai&PDNiSj-*AW$%hTy9>}K@8 zgmnY?!#*sIF-Sx|rGpi%JaX8&i@kn}&IQfG^fIo?>7`Z#s(?_Nwh)dq(rzrFaDhJ} z=4nm5SP-OEOFRwto3kq-nPSJRT{k-K2qGeQ#u!ye^p8YD?tJza{<0=3WmgU|7QRsO zUg##P1P`SRLGF4PI%?vCIsQ-0?HCi~G;=dq4#US4%`92JMFew3DQ-P`LfSd7s2#X; z0Er~3iA!b5-0uRe6(!-EkwD`5%~Hme z6f&KXaxSaKC>D0 z#G&vD+jhk>@4{~{F}tq4Y3_4kqvZy~7EDlA9v76}>G-t?ITY5mkh1AwZ#34yo`n|4 z_n29>HA(F6T#BVZx#JT^x@em-z3LY6M6-z#NdJIFnTkyAFjN+Msu*H`HO*-l?&-`( z5DHOmbTr$$>gq-_H$B~zz}{owgn~D~zlSp1Ny_BL?10tUh$Phf@XZENL!cb>`3WTP zvc)-ic%sPrj22cmM~y#uiKdx_GB4vQ}-dy#N&Ia}9nL5YRxiyPuuh9;GmM-qH+ ziG}?)-(*=5{($iy{m7ax@TJ2Hn4!xH0xV`{I$=S`IH+_&o zRrz*Td@^G1O1y|qyQ}0}$Wx=^{SFju^@*H@vjiV384=uCRFWuVz&|6`8#9PH#@xFa z9wO`+`4^}jel$wPFs5{FDT0Ow^=yxf!NDxkc{s?tE_^oO zE*e>rOX}pgx0HB3qNrlq&8}JbXv9l}FYHv*YPo&KHBshlV;TY)V^~lea1(07b|Gh) zy*3S6Rr>7%$q`@4+&5hvoS*>;kf4gV`SWHJaW^8Y3{T`t`JHnZ(_$;y{bR%R)k#KK z>#6OC@AC1F3>Df;=R06USqP+*E$w98g9=7@<734~T70g!L2NCCkg6jB#cvR_& zFJ|L!X5a&wkcuR=(c=ZJ+H*#3_;sh19M4z6S!~IDtCR^~>w8v1jS)!KH*8J_&#o0) z8-uw_<%rOw5-HJ#z2hENPi6l#l%Q4asKQr@wnzB!Atad9=rA&3gzJif43$StIo?4% zBwX?#zPP>2VtYPhhCu^%xgt6xP>A}a{(MooTz&>qCkIKmYj2F^F@RMr+W$ zo*`i@CvlVg&e}wRp#?I(BrZDeyD(^B&d;#QHYXl_l3$qVZ#4+o99 zL-W|BBGyag)dp%SK=U?9v)#hTC>yV=jBNqEL%r2isS@ZMoq22{F_bqBZ?f@Y8pWup zxH%`dTkV96ejO$wHXRXu!#&s#Tn~u)Y*2Cv^XW@ReP)7)X%zQ&YE@@1=lJ26)Xs80&~$s8!#9X(NY zLe$fP#RI7~#q{6v0ypZyW3#tj`>E(Nku3iRG?ELKjX@$wde;k9-P1RsM|MWluNRu> z5;Rj)7_e?_84~Yp$iZ6^tIG_Bh85r6z_cD-|m2 zyz+f2*uw@3vTItnTD^YVCJ*}C*?-e8fwzL$*(gd_mH+ff>kyQu`%mh5wUeU$;ZwgQ$kdYy7Wv+ixL~? zPizuq&Q-mAP6O!tH1ihd9)C~i(-6KDhjIUp%Dy@vs;zsQQfv?j0SS>tUF)0C z?rx5>gp>$~gc3@ZbhmVhbVzr1euG}Gg7^Nu_s&0hmiz4UthLu(d(XI^=OkBQM6$iI zOm4}*uG7SAL;a8@O3$JZpqIX03aqL0B2%5*<9NR+XAHjKk~lSeBw1`KPFLTC z_l9x3(n+IZ@tsfH^GMihUl*e88<8BcZ|X9rh@{#0Q+bS`@EJap!6&W?DgxduZn5Nd zMTch#@|R2sl2+dyK%LR84ILuOT-kTjKqUkM^(jm| zmFbVPGS5DmkAwPdrUw#h97^3bj(r{n|7licW~%WT-7Df(8_hH`=oKe`2<8k)E(*JM z!W8?aq`zvj< z9-(U*>MamUA?b{e2`8YC0?!u0i?7G1xj$S)LCiMK@aE|Mh*rw(7CC5-d6T3@%fG^j zwuhGJt6=}6chk)C?z^KEVF~%>s|qXQhc^pk?d?{89^y*8QgbKHe0)}3FUs>EwY{5f z6W@0^B9Kmsq~G2hFU%B|RP*G#X}TejwEE>;<>VJ>LtcGbls^1Mie$jV!Cv`WZEyFB zm-;Ovvb!@#o4s}Bub2v+u-?ZvYb-Ft-s+?5eUpfF&LtKytDpJ6gN!^wbO2JB7Y6z) zm9+j@i@UXJsIcVKCx5JcQR!%5tTgh@tjE|2Nq6B)V~Vi`_Qlj9u48z#589Uc-E1$i zwNO~+uZW=JRbT67aZK+4fSY!johlCZAH>|er#R-c>RsHfBFqgm1qVC%&t(#tG+|co zAMSpgV?L8zejD~p`BUF@N2ztUPI}S8*THS=1?XWhCdjU#{4PhDxEX~2zLMTe2^?z9 zNtSw24E#;5V*KQ{B_(`caik_9x$Nf3^gTmQ#ay8Bd2k;Ok|*9W02tm~PHqle)}9P9 zFY37v3Ik#}P+d9(8y=oy$XNS5b*W{bg525CLOHN z+}23nM(5Lv2DkD8os#g^9Uo4^Q5=eI6ddz7n?Iq-ZwYVNbPT#Jn_ezU)Km9zh#jf^ z{uFW(kE10I!V-P%vmGGB<%k^~x~GI=7`Ttbfiy?MX|`oL-a?6)HA$2bMY5knSku)c z602LJZST-V#%}RptCx&-g~Wp}v*b>xluM8gZ|?hGo83t)+YXuF3?RT&$j77LfLRVR ziY`{Wy+Ip6AQgN)Xkxu--&JQG_xQH=c-5h*a<$hs8lL&mNdVA}Mm3Bk{_%~j* zkLQF9-QSN%t>eg_^wU`Ugp@xHNV6$X(DDf;Yb{t$J`)J<5+FXv_?jis!a;xppkPBNk*HKD!_}Cn1jvi5{c0 zm~u3K9at1fq;)T)CvNN(qh`#u$)cx+OIQ+Lguo}%Y~kizAhXCSRhIHAGH%rKt*`su z&G0z$nU5cSjp4q@=;3*cfhZxeU9s|Y9E{y#EN!Di-|8|Z%h&L>av+mOJ}bMZg%OM3{=ulJQbaC>n ziqZ06*9Wia3knl@O9iG9hAj`=1KTo|HOzU^C~cn!H54Y5X1q~X>W_^SiH{YOwtJq` zb7u=u)q(Y;jgrEb9xPlI?D@V?`(=RB!$^H$wFzzh6hRUIG4DmFvDoR3Tb?E5G(WqX z_2%OEfrz$fdC#kx#Bs?I8{C?(( z{)c2BGXzS=2x0!8&wRm7b_v;PnHuSEnH&6mSZ6;u@bF3U#z{}#WC;(CIBUc5~M z&x;E%{RjUAxOt=%r7!$v_|5&_yr=sqmC;xy8 zUB&;)KSo$2|HZ!_Vvv$B&Bq@?j2B{xmRi<&=HJy3zyIwo4aE!b#9u;)zsKdS5iFS) znSTZbFBKLT3=?==SYZB(RHl#+zmT{vY~W>-{!J^Bj+u~}nE^xy27?(085yC!G9PyI z@lUBt0CuMGpF=|phULN!wM+=?#(xQpG_97UrL~3QkI-mYTU$8%2*!mDrr!4megE4J zBg|lSA#iDCWDX0JnVqTa6C+Dgr{8A@(^ZK`rXLcK#UX+4QICLsI2!t|WkN<+QjzE4 zWT=eNzvU5Zo-jk9uwXI4$^_$YW#S)$rDtRGKLqRFGs(zY-^kp^*6BC@|8W23@z1E$ z3V6H+U}aU;j}HdHWkI%%TtYz=v=e8#N(+J z(8Zu6GDt7gaScJz-T}dK8=>SHZ^<>jk`g#pRn@w4qOuZyI9+PC8U{G1`1AbRNJx#E z5mr{a)`%lR_3`_M186nc9k(ViF)?Qj=pPZT-mykhQQ?L&js&@cZf^&FjTDE&!!iNg znA_E$P;6My0x8@l?C$G()z^#Nx;Ujz2Gq8~Zy?pLzz-9WH+LZFA|52^Juge4Us(Uj z1bzr#wx_wEaSsnmCHi9u?u`voO9T}!!tQxghZlF7?`~AEa0&=vy!&>`^Mp_SG_VH# z;MfvwGf4f7h!n0NB>PLuB9Iw-uuM>=W3OC~;MoFDSu zBzTK=x0j;wBV>h@g90^CaiSnhpuWI9G;EUSit9$#?OAf zJ9#v{zy5mhQ=O?Qp}6|_`*Wv8PPc1HW_R!IRjZs8Z}(G06~iS&Rh&GJVm(oXGY8D^ z*`H5t*R5A?8!CIAXHOI438SiDJ>SrnWl!j<7T!BhL3|3J+@OMKW2Tj}Qeh!!9)@&_ zl^m32CUA_NcUhm)&zwul0=kFQw@v}7a0dtLqrR>!tZ(Pj#kSX3oK8C&<+E8Ybs+L9U)=0{@o)2Hna-O4bQy(~Fz1xdgZopSPGdDd0Q~A8-+v+vpX$q+YnH*Qk zZbzxDhd9|F@NmY^NNy0&w%ed%4V)ju`?U{m9%6W~i)>3^Ejam}xo9xIC=Bc%sBfyL zh0C?I`Lt8#ShZ}>fU@z;Jzf~MdxWF$4xBZ&s%F>Y=kxfda78rc4*}IoI1T`g{M2tz zf|wi$F8v($=52)Mk>^}p>>1~TT5#P*6AK}&9t`KtN8tz;2ttwJ3Qmz{uEDLI!6%5o zog=av*q@=e%0p1MP!3{;W(h)3;B1eP(c$2<&V9QKu6sM3y*eEYJ?5CS5x_t9VC_n) zJiB`sA2&`|T%CBn+?+KwHX091Bybo^AF`kMoV%`YzAGj)2|6U8`I`9t9`wE0fLt$n zJS`BsxuLb6z@LzWZQ2s%WNLD)?ZsH^=G^CYAqTPZfKsI=gYy*b#|s2FXx+RZs&W?r-@+w-A} zOru=s>3vF@dU!I-Iz`nxlxd-;w3yt6<+l7TjTy#^X^Zzrt}mp08C)l(JREylP^E=` z_VUa}`kv#4Gfv|;eo;oNQ&W7y=QwkCYmC5~HR#jw#g7)pTp}m8i@FIhsTN)Y6IU93 z=>6J|Hnk`p8(yULYN`fD8_=LkY#(+hn}*sht`y6+e z>D}_4+FFRNv{~4Ch5Q~GJ9I!-2wQNoSK7gFFZj^ zQA~C-_XeBpn4a;6-Wc`EU?;|1$SduzI;?g3I$;8Oq?3(0bc~q9LYXm)*2eR?vmZ@r zey_f5il~>heAV{`$Dq-2Sp*8UjBty0&lkQAd=Y5;FV?m3(E&75mfh|OA?8O~N9f8_ zzNkV=FormsyYTsBgcD#IdW6oOqQIv87WJjl9Ao@3X=i)P6VWA+014gIT+ZV2o^;)U zd~pLYBa5uh*LbW~nM)#rza{fO!F;m*K&L z4o@71^OG2clDkV=9VaMtSaBRK>5BsW4S`Z-%vm?YKUTdq3r8*hw5cQ|w4iHIk4&%4 ziua{;&&Z%Y9o3Ke0RQxLujm((p=b8Nh1QtBr^jgidz2etNt5^QhgxBO0tKyhK6DQK zgx$bBy$21$pMQ+8u;&}%oH*kX>lO*|^hKOFyzhD<)!$oDjByNRu^X_Gp?SpqQSf@z zLS>Tjxwp12ILTN;9oRe+zsW!4CvYu>cZ^tjX>cy|t7%D7e-#tEP+8wK?kD~+W}9q|)~n8Hu%3^knIbbU|DKaIcBjQ`f=(WOo5AQhA$ z6l#SSiAv<|KoTzZVV#QMPI%X;JkwOK{wD3P&4EDaVpewK4`}+$yTx5pwykxryIm*q%Hs=^p2Nidc*HS(y40yF#13I|bioOSc5<@5dvkiIOB8U}x$6|_dNapgZ7gB=^eC0qJRrqy zo4Xm%H8o)i25#g!I(J}k`8{f`rWUs2?;U!&1S(E@wAJj+Hn0*dg!@TNxnb#bvk@u( z3x?9DQ;3=V$F*cy>wK*A7p1ms(ww#;^oun$hi9Z7lKPvC?;7?^aEqx=Xp&Ud&Bte? zl&tBW;Y60tO6N47we+?&su*IcGRZPTpv%_^bV&H8a|2FpY;NaGWuP3v>J6Rgs)<(4 zoVlr7wC$v#*i-2?xG6lSo(UnV_t#y}1j^_z_VNyYSSg_t5st_F9>P2inR16`K~ss0 zG`R%!yZqc36di8DINALPo+{U7oX`;#P}kj$hLrP>AtG`4J%EqT z-mo=lHRn)ykr4RJa-7Q?rj_QdxA=6T$kXm-gx5pCuM-SYZ50}lDF^WxN63f7-p4Vd z4BaMFWt;x0gJKa^Dr2BzF|Veax5UkG7RE){D|-W=Ul%Fbv-cV;opT!V_i$6A9UV0+ zFHU2{&+An+|G2Nc+DY3F)_8_pN-0sTP)&C_b5vMjrEQNkx4 z-4Ca1&uD=f)yaHgFFt8%6Xx7XPa{#umLNf&dn0o2-3d^Qkk6l~gibUD?>OA|Eg-Qi zcgOSt?g%9|=f`T2nEH#@URx1=CUC8;%Vj=&dqN=bK`55yH&>47hx(K7y{EqQB+owG zC2z%SPSMis*MF3+j2YuV-g5Ikr&zKTJCS$};KlItl+DYl zHzWhE>DqS7p14UXcRM0!>s4fy9$IeO4d>{*h;LYxk{m~ymh3}p(~Zj3MNkqP zCMUaJL{dzNW)Npke`Ao2)s!!9iTbc>~(;;bM?@>{RBgB??W$NYm^0KYj~?Hvwl06sXsOSZV|DBFM7Cwzr( z4==T50Xv@~i{gp*BMRmmlsI<<`{|=+hf~vJnyp+D>Jb*u_J->$v}kD(tef8 z8*A%{cV=~9uPyC2rA5WxL<9D3d>PgvidgqtDU&}wc9(U6lLUy49ZQfDB2yY3%uBxw$mV8vc#Jdw6e~Y~_0wg+nn*$(8 zS$M0j{L$-;v+crW{Jp9cvo&`VYgKyjg2cJfn@r~R^0qIg_FT5RmG!e*c&5rtDQqQ~ z76_PGrxcS)-CO3Zw})H-7KHWZ);y{wWb9Utj+B(&3mn;UHz++CR~njJno8|1#6Mrw z-=>IVYtMO=Sw2sQZZ-dYcjUch*hfErbZwD|HG?0?bf~Kih4#dEmYN6^u#L1)Q?g(* z=h`ZW;x3Dzd7`#lQS&VP$@qx{r%>TD1`F{7&iTm&GSe(kJvWboT~EkOtU)%82VE^K z?)X9~NqMzQ^*SG8B45lojtEAzXbnWq&$r1>zVVCTd37+@7gK5+AnW)|F3lhWINB$T zkmNWd!R3)EnDc(Wz|$4&p&_6XL>+0|_?3+r{PCbC=AaXIYksqNPOK zk5xC*PL!}tWeRn#v@AE{Uis$}U`Mds?_+o6y%R(j) z!{fTB3&%sNZmSZ#^-{_`;CQ_geMrGt%lL%LQ)}tY?e}F|b`I(C?6%V1;H~di>1iVVl=W8}ufJhis}4^(+ox-&RCvR90 z>2@6US7&=>2&Omn=A{1<+V?1AXRm?M0 zTCJP!-HaYTj$%_?`?ib_o8D_7B~|*22WKKTnT?o4NBWhGyov!T!`lZtc<-mg@#U$e z4>xXbdsRUvoJEH_u-$^Iu?B=eU?&;M_h<&Hvfmz#E)_42dhRAq2k&eHLs8#8pkY_F z9Fb@js*$UXuIqX>n8~?W9mB6wD-Eb_Xw!AfJf*=E!F7m=U`4xGM1JpD2!h$B+_3S` z`>fLZac0);SL`!WpMBZb_j1bN@$jTL_=uAq!)F(l)evlpiTX-x_IdfVl?Ik=K9Vkb ztd$tA7agKN(x*G*Czmol0Stc#_$t`6U%^GMVECdf*#GO)IO1olNEOBaOnS^awCt)| zyHgWW+CiT)?~`{@MeD)6(K5U)aUJCq&;E$cTEvN|yxWV^T{<6MR&0;H`s>7M1@XOU$mqcn*WcLnHzeBvq+UGJl*4#X zAJdlB7!u+(`_9&SemD-hZ;l9Z&v%zc;wa-t2hlQQt?s1tZF}{6vZ>CHv-^^FSU%gR zpqO-Iv}oWn$yMcLlO)t<-%mk4w}in_fEsgyHj=m5CXhZbls+6&Y$ti0Wjf5PA-P@S zPCvE6Bc04;zku}F%%DvdpdSDJm)H>YFJ8w4Bd?zr%%_X(v(62_h8-^W$F-04WL?yO#8FweWco_ z;)X9@FlH{7tV}n}8h~?}ijNsM*6nbgSSyXQbB@6+-4iQkSl%3HZ~IFAsp>v`iLcTp zGovII!k0OpY6+e-kjyd;81~I0feQ$3e``M(Fei{g8Cm00R!;Xk7VzHA`j`Wk9cWql z;ek)dO@EGO*%&VO))0~bYzLH>1I;|wuLl|=cV|5ZGFVmb^*YB6ez0yjn%*l^vrkO* zF`uGbf4xz|$Z9usn=AvWB_oA!wiW4LHd5e3-m5V|jzT0yV`{~jO+GcUWdpo=ePnL2 zYk{iqaECnX;gs0T;N`>OD2-@3ZnZ8v(F7bY&S{{eQreGlejLzM3f`2y>zksl0 zWyH*C$8y^+PjkW!Y`;j#=OME(y{o@~ts(d#?Tq-NOL^kjDQ}EE!;u);5P5Gfmv+lt z3|d9!^CP+FV(}-ejusTq_GKa@B?-i_5=H?ox;|{Ht-z(4Z+&|!Hv?XMu+c+xM{MoU zPRl^|uBUqUHhdkq1t2fD;VziGp5^T9HWxUCioqj-f24A!z>(J>noOkr^bw&LC^01W zgSkzzrGY)7Kw=^AICdk3$Nif1oSt!p;h83Bdhm2gYSfE6svkb;q{KUULf=2KioAmy zY1;>`;+Y z4bjKspP4*(^OS0{+|wU=a!5kDk{pD2SS&r*LRRiWz!0O4`>N#nvT@iWpJdCmBueDG zI+_e7%W>CG{1tIPnLBhW#CUvG29R3{wjVBByjCB#!C-gVdy+-|CL45y_)&LXa7uR; zV%cJ}SlCA=)5LI}nJc2`oCUE&j&;7AIiMzxT89tP{lo)#{wla?p$oylI zyd~Xaji}I@F(HTIef6KCh9ae$X&c;v=uvi%#!GWE=z?j0Kn__o#QbPw6SnI-8)K)f zZT3 zs#+|ja9%UCa;PfxQS(nO;<#onYN9DJHv|kWJk4V7#Y`=8uNn$E&}7wtq?M&wZIw>8 ziW~;YqfzMrQKYOyD383Nzj3~0`*f%5x*bL@61I5L;|>{Wf5;59RkuV?p^k;CM#@7c z0Ppb(*38{qcS>trY~NEVk0fP!zqzq%t;KmVX!7B;P+<);Xx)Kou6!pWBqA^*=N63# zLGkpc^v937_mg<*kiAp!-V!(wKM}O+3%$o|UdWDX1|(5ICsuvGR)vr7$**Zzo6r|= zlVPX#b}wSZ?Ez0{O;2B*9of7ow4+pN3n{pV+wXxum3@X%A9nywkY70tG6*p#;CT@d zcpVPSwC`3*^w#=Z3xgZ4UNo1u@K@hXIM?8y(it&OyXuf9Ur9@ zEhWW_$bnH#janLs82Hz;z5#~DP~#TjcL*v7o2$oVEW@}{6$kK7O+^c(76S{6dRj9| zJq$S>WqcGhhGc^3G5BfeXfvQGa~3*)8f>faSY}E1&7)u}vmE`& zUF5~VFJ8A_e#Aw-F0&d=r7-w(iFh4rB1s?9*jJ!Uv(>vuKQ2Bmy|cN6X3~ziEG@|VtZ;kc0CQM3^lF9dh7$n!>!fiWhaoJss^LO zW5ht<&gv*-MP~oNZAfdFEqZBq@yzzUpz61zFWvX;2+|(15?d#H_?+cB*m(_yxi0yc zHIonGfrJHXqjLeAWi)M;9V((LL7(TTW9}s7*lzp8OGT{xy@*#m^!bUD?raZEiSiwY zr!%AZze;vdjU17LB#tmI-ZY4vz2~I-^`pc47~tuPFQ#bbR8(*p2m)5d5>@qO4qR%H zigS*$$OzH;STPW%3hd!fZsiC5Aax^ALSpLB*i7wAeTmIlr8VK&evrwtd29O5ss*oI z+v1k4q3U;j@gI_x(aOh;jd?{8w)urCCVt0IWl2a&kMf(zrme)Gk**|uS(ar#VL2#n z@e?r17RJ*{I(KC5%RR&N{Jb$aun@b{#FV8&x_y?PEzj%OS0A5#U#k8G($ze+%{Oyu zb7)qv1Rc=kL#&yZ

JyhtN4}JC;$qI2eK?IxxD;*$#_9uw4{d-r6gM6P&Z46+Hq3GloIr{Q}LyzRWM3 z(ZM(9M6k5n4GJQI&sWIApB9j#aS)^6`%DfQ7 z)z7P?T^bir23@Jm#Pw=Le(!2=aA+iO0d%*O51+q^hI*58n5ie=kqg8 z?yg&M5tDO@2TKt;Djy=M^R+!|w{ zL{L|hj7x9Db-+#W2Xvvj9;J)+eRi>}J?#~2^V%qmUU5nuWT`wkn6XheNb6z>53ZP3 zjp(yIZ3YFU#!&bSIC(wQ;x>*yB*8Cjb*L-suqea`EhUi(%a4bvh@7s+-`ubcv=ZS< z9gSEeI>DF3)MmQ=S&d#q-3$&`Rk&8oOfPhr)Bd)obKqq}X5L0qS@7yC`KKIcHT7Hq zM5ob2pxfl#KC7)Zsaq9Q!|=p{rW2<->s=bd;GH+kA1uGzc1%8fW5)IIQ?>Ql_!{0m z#Y%=o+4JN8gN#7=IN#nIO*zlUiSHfD_wHpk(^COcDW8yWWsa-h)O$jGffgyNQ@s|? znFJ`0Z9t4Y<>Fpp%I32FHY-!S$30!i%rCd0^iu)v6;&Xd8+^V83{}weWv^M~&c%{3 zHa42m>~E7^c(oK|WjI*TidP#;?f{>nu{zB|pGfR1oT7$u;E)Ze4Iw(~Ecr@C_;uDPH$G{2 zv!dQv_`(|Bko{?guysDtNh0dvgj{uchlMK5d2pa|@Ho}VY*Y!p%45n!9+eXxbLh5= z&wXm@7=ip?lWisp^+{t_bI-m}gFN@#B;Dh7)Yvbb4n+kPs6eoM`3=1jKN_@Bc2Y6&%(z)Cohw+zrqeA(#5HrIY8KBWoa8ySQP0`}KR()uxsNV2oUpr;jWLD}c;+ z0NeEFeO$|$H!Hkb9WTy<6t&k%?lG1)D$EgM^-5er(ew(-U(hl1BVIN|D%?$-vq2Vq zfN(ol3=<(ayN@PJ(Xsg{!K=!r`&Gdi`)PRyt=?{_Ar0Oi?cFTk)Rj)Fvs(C8h3;S~ z7h-_Oa{~vY)y)@`U4e5o$8di^VH4kL6f3D`+Hx$}i+D#gsSH?|*!rVA_iok_?C8vb zM;eE1Xg1`v`_^XaQSNJoA;gEMb(UatoI+mpsl6LAL|gfC+ksn{V>4ozHFaW0m-x0w zc;T+%D!EzEUE2MILIYQBXj=NMudD7T8rM;gmYBqbqrqF&&~(67yL6d5qEm9&<)wGk zB#mq;rphO*k9R?L;L9b=>Ov!8(y>NcWZZKAqO>>N()ZP#!TEv02A{1md4H0|pvV2h z=qj`;${pk1asDpy)fm%PUw@B@0dejVAEz;K;gJSby5LpsQ__UIl6!lPdt1ekM4F%b zm4$wB(P%!jk;c*h-a74P^rWWK9)3ay^$SBM!k;wv!Q8qZ`(zWriFuE6T7rv&cm0J%YH>(6d`uP>@P>EVjmsywoB)2VUnzqBPzU0 zBW_HKJDGL`9~N^>xFtcIvQpYzYx?JWS*Dui5w8!N&^uLc0%E~ROZ9oGug&^!+A)+D z-D6<9wdFxHt~XT{J15HRMG_TGTt#25+v+%%w^g2*_sJE5r@tw``Y>pU)VHIN$sj?S z>&i}4@Zv?*>;qi|RC|5{tv!kwf0oR=p*@j&Y0@5|C5x!Vm(-e67zd3j;JvIz6{%`w z*%Da9xGE8mAmHfXg6S4Ulxdf?pCHDZRLXROg#*P51If9$J*!0Jli;(hy?9?|b)^X?}GJV^3Ky35jI+nU@S+`IFa#g(zv`ithmT3?4TJ4r`dbsKI zQ4fPCMh;+!ZJiLgI*SfpZ3szr-Bs_PFMR2~bkC4So?~-(n|j&gC0Czh;C*G!1Z4Z7 zYDOMjyP_xc0XS2YiP54hOln>Xp*Q3#^1Ctx)655VjJj1L)uKI*Rl4el5ol@c3js*jr$$F#?WG%PmZ zUQ-qVUKaRgLHKJJT8fVj6nFMcqeHoj zGMhV8CI(BS*f1yYH5tW-dIS|LB9(Kk{_!-qG#)?X3UXP~)+pfx7S@iRE)2`a7fds)lK96U%Is^9J zb~M0Q4PtmXh1-FBzIG*oFA*t^1Y=W?sne|;Y7A^LkMv2TyfZcYUJ4=Ed)M!#g+g25?69XBT>IEw5Y_DxUmjaUiG^23J( zr-DUSgO{#aBxll&PQo6=ka7z?}S9Xz<6E&GneWn}Iz_d$`KHmM59dl{XNWShIHtQXl zCRK!-QQ>{0k_Z&yhr{G(*Cu2K5S@I`(P#L1^;B_m`R}H`!c}E+0&t4o%a(C?ACdv4 zfn(R6%2<+$WC0>en5pkdjytk4gbVc4ADwe{@7A|yMpc=+qHM}#D`d)jom!yTgGmWa zC?3d5bIQ2xQai3bW)i41bfyhxZCZW)Ewh&FX5JziiAMEOCOVZ21^Y^a0vC@;bSBw5 znfPzWI7CT7@90rq59-ey7hAfQ%O`39@0ITQ)7~VdZ3@N7<>qO0F3W8lbkPogj5&hrR5we8}b-AvFg-=6vtunQ*JJj1i6*c7UPi#N*utF z*!$hOxiM_vZ{{X$ZL4F#wi}-JfJ9s1 z=%upaq71gg$$O8(46(9QiIMlarkk-Pz9|)tk?8E^J8zx=ED|BZh7uU0wE^_g zLC^vIg+U3o7A+Sy?#BS77HUCGBw($Cs<5j!wJpbUyIFR7j{RL#<4ykDS^8MiPWePc zYNC~gLAf*vdTh?FLdGo8P5PM2&bwUIkk@0jRc*EYelJa-uDM1&i6lq8oSnK~%NLww zhg22ayX6k19E)>68eNKS!J`B_w;PzVcG&BR+t#0CwR!t(m@a0mqg%apH3~Wixr~BB1Ml*+37K&;i zM7H~x5A=lG=hCmFPO@-imQex%bdkbrRES$uV;=c_u#&Fv2ts@m9cj{DP3(|RGHxo+ za0d@@r$>ghPp(SizBs$+i+fQN-BK?I+<>&lhMhu>!_1$xW~10il(!QjP>hdfliCE8 zh<78~f4ELeP$FlSOk|N|ua|;+!;;KiX>&`Pauk`eFnGVULO0>=rc`M?aEy97oGs}_ zV|dJ8lIw40_nEGc^&In4tlLv&y3^;K z`=Eu9k&wU_nU}j#uDoQTivT@xl(pb-hw`u~o*zg?Fk9wrik>aSQWb&F_H>~%>$C2) zt#`W&52YHIAIbw=j!_}=yv|!})KP=xJ=E_OwM*@Ho{4JU;)4^skrE!{_Wjk<+) zNb&cbGFDI&`1ufc7wjKOa}4~U2%0D((jr?X%63t~V&fxou z?PThfE7N~ z224tqK77O|O6j}*^_dc!Uci9Ktkrt|DqmjVhmZI-1#jE|JvwndJMGyGHj=;@9=Uc*}&$t?$~1_4{RebuZ*Q>H#P( zLsH>b<3^9ZibL-ZpAN;riq8oJsl`&_3)I%O_GEgfh_0HqW#|0|e7*G7;t&0evKdac z7AwY-k2m;kK)^SiE|uYm+{&3^DZo*Kda>?py%N(hdTV^N6{S}@j*z`8#m93R4Ia?% z&k#C*+orZ|Ep5HqwK5_@S9av3-k!E*7SJOoHfQ@KKeE>O39}TW zd`R0SHrp_%aBR_zOR*9L;d!36Mc8X<)Kd4O^ajsZBlokcU!ghXRxxNA?$NQAq zlRm$fH$9i2U7u-0ZbMk2IL*uTb1LdX^3JHQv^b{MKPX6X6t2nE7~LiDY*TdlYBCP# zdz*|pF?Jui@AhSl6OgoH0)1&Yt?VL{`qJw3@J<21T;;Q4zW#tuDz8zW=&_25IdXo% z*SL+i7?P=*_^BntW+l@fn4iA%E2UA2v9P3kkkdOViDtE9h;560Gk#blKZwFX_X#Kyb?;yB-|1tf9H&>6 zmsQrY8jU{QAe+A1sI21j!5wASs4wO$RU+>bTAx38lj?V_pxnCkd_@lz+v!^v*~n{wY22q=4l~>Sp+(Jvha_6!5hBR=`2ps= zc{+LWVNbcc{Gcn3-LY$k0V{h|Dz^am+L9ns1h2XV31 z5yWSc-`*>HQf(3Uk}HowzkbLQi)Rtv>K)j|8C(_Ly-ogLyJUg-6_om=VyDXOwYkF@ zH=6gI{thV{57q!JR{3`1L|KW$ya+xbqX0jWLOhSAjkB8Zq-aGG(qt7%@s~rx*HiEx z%=_17DcasMY;jp}uIN6@mtw)|+?R8XVJR_hsBHaYFl^#{YKBd(Ug}hO*G9q5$mtxp zYyUC*pJXAX-^oINtdk{72Ks{i@-G6>0=&`^5-=KotkA!aCg`Dm@kzjRkpGEK@*52R z_?<8F8)Md1;#Pa`guVIyHYUHwKcRMgazSp!a@F-t#pePxD4laG!n8>5;9yr&|E0AUqN%x z<0UjqutvYofMH4U7aG_=Tt)-_MVf>8|L?*19gTp9xB`z73=Q8u#^!=wbQ#ShFuy_r zxp?+3HXmSo3;b`f`S;LB$%@E{Uw{$&QJSuV=Az790t1F6&TpZCRhXXx^_>{?3y$$E zx{IOv|L4u`p%GP37MGFxj^=__cm>Q4e}BuGOXCE<=w^STf&7T#FQy~-V&wiC7-4B; zCCLkpqnOYIdFwJ580+s!WPl5{+ON>i!6x3%&|J-$-xrVnEoTG;C8dNfGFbW_rW51$ z1cv3`Z}aIA6xf*kgz{rRf5qj$kI|L49sC^@;NrCiuo`_eE|5!M`E86~W&QX3HNJIm z>wg=f-)XoP{{Ic;2bMpwm+^wi_IH^9!^-B*xLlq~u;l&EU;x_7q}VH1{zzU3EUEs+ za&hq&6c}Cja#+Cs8XW;QuRIfL}|&?^F6J zVe|@?KWgu#5d!^|xmQ`4u$A#rx&VJ|!LF`Lzk|8L$Gn2&kJSAg3*=X_K(0iFymA|qlyn^MA)V-80;NMrsAC-t5_?y)YzF5Kk8=9+Iu`6i)NZ#+S0r@qNE>=k3 z$AS&HI;+7KhX07>%I4@Yn(zCpOZoeK9RPm9xw!f{m#*$*{=_1wWuRvR+YDLQ!S*e% z1w`_KS8Yqk{3G3HMT~T92vxpkDdG3d2bmwVvRf@uv{7+he1 z#o?#hzotBlz5nYLNoxyTI~_f1LUJ)95m`M&LQ7qJ*dNqj8VHCc3QHN0ln%@cVg@mQ z8KI2yU@8zD83;rM+gyrS=<;gW>JgIjKBEI&X%c0jj0ggLbV&W9Lqa+lW*SBij7U!Y zy=yuU1;uZXb+p#gzXc+MDFuN3{tz-ip|I~z`h-7i^h~hneDNVP|Jz1)QTndfKo>;~ z1pL+zCP4tXi1qIcVK(}Ua(Kl?cTt-!+n@}fiwN_Uij5KU+r1ahzxY5d z*3XO2&zoWL3G|GAfT3r+7?;cKAfP|*g)lO}lHf`^=Bog~%uoQ#^hbwK2*VXmU|<-a zf3~B)SS&9;1PZ!X#(uYfKnxc=_p3Ihi(TyZ`2X}61fpkVhGp>YH^aiua52*^+vu5L z?^U{F1A##dper83Y*5gZ2!cS2U?^;!{oUX9_=6!Z_kJ^8{3{qj2mP}{#;X89U`8j|MGaLAsvYMLYU!_4a`V?^=8=EF7hfMT;JcJH(QK~MtqoZTE8U;E!*lVKxXvaWz zDUUAV4{LWdt3h=146s>!{YN9`eUS7?>}#Auiv{$nZzbz{(86ACX~#6@e@FLLf|ZfAt6ajRpdX{?!D5($oKe z8cNS_@#XUp7zTPe=Bpkvz@B^6#>m7(cNrio{*27vKjtSB1JfTJGQslgDnMpNn0r^i zFvE)8l?a0A=pa}71JluiAYkC~&0u_60Q_YGer7+Ei3xILjKNUm3ni1wU>F!-8a#j4U`61H4W{C8@jd5~BaBcO>dQ7* z{bhu?eAx)I!5)3Z23uV(cD|Q7WCk()@sNvGvRwrYs}+BQpBZ{_?~nE8XA;7S3arat z53#k@f~m(?!+roFq?Ivp*1K4GX{9YJVA~{EYF+$5AY`s@LHK>IaB;y)sKN^6hw#z! zgSq*5z}$3nuzJe_<>qAuGckeb7@2s%4D5uzH=+CIHfn^horsOCmbLBoH6P5(0EQ_a Lk&y67@Zb7>8vw#+ From da220dca2f1f272df3d77ca869797fab2d642984 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 18 Sep 2021 09:36:03 -0400 Subject: [PATCH 07/36] Add the Preintegrated IMU jacobians tech report and mention it in the docs --- doc/PreintegratedIMUJacobians.pdf | Bin 0 -> 322728 bytes gtsam/navigation/CombinedImuFactor.h | 2 ++ gtsam/navigation/ImuFactor.h | 2 ++ 3 files changed, 4 insertions(+) create mode 100644 doc/PreintegratedIMUJacobians.pdf diff --git a/doc/PreintegratedIMUJacobians.pdf b/doc/PreintegratedIMUJacobians.pdf new file mode 100644 index 0000000000000000000000000000000000000000..02616ee072a30a63e88c2bee32de0387d4e7d14a GIT binary patch literal 322728 zcmb5#Ly$1A)+XS#ZQHhO+qUiQuWj45ZQHhO+nhU7vzxp4C#$TIO;Ybu=Om;GB4V_R zbgWRM^UEXaP|O4j1olQ&1Ux)Y^fIP)<}MZljO;9|1pjA1(TiEyxR^Q-(2Lm^x|oWX z8rz$gLhB~cRZQAs((&@Lupk0gC~aGF9E3_t zIkpUMntjZHKo{&U6;DTre$M|fKS(}3&(X{^ne=*N{PvO@yi6V5Ft(3aYPKY*9EUII ztkp6MYoN;plc}*f`AS7S@<`X~g}*#a~B=zM&!Y}ch)=D%pG@N-f>cHg6@ZyfUQc*%y)q^%TFm|J3wFS)0g zcIp_FrQI~X%EF1!*om@LzDqz%hDi9|zKmYxe|c(F(*;Gz`TEGBqP`o(1unE2GrNbY z2aP0hP!1ZMFM5=9g*X(O@_Ch8eSc&+bQhZ+@rCR(ZVDFup zK`eo-u8_cI=97=Mmp45R$&$K28nz>4xiy5!xk1n}Lc~bsDb?HN6yyh5e7br#SJ(K| zSwoy>csVnBQBg_UGJEeTD6XGJ*9S;BLNXEMz^I(GIweYs7Qw~D-ElFIER27|qPuZT zMMLo3(QMon%I6tk;@eRL*-l_!dY?*zsDnDlw0st<-t}|+_!2I zv#C707m{*ptWFo&hYyK0U?GoOrz%#9i#4>1qWF1fUWhbq_LU8T2Pm~buWO0-qvvDC zCQea0^2F=u7Mt#9*y40H+H%*#OkIB)?WEd*gMauH7`m1FSS=eEEx4@GOblgtI&D;2 zuDWTJkKw9}Om&j8XVWD;oysZsu{y5Oc%M}C{(GulD^#_XM7x*s=U&39FVOF+X^|Sr zt759EZ1zl|!H2z09Im++MIK+8{HLuQfM@&dQ4R(G1i-wg_xWa3H0Sq~fQegf;=m)^ zT#(P|2D_pGA>?&;qP*8avShT;X&$7^3tD~i^)D-q2n>0^)~TDk?rgRXd?zNbPZ1>6 zmxK57Y@ELo(M=6QMGy@#2*ZIcb2d(|r(gkw9y`RC zsDQxK)yQW$0+-vwKIP@h&0>&qFQvYxTHh>6H=`7?=rdEMiyNAcbSXGL7+5`KoF&Hh z;FTm(0cOTUr*NkM`IRgaLyBd72s)2@;h7eB=2@#UY4)k;KWj%`UW^8-&v32`=3wnQ zfCKtYA0h$UHhJ#RLlGo1v3##E@oJv{;wM|~;(;8*jPdgU)-<;Yhb;;9H_i7K_Xj>TA#|;0NE!K7ya~NiGU5zfn08cnC2fWb|=!o zpg&ZTEkS#GhA7n5t0CCzh)bF5Zbrd^9oEo4r;uLeC9G2CZ}NihZ10n-Ntf03;>oPX zrc%gl^wF17bm~Y9lSn;Rs;L?$|MAu197DKxp5NXI4vFhydp=&r;bO-|xSaihdbssQ+`lioZ__RUn@1bY}># zuCNmI($S=<1RUFc}Zc(uURM zBQ0CIS<`EA$79;t!Ns;;z8|{8kN6&K8Z-fcB>bBw0PbXU94G$Q-5XIU@a;4HYsA8j zvUMJ>XRAaK(^nmH9GPi@)-+rHVQCLv=k69PvK^InEB%b@}|&(65JN5RtfIJ$mJP9pG&P*3>T5Txb4WNTs zrv~f(M_Ni2%Q55ngliU2&*ps=R;g!iR^_F*Dj586WZaYKr0iXbCl}|xWdTxIF8I3Q zdkzK0FxIfo5$}OpJG%zk=J09P)tyyPugAmRPoU=!i!caHAVLhFSB}m0^yTo|npxLp z4K{rU=qzkfRjeK`EW_d`rculwBF&c&%(yXY>;ZFwFhfx=Dr1&O@qTXtUm>n|<6qME zC;No6l@JO^l$`EB)B>ThM{Z)4Oi{XZW)hW+lt_+8ACcHeEer?l8y?gi2z=#)@DGmb zkN_En<$&ez9(TQ$?LfHAybg(Zg3?jP6_XzaOUo;CW&-lG0`hheKxMTY5}1jUNNC`HR}0Dfj3j){<};W z34HFHstRv56DWr2`wmO@hdqVFvnZHzsT=XqHn4yMhnSgok=3Y2=7AZD%v>HAN)`|> zQDIU$#7?O|h!dO9Shz;oKS6j%#VU+!_MZNN6lQ&DTF8#6^CS1!!Sd;(Y+C(9v(9IC zbqZdyF2=>R->ale@0Ytx&$svG6*x?2==ze6o+*+hEe922Bi)iY${0E<`+yo)w73tD z%I$NiKY(;P{J|mL$-#hrSa29Nz<|guLI^wxEbC&lU_C5w902LNEF!Af5HTmWFW2sA zaPZtTB!*^H!RJXupFBu88mH*!IeF29ZoK_nXhkFVa6oAYkmO2n2zyRywsA1a%Shua zl--f2J0tpd8b%aDcbM*Qd!#BL7e&ForYUR zg3fF2kRg#Bj)8p-2eGjW_LZCpO?yTyAU%95 zFnIsTyjAe!E&Yv^9`?}q*e zlpyPJGeO`98nSHdz$g&w+Bc7IBrK9dHa)*iR1tJ*iup8UJld(8zaf;{mj=NjLus9K z+jYBM3~1YFY!_?7$*N7MHgeHO&y$L;)V2MhwuhJ=UTq#K&*Icr=tZ~E@fDU|xLVIc zTX5l1F+v1~f%1zW`r3N-9Y^V5Q7F`S0h#VqOCA$nr0|2H-@^NN=)*(wN!^)A0@Vmx|O%Vs2ah$P#9c8asNw?4TVir$>r z;?ja9IVe?|Nv;-W$mrsbh_oBAS$$;)X!@NQuBuLWTjRU{r$L>TW2%Z!O@$ij9^a)O z6cw9SsfeCZ^5UJMy^^Ic^}c>~#+*?o)>{ZQlB1rM*95nYs$k7R-=djqK~JN*mydS7er-MQy2TzP-@(VGKi0917fC*`n1ABcN6~WO$ z&tP9*@qX$lQ{3?8NJub{s%_Dbf4>F8c3MS-#VbF9%wtXS%Fy5urFz{w*9WHOEWs;= zdRg{<=|>af{4CvpOCiNGkbI!>ZR^C>Sy|`@Vm(%6OoYx`(li;g3dOl1O+>bX6c3(`%hPRwnDgXsh~Qd(&SKBmrk2l1&rivBC!m1G##;53V2Xbyn;aPu)={lKskUA25++^SM-%b)1v zjP^~od%v!f=x;OirwYu~)7BHbn>2Q>R~yWB{mp#*aKJ3=A_CqwX?+(+7+3IDpQuZy z^M;b=!x?;``EZJ#J6zy^x2vUo144Le=|`yPY!x*Wdd%(;)xO0y6QWo+Mlq$u_9drs zcRec#CTBu<9sWF_ISm3|j(Ps=%Fxa6-;SQUcX-7n{?~C+6hGz4ux=<$%ejwE{`;fA zfzyD2-cAJLi~;+ja-`xwfmeV5A2ZjOw*(tt5d4A)wLY8XKXC~LtLQ*jIPdk@(}=WW zJbXO^T~Vs3-zh$67LwOAk zk_~S0eFuR!#S05rPxQavpCf+&+!Zox|AmFD|AmEYtZe^t7S1?tbt3kC)fw1577qf~ zzw?-s`Y_KBhRrrVH0MY@nxSZW7K|n8NX~w7Jlo&V2~H9~PSuM{JWA7-$^;zW8ojmk z>H2>@9A1aD38CkD63aS1lpp|1W2s}so+3O`;iFrYFhNt30B?PR1n5p&&9S7f}tvy7nx8~(|bk6~I6 z+(cKmd}YV$Fj~qoqRD({^{M*|u*`;#J~W5M=oHeY8LQ>%2r<-NnfDebx>N`biKPBs zsE`l8kc%*xTJ@Cm?UJ3&Fr0}Hq8wfBo|p&;k6B1Lco^sM=f$;1T1Lp_XH)rO7C0{- z&)O<4y|?C?`}J^q&1Li_bt8Z}Om(A$0LG$!96GtZ9w5`#-cPw7i|?ZLsR)~c?r&p7 z;M+&Onfvj7HAHS}h$5Wl>_ZcSGHZ=km43@RWJ{zu^{{ z3+6(YL;uWlt6BHkdqWy)Unac2F%F>rK_=42r+yS<1P?g~cOiI%_6}(k+FsRTn!8a3 z(l-a~#b&sFkqg)>q<|aJJ=iIn_*32|@AJ-~E0ZJ_pH%AL#8O@-E(7SAfd}~vV6U79 zOCLJoizPro1l6>tsgz-m0jr0Z@4yKPUFnhZrva^Dh$+P9JgWc)!UT4dWWBIlbq`|9 zwRI zoXXfyGbcm-Sb8!`I+%Gy$<{RCV!l3}rWFSjQN{k}d|dT#MAJDsIt)*_Q#olSuaLQ( zfJqg&Rbi5PFF$QQ4}T!gEvuH0dD80ReC%&NWlM`ZSzNi^s!fC{2yidsgpsMd&Y`oJ zEhstHKZ!F-P*J5QbnmOq#9ikZT=V`lY;n^&}L^Yaj>V*@}R~kVlHclu*r)FczsY5FceX8o> z(VGSqU)Ih(Ez0>qtS_}`qElyj=wbw&D{|rUiY2>US8j?kMqA!bPi}Ro%Hb0`r*gQT zI3gfyZ?L54!o;;Ld$#nTQT3<$6a!BG_B8Ft3dLL=ylLt~A z^h^e_r(swejw(}LshvH~l~cJ^2}5c?;5%I-dh+ec-bbdAYJR;+bn&eRbw<`{pqZ3W zh1Dpqy~Q7NrEv%qyx1d3UiXa@+^ow+%B6EqM-|WxI|1xEQtz!rm}^3I#1){kexsBM z?c-{l(Rc5Qp&~lMpoR^OL2|q#VK+nL{R$*KD-tuNND)4t(`Qqms2gm**dA0hL28xgI2^&hkCb&A~zU` zm{;kk#g`h^7Akkz)Vd+=Txnv1Z)0+s)xsVEh zcFtBhb@o&_`Hm|*%bG6`y(CaATqexEL@-`V8*Gpyl}TkQ;y={T(H(b^=dsIM*|7s3 z_K(fma7f(Yv&0!|D$!!X$RJ;p@uZ^JpHd(P!oT@8^(gNWE{pdxRd$ls0ss)mweww8 z>545}|HXCfjUJnbGmg7qdCuRk7#m&#BNf7>O8hw@w_`8_3>iS`yiddM89=qoB@Dt( zXt~4hXTR@+?EKc)gT^^+pm*cWGF8Bnt>vnKzPfw5@J#<}{)UZojNkBt&W-DQ&8Tvj z{*?7n;OWp4`T8u+`;7jVUaPE{!}`y*eKJAyn$FsqAC-|kt1Sm=11bGB+C|Gd+iSG> zkn~BtTL$kZnzyp&kd&1V(NLQ!T713pkkmrFWV7**6xMvPLr80c2j3zMMm8PGA**;c zKu8=qURI&c3pIP5=)A(H`oZn>JqL39Ql|eQJmxo+3)%DjwsBwgRypOK+*XJa%H(gL z3%z%96$AFup+#pq^!Km%wtnhEb-P$YKCNk`Oyy|Pq8ok_P-mroR;wupnKmLXhW=U! zek}bOZ_LC4Cdn3#EUL)Z=^yod?ugl%&Oc=Po{(48^lIYWHf{p*k>GdW5s|pGOc*^Y zC(jCRAo`WAR#EP*cT4opk$Hvjv3a|%dnJHbmbDO&AoSCoz9amtQF&yrx%#L)kBV@x z1uwo7ClTo#e*_N|t;wH=|I`Q|PL*JPG-kuWM5mkEFhw3K8>>ejW^x%}K-X>3W!hU! z465Aa*`grG`>Ev;m)!_l-ZSnLENHSomza>cxeNRx-yG*5E%cLc>*wn5N%qF=ZOb$N0vUX)GchwRxG zf!SWR7mzHps%MYRRb8VIC{=w~o7~fM9a(Bep@OYX<45k4XDGVEiqjT&M*RbKsxn@$ zh<35HIDl&4LgBC(j=2k1}q=n!kX-`r{VGpX$f#I)q}_;Zo10DEA7hCQCXjVueJegOIDO(YD=e>x<4iUt`?lU zJlk|c%TR8{ZFk9aLIhXvbU!OMi=^@C(4SU1J$LG`grO~cuq9Z!QEdIZAmsAyM0;NC z`wT%G_Wp5)HT$x6=y=nSKdJtN63f*jEzgM>ueFAb%Km|uer1;Z7q4>s7q7B#GW^fI zD(#HTj?{al9&N8O5(Hqug9WZ$qJ)a?w5fYluPWIZnR=d{AVEpevavbz`)WHKgfndr zn$J;8vW1?M2^b(&)OTBl?eEv!`TpC3kYPM4k)-Q02?Edr##}_3l;2d9b)7Z=pVp`Q z^ZoPBrg;el)uh||kNT|82I)BjroDRWyUWIac_12_?5<7Adko=FUV&i5Z&9({}n1FE} z!GgM!Y$TX8N2;_LYSe0$0^F<{C|y{c?bE!NUT>N^El^UC^{a@Q-SwpP>YI+Ny>Jix zPm4l(Bw1!KT!=(B?j$5=c zR!n8y9|3Frtj(>`K9g`GcH2l*WM4E%Jf;Y68g5V;nc^P7+YqRi09Kz2RG$b{p98Cx z08-z<*ZYFddqTvcWyO`H(}ljXyH#Y>;wi`e=mZ6+F_blD=ak5B29a*Zd25@<$T?OM z#gdJD*4k-;j(6kKAa7swUS?lTlu@_?#4)g4r{*9Y8y<;L75M-$ilm!T1rJ21EWP-6J)Ztq zX`j0Y5xG0L{y1dWKM!ayi>M~{vdpPbtC3SGpu{wFi`XZ{II_#$@)7eVNAlkNG^_9H z^iJtJNAk(tu73|RlYFDC=tTWi!p|Jje-_2+w3u&rujN%r%T8vIAvgUXexxTmn8u$c zK`+QyIa@uabArA!7|rnI#EJY+_g{^WZTOJK+QoOMw#_*Dp|0g3@5nGnx3rwk6<{~D ztWW&2_z~|uJ5m7T)kjPrWSd)GAd3Qnbi+79m7atzPHKYIMICS`Nd;5l=n&yZ5V;*g zzQ+V8a`=c5mx?@jYC%!S`YqgJlU*<_-$yWRFCV}4Qbh`PxK>OrdV85&^{gJdn(=DP zj)ki+Yito~Ns%itGPRv9{cgY_3%>)c-`1x4fee>P=@2N0)38WdE7D)O#N0e3JImjxM) zUSANhbXrMkTEtRXWs)nA=axu3Ap&(+$ktt~+}^Ghy!QLrF3{ zCZR5Klpv@^`StD9vVZ(qnXz$|e4dsog@>>Dl8#9Fn?_f@G`qk*I{sDu@Otu8^Yzr2 zIhEeCWB&4C-I=zl9D5GXi~KBeYfP72(<>cYv0#fFNPo(-fpb3L zRxO^mczHQGRN9<4(k%h{TaLToXLoH{)rk_n+Bll=xh>mHzt#Rv3w@sbbISVY>3g&9 zONYPkuIa{IN%CV#XqAWTS`E0*Ng;;y8TqFAV5{-M8@B+dB<4&h$)5Sb?y3NqR@Nd_ zvdjREk9^PBNE1F+<29PZ)LQ4-lyn#WJTQeq_28E6v=vp|R&OyD-xob|dzUULnQ;v0 z_qgKTqRm(|aXCn`jdAzT!-2uFd+^lO=2a+toRMMx1W^L2cOOgHa)jqG9?3+kJ5Hqr z?1@Rs2{E+06lE(HhSoZzadJEx*3+oY5row%<&VwnS5+D4rh*qHbsV)R8x0S$&Def* zM~tXLpLs{Q1O1?Z(Y&?cew>#>yz?BxB%RC?9f5*y!_Ich20JOKVcK+WQI(=ltP9u~ zA!5FRCAMHL5Ct$vJ%*oWdxkyhcg+Bt6yhi@Pp2#C7W$#3k&0?f9KvtI|MA zq3khXW5w+E;Ni%Nd5;IprZ)1fiK*K?(K8&?q*6*^?GPt%`}CXJqD}FWv?ThmZkI?- zMx*boLl(o!mi1#e5@?IQk?Op)_+#qVdN(oIrt;rzXw;fOD+#?qdzg)<5y=T)8YDxE z^#Q?JU=JuV4Kx{1i&5a5^BZ3Vtt&g~Aj5+b+o(M;O>82OUHC5+#V{V1je(>Uw@W*O zYlDsuavm_onM&FjvfTUV@8K*2q4*v40$RYwNsW^gEL-CwK%ho7mT3y0gy1S}!{pL? zY4&M5#8tbhnW@G#77V&fiA(cf zvAlRHWvt}nWh{sC%dSc^3nD_K#&NpHmy(i~zB%(W zhJ9zCrJ3w;s~}zU4PpYB;m1U5(%YG({)y~7Tq1LlDI7I4}kH-BsC_XS5gRcfMD zNIU6>pVn#tw(NknH| z`(x=ubp4?IH|FAFUqbSqvY%w~w87<^W4O%%({bT`%JfaAHOi5H%*=>)&@+9xdPgK@ zde-MyoPn>bSgJzz7?-gC$NivO2F`fVXRpOL4pCa1XkZ*;R9wN(7zM0p&BT$hsQyuXOj4F7djuDz zfVoR!tPi8k#3CIz0G9GqW;r{<1!jZ8rRf?T!hHBcpu4~Ho$Xz(R;Stc9oaeiTKdVX zjS-jAKXJT0d2@C5IO0>2RWD{vEK=LgTQ&z%qpkxt4E0hcCsR!@%nalB2OZ4Vp_B?7 zoeZf1#mfda??xFof++~UfPQ7J#*WmW@MKT9#bjby)jSzzq4Cs>Xo)he4JL`V#{!1J z92-n`8O@ZD35g^mPIq&Bd!ngniy;GYO|n;sR94uA44NQWn~Y0Lv35fsC@W}5Hw5)o z4GGCc*3uXvHe%J*GsWUG>Z;6tYa81`yMsv7_6h`9tlStx-JC1rHX3kus_Fm$M z2NI0>KtszP17-<3?M!Jg)Jc*$8Qa|IWXw*cbja$hFY%;Z^%Qo~EqWA6nIxpu`Jb%a zY_#f=8rcNKu3A}sSf!8TF{{P}mGW5lFk@LuJ&CjOb#lkx=^R-ENE5*chuwl?1c~oB z3qWiKFD^`3vbFray}uX-Fu`REH}s49V`Q)nVGC8b7rlZ|XcG>bwO*ZLuh*Hu^S#cB z%SwuVGc;j@OG8GaF2|dnG-5QN7$U-ju){Bw=k&+ft4gE=a5L;@uehxT$3itC>dP*vK!1r5j%CrW0sRco$Z|dQDSlr zvJq)R6X&{uM+38Rw+ECn7Cw&xxr=5;lwEW$l8Y1Vv)VqmHDCitqzc(>J6;Hinsp@J z{PXNEnc#ga4VGxZFgpsfTlVn+7ZEBj+jKM40Q*Ml$QRzS0w!|B zI?V$jErrUFd<4#Q>X`i!#=<_hocm*%D$(VQ;~c$T+m8y+9y2``VYU%IJvtH}n{qrY zKG%!q$I|ooZf)~sHyE6l62PS@=nK;*u7H8#l!F#eF&9;Rf1n;M6 z)V&rJeJmcQy7(7`|LXJDF1@c9!tM2HMf{_}{=&UwdNE(WH?`1fRxi$O8t{%CZzX8a znzzrs{tYmm)C-t;MN&*CY!~+n|0#<^O#9mc4XgFZm<$;L9@jzFv^_Rn!A=9zu2Yfu zJi>wPtw??JyQ|;9{uk!3{1@i1vHgD(yr%4M*wJ>bsHwOiGt9=P-T=S?0g^)8 zGaw}VNq{LD10kWqc{{HLs2V#fwP`o7r!Gq+R!@4)w$ZP$uA=ICT|>-w z<0)(XsDqRLcXO69omg9^kJ`8MJHy%WW$I0!%!)iG$VS+8&F-9?6d4%NSa`nM|F zPH33Z!5kmTp1!yHgX|uM8#5x<=jZe!FmxOxZK#y&%2-2CfZhS+eH~gY*2`RaFE(jC zGU4(21qf_&`XoaPzHLRz+E5#qIS6FZIwc0a6gt#-PytkV%N8t41Npv8`HthRh+8Qp z=F+Zj6a5Oe9EO55N;7#QS)xE`^^o9Lff_e2%ki6hxy*eK7cT#Ktkvj80MkVQeT_{}L{pGdqp&(^@Hwu&f`Zld zG!!Bc6vVc=oUtykODq_brMRQ)rU4Sy*sBOaa9%&_#r|=S&FOw-+<}(*C(yj$unDtq zHk+zzvzNIHq?kd=9l5&*i zCUNKLCa6|=!L06Ci}=#ydt&L26-$k?h1S`^vr71Cy|q?r2hUF8^^>Rt+i6D^WvU*6 zc)RilqOE|7H9(=sLRpbHq#ESGw)0t;LE7q<;B8^wMnFb2VskW4 zb2fPBLl|4{*RpODm}K(eT!Y1IwKB3rMR3T{Ih^>EhQg8b9ZXP<+&Keoyv{pO=@4K$ zA1iBpc0&ABc|cGT@eB^DgXCf`GEf-1IBe>1y2}`L5KT244e(l-Z!CUoc6WEzri66b z-7TKq-&3T{OINpdch}F+L&ejAJ$&5O{S`jGU2Y}+Ao+?q{-3VA^OwWl^TR10%$J6r z>sx!w@f_qKN@0<_al98(4HkiwcrZ|6X!zE^=1cLoF0_2d{Z@eX8FhqKRvSZXM>DKt-Fd#C9j65`fkWCWyJBt;pF{7R;1TZyL$ccS>M`i_dO ztMir04qT+r*rc76=f=#4Q-d89>K1)hOqm`jJS7b1DwtF_X~o)(3|d}CLb{yUh|8}= z#acooc1dHU(@1sY#6)GLJaJVfI`!Oa<*4zA$ifVVn1c=bB;eHyh*n@gV2kLyQmlvg z*ON7WKHz1hnFI(>5CZP?n@YHL$Bkz=wK-9(cSv{@yy$kkB5gho2Vw_=LsbMyHssZ( z$5rFK+A#oK4xWQ~a>MyGKpGqcy?3C$wWwy_CIyY9`$!TjqU=!wfC6?7IE7cP^NzF` zR@Me5E3?{O_e|Q--yHN&si3Eh{w}u;~lXM9aT`>k2Qomqa~+85*8Lm=MV~AWDdd>MDBEsoF`K zjS};7&`by}?{@8iCL2aX7Z&Cg(tpwUL2!4VSk2dw->JH9A5vq~U5g9$o30r^1WO~qcG#> z%3&boK(-i;3XhK?!(m$xk)gdxl~feF?G;JM13&S~D58X%fDKy!ZcZft4NkdnPG!zK zs%?uoa+;k+n2oY(C6^hSiM(mtIa?6IsvD0sp^tN`KFQ;&zPEf_6xv(5qe76ehwE7YcNq4i9^(B*hy;KjDOwS(GMI^N8s@{~`7(I|r|lrrVl~n_KtY~7rg*Z0 zr1czTwdT07`YWUy)oA}{(f}OUlr^>TDrZ)aTTZ;pY^ms{3Ey>keOBNCh^9c)rWtyQ zh4T%($yA`zlxD+)^UJO_kr=BIdTXthrn;AxtE{W;DfS~Abj4}Ad@!w!u>@prre&_S zdy5@#<=c=;DzruF-bm5SADO5$B13!3Eo8Xb;QpNwYK*U?tN$iKQ^-2ZGFLOEw3nM( zNxoL=I~AnBr=ML|s8{dQpZ-$_dSUL(mJbyw(P=WUoU75Jl-I7~!7W`RDYZIpr3!YH zIRH%S;eZeyEZ80urd2OI$d`N#Nu|c^2aQf8+#)Gm{m<$9y6~@@1y~W*fBUkbrwV+k zvuQi?DIr?k_;6}4sR=E)z*&+Y%PtNWF3ADqw$ztPO{0rFoRTHaPCbeR+Q5`>;Jm#y z;}YM->}hzQv8Tbl&~nF|MFoJ9sF)0FUZhL7D@!{4S~>XeMYJn=2heN1hSp8KgJ=DR zeY>C~a$?b-S>LGuss=u44{$Ac0{i>`7Yc5VQoIn zmhxzCW+mO~x0NI3yTuFcZ&|`;>WTw!+xrqN!34FN9xRY$H8RB3T`eQ^oucx_jz36$ z`S@zs)l;RX^ZNXD8JY`OmkGskmSMfiW{=hK&i{1IKlESB%Kl%>%E9(O{%f+MwG+41 zj_9}7H~2G<7HDHL=~{NPua~))B#Fs(DuUhO ztC3pK*oi~GFN4spv*%-JPGuH`5p&9{&7GNwgi&aQsRH82$*n8%Cslz-f1E|O6@J8f zAViYQxio19>(4ixe&2p!A3SH-J=Q??_@i94DZIKAQr@ypt5pE`V(yw|Mn!%B zy2dk8I^$UNN(~caT67WR14$o$yKEseXvK08a_-o|6IY@CsD1^V0o__fTmxiVNmv8)7&NOX`riGh5(KgiJNPhJiqA6g&>Ob6K z7ADBe+kMKoFzi&45*QD{!DsH+>*zo=X6C2zUhovBjABOSrFwo|Bc6J^cqZgtVO*N= zegtLTiQQbdH?nZE)2lbKxLerk&0;D~_1Y<_uz8B+$7x0DIh>ubuuiQGdUsdxxKdl$ zXeZEt0T;J~4%AdvV7diP*6Ee8j5kVY{72gFA_iF13H+|@5h#sX3rTiTVDsey=Eqq~ z?$Rp18CH3{!Rkz|(srZ%Wp6>-;D9v!N7J8zX?9%2o`xeH&+)C;PPae9Hro!WP|nW1 zIB&GD>Uf6;Z@HvNS@1qRjaKkl-an3$<;eMg5GTeS1kBD~Tda0+LU+XW(!y z;B%Ma3Usqpyc==9vV1Gr<6GH5E+gX|B& zr~MSEYy?zZs>(Hi^oC(Z1V9i6+?)q#1VfY|()}2C$T@3dWHv7h0LBcXKjg~3Mv-bF zPEcGY)X}Uzc5p=zE7n9L}Bo`|#)ulF?$3()b|CXuMpIX=~?k z-JMSMX$;Fok!A;ApW0}CTYMb2je->Ht1ucyq72gQnl(@5U+z><<^e)*1o9-0{QWPW z(|n0W>E)qB-BTDd3n6N68>^`As+~p$OX1tZP&9VP!D^_tT@+LlLV1mN7vgpbBv0rr z%zCXsZy~`113^>+-N7tsEvmNt#_dDvJZy3k9Z){D_x(MhC81%4W$6QwV)?(}9HU+! z*5OhyPG2Ybt?ue-!Z%fjHdP7Zs6*WpZs8{Vt6TI~sNnQAT%U~uZ!d~4t(vU4%UytO z6XG3wE!d#H*6dO6zHBjNv+Ho7>$D$*8!!e{>QruP=2c#Y`idQx7qq>V-c*|bFpO7V zfdrpH49VesZCN%BF-*iBl1qXc_|yJ**hYi`8a}a7BogKAr9uETd;G{!fD@GQI>ewm z<``Edr@P#m$a_K}6O5Uzzpvqz8!{c%m!l$BqXCwx!HCNB>d2W!;PgbK7eZ9|BZ&x!uTjXc{;2dv?TzWrn2ZnRh{_nW0&-GefnL~}_mz=MJy z4LggqDeK8TZ%WUOkU}y$ZhLo8vI_>>!1^|JFPQV_UoP+4sXh|UH9#qR zy}1}pBkY5TtR+`I7b}Cv#Z>PIz-C}jS+)_jU+)Pc?`>j)$lQl?l_Q8*@GT{@XcHJ8+^He4Wnt~#_){?v0N)<-m3s5h zUw-JQm-fk9lGV4p`|TLSNS(8Q8772S&gpz$*U|fN^XAeTXs_TIaCfyqF5TfK6jWyQ zdV6}u&VN9dKj+Gixcnsp!|Gk_9KHZe#Bv94&sWIj1C&o%Hq&ZlN7Eh_f3l}yZ zD1`vGH{!6xeZ`fC>)fAGVDLfLNGo7uS!8h^ksy=z@>2-Inb=_}L;6%SOoKEgj4x~g@XXtLb;>Zh*+kAf2OP5t=)|sHM z?zD_)=!kA?2-|o|Sit!3AZ6_upTh_pFe)sRAf-;uQbNJxrq=2N+CnL38)74;+7O{V zM55O4WY@k{yMr~oO{(9RaB~F3m(?Xi_y_vp1xm2CSq=~(V6oWd;0x85|0ol(eB1=i zQk2TO*n7n{DDD2aAxs{Y^I?(_uIL035=JBliTxy4k2R$F)eC-dpuqa*ovt?169ZO1 znIkNE{wD0vxCtoJvziX=dSGqL3X`ybCK{489&C4u7_4a&f1hkRg|rbHvbf`1?n(F# zEukEK=R49=(c;0@279te{TL}(_14@i;%0;^qJlJvE_3|xRv`(*VX#lxX%=*jFAEJ) z2Qtjr)jzOg2c`jcE{<>7JS5>Kw%`F zC{NK}0uRg(AbIi{z|)Et{IYZ)zM)Rsr_9njY+(uVD|m^wSNkwq8M!*kLt`29EWfgi z|8*c@c}`((`?9`014Cccr=U&KQQ@OgVWP@1ut({)_1pt%S4ULDJMlpI&JFKTPNBrL znK_WM*~RPL!PW}ZO4T>zF$Wv|CX->JtIe;6>cNZwajARS?kL`mB#(N<*!`tumnxgk za{Y=lQ*!ZStm<k1cLg8?0?MXZ3MY)Y5^Vbk6vvYLq zw;YrSY*!$o5F-K88C{t|GRd}BGL-L8wWM9t2lUgm9i7yK#9X_%J1H>UyXls;VNu=Y za809vt^L*dk^knzuB!i20@dJOl*ugkmV4s5g{=gc5)!7h7CDnx?;4P-ldJBjet zTe9PhAmr(oj@9un>En~ZN5YIqCYw_a$>XsN<^9hqN*-)p=Lz7|;}7ZYh1GYuu-e2w zkv6m_7Kj5Er*yZR0N>vXI!gCGzM>FIAb<01an+FqeWD>@%p$J46rZ}De}K|5E=K;Z z{AOYLFY=p-^M7WcTxm=HW1%4Yi+bNm5YD>o#G!P7Sp+h_QQaX+ix>G8~DnFWxY5g|u$zEaS_Hy&O-;$R>{ZHE3(Myq`EF!6Rb{v6D#qqt{ zLszO^gGy?GzlI&gZenKTPZ2_a&VasJ_05X8`V#*%`^wGU)$x0^*H0K#yNCBXNKW7S zKL--U5ww=%&tE+u7}+euWqQRBMRmvmKsDNz4y{ut$uyHJyc0Y13S}1iN_U{;$$vm%?>& z71rMnDa*2^r)F&u=ff0xuya?W1=t56R_w?QQv2g&kQ^hr+MKm4$18n;%wjAUw~2j3 zTK=CO{ZUR!7)9|d?k`K38%u9%su*-vO$kXzMYeNVkDzWr zVHm^M^c{j-(fvW+bw{3)G3!l!_KMXT~W)r z@sxB;%IUC{80{Gia((EQP$Ps?S`vg{dFa%#2&1%#N+mL-H`rEI3ArV3Y&RzR&X99J zD*-SiT!%3SB*6KR99zUdy$icAjV<1&naIH?rI86s?YD(V`111KTz5M~zo#%5dziKhbofv<#XN|x3{&3B{>5YBF-amV3b2J z@#Cug)hRSk#zf>cr-FkQn=}GSSWer4o!M+)ia=u0#5VSXtO~!5L7pHEtfUaWL%wkW`=XuY%s(SKN1DhN3RCNG$RP{pWgbU(c^fC_^alh?K+_ait2($@rlXR{|8 zb3^1nP9qAHOWX4{49dJ|;u7g}R-Ty42!L-WfyU;mmfb{7xYTl4c=|Wyb@Fr`Z@`2} z7j^@s0aFAdd*&v@^e(_xWOVrJIV>;~WNu6uL3MunEZt^5xenTxcs6zGWp7pga6Vji zzuP#^X*xSL8yvNrNC*V&n&wFt&dZ8LVkng)N(w_XCq8CjubWgws`s#{_zv9vCS(yMUcd$Vd;m z#wY@~Yo%Za)47SFt#c?=1qg?H@`~o|n3-m9|H zK!o!mr^@WfG{iFx@_WYmx;96_4O7g%XWZ6;)ul&bFL>yynR#m6VZ|hJ7%&V^PV;>` z5_ZUldWu5=;wvgzernel zhk-Nzqh9N4C45SjTX_Zw6}ApSzrq2p2)GmL8(~34()JiMMqq<7E{FWVptgGA^Vis_ zW_WQj7>!Q`;{n5QQ&CP4WR2cuTmp)3q|{#sohdDb^)DN`f$l4FTRX6H#YF!;y{Ft4 z5co)5@`aC*A6I;d8MfJtb%>6-6rC> zSP-#j;^q;B=v*(+HGYlo%_z)Ptun5Saz*Zx?3EA#3BLax*;Ci0Oo zd<9pX>bW2f2FGOY^A?DQZ$Rm>X;^J~J^rC#Lje2n=PP7vQRtem0h>2X26Gvdl*d+G8KSMf0>ddfHB zp2EwfQIbL@@&TL-CaN`}1JPEghAr+EIaLe?TUwlR=u4-szqy?0+xM?gncDdEZMt!j z$EuCbx4>bRJ{Ld0VZ=jW67lwR?w#5Bza43f?fny@Vk56bbSPckDa0TfJNrKN0eoiIMbbj%hNhZ&4o#D1wGXpD@BW!ixL?JY3L8cK?#fSBbI$^7q5ej6G zEv1uS*=bPgzN_EJHhw){arK^_44L5=_MM(CYn`QQpA%DE_@P?0NZ1NN_RhM$Db|kB zsUjUkQ<$quheuEW`09&voHZ8xods^3pnr@k3=~gbY3?@zML8#W3r2A@8aXlFJY1i8 zdke;KG-QH`kpC^}@7zZm{#)ndfA-mwze7OYG3{=ZH#i7Nn%9i41{9y=YAmw;zMhQI_a`&Khb=_J8~*~G14Wk05@+`S@T{l=oEyW9_${^Y6$LzS+n_4FDRxR z9}VwC^D9m3Z&ms>J?#rAjAD<(Ylr8*O{62XE@jQH^(~C@ zPIahYmQ1sM*)n51(bpQwJN_3L_1|tWSr{1qSA*e{)<*0W_Ls!-JT*cMj-TR^A z1~87}m~nCWOlUlhG~iL3La0-E`ON2?&EG{|ZuEToEDqTad%KBbWx|G@Au%3&85e^y z^&j{QeM!VVg0V=u*uhS4@)aMZRMr%ikbn9VV3EvU_HLLlX{Bay-__#J!JtCs-0gxr zL8SgNJr;d%iKA%aag|4fg4>m2h|{vvr;H`_qA$hr71J=JYIVwi%PWht0d;2)35?N? zlxGrh@t6LP&0*1KT9^ezg2=ttX$isMZFYkUn7{OI*<=p$AO*lIi?~MN=y8U_`l*); zZGs>a@*uRY29fol2#U$z?`7qxcRFTVMxL0=5Uzha6tegxIfdLN)U9eKYM5$`F!N@@Wb%`{ zF!di1-h9CcC*Q9?EoBjbUn_sJbF~b_a~T1kHnhbYV;=j2C_R=FxK2gH?vk}E-$vwyF4SbT{u)x#|RaBT7@oE04PNLut?uaF^&G=TToWp?SKLzkeyW2-9^@Z9gJ zu8Jii$1WP_9Qm*Hs-*6qOLtW1PBQf z)KzM4P%fL_)q?kaw{G}q*uET@bydKa3i#0uN$JzM)wkLKtxA6`>%?$qVY? zjxdIHhDBIXRLAu<^wpCP9kkl)*+-1S8VVj7sl;w_qy<4@u%A%4sWm5HKP^-Yo(J5H z%a$roH8pqV($r9^XqQZc(5a|v@a&VL=uaE-Pqn>?bP$s+)PtFZ-onn zC+6r_EZ4U0K)lKa<4}Dw1iYI#k$KE@Cd@nhjnTA}8KD6JE2hK+xPdJoR5)%df^B4M za#>qMk|+X2(l0N3Yb!I8AiEumOX|_ zvj6t+e#ph{$+Q5sXrZ7)0)CKdTH885e!|Y!I`Ho$ap2A5T}q_hX|Hc@(KY*NecPCF zf6Agfr^_Z8Hbhr)>7ym_hgr{iXeo0Ngc4@F#(Jd!Mu^5xv4iAZA{qWc+72j_T71f8 zfBLdTN^Dg$mS^E}B^RBG5l_%3jxu72>Td}feWeyrlu*&VO>i!-AO=Mrqj)EKuo7G> zgAl7?dRJjF$5VX;rVs&v#U;4}qKwVoBUHg(uvyBm&d-NvO_)QmD6iwiz@Mt~?T7Hd zl9m-+Dhn|mph*@o%=Z#PTZW5FVz3(57Tv-*j4XOHc^;gD_N@PND;o6%nY9tOW(ZH1 zXSumoaB@r6g(||i&=f&F60nIR^#$5jQN}IXXv1>ynogp%F3JpWEN~4aSy@Qj%>FmO zi?lhS`gq71{xtCNoOF4nMxf=5v1nTmnE)>+8jeV{*j;doOsy4QG%~H(75bn3ru5WoxbTsapzeV2hmJ2lNp)puugUyfUTG)@ z<>z1PjJ|S#e7M1~WkZ~rVh-hiX#jCF0dyFp(*u>7} z(;`T%{GCGXz;&}OmosF$?Nv~IQ5PG(2xu0BVX$m?m9?0(VLFm`XVkDs!6bwhUi~V z%(AnZo20#A#kzz95xqWRt&y^frg6}BbSEwZaI}>ooRF>5VHR|6N9)S~?lP^XUf)>F zKIeA~P?Zy{ZAN#j&Wo2xg}=>62K)B&^Wx%)@5 z@9m3w+|<}zjlVBT5V~vKgX^M=Us^)1xB9By%Km})Z7ah1e+3)se?uIy{eLAw;x;&t zx?gH$H*LU<<5g++&>(9u3_wWIC+x7i$4r3b*BcJRdWtuaWS(n#eE%eF(n>83G=HAT z5KHW*uBnu1JT0jY75H)Re|*PGbl!r?xP4m}BZR7vF`I;{Cui%M;FJAi`tkU`d|?++ zfffk_*?{*4(2IR3#U=s}w+mqYHUe4K1CZ7)j27L8O3!(-2?{Hjj$JX5C@GT#bNan$ zs(-k9=mvD>PVLql;%yemv90^c%57?pUSM+LkH#TBX;Lhw|Av~ms*waX3ihoj4QTV(P+gxYML(2AgK!BnT8(0Fy)kc2^%%QOjPxu1^ZEf zzZrnU_Kc5M3|Nz`k;yPx0Maeh;Fv)Qsl#-OP1HdUJrygPtk;SzACB1O3Sa(#Dk;zN~CBkGjfULhktdp;k$t=*Ud!t41>xR0S+9S+yL;PMj1?MmS!Mak8>VSP;;U zgM#3ZafTu)ri4~ zp@~gBXeZ>X<{iUv4{^-_qf5Fd9OF$>YAY?gDL1=Y`MdcbFQ1f>Tw zbVP%w?8owqB;9t-nshP@+_UA zij(Ilgr&SkjtI@~N1|Jpt=+=!a(z*PJlKKL;0(E9AcNH>y1C+_hvQF(1oJ`)UU~lH zuaH7}Ytqw`sSkbZA|(*oXsTAsDPgs_yd$Z-`v_|jkCrR?2y?TUsJ(-C@3}!!Q#I?$ zyXNufm~n}f{f?BK3X2Y233{y6%EUhe`EG4$E{53!LJvUH6=>-Q*so;1R7R@1%G-(2 zltjqmOj_zgeT+aQ+4TN(R!GH28}Rd4>5I`IR0U&p6vjmD&R|y5k%%LTbW1AmNI<%`C9c@9||z)PHKNaXI)@Nq*_avAA6I=hyi6ogX%VvMv zdDa%pdDh(4NVbv8@m7;V1ChmJi!0kS?9}fIT#$Q5bN`R<0p+tT>p@?PngS5xC$;8e zx(jXsv%k0qJPv6)%t|)eW#d_5^?eir$d)G_O@{13q?qz++D%8VC&x=PEh|Qi@Q1?zT!-M@Mtcx_D5Y~BAm)g!{QQT4$iM@&P;)K z4MT4&cYEfGPh842;Dy#UT`dzgx=NB@$&;)``9d8QA}QmE%ehb$dom+Xei4}FX>zGv zU-dd)sZO;_Yk~&OmuSi*gD#F@CYV@M!FuxMQMBIogoZx^Ye_l_z|X62z8dEz&O22E zqEdBY7U=hw9m78z`@8590-h=BUX|oAstEwPx5iPfSZ1+b$;n9P@3CGOuYT`{c00|j zm@~&d=Gh_Q@o!L#%tO{Bwa*j_i6adK z9Uih2Fp4oNDx^Y|Yx}GctpG*q90k;wqrPUUZJw(&&MOg)SH*BXk)UQ|#9 z*m}7*W1z4GjIdDJ-vo1iKm%>Un$6|Ouh!F`<}h1dFQ6?Z&R~<-k>42K5b|}2cX;}B zrp9(JtrTw}5kp=j)Od$SEa>ATQyF83sockY)2MHhTR=%9x^xCN9kr#scNVHRZO@EJ z{yyK9Oh|tfHl7EyPb(x@s1%zOPrc+;tFctY`4F^XU6&aVQ`Rp|<*@O)w%{7`bOj2$ zqCH_May!y>9gm9y5ZsVM7nZuLJ&?p4>#(zA6rjutUE#vIq6_3G*o{2s^gS35%vkTZ z?qvp)*LU78!G2;aM^81ut*TmsyDVkUYy)J}6*IhRKP;czb+f-~l%5LqOA%%yN(31C zIk6_#g2CU|Ey;s`!S8cmVa=UKWBM3`Tw{dt6+yGN|Clywsr%+l5~`RkQd~qO0(^59t<2V3VCglHSC zo@a%N`uk63rFEq;9{g2P%z5cH&t8T4odi@#omkItP*H;jT*elyb+yzY8 z66Rp5d$V%~C+{A=)g$4%MtA>B2+_5%E8(|K{bE7eB04nv>$D2d1vzs9UBAp)Y|63A zE7m3Ynr}bPr29y;3%| z0d*_c%KC6*vvP*6i)5&8rsxa1>>< zr1&e*Kz;pz>F*-PJlC|JiFDyGDIxqkoXV;n-(|91x|bNJdJej;QC(#)T|1oi%LQTe zh*D_L*-$K$_{@;%#qgeqf(Z|QCYP>>JnLUH!@`VskW6mdy%~V>K$vofo=UIXf50~S z3cS|5om+DScos2U1mL2L;GAcj+;^(D&*s>B5X&GzuuWr zsn1R1K?UTuCg7YWlmQ`O3v10}DMb9pB$j$YYD3tEjQ^hxD0tcoVn!c4dk>OpphV1E zKrApl8LVW|5G_CQQ=P^sTccOhLnPphPTGP1Ia|cSjw@f5DC|3c)XvF$9MkCA6g)Yd-IQoB|*`)X83HMqL0Vj}3tP5%szKnkjn@F+QqlTdZNq1U{oXEvAKe&Q1XUbd6E zp=H)7aNtNz=@;;R1$iD0vf4N>3tNo#Et-c(5^`t9$D$k@h_oNE@XP;MW*oJOdDaT% zkUFQOMND?20G^Iu?OyoswQ7 zn_Ojo{}mdPx_*zS86AboDsHSkXZ0g_(I3EQC3(&tGL?tzstA%9n9R(8pIJ5}W4p>s znIc@Kd*7)phZU^3Ws#Y#yaCU<*fIRHN!O%+3&-bOerObw(jl+;2}qwbf&{v z&wv66hgoiXSKM_;Q(4dg$;!-FrrdpOD`iq&XeZ!c{)^DmKRyakU<15D*W;O*Zxh8r z%a5Ug)skb5T~Pd+k|_2U;F}0!LIO32f#j|SiE9e!hDdxUn_yhsTK}1;S8{>v?V(7{ zF%|L&oIdlYX-ySsev0Z>e}d$nSOP+8G4N(}MWu+BCPar-BJTky2b;iS``9lO9$LKB z_I%wA_uS$;5L!*7;ju*N2T-1V_*vyg&^o7dVT$0V0OmTrJV!JqurE(EqboP1T?m*U9_Tl1}3joSr0vNVfGk-R_^Wn%xPJPvF zjuRhpJ^=$Kw7GYhrgKp(zZ8gt3EDWWC*?_$goM6v+02sFsdhOG1v#ycOgj3)5u6Po z3fKTpKGbalgyWfsnbT`~Tu7X#dL2QU`JfTPhbkSs65c(o6+l31_nvhIj=C}Zbmuzy zu+h#+I*(9jnN91KDSWN}^R<@-&pX-s6eHeq*9AJDV|;1+j7p9cO*(RIM2Ks*b2uAl zWDUFle9+3}kkrI#yRoQ2fWP+ZDyP6!ctq+j8y%2MEO}zgt8!tZ48LXWldWu}L5}+v z#Cm^R*mn??r+H<^x|n+$!jv@v%U=Q`DS_)Jhfei6Ep$`}I>8Z|Q-zH75PriiwTNaD zp0hy=f^ThYV|u_V0io^XW;XEW>h6uJz%q_r{11Wd`YU6j!%(j!1Hw#RlSUU9cx8&K zX+s<^MtESf2g+XWqF6w;b|mkUZLGrVid^AORMYL)w26HK!5#r*#2dpN*TMmgPn6Q80)5)xjN zAxx!J;cz+-r<>-^Q8QF9ubV2m$13sN?+=-R47GHn@@J%VHawAwr}=W#0My?a{A9ERK1aaPL87OOVZZVvJb;|iYWvYmuxn*0jxHsmkbjL_QTF~7B z8}L)DV|2y^gq2ZP!OU9HeSMF>=hXWEzTZbW0HD16GF6#GGq2bb@{X9T*3H1~fb2@p ztn1}|cxD=OT}56My^ETaipql_I@WrCEfM}N05y#yiKS0okU$UhW*C&jO81gX5mP4o z(B!2{fAmL|cmuD4w@~jMEJ+DEM%--jkJbn+54O!55j5#bVuC zh0<97A1VlITHy(YCaz!cz8a^Q}*K; zI+vEd8oYV^wmAeG`eO#$O=DB)6qx3hgKcL{h2k(rm>35wIcV@@OI*LzLm zm(#w#c8=%S=Nx^7rW>j>sM2vzXe-R0x~ZQIksS;89R+Sfeb9Q702=`>-l8`)N|vd} zc}xQ7=i1Wm@bPXp3?RcE0Pqk8mN z0;4tglbbz9Li_j;Z63WQegh5m_Vh?%A@E#1t8dnfw&9H9qP-m z?$mVZU>5>G5oe};DFd@XuA7;r`{+=dO@JK*QcB!=2hiUSClPjb9<#;<7&Vh_x-jAn)r3QL0Q|iZaLYIQl>EqeUugU}ZT} zrJ8W!BXIskYH$;^^h&aKdHUo)gZ1=EwK*+U0zv#Lkzx!1%@LLw<3Y?4F0l;4uQ7ce zD{Bep0#ecB)X>Sp3tdg|F5C=F7)*@eBDzDrgD7zqw`grZ3=T35bf5ok@zTFh!6xJ7 zGEBcQR&*TH7d|gb9vb+k2@W3dO@yS88USdqk}1BOydO`XGjwNL9ns8ZHqWGKoljQQ zv5y`}UHl(!m#%hFu0_6za_BRNv^qO{T^L{%1IG-N0S1^a8wLTQLOu0V!x|8-JYYTyzYp>{siZ2N8>PHYVR zCk9$k{M_iAb{m6@oo@U>YkD{N~MbA_2@c_Ju<@kuH0bCuE z@nO=CQFk6hUQKD^(5Ig&))&r9r&vGl>DkZS_4RShr~8}J{m9AZ-~A?fR6Hpfl!EXA z#kK&IKS#cIS3ZuMnw8_fGgV@2bx+<>?D70hiSQFBU4I`pjM+%|-;^9=3LU!nsPp&~ z7IcFABOY;mbiH00ap}pWMt>@g_r)dgKRjn%ZOujirSJ}G6XAGVY zi#kalR{x-~vRw{A)8}l2PWnUCQz5DNBS-=T;E@#G!+~7?WBqt ziMp4sPxRbT8)u?pAY~MD@j^diGNI_N?T*;REEWjC4XfiKed_VDFwiH=Hh>xmsr8B= zMS~vwh&ThGbw+toKq7K6;-(N-o7Ko9Jc1~aRZ?)D3s}eSAskhsfK=fH=i;hH8L%ew z;r7Vu7zmaS0~wh$#M4KVLGp0RZ6Vubk`}~)Y<`^XgF#TyW2p=*xdN{B>1Rmu+g%sg;t!9Qd(39-B2SP zsx8y*M%~TlQ43BrIdPz#g$I@B8TnoEP)J#>cqOoeFJVji!}jc@vZcu4 zW$>cdbFXW*xD7CWEzD;C5uG7O=ZIPmR6lwm?@2^|PT|2g$_OicY{#_Y)nC64-zGL! zFTZw6uk*nc8+)IL$AmnktIe7#oRWO)>*-TV;Pu6rWJ!+qklpZ}`S_|G=^;u9t$~KzQOu>d0>%`^gz6omw zhxH#}(Bw0w@X;vqWDFIL!mxAg4EVFul&TL)f3kV;x&P$3%VJ8i-sun%q^c#&s#is< zY6K+?u_05l57jJSFif4``ZxtQX=kXFHXbvM~@d&SOfBf6KN&o-YnQHk$>lJa^Z32C8M1k$dUAD@%4yHy3Mw= z<$*)mwnaZJIi*CG3s^yAfudghG_yF`ec1oz;%_88+O79=5h}kw1?z&1m7Bd;nuGG{ z#{0O5iZh0wP$O4^bBNx@MC?dI&50eH{<(@=f$|qi;~zlH37+Lj5x7_+w8)kU^s#bp zoW5q<$bAJK&7;I7AHTD$0+4m217CD5f<93P1s@UhL%I+u8mAOrj?0qfoz|7A%Ve(mo1Tqd&T zeG!sozEm~?)Xz52UaR+7`8dOqz+|#x}Yz7vfz3Va)K4Rwqcl@1_RrUE2fws7B#u#NOtKajVhJ&i^|Ck z+ViwsXa5CEB*|O9Orjlb-Yv+&jsLVHYomPz%id+RYI;KtFq;#@!AHQ7HX^r zxGk8rs=G4h@)N66d7Ij?9Rkg*(d`~5U^9tUCeto1OCLp>*7F7#xw)DQj&Tnr;=;T~ z^4EU65Yc1M-sfWW);`fO@_<9pr28Cgu@w5rm$kM`4cfzoQ|9{9t7*NyqtL zBpoXg`~T`U{ZDLX^IwO?3-wucI3&0CuT_IUT~MgnVY=Ee=+V9lAmhlykp!0U$<_Pg ze=QnoG7lqU*}}76Y0qlWrLj_?hP-@L^;`6FbHC1NqD}u3-f{CwVKj_X1fXSMST{UO zT-tt{-CckFKC~!~WbXIk6h%qX?2B-zPki?#HQg9z@w076oo)FOBzb<{(zr~iy|08| z>LNxxr%!1cqQw-uJHz}R`)I;JxHrc>xB; zQB{eStFD=rkp~ugjJoEy>ZWIA;T-+?zYNfs4g#5Jm=0?(Qh@}6xo*xRy(r5?Nm`7L zefCO88}}s)CQlD~2NrZ3iOz%ZUu5ro0={W~L%L@lm6m7>Tf?>kV%3U*@~ubTfLlRV z>0|YBi~R%%1(&EUZccd~1*DkKM*LSVMTxYZT8ikgo*z;~B@T4IKln3=H$qJVGmUcJ zH)x^9G4|_FBNU8TeL7MbP$$aq&>oI}UU zAv66Y*M~{%li#P~Kt^}ST%4nh5Ac-BmOXPLxS*4lpo;dd=hP^=`l%vS#Lol@K-6it zMQ=_Dm1qx3m0Y}XHFb;1+EqHYGQTqw#DvY7v==^1G@V#JnhhtCO{4O2AIzICQ8z1+ zVwDAm(_n`iC*RVc!KFkS7MM;Xy8aEu<5!hA)m8v^DA`^y+u2W+iqPo`aKvJY5`+X7_fX^&c6QL*(2bWTE~|f6 z{QD2{2Ut?@M_i3xOgX9Rsp0RWPF$79dJyk0e%)MX>8yxqTgShBEIDbbP1Rw0?K5bj zf#^z(Sj$DPHZ$+q0h>*l;JnX#;__oCxps(P!DdW@%7pcK-@oc_G)> zE+n8@b02~;UJ8a^K%wVU+=Fs>`FQDZZ9txq`z#jgLUqA5x zrz}1x=UlGf4Aa^FV2%BQQgWWPvr`ZR(8<1%lrR`+y6QZX6q~mys3Nz(m5Ra@v&McJ zoRMr?zFktZ;Kj)vv+(s0gr2*zu!YZKg_pie@ZdFR2f);XBUJ>itk<>OX3Us+X-JRU zX~_@f2LnZIKCU`~=)E9Pdn%wbNbI2$(Rx7h6k<;S@vIJrBUYgtLA~C>AJhNhi!B44 zY!(z$s3|)0;{03h* zmu-Jtk~=dhvB8bT)#9#wA|Z=o=QK>Y4*-h2{7{x=H%1rpafCU<6-at-c(kEpGJYeo6Q@SmRF`n8^zrp*UDbyG%I@1u~WEu-GGg4}d$sxfAw8zVJKou&=bcuZ6@G1D+n z$Ex7h3>Z}oA--x}4}5X6x0LWTS5&MMX(|rFS5O_r2errLpquKzMmXH=#l}ALxoi z_fdI{&Sr?#TmHhDf9$vX_0i*T$Dr$4C7gyRJYy$_6$+L9qs@K~lrLbN1H5>X6EWAt z7mS=UOp*ioH=gZMH7?IKlsS`0SG%<569+NacDfK<=c?1jkIK845B0LcyH{S)Xgi+h z&&d8#%hhu;sK4N91*EvhV%Ylna$$(FM%@(WqofmlHNA=9hek^PO^64szm18_E7aZR zj7K6mY0B4GtDMDWLDB*Y1L~87k=aCkWSJZ)?CSDiC04Po4&@0+y(B|&>E$mOD0(3? z?q4F4?%f=GY7gjaYMGkT@cNfuNk7(^z5r*}$veiX0V(Rc)Z(^s-D@hn>jk#r>+y(c z7HW-9^cKclVgi#NK=5u#lcu(=42*f8G)dYCKo9Lvbb+}LU69D68>4yF31{$?~ zeL92y%ka+V%JmZi`Tb0e2X6lB_ej4|BRlStz#l zl2}bc5Q6_l**nFG5^dX})3$A|Y1_8VHEr9rZQHhO+qUhu-c3$&le0heP1Q$@r2a?m zjhh_xOr<8`T)UW0OsCup23Z=KnvK{Dap$-+6@~s?;aytz$E9l605qe1DUke?%z4HD zPbT1V9!PWfBO|PVIWYEFrBdJhY=z|R6DWdAf9iEQl7tXhVEmlIq>)F-`-WxO2dOl` za7K<<)>gwP?WF_GY^Z8KMeZ+0D_3pZ?qhx)Rr)1_tnZt#KI-E#l3>n9ebM=Jz8^0_`^SO6%oQ5) zd>LU&yt@_8FI(e5k#Y*iYv>BVHYkdeBK?za3xzHzNP)MzHh+nXIkxMFf-*2#)*ENYBf30j_mWG|yd~$(kI%np_#oIQWs8XcISL z1fdV-5;m|7ANZv#E=m6Bz3fIwkhk7mtr06?YWhp&-vz{7{IpBPsYDWw+cnHZHo!S! zlU4ak>!@T|gl5u^59j17|B zo6#c+jRg_fN+*UmjP~6GS2?5#4goQ>XNNP@V6jPxw#cZ-(zlDvQD1s1?}5DHW!%AS zEU6cFQtM~T93z>LCE7gTT>_Rg66r^<7B&`yNr@F$NDy%b>cZ96@TevT*R(KFV80PO z`DM2vXZ!OF<3Vcjl($B_kMR>SwixOPyJ#^LYabJD9>?dqdP?0PWy7-+=vqLWXJV}Fe>sqac-b&O183p7W-ZDG_mX+Yt#|kl&A6Ju;q2NMTa{?j% zD-lJ-1@Rxc3iI-ZJ3g8B9cqr1wqE|c& zClRAOv%1r_FD^Q!tc@U`RGyT=CuLwbA$U?KW)6b2_N((O3Klj0J#|^~u^BfxO4-7( zp={ya$8|;*7q(Jd@KS3GVvnvHKpB7%gZ#rLseWD8G))L% zjm#7OXOl^5?yr85p!*C=cmH26I-)0JSJS*V@L}RPPgASiZ@l~~E0YPhS0xu6gLV9m zLrUQvMFG?W3K@7(H9H9kisWippW-n&)W4DxVG=>v?DPhqkU_X5LGNx*UbuEf8AF`l zP5k;28^7;!H$+#eA}(}#u2f?&e`qKg4&%hk1vpBmY1KA#oU(OtYX(6&Xn{BW)H{oN z&KTo0#m~q_o3!KI{=K~Vu);ObzbtyLXJxj^o*Z7GBuM2ihq1~|c;Z4pZ=vQghyTEQdSKukzhKTvUFj2U}n1_F9x zCJ|R9OGLTl56yS10L8azi2X_cebzd2%#Rkw98tCCW%Rl@23~olLTQ}qWkVNa?X404{0P#7uB{!IpKI_jg%e7SRRWx zsDybKJ>^E&A{W0lvj~`7p7(^w)WVo6E=^#CycxI+=uym&uZG2hxLsOrUAm&;9YUI6 z(N(&!3g`|xJFgVIm5Qe)$sCKD%to`!k!P)0aZ1d!phyEJopC}j&y8Db%~jDzu<4{s zr@A2(Zqm}pc>uf2F=vBaf&S;AJ=rW`Da7J|2XP^xjdtAEVbnVF+#aJ_-01j=itI>@ zYiJfh;r6hC$f~>j>5Tefex5l7h`)}cYLc-sq$=3?2n;A%`F*=r9Y|J()5*pCWnj^c z7P#&xhoOkwg13%|c1Z#J@#lm@A19g~*b_;r7iNho!55HtJd2#4DZyubW)ak+`bkRh zyQjNI53NLR38dpY!Kb}QFK5&mdn_LFyz-UC+^FS}mB4>Q)ttFSQrt+rRg>z_A^o!W z&8z$1v5K+&Pbwjj(ZLm~jScJJ7Id)M!Ni7Bi0$81oW>%iv0D9Vaj!(Sp&VsaV(q_fcqFSdcDmm5ZlvSnPNwzS3(78(oTjcY& z`EAD+4U;&*{X<3;i9qB;=0-+5rbOmaNAg7BfV3A}c2lq^Mjl}`$Y`ghxtEzJA-2Bq z<%Z9Ltq0o~u6#!5CLcI9NcGOTUm4uried!hQ!q4R6BiF~eE-9Be6ED=`6nkrMFjlG zUuGuIu-n<+KGI*NgkOPF8o(k|Ie=)Ly&%eJB@0O~@!7sxJ4}KsL8j|5fb?-p0?0#SvlFDTv=;Q5UpL>^JGL4jY!Yy+b zjk4v#)+Qn@dz00w4`^usWy1b>4g&NYeL=HD4I+O&>#yTQ=g~h+k2oE68g-ycD$?}$ zo5b4&2{bJ8)lE#{$u8A6Ljg3W+dCw7BLUUd(zs@{smHvPlMam|n(uUz%S?Nn+9{q@ zlMbG)1MxC>&sy>ZTS}JxMWr1*I!y+lQ0463SGUCc`L6h}C1_tTaw9cimgsWG>jrIK$YoeBD5wAWov!96(1GVtr(?HD=a=4DMhZ zo2sQ4oG1b8BOpD^p_XlvJo9)--7cx&DiUIKQ)jMv6m?`$P#su3bP@UL3T3(|i#iBq zied|%fIY-l<&(;htUeH^B5QW;uJ(&M{eTZd0HKHgPe(y%|9N;Qn z#F~YKbn)e}m}D9Dj8gw~zx(v`UTKl%SiA(Z6M!&Q#W zbKVG4k~3W{BIfDO4L`%K+F>6+cn>@AFurtzd4KGC7mPHZ+e5J0!U?_*Pn9RVbhm>* zm{w2%%paa#eZT#27${^I^?bhm>hRlR(xsH`-ZAaRbaQMM?tFJGYV_a-4z z5u%wL1K+N0Zl23rZpLDavG*eQtNj^`=)TIE0g651kX0jDnuumE?NIM>;r$mf!+uCi zLfXAqvwwEG(}Roz6*gZjTuOjakYF#ugY-F8bAmMpg$aUaN1g}OO!GWtLFSY~bZcd% zUM8FF=l$g%6?#DLApj~L@iPpw(AxOj6`!`}I|rTZ?f5c)>0IajSMo`S5JCg#=B?*n zW8L#Gx(Xf(3zF!b3Dhdl33IiY8dk?wer2xVkrfJeu9J);&Pu|YAmnzK8HN8_vdQx{ zK4h+->la~BlzMO9ru+a{cH_Is^nuzq%MnGS9_j1c=JoaJrE-OODcq$h za{F_KmNbeZgTMbqTRpPmw;v$bvR_TH^XVVU+?4T@(>^?}$3<3@GNER+YZK5XY7N8<1xiekwf2A)aWUA#m)_?0SKr$D_m)THz zYJV3XmZ#f(GL^TRH*7agnyS@&q(@7nTO<{$b=P60L((}_C0{?qD{UfvlHkDcuEdI7 zAiz<#XE90ghKjX40c&QbiTph(uxmkgisE!BLNjCXl_FEiz_8Qh7HB}LDV3cS}`ZvGh4GZqmH+pM=1Ong=P}_IaNG&q5_pC z-@Kmx;aTs+` zHU+ok3kXNM9F+%`Wnw{|riCsx`!f}96IfU$*s)3r91#_kn2>_}c?h*AA;b?@AqFcn zJrbpi55Cib~P3;Lx)Mw%)a8L_L!@zfBi-VT(=y z>Ik7kk|`{{BoT zh$)XR?p7j7XQ`0K04_>iyzBk9pq_cNrfr)J{W3nWQ3?mBs9~~6IZT0&A8L%N1g|)_ zv0f#!i(lQY_k{P&UaVgxnQ~AKpP9=|vtGfrs}91_+o7#m%(iWhH}WRa)OUkCEgG~B zuu1xknwW`dqQJ7v#ElSbn(>jv9zV_N-q#hTl?qn^ls!Lj+h9{S9Ugjc$pC~gJo-{n zQ^Od+Issgk2~dQU1B4tJwiq7WJnFd;S^q=c@2iPb0 zKl!IdLP@hm?4pE4aCL>7M?KPUL`N8}N#+*KTtkmGTyl>aK53xxjr9QFb*GG*vO78V zTcbc$ht}pO;QZ|pe%)~V9WOCDlWmthh%C8fwqEHK$@$iI6bD-5G}t&YF(=LUcX}v7 zlj9TNNr^hGW-O0nPsy;&ILPhvMj{$*^`4nFB(3%6FxUI6OXkxOLY|p;3{hsKc0e9j z&HK)6Y;|sVUC*?A8rItzFu?S<767cCxxhRIqam;mxHA!QuT{z|2N16JRdTok($+3B zXX|(thwa5xPjlcEM|V|XmPjrhGcO9*HX{bFA|>^TXBV`gwFZ|L0PjCNH>9j*V?8+z z4S>jT24H11Cag}hCPK!BtXsRO>lm(e{aNAB!0>^kGFE44YkmTPCqWTPkvrU5+q-nO zz7_Cl+_XE}+dE0F@NAKxAAZA&2m6DD6RT6f;F>P%>WF-a0v31qQJ7~broLwfLuV<# zYmSWDM6trH+?7n|IvvOK;6-}$;q-2TMBG_>P>|h8Ic|cQp|b|Ic=N7wipyqqPV z(aN*?8+Nd8O)b5av)qC!#7JgVV-eIfELo5M_2U|wq)5^u`-)%Q$Qu188%O2yP}7N? zJUsEa*vb4_a1t1hW2#9J^iq@dZ|BEdwT25y2!<{RX0_QxOJOy|cXe`t5n~7Hlm-At^E)xy zhhA5JI9$gFxE#9A36F#w8s#U{@ag3Wp=VENuJ}vZjWZK0o%Py{T=)f>4*=5$t5+Vg zbMx=^?T?2Jr=!QZyv~`|$7tjt+fWP3lZX!TtpV7go!wgp%w?NabY1L}7p$R{t4r5E zH9U;Ynfr(s3x3vJC9dL^sUPAFW}Ui0Y(8;3;ZVVE09T?#%DlPCd1ERoB$t@zKCyvO zcv%P(G&Kc_fiVj1Sce*S`65 z4uOLHUz7Wq5-F6jpPeqyHK?OQ&EMpChP7`ODpm>#nBCZHLlSY$X~BMJ!BrHwOuOG+ zcv!pPw>iI7&*`^0!M8TuOEF9_Xz~`+Ca4%itIzLpqtB57{{hndPYM8LM%Mot($$u- z#UB6v6#!ATBryL*y=`a=aU7C9EYI-j%vHcM)YTGwDL9eMNSuew$LB6)9_oa_d2t5> z9coRg73I~($_paBoPYHHtx+UJfl>|oZ#MyQ5V;EbW$;1^doRV#jBag8=JdnG;K#+F zSAKJjHDApFG}C4cYp!j@u6J%Fy_QOC?XGR=Wo7Qk?Tns3pYt2tSeTh~{hY3uTK#W# zNn$Ya{AJu(6a=rIW||pQg)K|+co8aXM}g3D<&rY8%Q-ikNVs;!90HXJVhEf;!D4Y7 z%|2hdl6by1wGpj`n$I5!x39{=+AyE;Fd|tr;2ebo3{&LVH3S{TEHqUR(DW{XUE)dQ z{Gf&&`2jZNUP($-pr^)FfOXz>KteVePozB|SsnY$kPlpJ)8c*KwEyEC&t&Z2IW)MfJVL9W3{ zQ0pV8z23Z@pR#D^Z=01sHh4n!-9=y86wufut=?2SS>K0O#_5=yNaYZNMN{Hf9;GKv z(3d8+nD6>B1>Au=hBzrfjvW9})ykuWgrh{^+MoTt7_b6fmB`6T&2rtQ%SBy0WWk|) zmA?#=MBxH_%;DzE_e2Cbv251~EHuGyc_lhGWXVNS0g68g){^tmA<=nvTpS{d1I239 z-@JFr0wp*SMzXV+IH09r)kMDw%ER~NHH~ry3G8O}Dol)B6 ztt-7WrTDN%3lDB1XQPmohkhM@Lzj{pJUY-Mt1)#2%Jf6eH6zP335?BSJCu?|aA%%n z(tA)DL4o););zL}mNi5@LhbMgAeH>8x%T6`6s43*uIDK5z^PS&PlcfYkc6&Awb*fN zW@Cpp{=6KiVxp0qO7soRG9^jZ1VQ^QEp4Oe=NFl$9 zFPSyp#zGC$E{1l=_XBIoc^NU$OcTjmUp8SfiwT(tONMv(91RkY#*{cS8ME7g&tYuP z9-Uft79%-(XZzgm#8AcvWhRVxB5+p<%eL`~tuP7)5(7$L-riv%+ww5?Rvl3cJz;u&jB);ODwu%9G*G@JGO-K$u-Dknrglo1N{Okm;|J7>#$%-~5Czp%rG@tZa?l zPrlE0@)}xveMj5FTju^;u-Nsq`qSMLx+)%)8KhfKdpW(N7-Un}nhMa&(nXmQFP&9F z**c0Rt0y!k1_irR9W=?(X$-Z`IzRY)Bsk(GHV}?Jww*@(^&GNy$Z20Ge-TL( zvrbJ!!t;--Gqmn^M2jqa@)I&!Le)FGJYEKMjZqg}L1eD#l*@vGJxyDnkSwb|U)NJc z1=#_8l_;i$p>i`|oI4El&xwma_hJ{EcP^c^brJZBfJ7&GhYt7LW$fEFc21VDy)oFh zY18616WzSv2Oo@(a2`taaMO3T64Kz5xfhi5AuFQGfiWAP5<$c#5-mpzFhr^-%~UxX z;(21%qC$Mpm(xxI%V>$Aulh(}vWyf>4^cv2nNp8a6VrT|0F4qWj%mK4aGagJ4iraZ zxH0l~+NoR(*TpfstV}vb*%+apG`G^@Gy!Q85o;{ADyzF^hqm?dl4H8&jS%IdTG?Na z{dnMo1(~G`&fVCn{|1}=*& zo$!$?b2bxfSNTayrsuYN3DP&)^d*fk#;L_tGnZ1jd_^w(7=oNaC*8FTCMtRqQ}k$n z-0Wms!b?sg`7JQ%_+w&Yeg)`Sjc%HuK7p2G3(~NC5*WhS^^@3$63>laG0q5~(!*Zev+H>v2Ufny9QNdKeu#ur5e7b?5mL8m^j1Vev zY=cUtjv`%0!ZCmtK$?Dgr-sfQTNr2QMOU3bqOCHl2+n|U?7E1jiEKZRUcLY>yfoKD zW&nDPy}j-EwFM#mv}56O&Tpy2>m@4ljr$=d?#e1GD%609vtwfqZx>eP%|fWNri*wf3n~tT(7vB{05A(q*x(*OHU#(* z0lR)@Bs_UPU}#{Vv^&zqS!X|BYDC!|a=V81VQwJsgZuVWdvMmv8v{wliMwcx3~BVz z6A&1-0W(Ue;4(6Xj1bHPq8Un2=&YU(M0jq5iR@a+nyMRm;cG)4Jp&#r_!pOymY7`- z5Hp%&F3XY$CE$2}{1BJ{9|{eDKr7sTg*b+|*aG9bFs5tLrIzeIXXAyiOf(y50C1lI zc5T~4AHIWweu}&T*nWhFQ}t_Qfq^03am3Ou0x_cy@T*#Gr-y^NX!zuX_gg^cnurt) z{_ODjehTOqW2Cx^!6`mK9uUlxm+E@ zaVAepR)+3_)?7u^QC99pZ#;83&ZtTOH#*s0+Y z6xz!bUpR3EB;VU}R27hb_W5)Ja$G(KZQ#`*;M#RqOzB5+6+jyl>Dd9QhxAP!%5nHr z1h0UWRO7%1mS2eAZ6-v0SYSY^Of3>)0F|%*(N zcb*wKU&_}Wnn((j4_tVEfk`S3()s&*0Y6yg{zDWM+kc8+XJY$*nB+EXwAj$RU)8d@ z#vz6tTH40}p`?|h{lOj?k%1rQoB&7_l-#|rHwEb6AFmtTXjk?TNfjpQFWLkFPSs1s zr@b{iX%rtS8xw1L9#s(f&DFBMl_^~U0&B8V2F#SQy~}*kzCNEu8&~zbOO3UvQc1sm0r$Rhky`r7qa5L^`ka8+4uGyXo8=oI$Cl6R@y6~>ihUsg9U z8af~>Tv}iSrF3Avtu9iwSM5(gT$VEqP)=yo6yIw2JhV0@{^pcP9^_Uu86(!2!BoI0 zclUC??~7@8_rdF_DW>gJ>Rsfg&fAbf#-cB0Ci-S|MZCwWS68E7F{CQg)!4pvW^E(& zyhs3bsXtRgPufR{Ug`!JfE<`>ckcfhYeQ^~4=KpDD$HUU1d9S0Tggi}t@lIFjg>jc zGg3hq9{MEQS!C-h506z9{k)bcos6^Ds&41e;K^tLDoy)1*nitE>&pmgdL#)qev)NC z0P8KmVM*?EkfA$=#;)$=#--uk$(A!Fkhq{5rR>f3A1;`XgcCrQkchUm>Wd3C*;Z z&w9sa+F-owNkhVGKoQ8K8r~wAL5Yk zN6@V_#>8c#sFN@w#nLt5LBx9sy;)^rMb#kx#?#Akbz_~UmI*C^AY0R|(;^eN-p11x;DUxOb&5zdh# zPmBH&_?lj(5058q#g$jdh6PMjeL)3YRSZyX1Jp~eYYYH2qq5dis(|+RA}arUT~gd* zt$YT+FLbkl60JomLJw8Bw~@1>=J9$rQvk3Qv{t%N;Zl35WbS!J#H57MVKbwslCB}V znm!V3Y76>g>CMYxR2M5joLcoege+=kSe@u`ueIhwI)Ee%ls0|_?y#@hU=3(VC=!vX z5t1Bb0UQxxuq%0-S=fMjcLd4L7Pi^Eb4>aq7;LwK+;QB9*FL3Cd?G;igP>Jx2|KUU zdBA(-9A&}gIqus#RVac1z*VmF6?p@L#F7LI0MmBzLI}5mUt7aJXp{nh%fx@Krd|>l zVGMfY+UTp`Ip)RJWPTyC>SX50)NM-%ml?7LA`r1)4uIQ)f98dI728&=qAKyVmfGp z%+iKr$>oyFd{zbx(V{b2ep6A<8cVQxguQJ|xXjy{r5wWUg$dG`e{xh?5!!YDnRLnH z$*|EWN@loL5X9AR(Ez7KeyMV4kqlaU0CkJlF_Apf)M#p^0{_ z=i=~U_^O8MqNh8%w>Q_<%*Tf#ciX!oTW=;4_>Lt?GN1L52`Bom8gasIvev}4D|6_z zDR!;)G8M;kst6WOtS!)hRnnPF=FEZd&=nv2D}-xmV`Susz033c-yIN37e_}=+{35K zgNB~Sf9k+iv`jeKfWNmX{doYLO_sHoexJ{gxZMVcBp#PQZtfho0VwjL-3n6XCOW;(zmyakQj-j{=#cOiA|T;XY;BaX8kR6wXTwg}u=gEI%%_f|5S9eA6|s zqcq$7H~5QEr4Gi06^%&X?d2zpa263DkT(HYX-ilqMoK$KS+sx|4u=tF1WJ`?!;j56 zcdDpTQGM4HeTRXc;z}gJ$;StRpkRek(}z$Q2efQUwnXFcC?=iSoj;pEKc|jGD&`W7 zn}zWiEL$!Yt}ha(P1KcIIk%fj%beQ&Ob+Qvn>NQBFrEK43j<$@#i*A&Bf&l_sEq)H zeO2%WBEkc~j<9D#H7&KCL4YJisZgjcvwiA}Se0=kHe{k}h+*g>tp0V(n@xbo$*`6rbHD8q$}UeRM> zl@OzFTae#tQS-w`hH68Bn%a?%`}pH-ymD{7*H*{!W4 z)KndEW^Z}MttBLo;miWU*Gb`SxSB^w`0){$;^>0TaVi?`*dagDuE-%K;xNOPG4-y^ zQQBJ0!P}P6=vl_`EmpzNC_23^$U zP52@^k7(|(G|m@0ypNxrwDGT9fnBS_Li7E{->E+SzIN_oSk6gW}7>oGJ=6EhUsUO%uO>Y?_pX{~KXr{|}-`1~&Hpo=nx0`DdF(=)P35vO$V4 zPQh^y#{+7D!y*u%lku7a-y6zQ7qDt?*g9I;-5LF^OZijN+(1n(;;68)V8;IV?}?q5 zzdyQXs%9eRZk&nXGf5Cvcfm|VlI*y8WA^0vX7}{`I=E*N`IiQ&2^XSiCZ(YZacgb; z+|aU6atWt*M|P>+O)1VAvc=LQs7RKqU#uxqj5TQEM_sk3vC~Z5tMjkimu~v1vEbPx zB8UwMY$xI;qFY+xf?}~yqh|Z*oZ2*Yb!b6VeSLCcZ0JE$+#UIV6ZWRq;1*&kQkYc~ zWkqzI8W~exq1F@fDi9wRhHtrMhip=zAx9Y^ukBum*}ROXp)o{Dj4@tlCZKrAfjEn4 zuny4cScfdQ{>HD36rEO(bQ`k%Ru8ZI#e;XUI{W8^s=kXVNHn^%@z|$@*khCk3!hb^ z++^1$`*@@!32hkK70WixF1XhEw4cgIo<109UUe1U3l3k}hcD-gC7wTj%t$mQXb3%> zKX1eoe}=qv7j2!A*ULW$!oaIqdX_2Nj@@b{^=kQOc6=U84O}lDM}uK3vD3d-4&(;3 zzYM6O-a9EM03crkb4$7IXb8_tp)VR~D7w)XX(lcXs0O!ES)ZiqMFEss@`e;pO~Opr zw=q45-7(9~?1Ovfg-9g_Pb_PF1@=a_(;x4pt{%AhmkO{BmD3xjRScR}lUR>L&>uX> z(8m6bb@Q7RP>43zm8wmtTBBlCK7c}PFF#Y{w=9}_=Mip7{TAK>0uFUjmhNSo%c$mJ zhB;m%sTa8)4?w=O&*(v!0W|mxy0jJVPm62S(^^_KtRKg9!9?tVsgb!T!Ttz=0Bsl6 zu7lbDIuuo3^ZB0*E9QcEw`P}ZBSr}d403E3Rme3+oc#}HF-WnRjWk`oz)S}Rq3s}= z;xvtuaR?H(mRagcih}9T^!<+@Wrx#zB0>65!Vn3-V&OMc1JLV%J>FC z5r_EoS}beQR3J9?XT!wT(k@Es17c#yaoBZAI5p%Q!QkS;1)z&Fn}Xve+?;Y zG9lQR#>gO`f`#&|!^vBv?6IoZ&-07fZ@F>rS<3-lZjGyvH*13rbyt9mja+I9p4eL+ zX{``lxJ{Cd@vR%dZe`%;zAU$EThDy7&V4-jw``WbUHPr}FSeAt=Wrjl$iB{Nw!aW2 zc47Yb#umM4?@(tB*2&+DY#HhMUN>Rr@iCdVt@)GNi(h|Di5gA-?VZ z$#gOg&G0>|iXV3=k3q*O|8^(8wiSztJ=rh0o?p<5P5$9l{P;v%*uCNtO-w8-;=3mJ zK4v|){T9EL+idE+V0+OCHr4x>OnPDyde~K|Rvh8=9@TRdf6K^U@IFPGr_CM%wRldq7QB_d;kd;NoNe{K zdafq!#qyK@?vGSXQjddqk z?#;zAvSh)<8=k4Fy*-AKeG{jF(-6M`RbGyr(djaGBs9}UIa6c9ZuOj%SdR{>)KfLobaCQJsV@sjlJ&V7r|ap9 z-U0qN@BeU_{s(0e69WVNe@$2EOxoadB5q&)(PYDh9GN4j93w&pLjq^eC(az&;DFmB zrzY%?b&6)M{Jf@o5n8-5k#jWZI3;`?crXh&C{%Z@xIoE#{5m-}haMV$w535~%Y_Cd z80#1aKs?g1f2?xhk?{k*cJHD5*DzX?GZ1hNwTW&j-Bx4r#sHux{)m>{a3B>Rpkw5<5u zaA+;M?assjvF}?1ItX_(zVTvh@WJ_7oyISfuHM)6fjc}IAj{+`x~gXj`ex4C=g?3$ zKwWa)WlO4r0zhP(IxHTu`uY%FUffnRn*QaCkDSv8^aAy&YUR=pzgx(73z#<9E0TH* z)EdI~pot)mbGDt;Q>ELcu_O=hO9q3bU7{xNl^HBo04Z$Rk7`VbJW%-r zy~x17+jTYwLsinPRLHf%Jf(q2RX|lO1$-s&r`h7@od;jKYynhd*NOc?wd_!p)65DN)StsC{zUBYlzt!$MxqTz!Vj7+ z+P3b`Jo+DH1hw8;v&MA<*ax|S=J;}wJUbG#$vscOt3HhV4iE6~80~fj+)fiKO@HhL zvK_^+_+wTM;9>Sn5wssuDt+)tEXx2u_I&P`48QFO5VJK9>fQy!zomVBFa7-Yxo7sI zBif`lBcizaaFS6~5E$UoGHKkvHgoy*z~lqb+ah?-Qw`#QxLiEpeN);%ol?h!itN#Z zE_N=TTNE!{Gpz@cSs2XN^jBnO(0=n4%s4&`l5Vnsdv{#%-@G6jRE;yW{Sw|yt_ zQg7=fCvXkvTx(-n=`aT~N5@KWGFt*@OoomQ3S6X2hOILq*BG$HU;AmD+y^maBsU8V zo8nv71oeP5e~G^Ra924-wggp1lw3`cI+$XT!yPv$%eaI{U@~aRxHwfVW@M$e z`;C^i8_-I2A77N{er%1h-|xw*^?8!9Pt7xD;FoRss72w}&OCpj(~A zdXxS_yIEUCb8*|6%EsOB8E@Etxm!%^NYm7+>k$yvhC;ZKyDRV&8LF`Cr4|hSl{vMRF;#XLLkP}PbT(7Sj;?qVhlVTR zR?uMm5~|qnqu^jFxf5j8s#C^Ju^5zH2Ais2ol~?{uYkp_gyoDgb;+;@{JVQ&a1l7r z^nZSt0uRRbzKPeey2Bg>b4+LkdsbS;YKVor)w8i&#xlFq1U_=uH91iP&i3|agl2k* zdf1^mZ3^W@OH;GToBA7=lh)w&6U*{Ikw`{kMjgXoY*3Jbn$mC}$Ltxv9+Tdw zT7R~ge!huVfyyplZKuQsS1hOq$q2_<_dGJ8|XDP@QD=0%~H?jUYF zL7Mywrij^f!hJze^pKP)M_u)RSJl9Ehxrn$qN{!!UB#GyG88D+PgQtKnXg%stNwqz zX-^;Fy6onHu(8DuvUv)b&s%E{-=a10k=6NzSs}w~GmyR#8UIR6TV^$;aMD{uBgU|q z#CP@>;4)}qm1kZ3`$@K7j~&?PIb07-%M^_5*bp|)6Op@p40Dw9$QC4T*Hhmp1Z;H> zFhRL;UU{LoOa*q>vyQG9G%s&X2bFE8;N8o=G;-b8KX?+-oMVrQUTtMFCQf&V-Hl4f zZ}B8D-D8jZk=$|Qj{FDtWREy(mb$t>Ngu|LP5zA@fZiOqtdr+;jU_zhVMCiUi#YER zwMsn*lhR1?vPt8gjnhYzk3ng?TY&XXi|iToJVU=5bN)c%sHZ2#LO6e91mATf3K9v+ zF5ae_>}h5C>C@USx&Q-0VqC6f;i%=h`A!neV&9EMU9S9grr^>TT>7$H-tj~yUvcIG zql53Opca9x{qk#SHS|ZC`Tm##QSCdzY?lYfWyF((amOM>Y+KDtS*=VtIhdd{b|ciY zw4cJzGx+`i6201IGYk`oNhuk>pbSDuVdCVwIuIN|hZ>-On107A^$QNvU{A~S3&iA; z7O1l9s@7Kz!Lhg+?zgjxnL+m>0oW28peC6*Br(8SrGancDLS2fA?!vj(g&MWbQAq? zpHaLTa!T`WMDZ{@k9C_)@(0aaM>xg5oz6$*No)Na&WFZrm?IP`5_&R{V}h9{l+#m| zdso+?OiZaF%t)jLh^fOK>-v33MhCHbKAgM`wUklQyU?p`?)*^h{(1TN?A+8FwCwu$ zDfW3hEZw!a<@2ukmwJ3N*!tRf>+@ZWr``-^Lh#Sx4<4a4yc+nP&d}KF~O$7a3 za?V4P1?6-y7pr=9oPc}#9GddMYRXNjJ zV$NWn+d_^vihtD@TzX`liZH9ohf+9?+9WuUC(H2uO1B8FW~F}Fe|}3Lfk~F_>+C0i zjmSrnm)C__(B^6SJ#bT$7*K>HphJ;6AKca`VEkdM4)1bKTGBC246i{h1@9?S z*17fY_wZzlS)G96C^JTJaT!KOiTY)tGHD<_2SrD2Q@5gMFDalejxyOeUwyiL|Vv zsmvNgE1PNKhZjzDCWD%%#YFaJgWwNq(?ge;xcWwDxR7EoNprlbc!U|z**AAny?R2K z)(lIEfw-IZn_T-$$*>DH6bIFpPOUuhbPsD!ive74X8mEC9He4GjKErvAZrVdq~Bks5qt}xY^<-)Nw6t|~(-crszE z`jLLD=YI>=(PXHK+L&7~eYlz`sXb4&VCOhW#skWR^%GgMU}igt2is_6gHdzvX)*Wg zWk?|pm|RXN?H~BlL-10Uf0R0yOb9l!QinieH8yjh4T9KK9?b?&I-kC4BIwoT{>Zg~ z-Czv6VA&VJ%`JE%0^urr43Z1en}Fndf6NYoiZkHQ^RYCS$prJ*Z#}w*;pW#aYtM=Z z)-iXMBO~HYf7{oJkb)W-r=UV;%YMzPG}#pOc#teP^8A?s<2_Zq63_7_5FV#iv7qqA z!pbL!9#Qfk2XEFZ)KOFTtmp7RGiqdo zpSRwjc|~|>nknfzh&IZ&_KUG-vC@JlztFk1ZV80SC@wHK?8*bRWj^ID_1mu;#YNr! z-Z~fdq8|8x3>`2Ei(0XyS=ADJHQ1ge~5xynkouuVi? zk{o4H6 zQ|ozq`A@^Pa+p*ftQm-sj{rhWhaOA8FDtZ?mI~fCI5;~zI2bxSR0J=|9{BTO$bcE3 zZ%2M`{U(B$ z2k8X(oj(#h3^L~mF!&2~CUA|A!;b-BcWVc>=|^z)iQ*bY0|C}{3pb~v0B+VEK;Y}Y z{0n3U@S_dqmm2w+>)_kqiwY#=j*-ZifG_80DJbKu|@bS=Od0l+ej2P5D)_u|ziZd>o=`^!L|&X02T`{N$S&FA~a zovC-1UW;OA{gdx*m-s|AK2?Q@-sD&4JvXn4dI@@O@?9CBZ~Qe0yl?Uk1pq>a@BOc9 zwy({e?MrX>2LD~|;&*KX6~e!a!6Q1P*Vb1y#8|$}{s%GEDnDP>xuBg}CWyX=+-J5! z_X$JC-@Wf&wEo+q-_4ufiicnA-(TMNg3iXrTlPskzh7cFCqORGUxBULMy>;0Y^*uY zVE!L$3y=?~xdwUD&EJ@E0>4+Nc>gu7U&m`R}g*A*o{ zy4!AXYXRL}SM0uNP=BHuC4kqXFF+T0jFsB(2cWiNffyHDo((NnhN+?h8h*?V*R>GsYZ@F@_WZ?~Bz6%v(b%yWwLwD$J8C4I% zy0Y)o$>)##T$GrUG8APBa^WGP>E6b!y5$M8Z)n|-y76h_ND)!kY4GO~S&B?WMeuVa ze!(b?l3kFBw*)3vQ!h>Kz>cgJW^?@~sTg8}6WEW&L%}D~0dCzqO#F8z4}`9icG?oSG{bP_=?1z=kyZzZ zx;4E4Hw4@zw7aWKucoxCosP0%%ANwXLAI_i%wF z&nhIPMg4{#Dc3}Z*oF{2Tt7u%`L={OR9;67ZhBHo!Qje^s%|CX+Iz9E@=+sBHCEB^ zXLzx%lKV0{CM~`+@tSiSB%BCuPz%wDG5xH$UgOC(SY{kA=k>}Xk23p%)Cy-cW`+I4 zuU_vY$V#bB&^Lhk-$w^7drkaQqTP?-ef$R~>u7>H+#VDN&94YPHPg|X%6m@CIx6^)m~WuN?yc1HF+6o zj^CP57S35xO!~d-V|EP_utGY?+YUH`_6;_;(DtuWLe{jgFFa#YxWqc&>i-{O=MXGd z&}Q3f+qP}nsB7D{ZQE8|+qP}nwyjq^=ocN)|Db0lCufqAFLSTGa+Fqei$OuulCRcH8kC@-er-yD%In$iS+Zvife=MKA`X4(>mmQ~YspIYj} zDB2;=&?Lhn|HXn*@?)W@HRC8eNG&MW(E3mdaYnA5yABoA!6b&Q)?N77{Orb4;o*Jl z0=^8-_s3Wim6pa5XZPW&vr+Jz_^AXTr3;x-X;v{={Bn>jeTq!43W{$>Rg)H{Th(Nok1XN}yG3NA0_xc5}+Qrq0cX^H@S znqnlmgYf!EVBQO8-c|0mVa_SMRjKT71&#I9X{JetYph{?iz3YZ%+pmMc=6Kq3&o~G zPg-fPb=qW@o)YC~eFW!|Gu!>!PVlUU6PAoPtnY}(g!rsuIIWXL+@X691} z{BP2L+msPy;H^;XyCOP%&y~KAk(nf?$2E$viZEfX2u8d8S`jY=FQ2VRe#W^edr z)9K4v#jRMZK8C_Dgf~fqJTVFGW1vRZW6)(3y&O@7UWpaMD#S7(8*-0OdX+XmLy!Xa z2d~ULg|(-Y-e+KSH&SoVhrX{|7nLW8C?8u#YN5(^SPrq5<3PXs=Vxr(nAzug&_7cn z&-N)COj$AYP07OJj}^Dm(_+7RPzx0#lyy1|z-X+^dPHNJjRRIien5ebJ|E+7a<( zb4c9!GHkY;z(FKPhICctKUb!2wiT6c2SzH9!2xj2#Y3m>{^ZRhXVGF}Z}q8alV(b0 zckwx3pC0rS&Vym$^Ku@GX)RekrxW#qXViuwcIPyiQbe5?jc@|byyPi_?QoN3@*Cy& z0%UQEBKtZn5w$l^6=mlvT83;PN9~}!6_p00AcQVA>@Xl|WmU6q=tL;Shgl-siQPz3 zsU`!i0&9m*w6C!KShM_EfFm5K$nAFkIS65HA3L>UE7k7H>7vHla3&HwoBs%|mnvYu?PyB7D`M#ViJOD)x zA7illKs9@NSDj(CsHYSpf^uA6)!l;U&_jq7TEqD2#**H-P=1Cvs8An=^Y7* zZ{^F93wsq;nvL=is?uYVl8&A_A%3rb_Aj3zFf?2Ld3M=aQoq0sFrT)|_n)4rglI68 z9EXFHcO~qVUBEcKBR;GG?Xp@F=6puk^O5QSRZg9Vo0^RveZPe;=d}xASc&% zig+Ehy1L0|TRl543~0egK}!k*)pE_i*~qCO7WExPm9^;@pcQ&1XGzq*3J*hsT_*4s z6_>CPD>)I_F*;wN0x!tkfE5VIkIqfwqGrr@P}4#6&x07@3Jjb6P}CwTXD);c9R{)3!%li^wowYMuZQ&t z9k1Q5H@l~@$^_`&y%V-H97iG=eMVlsrr2FZy1eZ>40mFp;KqdACC(EqKJ~ZIvZdgf znT1GXwp$+bQP-u5(60kn(Up_K_SE&Xc8F~73&*h+Wc30BE0w8m>gQCv);96+?>hQe zIa*Hxk^+vpz-71rw?GbvmWof+yN%&Ky<~I;L`6ZqLNMD$w=@9Q7Ig()WcsQ^or)|6R#26Kxey4?m7I_ zT{{AzvhN$UQz(7|sKpfwS1gN*2NZgi^v*d})G1;qMoXMAup5~O-1#11lu!#8lWC|myOz6_uS)6=FE)F z%x{$vr*mCFKD-3-@`>RRaVN|)%t79W)?0+M5Z^YHjzAO!A1io)-;F_RjzNEagse`M z4td>l+`^X(&tOvB^>2?UrjB>pbrcQ74qTUEZcGQ{@^g`??Sx5e4v9)5iNuxKZm#yP z60}`Ey)3)PNRPxGhG{Tpp*<%DO?0w5_9e_35UFYLQhH-P53XiLy*A#NFK4wru=)n> z%Qfll&&2Fc69b@~iM|nxV(Ib6!AO_$SSg$iqvRGUD2h1@p5N!sg~AU=X-(mpKHJ#S z|8iJ4iA&<{dP(@{o^`ej49tJ%lxh_z_-pIz6i+fw;3Me?U~9MhQRCR;N#x&+s77!b zVr65p^=-ru98WlMPwf}2cJEHlj{D-ug5=aV2ljxDFyaPhULec>d<@ssfQ0|i~!JO7kEgkQrAZXb|51B1RSLh^-rE3AKogU>xG!Cjw#l{<~hxn87r zZc^)pow&VZHHa^lE*hh);msrfXs2Y6J}7iPt4P!DX@geGN-=%PN@Ayyi_7HMUsnr}?RfWYJ$0?GO<49rY8G-)8_e|$ygyI5W1n>WROIBy)9ywH(==uKQBFk} zk+>YAu$pm|3hrZ?LERyu2XXsOgr1Ai9 z*`HD9__KLizlf>vw@+)hGl-#$KkNQFOrzN?HsqY&T6-E8cp+q%yO{l;bKwnphl|bb z-XyeFUrG=SaRG9M^MK}_-KpUv9~3P=?VZC5+K{aheOKBevoRG z^w|Q-LbHgraY0t#HM;hQ!gZ^y-2(%CFew0RS8+8AYS4HsXW7PP8QosgJJc<*|F$mQ zt?uC@itU^#|4ZJkU{zSvAbLCqFPfy}eCejz9oOl8b}rYTv%bvVqLUrT7V{QcQrSyt z^62~z+D7TpQ8^g7b;r!BddtvbH03|9SR0d@`Dn6Rmcx6>IMGLfP?XA{Y^OqV2py6V z2H(Qac?0`8MpcU9Nvde;B?_$(};wA04=?k(W^lP?aM{%}~ zQ_66gB?f0r#wMTF=@k><*@#&Q5?Wg()^EG{Wm6%Qvh?TP zBUY{a{YsN&4t!Q1#_+`P966K_H3f2ZsJpycWJW~vR%aAX!O$9o%AkGCgkH_tBI$K$ zT*eD7_ps{}4zOwCqBy_m@N}COTp-#-^rOUNF$i*gVHo~OGRb6c)3KFbO46b5Fia6 ze5epQFxQ(if$FIVqXR})8D=(Hc8^x-9)CRo2G?kh1#a(%D-~Z;X2n`GA<>D(5cI1MjVraI}A7d)bWj z#}o%6lu3ihLPsvaz11E((kJb*HBG=nl#X1*e$f!xfMu7(>W=lx*0?yY=%bK{mnQ&@ z14Bglp+JMoY;{7ICLq~ypHO>Ry#qdQBovD>1r&G7qjiG4C2Xg}vZ;=9yiQyRaoaN? zG=a+~s(Ral|BpU^?M$|2d!23W{?nmVt8UIm!fSuSan9lJD9d&R*nJ^v-|PMfB@Bj} zkp=oYw%1dQsNF@3NpmYs(fzi3VyWju8;s@p+fm6B2eS#vCOKO-2WPVR?(op=8rvcg z&zpQ>!wxy~t8v*_3DyCSDqe>V&^!h& zn|Q8>)W`+r=S=bCP`-#8Zpf~0!G^N1`w2hUXuYrHfgSnoH(e@$**+i>5-PY0Pa*l& z#n_+nravgAJ1^{3?1{X_kE3SSVvE+Hnhq>j$Kmf5aNR~;(lFAGA2_*lX{cV=Qoa81s(ifjp-+-My1|aFXO&^#Q>osuZaR`YTrL#{ z`nJn3H=heRw;k(2i`f+w1(xAMKi;g|cF?$?kNL5$cRN6;dRi(N_oH?+u%qsxgs>mC zlNFjJm*>03Mje9I8fXsbjonNA?0AAE{2CVM6;h(S>fVGox5Uxg+!y#It9_K5K3&N& z^iAm<$13TCWjmhfxFiQ%M7CJyLd}#b&d`?VLk$ah-H=A{G^?yKPn`{Rxiv8!lY&{? zvw1MX(KZD24noZoY%mz4A4vu5lo!5zzsksY5>4kf_GNj;4? zOZ6dm#~tgX2TW^%;O<{)P@_U^gKo)$q99wh%B}2mI#LBP3kAp4&nXtV3;{IOFM$_? z{g6|)W{;FNhQ4yf5?vFrFjPs&>2g50W!smAOf18emR9R} zsv#uk7sZ@X>tsZ=kL=8@{5NN^gv@L&^(;9k8Apv5h$E#+boD4Jyx02MyqI;9w2B+B z18>}V`NOa`;TdLZowOs7Otw91;B8wVU@F^$&;Pn6yUo#VxO?ep-s=Ucsq7nvq=C6> z^zyD$!i-U<$hQBkjJTi0Rj;h@T67fsaoN?ipJNz`#Bgb*fGKe-X!$)Q%x>(CX}r4^ zP4pDkBJ&z0lJW+L-Hgv8t|E#yI}v5czDnr>@6l%jB{3Byfi>ADhCl1L#u)+>7QjfU zP)88uj}Kx6Q|gy$Y&65)!3d)E#b(oNOB99rIs1mI>a!t>X2QnF;e=ChCZ4Zwq%>#Z zBBd^VzEkmHD!~~f`73%|G+Rosi`P`Hbzv*6eGA0f#%N%uUJ_$o6!EZX4a4!E!HO=vL?r+fVX zd;^mBJofB}k*4u984u1?a1|B7DePcV=oprOEWJ~S$NB1Z|kkd>bH3l2Yu;&fr4=M9^{sxr)3H(@>QcQ zO;L48|6wz#jpJFOm&%tJ&;rbEtC`$3{>9D%qM0`px? z8-D3*7knMlDx5d0xRFXOj5JyclsF8IlrCJ`vDq{tJs2*$RNw~NfchdX27 z@X(j+_o8#}F81CNE^0$$0cx(6Kho_7avjf*T{j1x)+?$gE}G^F|v z8z(})alG%7oayNi33rYlG@PhR;^Mk#X=YgEkXEHvGD5ZispCya#TI}6q2qUIgU%#ve4VI?;dSDHreD;MTGJJ2A-8c#w((22Ps&uID2jsCFogFO&baPLvF>$W+~*tXGuB&yNUKi;pz+9lcKn_<~I*z(CcR~)af)gdf&)%4`?AU6va zFq0Ap?kUu0-WJvh2{~s{VBLl(9H-IGkgV*=e%1# zhhCakwXPn$Fo$Fp0Czxo(djDY96WA!kmdg#FQLyH7OY^D4wHH$JhG1t*hiU99d9FT++xqAX4f7S@ z88s*3Z*b5HW5D0|%1y*V^~iNqPLNEq!)SM6Snq!S{{Ga1S<^qV>Mb%CXIE$ymMXu= z06JoIsPZ?|-KTt}8%ziY{3iWyrDJ#A3@bAp)a!lJlxo>N ziy9K7u%1I$qKLX(g%q=7W-ex}-8klmBO(E7eNP)VWl2WVq&rTWdZr7p?beHH4t5bi z=9eO+zR~BDMbXwYo-O9;?bppD2}r!S)0`pAeov@$yR=f-(M9i&dE=dKz?19|F10(@ zGp2>nWj$ojt*|A&{QbD<$@WzULSA5L5REM_`ZG2zvUV!e@FI|E>-Efe2%~bw9N{j; zmuVGK$U^5IRNPoK!&C2W%UH$GSNRD3h(NnxRD3s? z_qZ&B#gD<^zA8P5j~Z35I;SJ9ypC`D0}tl2{BO3kHFk1#G%>LGudjdJbtp#0|II)D z0}+@x+5ek2U?N~+(AC|3QH?gg=R~VmnvS%=9Ud1 zAt4fy`d6c6D$(l=uSyNgCR5brD8I5FiME0Y$&ABKal&75eZTAb+Vr=7b3I zF&ybolPlS=ZXgB^Ccbk$fIkEdNBa$hc|=? z*YEsF^;3fn8tRz%3&_dI5!OMAL4>#_pCSXe57aaG1EK(ndI=Ev=lKJ^_S4Pnjs=gk z1BfwjoV4yB9Q!|m6y^hD0|B;%5izzwxRHQFg6%~D!?3ylz-#A^?apxZ;(`G9c>*J# zA^nhV=bhz6?2YO5>w9@6M^R&(!-{hO;p{;-hhBCJ4D0{{>c^5gbHz(AqHzW@v( z>T_og)@B6(UPyfaFu?8MyJL8Q5Pb_|F&2d z_O~6&3vm(sSPl5&1^}zcVN%rnc7XMa*^D71@mvFI6ft>&*#a;RRh*-{sGJ< z{O&aRa}gqK#7DK6?b=7X(y$5QQO7q;PfoXTE-oyZzr1C zKk@)2MHg?o-YhLtO~-A0G~jN0_M>tcX#?fdq%g34gfX>$_)xpub(SpMEQe9@aTR#cvd?k0ixvaGQk*7w;VWUH)_rbVR0 zRs%BawM;(pjrT=T$dwD%RDVy5#o-8T>lSy}u;AMma8f-eNT*==R=zSniS}54L5+1H z&XJqa(lIh1YGNUYJ;@xcIV+SVu7h;+I;>crfs`bm#9LGD=px(+WRxAuq-qCt7ht3) z!|-nm=e##M4MplG)nGZXu2FpAmkt6Jueb7}oXJnvM9mH_3OW%lEs8v-{1z_VhR?&C zdruMXY7Kxx$@Xl4fko(>oE%~vCs|Xg(VW`Sc~bVuE;M%%9_*CjyF3(&OxfkRMUX$f zYN&>cREv{|vpMs&;@fe$j~;du4mQ8Gg!J%hY_(-4=f(37pkS5|l!~nP?`1|h5-7U5 zOP8%`TM`F2=5A^8o0LrF6h7Eh?=n5y&6QcN!ujdXEkN83x~!yeFD$T*Mwf{7*L7>) z-^%B63{d%%c516Or)z^{A_{f>sLyDv3ouucI&d3Js}rv{=2mmBHWF7zx0B4q4yC_lr88Czv1WF0pIgBMO)+@_GD9mGq)-cU z3gp;|Yr*>Qt`R7wP!ShM<`!Rk~`%Y&cneqm9m4wW|=%!+K>{t2s4={0H-EGBVXY*HZn9jf*6jrKGb zlq-%edL5!p`38e0peQ%w$PJK>-U>Q~Et}^^7LU4vB%h#7%C)6wu<5>Bh^EH7Xp?e| zJUtWVcR8iPkICnZl#fL55mv2WnndZpaj3+w`K;)}=sjETkUcd%vOSyHey9LQTERYo z$A0*<8TX2TEwV zX*cClniXFf?Zr`Z=8Lwia3 z`R0<+RQ2NDj4qYPm@^}duaiYbbP1~;y!6ip!fxbrkRBzl4jwmZ&hTMA{iLGND6kB} z_{wQ0m_f68eh5!5vk_v})lQG`a{O`Yw~PbK)HlvAWh+wC`yt{ofcaXaP%4-%L-jLx z#=g(ntTW8TS7@nq{B8tZLv~{^_IUtd_3?u2)wN!3CC*@y0U)VERSRgQ!^*Y~P(8S$ zf}ZrY!B<9g{;Fmq=J?G@z*sTCpw)7(-<{j^jLjwSud8=TW%lgdI7TC2KD?wwxjF?^ zUglX2Vdw%YtbaBD0%jvcTIG6M^Od_1?)f1t3oN0B{4ka8-2D0DQb5#ddT7f5SgDCgoYvG_S1Z*BzJIP&7*5ZJ2|Tu~Qmg2l7btn@^Cdd@U01nZOw&>*=nRCC6|@JEttA2~05Nnyq-Z}j$v zwGmnS47@0{0ly;tkN8AYtT0&7@mU5urpjOiwx+-;8gA~(o8 zLL(bvryQ2oj)WEL`w%m&mO=$Zv!H;4`EX_v2lsvf4vq%@+{gsinxAy@g(Q?3^S9t2 z_CW!jyEdT>Tf$#E8em~fz?I9`SE^K1S;?7r6^0|`Plnq}nX>P0c37_E?VLgtA~}6I z5$Z=`|9RF(eD(-9jgwmVR4LKybP3$RJ8)S6opd>mH_8X57RLVa6V=I$bGHz-4>6M% z&k4=6(sjHN+Qd1$wyu)?OMAoU^zXM!AjwCABhmJ^=_F&@{9xDTHGeuDUh2yd3Q3pb zAHkxqGx7`s#6YQz7*6L4-a&IJNw8RuL7EnY`x~<9s_6bK+Be!zJS>9sPMAeFK?hI) zZnL3S7UR%!jj3f`657^@AOR#MO_BAzYVJ8pQIar`Jiou~O1u-iVa#K8Ik#cL>$qYs zEtmyDfUH&(x3D^U&xe;ZT|kq`kP#}3T=kPE9*9!ybwyElS&yWtJq>N1z`?}6zX_Ot zG;BGLJS)g~LTZ~o7o^!yvC-#W;q<>DQ8p$0bM+S^>LA;|jO#5BnPJ7r4zLO=k=uq( z(k?GKP7Eov>!L!!hSV1?zLu1M*TMX;X~WVreDWRrW(bs6PdTjg?|jnj^c5AGsV8J> zQyA6J5z~k$WGJIkBmM2US-tFseht=CpZh>%E|cHKbGD&Z{ijwLz`=#v6|tGhD7p*9 zt?F~RcAXjeM~KH@>_!zIg&2>SC%{bx4(|zI*elLiqK|$mwGY zucuF@bmBa9rQy8;Qpj`OJX@dDZkqWHPn^QUiaUn1~l~$$z$E z*=rh-`CORN+0gGMtgo=d;LD}YhsW+K!f@7nJ#hs#tTuYUf~{G~3CO*a>dJ*ZfyHUq zxw(J`FLXI!uD3PYb!UQ>A`}8%63io{oxH?-U_zL3G|jra>Ky0$n0!|%))$}~rfhS2 z4XV`^7TnZl%DNHU7;6*&-c?H}7W5KRnLTo)UujF&4iF1G^!rdG*5cUUi6f#W@mgU7 z>R1JnDcw0O6n=tUrxG(7x12I4ORF zR;+#qUaYZFh}NlzFIQu#RZaTX7$nM6>I*_Qg_wf}CFW(!LHO_z7}siz)g zLAG@C2R?9t(mLRnZjpe{Y;cF{e6qf)jLmQMiQUY?m3q;+q|!~-acSzxq=cgD{3kql z@&Z9aHS20SKSl5X#~hiYGCK3mitO?I@5?#J5+N#t1$(;7V|mGyhG&hBC~%{%u- zR~1AmB9JPop(yvB4XZ3QB5sB|<=V|(1mpd0Qey{yn>|o(KZVBou=HjmhDyF#${*!( z3*k%y6fw+k9;3fW`;w|hoqQQRm9oMw`juwi?46dV8}Fjr@yRGhf383&5%-sZ;)BFj zr{dzKHq0TWnm*g3W&Z8+G`cpyQ>wLO4`u88AF3v81H@1$CBswd*4@obE?(%Le9LA9 zrVf`ba&Y^DtpaWao@;wPg{J(JJw9&O%Z}q!X^(+;8A2K=-;8!_>|Bv%Ooq;*;IuA1 z!rZk(5Z5E}IVDaeP0Snd`%8CGOES`1%G|B4J|mkS2}>LwE|$1R4ucso2zDDZqUl(G zYbV=T>FiS9qp`MWw0>)5Po`zHY(5v$P9I`-M4uf$+C_Fe<{PUNDcP1?R<(FHYJTbS zF_S73DHQ!>2s4f8@iA>m9GKsk2$-bgLGpb4~TKr@bI4sv9I}n)OpKWMcQKah1(O09o4WSEV>8})!DPLU?M4^H(RM2r3brpP2o{*4pZ#Kv@*$BzPugjy;0Kn zoJ`(=Hy1Y8MS`;c3(9(Rw?l6;f({VfUWYQPHK0KC>N!&%q=V)P8fG}IyvYb;h=npOyBl8aT{e=1;SZ_Kv9ASC$h93sAW?t5c$^R+JwWMsfOZdkbMbz zN1gPWPLPc&?2PFLl9Od;lzn!@Rpk%HCsb4YEN+}Zp0Pl~%8R8b?eUrDzuzonPBhN% zC=IW|&l@d9*p+gL$M+Yq30i+Ydv)k&J)^ybrkY8D;tp|a-_M?;1&|dBzB+Z&a#D9o z(30qOQKEVA&an{o4W++oLVRgDDax~Y-Pw}el8rwQlP1f{lXU)Ell6nLH!zvjzmo6H zGsK$q*GAbBHDJbxg}HD&J(uIu6inI)TsGHHGaq@EUe!dq5%6GEu+imN9XAzRHd|u+ zlNPNF_w2pD0cjsFt<*a>JSN%HWa!?_{IwP=G*1hZ6zPe-4Y0U)bZb&P9{B7Cgxh{M z)e6g_*~MV8xEXbt7~i34ul<{WS7zd2I*j!)xRGa0(R!YO%!;7r*(h5Qe)IeyUT6fz zYBM6WF-KK8WX|7+^Rr!$pBXVcy4yUps%Qcq_Z{7O4^^$Pt$|-b&UMe!yP|PD__&_n zd709OUHD^8F>~+g#xZ{?$eywezCR&1N*&E!B^(WTPMNw}B`11>S2C%C?2+FP69?ga z*S3i9DtEwjnc(&hL#|jPI%J38E* z;C&-lh!||PJO3E_)-qptL;6qR7M%LdHB|$axX2t5!*_wP^Inl`7Hn3s{HE!}F%~%j zrSr<$j)jF9^)O4qIE6vZSJEf#*KlvJYN>Rrp861cZe@u=*+9Iw;J?tFHQ&(b8hmqj zqi5t60sdjEZL)$j1o~OzXcERR37U`fxgOB}^u}xhDvYiSB2S42XcMqDG zu@rA=)iOtJCUD&U@qvJ4-4fl)J@zFocRt@(79fKS+`Z7-kAF_C!nt zXaj4YP6QoYS>VnFR=LIyeg3m}o#rPf*Q7X7#6rgFFbbO+2ld_TC&CDOoSkirsxeWA zwYGbyO~p!|hpn!+eT;qiZ?XEb#lb?i3CGuD66&UP0Y&4h38|WL4|5x`rH_wc*9}pM zt2h-6A-S+_MmWwTP4<#{8Atk}`*buz*jrN!ib2PNufS9J@PKM#SBQv{68|gBGnzu{ zC1vM?zpJ32t(@<+b$l}x98+Z&6s(vBO^t%5+B8_4A&~F}NLL=auTJIoWHdhH z5pp3@4R)gysj<2%QFn9JjXazZbBHsiL8Hx!R1wh_o#w#kH_hv;@I}z#^ucYMwvcer zC^dQ7`EY9>Ri;?Mxe1`5p=m(C95+=qjb>a{Uvv^fVN7|H<_}rienJ?(H!bNK*Sluy zh4{P|oF(J#EKH%r=6dB0>}r%a4Z@%$WBe%V2%4#N6ZN*{wwtCi0Bo}_#i-peZ|8zb zNSICT1I`1L;UpBDb)O6&d&`e*Mfv-fTEd3!bdw@D*Z@x0gN}7+f45I_5YyXMCFEw2 zag59cx#$dP9-3}PLe5~rC&$O2XKwkDG0W07>B=n)`}4=VkQwRFwFTfC&Idz^*O2zg z++QVh$r3b%mk_<3oJJHf0072-|5x0JfFr;x>BkS^ObjGx4ic zQWY`n(sGC4FTtwpz5wi5$5-;0EXUYWI-T~8A)M)kUU&3!%M&0)?KC%qROQEV_=;jf z<$tjX%SwZ@klv^_?N~u?jP=I3>H%e(r6`c&B#iX zW*Os2aKi)sV{!UNkk0}FmlLba%R4f{m`Wz5$=gkhc(uW_%)Hh*pSy~y?@6`#v4u^O zyM6a_@NW8QZy&fznNIqG(xfk3?u|N}xyF&&=q6i+Mng>z7xksFJsphuRA0=zdB>;9 zo6(m{%GZvIl3J=Nl{1kRrYpOzyA5c^yRw>pB@W{hTIOpquhv<6whNn*=4~q)bhr$7 z0|M>RiVT%|vVF=VexAMM=3=S`yjBQEMB4k*I0R2Pdm{v`Lvqv2eqf4Qb-mOLJ~Z2@ zX@C?z&){!?-9FT8vF~h)!(onu00poddZ|rJMuS;zYab_A=;Ve^J@rd)iXr#I73FrVEvTSt8#_NUdxzg8}-AH_| z3^3c-r&(@qujqs}%mG6Z|B_1`Nh-yG)<(k*{40)T+5eO$a{Q-aGY7~2?=LeEaIi4{ z$2^gfm6_@Ps$Gh4{jXv(I-L&C0wIwwqy*gdw$1`;AAm3{jIgvDvEl+HK@8Bs0#u-X zle1gtlBk@=jNfX9+q5S0ZfBm(Z0swxr=<(6Dx`E7r#jjNgc)dq0|Zc!vhkBY4gee+ z9UB~+ERCn9&A&wID-9<~7aYbZKmZriZ!tbFK=95hg9XC3whYJxgrZ{u*k2ofpq3zB zEls47NgoIR6y#0a zHv^air;i~VbPVw?P~fIN?hUb~{}rI7JTwHx%{x7M^Z=WETM_|xXJ;oj_E>)iEL0w+ZUj@VD;V&0S1OWeO;KkKd#P= zj5aQ9KSQ67vwvzJlfX3O)mvD@13nauKYtW3Km*{f>uc$=oH)X$-UtCSbXgGc*gW!q zIc#0vS`eUR!-TaxJO?zuk@>q4qVX+IcPn^%0Kp5vqgRMtc@RJY5*EN5?;!tsyLumi ztUWp#dib|o>=pm^R+`4hydu=a9)N3br~dbp92O9;*4FBF()aAi2B*+AZuc*jh9C}Y zweLcmvx}kM4TOU$D7D0IxfA`shqx(hD6l&R2*@CgcT3T}LV4OMrU7tzTW2j)1K`0L}^2%l!}T+bbkA1cF3WN0Um&G?B_i&5Qnetk1tbC9)omQVfQKjMX%;mO(}IXQRV0t`EjqHq+}U* zUsg&IcHabL-y|S_>VF8{|*HuXF`m;8(_u9UUr8^Z+a>^clg-VKrO*-Twmxa{y{fsA_MaqKes|c z+Qx)<`qC~CTLUL?oFA3&uQ%6(vHC7$&_|~^!1|z$_Fv$gdfd>RpI*bqJzBj4ci*bt z+(prapi2*@9}W+9KmrUHW5}01@2})|{_Jnzhcx~E%0Gj*m``8>bEm-|m`7OlZ8~zC%>}c;D`)m2g5A%oqC5x2afBXE0&+#kI zKKmE!N07r8c*?I4;Nchh4SfIj2RGoC_Vi~P=;kSoyodkzcQWLXf6Q**Py8n(tTL=+wXrNivW7&NS5oLvFaV+_tL~d#5mrwP(S+!_&d$L($2-8Pduzyy(=b zzh$V?R%&XrYU99)-ZoqB3}lUvouGws;gqBE;jrQqQMb))+@tH#_n*t;?5$!%leBgr z=(3f#igC6u1}IYO+-aJ5bj*BiuPPa176Oh3FE%&Vhj{GAQ@r>s5p&XvJhXCdQ$K+D z#c|52k|RG!JC12mLBt(n?FeXr8O1pBZ<`Mk@{cYph2y+YPiuL z()$wLkq}UA4VG7Bu3&!@CG4(%bUjjfd`HyEPA^V!S3;0=SWrC;zMXk0uHK*V5F4G_ zYeWoQ2fofa$vcy&yNxa~@Pyu%P?39}`=U!fvz+&sT$Vv<-B{R~NOu<+v<~%cTyNIcfP#QngNyQZil@6$)QcEp zZSx2io>!&caW>!$`s$P=eK$ZJ-t-{chkNZ6)ZN5n?!e%gGDalz`eG4aTysZw+1?Hn zyiprRB_n}>9_()q;oE?C~}1_kr3qb1W=X!E>(o zaHe0jc1u~ZwpPh&4gS`?a6c#4drKP$<`KcCY2`s-U&EEXKf>j6l-k?pTwR?*{~g^R zDY#DFIrHwYta$I{6bCu~$SkF%otOF+S(+6Xv`O?bVkGCP3oi_MdAS>AgF4m~NfqWz zzrp%%3YPrwbP7e@u}UBKu~!ju5;$ATKQWD#C!&*qr#EsN=O%?>q`UxBAhg0RSz)y1 zlpo|P@h=pET)q^&E;EuIGE=AR#HV|-LLVx7@QN=9W6SP5T>z>xKa9tI;$QwMwA*4|cH3esWvV!5Z zj7hVg{kAxNO}clohdU3Y*Ur0QH={#izw{3%Suqn-G#N7_RVe%^ATcd|OLKK3tXAtL z#YeX(d$*G*Uf*5O2q*Q%Qygt-Q3tfA0(9qOZZffsX7x_IZpSlss@1KAm9(Z@hB_-) zB_irsDlbI8)v;n`v#uYw1Mgb8Hz-;$N2jt4L`0rM2LXkbu*;1$O!kuDCH|~YtkuaI z%079QyRNbJ>o9Gl;TGWbo_8(7DYL65>2iuhR84Hm&tPe0>(22~w(qW4CObxpia}R$ zUghDGk>eHApP;c4>CiMrwn|&c21))@9xU}O(>Dq{S-2}g-J^=<5ng$P%$Qep-cF{R zi$vgQ%T`H(EaDeYIC~5fY0p}eqXYHW+Lpf#RJo*TRpGjTZ!EnAA}~}b_oDO#MY2P~ zMlf=TEmnt+J{22llxA#4v1vTMp?4hRu!9+!YT@*!+uy&mM+iEMB-M{4rO4Wn!-Gy? zp%ayzX~kyXWH3APs~3N`^maZ^q#BBVIbotHn`;e6iZ~+rgoqAy-%fD+lphSc31<0l zy_g1xg7D*&K8fSoYa@Cd)=<=t%<2;263zwBRKmgQk!~-CtWINPW3qsSJ~advpr+XK zrnB9|d0z?FM@uZ3(Rp(I)S zl`9m0mMVq5;D<_2^`JleXuUdyu|_Fyhx!%##Ic)14m6+-HK%{aB8N}>UJ zXN@IL8zGr|~&Ap@Z#0^d}dIYBwIRJ?j~CzeHE%gKPe^wWZ z9Bp*cZuWpiuf7#w!ITl6P`O%@Zk$MYeLo&@cFhKc?O*|1ytw6N!2rxZ=dVtAE|4g( zhYPRz`~v+hvYTOoBTVM2YE0HbR@JcmWk=g*zT6eZMXW9b-Nd+_3Dt^q(MlHELhg(j z;&kjmrp(8mF`do90AyO6)B;_2!_cD@(LjZ&FXMmB)~SN#Y3-nF`6-~pK^9LzCf4Umanqu^-zH;`y)+9Rb*-r`^G$dicHgZ*t1VPh|;o! zyM%a zg2j8`RW&Ap1nS0(qC4@Fj}zk1DPBDO(3c0K?0S#u3w9|da?jQuvX#mdK}K(T!sPbJU4OQmt9twssAr8o-6!W*L{Zf3IMU6zuPAwY%;1ZBl z^(s6Jc`f13O&hVns8=*~8)33k*KUT6xYmiPGQH|(r? zy+k>~*^NQSn8 z^{7S4qKWD?&3Mz;X^`qeXENmB%Lhl(#DkWf_i(~kz8+uHmjqn~iFiq$j}!8i2gxhk zyfr%Ep!O<&Ahbotf@*lBxN;1B4ez$N&ZqEP)3q=wYlk2ywS!T6Q~iQ0rs(GYwo_0E z8}S$FuZNSoTgY_gAuaByV?|wh;7AgEJpA*hwQbU9n0r-g1_l$Pz3~{{8ONWvT|5^K zK11CBovT?%sOUls!c<6aek@%&1b#84+JQ!#&yfD`P~Ld5MlE-<@tq#bZi4K7spK5~ z=JRdGMm*e8R@iix{JjTHJKIf1H(WGCo3tva!HLJ zYHNIKhSmoeI3#&-B#jD|v6=(-3p-P;m<8$^C&CC-7CX{e<&RJh^;cL{IM%*eC>g#s z;RYMnKQ6x+OXfXrj^sGx`Ul=HD)ya~Wvw!*tvPkqzZ7bt=o$K???lI5)SmuN&IR7h zA=Q`UiuTubmd3rK-Pg0=Y0=y}^>mYrV&mzq`@`abRB|DOoC)UuVuM@GX2fVpIOM>_ zKOb!~Jz-An(B8_K;@rur`1~**lZ5k1I&v|7)poc4er~Dckr`J`i9ON~x#6G}IzSaJ zt)_gS!(8)wd7H&_8dMNH9`3Ubi_K*(SOZ>b4_Ook7y)bkc+W6Z~2c{)2NFYC{3!!ve5 ztnW|_!$yJ_QnwQXw0Q;BJ5(#)z5f8Np4Rw$EBfyoCPn9BkluZiVIO%a&qg}tB8DD+ zp*227he(uljhr2>>~`91u8E{6lcAPT^9o#F7p4d-1mza5BHfZ$SL1xRUyV*ch8Q#? zk;ksCWdd}`oPE!6-Vbo_dat8Lz`{1%TRoCXZbdBRy!DPWR+FD*X)44^ec{pi_MHKizV3F8+{V<#(kfQf=^LqL& z1@z-n{m8s!YFz)tdbZTz*^D!9YwVJxsl0eoIA=(>i*EKm{lSvSpYy6OlOlcjV|I)5 z51v1u#=R0*xpO)(kXp84n?W5s+>=b5kx?=5d zZMfY}^uAU{PpFAu?m(L-g(%;{O*zM9C6w^o2FwEX*|-%IHmsu8>Ues@RClDw8lc{gcHq_x#~XXx_ajgDma1q6R7G@DusNJa zu}fEN(;F)6k6w**L%e93iZ4bc@Z`xXPG0ST{%fcwl*qb>YqYKAnv5x_@-IYLQ$Nvy zxMn<@V)Ur>`_E8Oz@E$K*t;P$yp@|&lj3%~$*9;Yqg7HzHanTL^5%HVUr|^103IFX zHakN-a<)X`_%Sw6wo7DcqE#h|w^2w~xzeZEIRtg%op*L0MQeQz>Tx06e22#z3X!Or z^_JK|9RYA&BKN5tH?M_fYgSDT}G(h21n_3{yOya$fK-KW`}?10K)9FU&YPvuD> zp?1-&T*!H0KM1`~mw2__d{aX8*{xi;OK)tn+xDw%+ypMF<7==$nYyNh7noS}hIr^S zTWmHg76f=?AKARn(iUo*1`2gM3Y8#qC4T8e?P?B4R@S5fskIx{71lD)t z!iFeXqf_r&54o&LXjP&7gL<)Ff8|M>7S&X`6j#&6WkS+dnMw)Nuw)3WK25~r!LpF04jCt zF(tIpdlNqyZr&pd$jFrw>)RZj0evGe&RN%?GhWE)?7wVK;L zi5oEnZ~X;R3D%W~M=|V^8e=S)CdXdWJfzL%Jd?bLUhipBU-4!A z3A6cDs_bLEjeD@J{-UmnTbYxBpsZG~RH*VPS6(BNqFq00U<*HfYx<!55y~T!}tgN_?sZ-h+7``qq__cePw5eis~*KJ9Y}dVL1RG?c}2 zn4P(AC>BUUpqg+f`l}{WoCix*xdNiZq_u6wp4W7(-Et({*Sz_@5TsCDibTQy z5^7IqhEa3qvf)*6ecu6fuG9Ay7=$;Pdxf{r4cdttXiL;}XLZ`|%S^>xzjFW!;z=`~ zPv@jALl%zp+3hl-(bDn?2X9F+6p;v}o>Xl@s{~Rz+>SDiHuW-LfbJknJjQmW9Q}0v zk?un0RH3;jJG|%JS;sM=rrKWHfo@09u|?)3bo$02t}KkF6NlAD58(P~;8mHD3S<6!5={liiZ)uG82>1qD zP+dqe*V%E-xOJIiMyQ@e{Ne@NOip%Xo`;|QKT@GfQeQ=dP`vWy+YkW9xB_9`s zXe`kigqvNFuwqfEFG<`M5lIVul&zf){b^E1Jj=X{D3!QcpFt9J==+l*?Cw?Kw?$cX z2`!)0BmL@%$F-=A3sW> zT@mbDNnj6}n4V`PkcF2LflumVnk)sb?_IQkxoU?roh`cN;0)*sO?@0!Ao?)~uc{re z7RdI&+2ord~PiY;8zm*qeC3IvoL5e^oCo0mMEd#jrD%2ms!L6TnRVv zQ;~11rqsK^af8*;W>%#M+3i65i>b%pWxoRFu%ryMi}L)~#JVS%i!4RF!fCc*VriPy zdZ-Qg8jUF%8&U)Y2sQonD)s2&L@2Q%);zz%2?AKXTghMUcw{j1q=dakHhEEubv^&d#K6xcLWskN^5FPj$JvaAY^|$_0`C3bJd0S#|Fkk+|+U#8DISq zVBRzzso4khRWFeaz81zmW(B)<&ommGC!Td`I6SKOE^SXE zsUoJZ+M#kp;|C39@>1EYz2W{jH0rgS;HpUc?+7Y1MrWN zWZQd!8F68(hS-^TYeuRW{KbOv{964tO?~>@xpt$KFCNgwwEA@ zqG_F)qJhP4ROC>z8IwT`U=t?v+i7i+l*!{nT5dV^fhb4y)ws?0WHyaT7~&KLizPp@ zjv_S*QiNW?A;M)cq05^a6GhNmSa7270ki}Z$n=WsyYcZUxGmm$OXayP=i9{AF<*i}GjJ~MY3^h6k>V##8E~`d8W@xe@a`!O3z+9s5&X7^|P#rxF~cTfux@ZM?Zz>FU~E+lTP}gsx*~Q4ame&QCga zhfmdY1WD)fX{Rw5n6FDUsLj`3J4yMY{rw6%R@&HU3~|4 zuk_&~qQJrN6F0^CTNq~Pg6c#wzBmC|IK6An}>zRwj&J1IeZ17YSQrq7|F9W5=cj;m7}Fiuus)&0;=TE%N}qhVIX zUo)}l6;=_Z7W(J@$*heJ8xo**rv4(*!KVBt8P!dc}1nk(Tag zo2#odZrM5CH4c%b-8bKdsjF{i94i5NTE0L6ff9G9TPivwQHsrs+?+RDR_%&A&XHlq zNn*oxO-NVnd0g}-qll)h_wbHejvu%fc@rW3?Pfy*J6RKdI>lGj1x`^u;68oiPb$Ok2Y_wwH7Vthz z#YGW-jl42q!yb{xG~H$FOeq1Ht46J*g$aRKmU3y2f$a?7>XS(|uWqy&q`$u->B=VVC7VGuJ4BO^i9co@dh}mx*f3X zqw*~f&7>8%Da&9VM0iUYl7sJVuz7J{Cb8Q$6NzuK`g(QCqek0cXgY`DZAF^*sQ)Rqy0?gB&L1KVx!V06caG{5JxxOk}7pGd&r28O~T4PhHY); zQFLgih|sdI;fNCoT)>q|@%66Ic}q=<{pTt1P9GvW!vP;M zLqR{P9JekW%AhJdRogMrzkdTVmC+4No?wZc(rL$ZJ9UTFp~(%H17RMaf9!gXfTYV_ zL7>U6=1Mrz3kRTnz3i~^+v%ezfEh`c@$ODcQz)?{nTdT+!d63J9!}fR%?z zM`FadU20g1=qklMd>=~rVNb5I-~BLr7R>x$f9*u_T6&DeA- z2>9|FoGC&{P|h2eSY;x@x)k;o@Y@&5Op)~j&)C)M8@{X?M2w?B>|4-uBsNG?6`de* zW)mY8gf%pmr|*h!n+1J+uU?d}=mq}u{^Kw#!5kY`oId&7sX1pSimpf=eIgDkImEy0 z&qlgm7G@cvb$GdFC6+@?RRo%l2RO_{gpf{ZO4?p#A$r;wiUKrn<+-dx=NFees0p0Uu6#lbVs07Y)?yu5jw5 zZU&J_0(NnDBMyR87oDe^vhZ_JD~Wp-sMS*|4o``7T5fjrdOymKhG_yeB0A0gidI9+ zT^h}7GHp)BTj{Phlg6G(Jf>tAK&UgV@5|KBy?R3q40%@Mp|!)qATqe~)%chTAT*{< zgoM$Un2}A6maUta2a!f?IC2DWoJs+U)_3p{=ma)d|_*qH|UQ8o^FFQRS?HJ()n{6=ftClrv7cmp28}H zUOEiS(%WtH!M`P28iP;4zz0wP)Wo-r>a&Njhoq@Z9~fe)KdzDw(7(~0e?=f~nUulY z!xIJX{$;3<)_lQV17hk^jM9+jUqDNXs=)uy*UTd3Ia++^1yXybkwuOJU)dA-7fEWU+iuKR?1bqom1_Y%g zMUntOpqzjMg+{Ee!x~zUpV>1rehO0{feQDR{s=1w2nn81XA?pAjw}lG176t4{hQwh z6lA0nbf6$WAOHc8{*n+oB_bg>xVxW%a~8iL zN_2m2^#HhIY~U5ZiwY*j7b5h}1^{jln4jq<-Xk{y!(1Cy^j(2LXt!`fK!WOE<`@`I z;J6;|gM|wu22@W2f>~t&;G$D}(KnswgXs0&ZUKP2gZ?IdUVke?fc+lB00kq?&=GKe zfwcp#4dxU8;F`+%wSZ@#0|W{CAqmP+45#v+F+!YxG<6bvadAQv(A0wi=z_j+^Ppfr zItv!RDKeDj6GDBZbpCBZ!YK-Ha0?rpr#Q$zRSqF6+^cRe2KlL~A;#H>;+zk4U7ovBeKztzp%L44h;j{kUENWu`0RRwiF(8`)H%88z{xdc6 z(o6lb>U|;ud;sTN)hh^KfBr1Letg{qbWi}d;ZNyrReeBRVq0(G%XS~p54iUoz(2Fd z0WuQk9i(KG6aa`Qi74Q~fe=7Gzw6IL|L**6(?yU$pFH@Nx)Q8iG=Rhp>agm|58ToH zZSUR(FY{Iazx$k+4l6TC|FiwAHh^g0UN!!}?r) z@4;VwhH=c3kayXR3sd%|WgQE`x-#IOJ{99L{pK3b(EhEQUvyRB;JOoGJiF5;c`QQ; z(+qHwB52{@>tCy)zG?^3TaaL3S44`n*-fy1atM$gcsEu@gRyFCP*>GzeS{~gf}brV zNH{S8Ke@bw3Jib{ksyZQ{%SB}BveojNWEAJkc<23c0iyn2au1ypbn^c@cn3kBtM#p zhKK<_PmKdQ(-_(%M5Nxz{#^Pj}^2JAST^%V2`dW+Bs9qtdR9OOn)KhtYg z!xKcuWeWSIxy6vQbMsCE+@wNLZe3-VyDMgytKJbxCoagP=VUEa^DAa%v@qdo^EWG( z?%nu*W1SZ7yKemPqoYNk|Qyq(s zX)WIrz#W0L9cHGm%PDbvhKTV0$)`LS38O7#@Ou|JDRRvCIre+->c$8Tdqyxw@h#Pj zjPPg_nZ_#Q(tdMDJt_U#0`;X3rmpCcf_Jf8vE8Rv;vw*Fc37hK<8dligF|RWIGJo>Q4P&+rc?{(Xb%g$RiE zsjNPGHO(_AN95Hoak?#&O1~F$oo~+i2Z_xDo8BB=~!$VXP)p*o`{qayN8*@ z*xTKT2mJYjtB2&cd7snBnQyVm@VMB7@S~Ihh;=Z@S z4=0=O4#YE6zM~kIpNyc_m@$BmNV0c*HG2Y$V{x|(Arb4hJUKt^D3gP0uI*%nwNj&B zu}>6om?~j_${EJwC_(c*cxl7{ufumeqfe1pY2nM2*p0h9I3K|B#R$Tcp87t3koCSCz0=D zSu+yQ{cj(PA+p-(4hKpb>lUQv15kchT%TfSk*g}X?aBdSstwFkY(ob z?{is-<>x~JLmhUP1(FnAq6_3ZkC*c%S`$~F2n<6OZzVPk{3>0g*cspu zMfw&fi3rFXZfnNt{bg&t_?WTQE4148=83#`u(S4_#E{yzo{RbLTFqS(e2uy5g_aA= zYgW=m6|b#JrvSpo=9ijo7DiZ}+*(a?hb&n@%qIt-g?(E^lcL4`af|+0w)yh@T<_4~ zP9v0p#pe*7jZ>Ka5t`diDf%Y$1+U&&2{Yz6s?5PP1wQATqQ(y_fHjNn)*EZ_X=pY^ z;KQ;#VApZxkfjjdoDZIzKTe!eLgIe^=TuT}HLOQ+e^V5Yd%k{g6M|(A*RrHaj_!%0 zl6lwL&yEjM>4jlz?!lF=m*_lhE5^@v>2b0ndfUQA#3{V*!Ql3E^KalsZd)KK0aWnh z+x&gW$$Wb0Ep4Oyppbi5DuS`Mwu>?ZH?G3h$5~?sQi9RqT z&Nm$qmK)9-KScMLX7#IH<$5obZE;IGDsh^&*G;ud#|8Qz!Ehi<1OB(df1O>qF6QUqV=xRL7~C#}bpc7U7ED$-*T%Jp~q( zfjF(52lW8D>A&eS5Tm;*?B-GZyb^Xou01qVzI#?!itUjl0 z+hVR>f{7UgpwNZ+^m$S&8lE|_2^)Fwe zJ_wFz17i+B%B68;&tn?J(@yP>dR_Jg=IPz_{?)V2IDEOY(!>5K-#+U{7Zol3s-)v1 zB;M38B$Xr2Utbu*--Xu@PLBw7uXQcev9sprIL^(Dza>EKF~?0RsnF_EQ+^XAFW+7t z;msE}sf$v?$it@Ofr_QGj@C7~~x?#8vgR~2tu3k09FCq7u$jGr5WAX~x z3g*jlb3D!()!NoJIqE0je!m=NxjV2(OjL&wRppJyj1E*Fy@969Hzf?LKP}c|`j)9` z*M4JTP^n7aI+4E7u)ts3n|XXg_)}ZFuawF5p$uFQ!>2Jl>L!no^R6ffi77vF$X7gk z8m22ZGxZ<6^73MxEl)ot;~r_n4gL;PL<;1s;%uco4^s4OcNK~e{KnIaL@i5G0##;I7IXki=`zE3c?E95#TPdYUf2alW zSTNJ2=NA|+4c0y#(9_q`*^V`#)h&6E!WYki4igyFT$wha-E3QqdM`DIhz)iB&TIAb z4%Rkrvujz?^vZWB%=Hj_y+gTjj->z0dU`{S$2Mxv4KRRDTU~@D~>yP~yQ4v&h zmD?o_Vp&R40~52S_N_OL73^Q9x$DhUIA&qJ^Dx)bi02&-WGGL@^Im>k2Z_mt`?kGW zk1FfQt}`&P`#FlEcGI4wyd4B;HOk7PG!Tc?#GPAqoc)_YxCMJgJ8%8o5x!+ zxS_UdCD!6v&oIKtq|f&|#ORpBPaoJbw_1u!*$}JF{eX>J3bt*w_VD7?f(k zF2UIMR+oi%HMOHl&5NIsnoBjUVk~}n(f;HvpI#FOPM#UY`zB(whQ1;?E)4o^5!p?I zctYBveZ{r5GbmG#k@6s0e|JT4I)i$zEZ+MT8BK70-%S8$jW%%z_x#ku5RMh`(mhBQ zQARHajw?-Sb$D(~wbzHp9o6PLyq)#sHN0)p);>IkE7;kWsW@NtA#TkJ;b+ zQJ57hRNCBuAPjxc&0jP_qO%o+jN4uyH-fy*m5zX@AMEceySr3i+WLzGvNdMz?hN@5 z_MIOl6XxC^4o+KTMY=j;9Otf@waU_Z;aK#7KmCXIIFtBur3G2o;6wDV_fA|c?tONF z1a*5nW^YdJkb6Re3(_GJJ0o`18cuSS?-;phxU76hxPgDjq&_x5MG+v3gvs@kU)>bb zU~&`{EGr8``_SbSF6Rv&T2=+V)l189#RaOSBAUI|8o?Zr*kIgC59lk=Tsh~+*O57A12_<_`{wNFTu@h`V1W;8O^&Ku1lE`URkGT~*UTQ-%=UoTt?cFt z+82>M~6xu8P{ZBm+8T}k^kHcmM97y)W|+ol`9x%S;R z&DG{q+}oz?X9}M3-<*BD&jrj*tcXig;>Wd49Le2sw}Cw_4qEj5SHsx1)n<|0^@kr} z^KK4xWex$oFcB=3+X#4qj1 ze@oTzkc1@Msu1|?j6P8|22swaUcBwyJx%+Qx?38^dgvl=4}TrXmgEp)Jq1KW?A~dd zkQlaKx3-z4-3b{F_S}p>XQld;@zPhNveO6y=r}{88=<5eAC~sn^D%BvL3Nq>^=9Cn zyuphS3qE7IabnqbI+tSFJMv(pb~OkNs!1c3F*s7}NlV-QtQ&=5%4jPNr|`At3yO=C zoKH?=P=oEdv?nw7|YR~Hs`_UFo{7-P34!>*q?s8_enu3EO57*U)uS!}*21#a5&7J;RG zvvHf~7B+dUSn7LdW~P37@Z~a*bS1FUDu8*gcDFP?b-A#*l|0^y?!=5}zn{6^*w9Lm z)UxTe_#}^hq6x@Vx%_m>f3!ACqUR7yR#e#KdWj1bb$yZdLmYje)#dqTrlvDDqAXV+ zR6Dlr0QD*ypUN0O&>qq7E`~fF$F!D!&*;}x6K7r= zZU_lrT?|~^#x^mJtaN4Dn2lzhgo$8?x;C*x&Ph>4vUjA?v&l8+qaV1m?NdzJaQNjk zD(bqr-)MPlOlkJ_kCFosehOsPwkaOQc+cQWiuhoJD<1@lKC@u2T3m9T!%!R)jUYBa zE07Z~5aJ$^wq>;dvh-s2f5gp(p&}F;^|sp<7ejwoNL=P&nJ0o0c3G?ah+?xL{tCC0 z9Ak5ao+RJF*M!`=%JNgNWb%xhZi!ic+S4*03x$(!U`_`KdP3V@xvpcQwr4 zUVgsy_WK%d$zY!Vd{_R4zPlPjXg(Z67+NoXPv5Qzb5_jVquDRrcmwavz*q*bhkWVG z@N%<<2c?vOxOU8Ur%Ls)#GgCObFNUgYx+aTF=ZBj*xP9qN{~jUH1I7qGWmBAg9GsF zVl<;pAW3RSG$xNkDqF{r8F7)*6E~qrkk$Msv1aOb>9y~dshySqr}6IGo6|09X|AB4 zr)9=Gqo+Eo{V+CtiVsU{lr|Vw-i(KOxt@fXg`OgCL##s}W#?Bv5{V8oZ_RsD zWxTz(=mcTl4;&IgB&j;OR)MU?j_n--d$ITeY$nIzQCRdz3_SfE9>ANiwQLa^xhJ1O z`u=rK1|-8p_o}YB2{#vpwo3Qf4-~MeBtQT4*mmAJy1gYGrEZl`G=vQ9=Q6E*=VAtH zvy31S;n{#o=b9xppI-TmWA+hju$^~vd zNm+C184>Fc+_X{uq5UyB97_<23c5ZEI?ZX>Y3KYBkib%(rZAOJA|>*hiMKdWL>VCE z$0mQ_;}7;A+oDDYlUiaY)Hi0g|Xk=CT_{?R<99%Ky8hNfM#VgVqxy~Mv5RM!^L=O;r{ z{Wxmb=(9VM-rZ#8WfEC%^%N*2(X902bxo1l3+rhGmLz9+ZUw)$E*=r;<_gV(vulRF ztuMaJ!RkW8X73NJaoy0 zg)N!}42=MP)1;T8v^QqYoqvrPU$JOx|MQSX$-1E%q{ag*&oj}ibl?DJMIv|I{~hXTe@^~ z#)r~azNY5Ue4t z+YlDD^(GF4qDp@9>K-)lU)@aUqJO)4v{7qVK7$1`tVqs@W7TQdJRX@(K_zqcX^mHa zQ%$S#x8l&9K)SE%{a}g^_)s9}B?#w_7E*(KFj5F>cvtmG-`|5BIe+_Jr=pClmd2I~ zXlbkXrLejL%)uz_m~FC{l7(T6dW^?Z##+Cx_P5 z`KvX@RhC1hNAL1+%W2fjcJtTij*<PR;~r%6Xe=e!u{Rs#_4NwXEsnIAm!!tvo5chT`Fv|oxy`ABiEY2_aZ zo2>72`Pk`B^WD^HJQEN%kIRp+`)$Y%Gw_L=B1Of8k*Zy8DD@<)KI0on*a?`^MWzV( z@fGuz3%hl4*MX$|y7gkh7;mK?P8p%=WyKl3tlha10mxw1%+{o(w?DRZhSn&(9Ll-$ zm>7@OH|)GUAozBBrmu$F?%f(GH6IU_!d@R?zTdrDDJYLhiUn~$7Em8iu6eZ{u4qDRNG-<9V)rS?y?j|a9P&+c>FVhhR!wD6%r-~M z%wLE1=Xw1=Yf=HSV=8~>3pL4fBCwkb{>?Ya;5AJ_{IG+JVN`80(2hp%`nDb(b%?VrHcnQIUpqV0YAC}Lg0yq41Zq8x zx;W4q0#T~j%Uel5?Rb}E_SX9RNLeQ$*Eu5W;%dH~*fGWI<4^Z&rH=kxsje^rlQidS zsdk*sA;y(4c$Mk!Vv+ee3+}f%xQaYC+kr=qv)BZ&?YnnVuKdZX>#3z(bYsrEelte< z`TLgXlRzJRB=*9bZ2qkMHfF8AsONC` z+md5iIbXGACoc`=!&5ipvutNk(W?qOiILa#xa5hZ6Hcl-oSHZwu(y6j-MRLZB$6LU zR+1b@!5ysHfeF3-xC z2>CWyX9V=no_b2!eblFSMkn~gkF%|2!BObS@R4B&ZDZK($7OCZ#{5gOok7DMwg%?4S3houYL(Y|%UGtVF@zUr*D z$SYRP488vG)6Nh;J+Ic$V^51aWUM{p(tXl9?Q$ea49D&)&D z98r+vOVvv%iu_>-Gy`N+VrvWAW zJeS<`8>$4;oW;c3WxEE~mD5*PZ$H#PKcm|c)w_6lgEgdq+m3xdrQwV0(ZM+9&d|}m z^!MAR{!uzUkH*9eT*n_VAFM2%jpp12p}*c^==9uGi=3fXPz;yRq3|ZxxmQ}Aitdc$ zviyGG!n5DqeQ3a5QN~LL=N4Pm8(&>9NzHkCcZ_cEe!#Dw_z^A^sdKkg+$~+d6QFE>Ta?*}=GzV@BZ7Sn-^R|hTuWEKL?%Ia+$ACul9~slp zM-SS2Gw}G!Nv)###M;XknC5J{14C3a;i%CG^Y!!>Scz(`>_0{OO#dm`=U`#^Z=nMd z0VCr--NSz$|97^}$i&RR`G3QGD0(qV8y8b20(vnULl;vKQ)7D*Qz$+@sQ)LE@YslL z2UW;fN28SqKp+8uB;<$%v)|g@rWM4tC}gewFb_nX`1_T0eCznV7arZSbyP4Yh z{8hbGRiEG8XnWx^zplrkVlrhFLqx7X)IhQVHa0OdIsuKKq!@2t0M5u<&&bHsRIIF6 zB4nVx^S`Q4$ujT;hgb@G)kidXF+jMQAcG6y1*H;Xrp^UV0K zj$j-ID*y<}46e<`h!s==V69*TfpLDXM`HOpVaTARM>sn=8U|@{GYHzqhFo9*$RS{G z4xm~Cw7G>~1N_3nEP!YN`(?#Kra~3i#yPkv7lyThat2xt29yV*j$m9H-KRV*j)h#q zyBmg6NKOQ&SP!!Ofl2#i4gkDc-3QRf(Du+~n9g&rP-F@S0W z0!|@0&NP@|00S5wJ#r@){|oq$0`CMOSR)`N59r?l2P6?y0U#ic{KJ|b+{inOcG70^kG!Z193VfM@sX_Qft_Y6zGi5Mu~H+<-X@_MCqqZ`N?0 z|91X!O*jL9dqV!+2$13L|Kqpdt&{<|H2U{A|Bk;7gMyy8kf>7hcXiyKTU4}g27q0R zO$~sU8k{*GG&2{w|M_X}e%JMfFYs69H(V7H{OyN1@=$-F z;N9BZ0`OP15W*LU1w-I5{>L?wGb1+tr{Rm=egL2H*Z<&G_xQK!_xD=jp*VFJ-!F?F z_=n#wfpz%raeV~2pnnK2Z8*@ArKrshy9)HzsTg&DECGJ)?F6`0t!I; z4U(VM_=e_lHU5V8*-#~TvLAmL25tq*{;pccYkyg+$@_o=#Xf&b-8-6b3IA1L3+{Rym*hney3 z|6K^U7x(@oPyA}^kq3H*|2ZUu1>+8mRXjB>81?xSutK_T0lSIlb(5PlDN=zp@`bhHLaV<>#|)*Sm|oeXGoH|$wzRg%B5;h_Y4n5WB82Z z9{N7c^FO zQOlI}UyPkYmnKTrD9h|pmu=hilx^F#ZQJOwZQHhO+qSg~06GVvP&*w~>L>(*65HAeKo zyXjPFILb|bIy;Sld}&%`DWcMyTo`xz?(6P%)sXMn!A-wXIN3Cxyfw2$p<==xgU6eq z-MR#Si0v`5hQ+7S+CD+#CMFGtW%i*`nx<}Lz3=&62DJ>-=X0XH2k%~W?%WQRf}kka zSn1^Ysrn9<0_F`y)^i`h;dJeD_V3l}021R`DchRC9&ftI)xISW@MeA0*}Rag9>|%H zRy;rt4pz#9zDg1pgIhuO&qOjL9rUpi{=2r;%I=k88yZTg7}v(A`%AT{)gmCgW76Ei zd<(C$Yg16rvWwul2^US+@w`|(f^a)H5q~XCs&}5=;k(QD=84F^LlAm3auZg%Avo7V zeB+(vBlDl*W(zr440tRYVbrWCGn3G`(O)_E1a+sv-yeAQRW55csL-Mij(trJF|8^aj`DtnYD)SRjdXb+O^a3dt}*0)vTb#@_lcP18hF~ zIO@$f3lV^}XE5@737ZVvmbZAe>lJu(E(zGefne2^=K4E3$VW)b1=6tGLoJ9ul@^3S zmxuE+0ft4VTOZTZR$w?G{)GgGKO&AaOE!BT!(s>1@l7_!?u|BC?8_Y??Y% z@|al~N*4wtch(FqA0~F)&0ymQ9!NAg3gD&mg%Wo5dd|Xg1-FexEtI{*aK8BEwdd%JTXG1%9ai!INjzpD} zvX^A-J))*_Z{#N}6Y`37J8o8^C6?crB#8?F`qMJ@R3K?OnhG?ga5~$Dc==S%Z^oT( zD@S3O0J=_n3fD7OAM*P^VuQMg^zlmFU>?Mwqwlt#412L`#D;4rC~SO%=D4#|G9<&h zYg&ol^>?XYhX*FW;kFH^@)C1@XRX`CoI?ONXTfTWUYM=+L)R&#wH~oTiFq_)08Ce9 zH#3K_I$z!Wfe8yD{9SJcG9 zbQSr6_v?24ij?dVJ`=lUQ_IuEPKrsnIJOvVKW2WRO*^cj9HZ~e`d#Zv`+()eOf%1h zdQZPLNtUoyt2Co(m4Zhre75jsnk-P6S52jG4&`eP`=MM}V3pt*y^(d}oovc&nHXXe zbf-9FDIZ#Bx*fJHwucT8t3RqP4E8&DYs1=J74HtjYCsuU!^-53Zy`nH*&*xWgNbx7 zDML$EN8sVt@oGfDWyd)HC6{VM<^44SpBMYvcy(q8)AWbKI)Ivj(M01~N2cVvSc$iz z`{zQ*FIrUbSY!i&pK$C#R42o{&-9?5v>Lr?e)ZM;6pPM;XpVU-wM`K;L5 z7P*7%orXF^i5ziAO2(=VY89Lb*kkYgW7H()I!3Z%LULYHoi}6jjCKquG1IaAJ z{>^rb&k8G~**K91$5Pk`|7%O&e2BgtEhlfVJ4SVMKSDRjJaBeZk;zC~JnI~0v@B_- zd3(eQ{GTWhq1cMcbm#2|n5^`_Hz{>JJ?y*Kh)^)f!6biR&Gp#e_+=OTA?Ui!dTCX%y<}SA>-@4}d*G2d8yz*zjb>R8v z?0cO&3X2#;-u5bQ?up_Fl<mgPNXR;#tO2_3CbgY|WZ|Dj|qdV(@on_0qbq~Ctzc=Jl9{KqD zEl+`8#BETbjLS`vzM~tj6>*TSt+g0O)*?z@;beQg^>PUmHZKgNnt$Tam`~1xZA%7t zgXN+34=&)U%WkF)>TXP6`8rf0>bjc)r;AJixFE9D4p7J8nIK51&jlF*HC=oIYJK->)&ZVbMLxhFnN5VKo~|#N>biYNl7vF z!TFjVopB>CT^KEu?Z6@p1tukc*1zqj;ycgBs~-jo1MB;`rzCvzpZm%tY#(vSJhk2- zZ`-()2BK={zyTW;OefN-yx*4zjf(_IGDJ)xe7SQbhG(I*0FmKPlGqQ$OAJm>(zCfZ zewX@(k$#pQHg-GN)s4-yf8d%Tz1JZ)EM47^XWOLp=*G?%BLu3pZW}_l?zP{ZdSvX? zc2t=2Ju+_fJ)5tWhp$>H3`=v2uHEZ9N7dDHv-9N-kQ$E^ODO70yH+6k2BGI-2K+bu*ir;h(SuT52 zsJdnyN>^hZcb7Kvu$lv4mG5(WcTkhsC-uHf)&`3=EuzeU5O*>fLab4AcAu7TOpt)H?@HCm zkvGSc!iNuOe0U{;m>P-!7@K(~1y{K~8*Av_i2ghsXkPQ={?Mn!Rzd*}+{}5(x^WCg zwiitiW&W$}{rh039R+hIpVP~6vpZTSU1+rz4d}&WXdUGse-t7FPkp%l^WUe^+{b{j z@qq{Bb01AY7jGa)YAexHgGMg?{-5$c%U{;7Or~x11tdLxoJL;4G;$7@$$#<$ihXK z_kuKJs~Jj6uIiDMP|;TSQfWGPrThInn!hSD_Amp(713lo@&?rwsi-oFwKkFNMJyau zFHXm!Tk_2v!*Y@dMX}ASjY059WmQ}c6XPvjhTq>UX{fv)v29gPOt(lDXE%(P!RhSmWuinbq9ROd!>*MNplCM5;;_kb_KLLDljrL$ zXx)k^0->3YTo2N%!u?=SW!D-=bnyz$#Yl3y20VgH%C5>^#Hk2czbHr?x@pDIQbcux z{ILF6)k=*=3YIft!#n5Hn^=Wy{{HA5DwSvNK5}xp4_bTi-xot^YGgsU>HVUcvt(Bf zN)=c+M|{CjPYMznV55F48t^Ws*=J6zA*%kjtOcX}`|gSGF9o-K8vu}T;fwrh8~A)T z1*QeP<67DuJ>{ScZDiflR+Y1W2b})69WS`>VW`}&)|5UCR}lkmy}uC>-@d1HSWj!4eD;D5Ox zLVrAiHyz`_{xt>-**Ry&=PW<{aUq7KPs<6G1LA>Gu$-TqOvX->n%+s_tjk~;dhmYC zyn}Gm5pcv1@8@dcx~GL7)@NP&W_zD1JK&Ol*^o-}MtpTgbz0D``#d|+?feUUU9r7} zR$>hDhg5+QmRGH>owN6S^05y5sU0NfnjR$1A?@`^0u@=3TPuJFZ_qv0d45Ibi4g-V z3vQrOk|n2A*rmqzKv@vJ0a0gd4-E$K;kTajr;8MXE>xWSVM>JCx92dVSv3Gyq)Gwf zjB$QD0!?bf9BB&qv*ttSTp@@W^@o`oO$?IsmW=P&j5R7{5l4b-1D-u%Awk8LEJd?L zTg#QM0{QEks(dX<+AWHR4g4L$K9yo;X(`@I~FwIxx#Rc?u1E^ zZfj7)p=o1Tm=Kx8hSh~$v8};OK;nHF} zSA{bw1J~!MC^8A$^((6e$#c^(A0;_WA5vO{?N>HJ0%~ju@G&Aoh4W~*HU3;QS@Heu zM6sBku#GB%1}4|+kiOHVj$;b##HcUp&W58L3>Qn7|v|aU|m$YY%&S@H_kgP8w9sb^s#o6^g61u!ep%h`!_m(8siL{pJMA1Cd#F6;*P$NTX8~`K@ zY`JRtq*lBdUt$(ovc>50ZjZrD2+z*~tH$a-u4E6Ix?z&V#_5DoO|+*n_cVo$4ogr` zeLr`yxY5(CA9CFNwS0p8R{ipEKvAX6>mM4!QFIO!+*Kw;jhtKc?7}Yzn`R?=wdRsR zSKYTk#M|2de5f->OFm{8`i?)}7+sDPcCc*ZFGaepD7`@S4kF+kZILc+=n3IQ^dz_| z?UFA#k9iE+Qy1=tV4~bJ9QtP&|(~YYM^H%v_Pm1N46TbgS0&nb7If6vbz3jfiox2oq%dFzi6i6A8 zOC}j^r~gy4J&ij!1gIF_r5L2x$p*7+W)ETDNt{UF;8#t=UB;5c_>s;Frwe@B|7`Q= zdwzv$sGZY`Y2$kwYy4`uB_;R7sFgKuM527&?bWPx3=;-cj`|cv1mJ6}Yyi1j06c}USem3T`m*vQ4~mY+`mZB=5Ll3$bUtc?*DcBD@ph%x*d}p!C$w* zW_VPZsIi~LCkbbP&ax~ugKm2meO}XQw)VuNU2cc;+O~lxcHNcH^YBq3PygFlOHag4 zDg0dxF~^z^djvzD7s-C#S}Sm)Y`uP6vfob0p#rKI)~2s;RN)jzoB27C8rWL7R*}!A zvn=Ax!QOVAsG7tYO08=e-`+76CIkA#eVvdR<%e;%4eQ^xFquh?FrcFc8VUe4CM3dI zPcc&I{%-hPRmUFlP!)N?ysq%ma)#lfuA$@T-n-7gbW1Ka(&G*9EHq4+=FF_he7XoZ zua$)8i*S`$oMsp~o@@bMOEb>D&Nm~!kY*VGlkfULqx%hKU6Q0`-5cItsP!oU!Td(M ziW8tiE}3v**kPjoZw~KFqv*eQd&$m!xfH@_IYF)98X(L>C(~H4hu!8n8%oE*VNVb8 z1!V*bUzm0`yfk`t+)xz~LZ8xYuj!4u`4qQifk=xb5TGQ+Seyhe8@}TqgcLw+IsEnc zIa@5MxAcV2i?$QnjZ7R=unh~>D)@WgpgJL$`uLE*;qi$)D=Q1v*QlD%e6$ejeR89z zX_ZQ=@1s66G(n_H)SlnLMS^zRHD&Kl^`fL0??w>u)I@y< zS5LGL@7d|6WcWG9tx}U^6zsjHW`H}T!y>1U8)MaXzYiK`+n)%=rep8~I-Y}36h{u3 zo1E4-vfkUPt2mka$0_JnBJV(R47ZbOrh=WMKjz&wN5DEyFKMf|NsOqf}<$+iZr z!24WnPqVY<>uXb)>c@5MXO*OCByj3(I?Zs90r}>90ol5!+7g5m*@nMMRh8z0pDChR zp-=#&6zKCQ#gFOI@@y^JMn;<3hyodn_BUm0Y8MpBY6_)tK4<1G5>30-h}2JuEKmiFe2pEbwsn?0>p!%Diz*BB*8O&3;G8@*IgXFrY*cx44S0#_zJ!AS}b>`#Q zaj^{x)RY?Hu2OtW1C?#cFXH#_DCDpZmJQW%%}W10+;w|RgD3jJF>G&pr0Z|dL@xT- znlX*H;Z~6rVWF!5=vIxt>C)frk~OImxDI}HPk{}5Re^nP@c4>|lfq?e@A$Btry+>I z!DFhvB0^?m+Rrvp^hL}usP3E~?5Bcu_}p20-H=#tz+6p3FnDZTy^ z@^tm^Y}Jjd__;H8Jbxk^fYRE7A|=0a9t$Z{`Ha~CWQ`HXfG?(0wMgu9jis8yf=W+&0UOf}c-fIw)I|}enbQd) z>mX>@rQ5gr8L$ew@Dj=3f9(hx@iM*&QhC;Aj_v-e=0gkM;NQ;lb7;6uCkeTfJ4jMp zjYo&kH1}&_=ZZaZ6g<}7I3x{$myZ<62IZ`!5!!P0v_j7B`oeQUdue-pls}kXj#@#> zqHqEX13chh1}r9ls-uXX9~Jwajw40lpX4U~x}P(0nuVbeS^e=X-*d1Zl_Ul`4pOu` zc?p?^vHBZg?8|2ufQ$*bChZoszKe@PW$2hlH_VRH74IK28JS?MTEp90UISu9)FinE zn>Mi$!X3`e^QW{qnzp(10|rsJ&t!$f3oY$Ciz?l2PVTE~%s1Zm2k@u}*@)}Xejl3v z3W)%c<#v)~2!etg$eNpuq6OFzw<0sJ+Jx{c)_Wr9G=>d^kYnm@vqu5d+(PezUaP5N z8CDl9ky;aP3o5{`=^r9p`!zv3`#S8%Kzg~AKjQna#Hs0AI}N%?b|8FDoYpMn4Xl8k zi3L($+}5u6>QoO~8?`V2BSLvAa^3aCAU@mhnnHK=E~l?$!|lye>DV$r3951e&)*_ zIM53`<$dHwqU}rtJ=0Id;jhbB^XGJ`UbmwRG@w{T56fbd7xCR&Z}aCA8;j`#LX6fB z-z3M~;?1;^Fmwi}Z%OXJ)8<5M^9avN+BO6f<8&rFJv@1SE(bO_*R?|$Q`8fyQUysm z6Qg-@jh#2d?xT$3I5tYWs1K?~yc(q~?Uk;tGy>(!#^7MJq7rhGkC6-XHl2#PI)*V5 zRhO2W92tHM`#u!Kmd%6boA#aUEsF1oWRNb}03ZNTAfHe?;*sILNEBNrh#*bQ9J`^* zIJL6}*7=g&kFkDmBnXgL{rg_ce*wE%6R1Us^;K1ZkG=-HJgiSj2IO+AwB|@?AbcY75u+A3k+8Iw)*ZjR2{y*3bP3Ijk zTrcVL@YgZsR6IctBF_;FHLarP2FH^B%3S z+X|Ull#Dxk57nw6D$-1a3npobl_s^_lbiSZ7{kBl9yi0@AdXcqg-LkqTZJHR9Z~Mbfk4Yb?bcaTZDkCxK{76pV@Qa$ zmZJIi3=5Sl%qS<{G4q||gG|tcMlJ53YVNU2NUcEuS7hQL4?k}Z^~h0p_L|HiQDupv zLJ;0NU!nuQv>;un1i9j%KTfhy-MQij(rds8+oN=3ZTqzkT3obunjj~Z-&Y8iwli(H zgmgBZfAbNM{S^yz>yb@_-*TDNQC)n7jK zD~vIor78)-j3AWjk#40Vt!<|BoghSnd?*A9hX@74)nwD_$Fy73 zSZ8HcszlKr;EE#lQORPi_oM!|@_q3j9N`4tumgeD4QIctW+-%Q6KK^6@Z1eH6DG~!dxnncd?YU z)9XJggAR-tv&vdKnL%Y|A$|D3B9y@(UEr|K%I>UL4jp=hZMW){{ zUgx|9sfL{%SKzF43AVk=qf9>7g*8Q`>A=4?nFIWCS+7yMeEa>Uu3$8Z{vcp?0Tvh; zf0sHgLrH_cXJ=rqQu5N~4V$vja1=q`(q_v_L9lKtTL?V<47@E}v4+N)8Q`~uJY+w} z=y_H(MSj2^PXoYcD#h~u<9QQ;upXeK$48Nh*2?&pSX|`f!`0J{Xez)I(j(F{Vy?LL;oveZtSHFcyGN^h%dM-nx(r+{>fhbt`iys;tAlCm2E$*! zo5}+pE=51mY8L%xES_m|AqFZ=X;ij_SUC?G$pXmf|0|G~4D-<}^(96}fp!NpS5k>) zaIdY~3;qigf|^>&^J%B=upcCDT`@wby{lTB|FsGmN$<>Gt05m-(y~0O`C%( zxVPGW=(u=5|0n4qLwl9!q#%ArTy$ZDQIWY@zo&Npz7c<>LN-n@=EhQ0D_!)Y-|JMr zpez*lXQ&R#6t9NBsl_ecq&{PS^GGe8g(Zm%9q)c)@OvzxkP8V+Qu$iL_P28I^^^}S z&i8?Os9<_^r%3Od(}wJ5s2Uf&L%Egl3WhP`8Mjfvr2_T9eArxZKCCHl7gypTJ&24xy?Ir|XR{45laUQ0%xyjNZU9t8m`r<~ zxTwg+_7!hs-;7m~#`9bjG<`?x*Z!#!b_eeW_V~~!fM^v$usS7uPr%sl0tg!JO=o< z{pDEFijK+KUIl++AA$-BRy+hSS0}h^@s=fMYd4YYW&v!n$2Bwmg=Cj}{^}f3oEROk zC$#1gd)9}X8&iDFx_0jvsPte8@myw^R#yJkKz46`6dYpx7JmQvnAmdy%AHHLsJ!N` z#l=MP>5^K=H!9L}SwTssfk9cORqMyKev0KSIyKC|9&iqu_@}X~(b}30uvu5;;BG9$ zp$s?mxUEht{yO0WCx)~e-5dZfIjuGQB%qIHTJA}kyy9NpnK@%mL@m!O+WKT|vD!9p z0aNJhr&%U%`-0*U(UKMNJ}7+~1)}b*9G!CAvFpO8J#OkLw1`1V*97)(YVYL@Jv|Gz z6o0wf_4J zi}FTAnaM=vINB{}ctVQhdyhbfa<7z7{aOI7LYgof zX%>TtuWIF)Q624vK?_8BQJb!y9e(>3>(xRIc|C-Izk=Dm+`>H7${Tt#ETvYYKQgE^ zbU0qzl_USLw&NIYG-AADjwU(0bKYr#0D7fQ37*TVdV|gsOdjISq*+I}D@()0G$v0+?gMfHaAp!aE6Lad#Yyj}kmH zi^W_kiai`x6DScvr6y`eh~jc6D?vBs%~5kl+`Hl*(Ld@=n?ekOGAet^qUMIyHcVdL zvelV%#fZ02f7&U6GO3X<9^1q^Jn7uTIy^Mn6FTG-kXmrA^$MP2hZUkPAJu;y6>G(D{$1$l_5OpH1X((hr4}a9#ireB5|ql? zeIu?O!R~v)4?@XgmIOk2cxr#{x91rR_q{_ke?c>ho+8u04g!cJ1Xar<2}il|_5@~F z*14d+pIUf;;gH-IgA4(Qgd`{}ah(s2f++Yc>x@MzHsrc1HVU<-N9>ZN^m>{sO{`&G z73l07{~qfe*(41~*ScRKzTc$~PbP)}RD__1++fKsMC$<-+3=xOYu+K$f22_VrDa#5 zlnZ(_+YhmGBXFQj=KOer|6EnH1FFMVkM6p`VtTlke{rl%@Y z1;JWmVrARJi$+T#Nh^;l6>uo5M6%;YjgZ{0L$bQ%$A;9dauF;B3HQhlY_UqXlrx#& z5-I(y3vdj}2TJ~i@m!_LCF9o8ws@{~7gGHh(PAbH7cJ9rf@XL^hw#S326(oXC0b z2H=u4VV6IKiT(Yg1kRNa zqU$gc`$fv!zG_Z)2ZB2oD%^|rsIUEb+* zOk83yIp$F{Uu9BMY{=!L0b?P$INjWo!DL)iPuhj+gJo_wUY7I+442{UJcvVlUrk^A zSuxl%HR@NLxX{ffT26M6`SN7pX%C{nl{*kECxQ)hPnMFZ9I@UOmp>Ttm}8WeoDEE; zRN|=3x!&+R>>$FNlc*ZkDH5J}C^`ylqy^G7rW(N77NQJJrx=Ty3#;(vnOmK@1Atdu z>!FS(x-`PWyZq#h`ZXfwpsLBLsqmzJ>O#S*mJJ8$J6KhG=INDFh{$1TU3@~fY7w`X ztey}y%mhLJwyuNsKG|4j5gT7m&u z3J@?5cYprdjG2lGd#z6o5oL{Pb8dJzHt_XVv4|jL_KpY)_0bR>q znkyg#s4e(BP*?EIwxDWYK4?%D{@A_UDUNzfAWv7s)m>kmG`KC$BM=Az9C$=(h9%U5 zeTZg=P9VfEQ0L@jpbT04GrPJCJ0PyT*-l`4C&yo%o7t<}5P~_qaRO@Uv_fR43+R9i z5NiT>egBd`Eb=e#EL@;K&0nxU9BqSe?|3e#1E27pO8+&-zz!z1CSO$?N0L5+i~8o0q(pVKP)!HvgT>I zzbm$~+8^@ajo9iMH*!z|A>VPcXn!E@KtsShLi~a1n1Q|qCSotmJb3=A!`2eK%CQFq z)V3l|LF)$*0KbH+`6KzQ?bHysF#z2hK)gKv%=Y!tTHD(Cvkt+)*MV&c=B@oIi?#K$ z_1X;G=@8HZk?{w=wEgE9?Css1LVRcl6~O(kKl+`9%!d4 z5C|U6mq4(_djLpaDC)Mi@@x8+{-(D}lVB{j8~B&9>`!w5a9cnxfPn6n9`D9)BJh1S z*#P+K6ABJPa8e)Wk#B(=`~kEY5#i?d5#&qq{rCLGEcsXF<99ngFf(Ydmf^AX?H3sW zAc({L3r0|M1tC@y!uh8jXYMx?E6}gDfpZP(;N)#r!Gr^<9&bTjD|iUd_RbOD-TRHG z20jK`*Ng^cYx1fk?l%qM5DE$gvl7@Y=o%TFybF_~RpEH3BfU=tmli&Lb}eXx&4OEVhqIv&lfCOb1V znW;>nntHaUPTO=dALGz7rJweG)U7S9emvqj%~M%xDQ=F=?BNs3k$&oNe{#>rL!w+| z&}RhZP!`s~{E!^!)i-jVh{%!9 zb=F4=;EkpV3gQ0R%rboKehS-3i5yb&TIn{Kq!~|T#VU2ZEcG&VuA1RlheP2>`wX#+ zgr;9~GJ-%Z5AtY+|&mLo0RBWroDULl=LbQLYsU4H2MXb(e!8#+ij69=T_0 zhG>i~k_t(dK~VVqhwM9~z%3+J%!hB|=@FFdhc!JOuC$^9w^J&9je0@$4odv%mFPt% z{vKxQj#-@@ehaIdRC4U5o%A;SQhkVfNjW^2P)fGOB?;ebE6f{NQPG_y0*!x=dupAa zm!Hn?w*V)WlNsc-h!?{r6~9_l7;vo?y_Cfp;m4;;JdE9S!a$XSZY*6BFIu1ZOl8GF z(82b7oX26*N5R9sm>leN+AY|`sElDNp(A#w3^cyymS>${d-tKJ)O4x3MXg9ln&rOc z{ItKmxt8G6tzccDnjW221^_|wZjgI`gikVJRsn6UPqg%2TQhZq_dG2)O_KuCWwV&E zO3gtzW)Jx*=nlRmZ0A`ht&XKNUa@?J!(d)<+G|FmB!PVP8(#shnwgdJX-vmC=Q?;9 zLDntfPmgbily^4sL{MmXv|sjhH@Y-^6yI;MS*Xn)!wYZIq>>F;LUoPFkkuA9YIgvC z_|u~|21^@hxmm9NHh2i}P8(Uf**c~Eks_7yU~!acg>3|pfRbTU&8=)~VEh6t7leWV z-@EHj@h-1EIuB@xq2%4NE^kDa;d1eWlo`b03eEQ5q@C6^9?recjfAQ zMc#?#sML&$F++bm{?4AF-2rO-7f)IJx7;CpnC)cQtIEMSVv;QjX{8A&nT_*w@!6}u zyPE1(JL(l(i!0(ppsitIjNM)Dv{Q7%yOo0ftGLPh3Wpp{il<=!BG(R6gh|py;MzqM>h$#qS(1-$wShI~9duT7j7^P)~(i3n* zQ!y+aB+hHEkk5dClR8VOtytb+L~`$&G7Oy#*VPyaWlJ#mQr*RiXdu?&;ifb4N=$Ib zC^4o*xK*K{?4+3KQzRR`{`|!$v|4nfmH|!txv|b8;?mj8U(^VZ$P1xiG=F!vU642; zkMIlGe`Pm>Gyh1XzQth818VI2dH>IJF(FH7PWWXUfohRuvRBRu)=Bedh`9=0f=Tp^ zxukkR&WFiO%~Ak$sfmTnvqzXweUO=?#)buFkio0qa;Qc?ey#K0`M$@Mk|Uw?TQtuk z-H;nq>Q7gaZ{HpN-NTn{w@*`s2yEcR=Ww}*(>O)Tdi~SyaD5s10}Mhu+xab(WSo_!2<&t*ox;xAbg>j6rm*g zScKWtz{mJT%-$j8N7nm{G8i5%m@dzY`VB>gHZ_Ew}Ou>6@Nld7+Q0kGhGkoo?*ys@eZS+E!DaaBKcf zbf@@qA!RCihyR%44gy0Y{P)BL+0KZrB9Kns?s@BIe3QyFA@i|v*SRB3yD5lrtROOg z(BMn4mscqKS6dRlSkO}XCB9XnXeJemYc6#0VmU&hq5^yQ{U5r_6_qHRx>Qiil0X}a zY=>d}h{o4dYfGT&^{&;$VS5@=u-G?uQ(zfh2lNs4f!En5@V#p5DE!>o#bOrAyLcG6 zdYLu8*H;6!-o=dC@LYM%isy#CSl9w z>pYA5b_djm6Od?>Ra2Ry83ag176|Bxu#6Y}eoZ(k*z5E}$G#8%g8I($LL|Nk_{397 z-+MKm0g7%>0ncB3G$bQ2IA-BO)=)uYB5hJ z*ieh7;Hf=%X;8w2viG#lDO|pxtf$&_&OMjRX{L0UI{C3_Ks}b?wu)P|Rt0jG=uco@DMCg~w|7d1 zumtuE)ph7E{t90+C0sCu5 z$=(DvL$)t=_cMr8CS7*-Y@=f#hAkj-#%aAAaknh7(D|-cGLDNo3h5x zwcfzTwJDEqdYF>vhhdX{jOcq z|A5oSDMi@&BrZJ9pU@&qVX_2_mrqxZ)~FnProiSNyMs)LarBGDhWKuZ&Lue_tL!`d z9QXhQl*^iRX+T`}&3tze+Biy*wDM~x+`i&9{hEUIL0K7`^*IyidC99^?ZnUlGl5MH zScV+<$2cy{5sJQU2o0*{MB`bfHAwY#blnshl*kL({0J}4Fg{k?0m>I>(AlU0Dm0mn{i5q$^9F6T)LQ9f2zl9<_957f) zALByt*H&9`aq>k~9dLI$5INJ`;W$;0iXhn=`mZT{ z+S}iXxn~qP2@ICd-28cKqWO+LE_!fwTUCorZ*le&wcJ+uo1xzU+>PEX_Y#$0EIavd zFC9_e6+M}+C=ek#b8Sr=oM^h2JvZJy(f zRZaW0JgZ7QLWPLR;^M!W!s{JVefAmh!U*5yj#rPm3UkQNiZu1cT5`9XZV#TY-9kxt z8=ZKIGbh(DL6+Qjr@o1%ACJ(ZV*`J)6VMS832m+Xa$o?&0L$v>Y23U z=ReALAuRsKp0g9FYNk29(2Ty$UM}dYF3UQJXeN1xT*D3?=JToMG(Tx24Z9jbDB@RJ zy>BI&N6?r)G?|8v!n*Vmg$$#OVu**8z_o}fr1KkGIKGddJl(IDf9y=1u*1mybg)#P z?qnvq91dXQr2TpjcXs8e_Kz zp@(ajqPoQL%yx^wN@=me`3!sPqrIYKQS%1NUXv(upPia9)w_M2aFknhLWZ>jq!?BZ z^75bZ|H*RIpTRqnQcr4eV^*)$Zl4-xd%SXhcVwbn78Cnex92~2czpOP+#7XRv%SRP zQF?Znh0hj{^oP8#|EC$geG?b?))DBsJe{akdK6i}le?ey`Ul?~7MkmVSfK{J=L$d$ z^OwP>B}+0BLa@?Ejdm`AgDUx}Ja+uZah=d>%#@isMt-}EoaY;~Qib9cX5KT=QwG0M zVze)>dLY=iitpgiBgAt;^QW;fCv)3R8$~28UB|I!bpI@ooe8 z)VP*D_{>ctn%XAYr-D)Cd%;|TygE@oFvS=1F6yD z>B}-#LdEQ2?39x^J%Jj!A;mw!447qo0zsE-Q*SltoMcE;?y(fyV9wPG^?VDgLf@u| zG*Y`ZQ2cJ+r-NnTZ#``*6YeJX3LML=DWsIJhnZ$)CF&=F9l5KmoPnC-l9Ns5JRU0D z27XR!(PDmqNf;v>UM?@+0S`MxWFb4(RU!V0Y%jdJp-u?vaTh^ax=BBE-*}xo;II4a zLy(}TyA=%X6T}QRUg5W{UO!Z(qg%uNla5A`#Ma@A)e`HtdU-VYeNqgr(cG=wss!e+ z?olvby!{Vi+-gY0fARHQd#OfrP5|d44}KF8^oO{IR*GGu=ktG|;L*CwsXKWIshC}7 zu6tSOT*w{r?_x-a#VHb&##jA=B(|a1d-dD=#A`(;5%^dITjYN4%LhVnQ6MX}tGm%x zZD6w$W6lBIYe2CWq+WqE<`(QCLX}%i_ZNwh#`yDt3ZODWNN1uJSe}-@o=fA5K zYiHoJ$U+e`TEt%-##abPCn7^OlgtBz9a@9s=X;ty{OcR z>6j(@PQ%WezMoCp;pyOLOL4K~5v_St64Qje7k^!%Oz^`x;aH3r=M1T4wZMNno*_HOyaS$?PPW;Z24hs?=Ws1Gov!)BJg#E6B$uPx%d4a0e&8mhD%BpDcmcPOxNlkBUyBE30C0tA4zYd#SYc39g z$zQPwiD#`s3UKg)-S;!2*dr7iD9h$+E1e##Wef#HVs?B|ly{VzH8f*2=9=~hOH-}Q zZ&8d|VkPK{R(SGlq~WI|%C-L-TG66ZisoU5#ltw8DQEw!Q(O-`sXfh8qi9E*$ddwh&$DD=2FG z3Pz+KZ2ZG9ef>7DEnkZ%vrpN|^)Pyz9W>hslM?(&dS*v2Q$nP)Smv5b=Z6PinC^2< z!rVDZ&;9S%#=gSGpz9J=>Tba*nv1?*bFiGGo@TfFA7$qdBMK9?*|u%lylva&ZQHhO z+qQMvwr$(C-P6fr{$!GGF|({%)T&a8dY<>3YB(>Gko^soqn)?Sp6A3fF&F0B-H1>r zI9BtiPwUtIAcreb7S3NA=RpqTUc0^UEzBC>kBkTGJ$&wMM05m*p@aD-_byoD!EOe1 zM^+V>TZVUq;GgEVP`bA>mTki$_=e2!El1Rs!OkrA3w$vUlOqzanDldeT+&BW7CY$_ zHu%KqhNQ#XY?B0g=-me`7atT%4=;(;(@`Kw6(acnbsZ`Zyywa~rJOL$M?_q2U+y7Jq1C7o6&ytDM8d?AZx}XJLC7{xhWT z-^bCv|3fyO)|&w6&K8&NEjt~^cTs1yM`Nt<_Gb?ne|Ne(xKlJQQLK5Mzi>Lgj})qv z@gqg*BRFvCP`z9xmh@mzvL_K%HzKh)#6Oc)zi93I6%36!cpK|BpNAd&02M0Iq{enbd`!66h{pTc{M|`;Cd<+#Za%Def0``y%o6-#brcl5g;o3I4mjbAM7K>pk}p=HE)&eDb?rD+>8Yqr&p5Qm!JG$5f;VrZ_&BKtUWUC^J8y;Yp`NqRF zQy!3~k;DJXfQ2YW!c8!Tf@w1&RS;3P@QMbfsPOI$rY3ILs7UU`e&J8V8ltZ6^pwa! zvB3s; zulzm=1KsapYoNRr3x_2zqwfJ!gvQH6by5Guh!k9c$6-Z}K3M1-d?@|x){4tkkek!8 zyAzxe6vl4yW)tI3XOhy3a3yD5cmMH);)=3+`By?mKFH^pA6u=!8zd-$*-Xe|&5ZF>!xb-@$Gj@)(2?Wgyu$Lw=F!A&|FHjz+NAxT z(5qNS+ijiG_0%xaL+rI693z-7iL#rdY67ml)hsfP6&lR2q4tP-Hs?d<5*QA%4Nlha zWvaJ`x$jO*!mJIpnpbJ35X#d#(HAsRx4CQ7*Il(IHR=@!!5H!v)}e#`JbnRslqDY- zFWt&iMm4`Z{Svb3!DTM_A<$)Pj>RxkreW!*o3_F|fzPw%GnRHuR*#91;aGAp6e`ro z)4U9?05DsalhmiA+$CY~Qn}#KX=&ZC;+_^u0Dn&AgT+0g1ir7;{%TYZUCMSNXv5yi zzE$p!ZV2R`y!eDwByKfGVpf%+isSzLn8!mK-Dcx^OL8k7K7w5invK5SSqtxu@s4{H z2l12??8E_qcqH7NyvaPh%sRkFxae6_3}fM4v|| zpyz|i$A+TL_4h)vQMR=>{ z;6P@=LI%(LoZjxz6lzkhdh#84!w6j-en}I+p+*lIc|6_vkvSA@dv~OX#p0@b0H#rx zMff|4npS+_qc1p}3OY`tv_e8BMz^w*XL&IJ03WL8H6Pjp-w=Hc(rV;**unh?lD+#J zGRrOo<1!F~8AQ=iOix1WF;pkivCA~WkJLYxoOMxM4~3EDO=@s?!Kv05r2;X_+gRTS zFD`wi%RfSl%HR9(c5Kdu&)a6tz-*K7P$PyVgq^ZMJ2PB4r7KLcG7MHn37#0HV7j9q z!Y$#ZHiLn2lhFzz&B>| zsn&c-S*>#<`T3)g*1VH(J)Diz?`qK{ni;_QW)yfL0-?$-V{6YUDS}l}975KRHo!UL zb4oq?fs}sSs*}Hv9q2k-?Bt#T-xE7J!p_Q0Il9|{aM%|HjX{Uxk(cGpQt#on!2&~N zD#)Cdy<}d+vU{wP0>Jw_!>gzC<*HpepX`4?4fPJia}}(U71$E{eq=GKTcrM=9_51b zeYUJpI&n}iFcGTK=35U6<0tG70u7Ayw7QJigUZ`voahNrt}I!zBqUT-Y@4%(Jc&x@ z=~TLDmM3!-+E(<-6y>G^g6aiu4!78&b-r}GXU!YEmM8C4?#|?{7nz(67NUSFk|P&x z&z!>wF`sfR#Wn2dAGG9E60$$Q9o3MR|CLR%{#Q25!ty`bJ4OO_CYJxqra73{ng4&X z=|$TG)?xz6ty*y@SK>D2c>;o38fcn2DH_;$an}|CNf@f@?h7ax$|1H!d843kZAv z0D(V#U=aGy_QEP4fj9u|c7IR;Zr@{3tP+|bf)d%`V?#s1*+%D*v9Aq?r=}rq{fMjp zIT2LDBDn^kZl(V4BOgM%6-HraV&<7bJAWCj1Zxs=^V1;!%3jc`axg^^nC*B9hrKOYyZ8Yqyhat;DNn*t-s;)F=+4_Kvg~*La$OD zCtE*qA0$9ul@Fo-T#cO(_b4uiGk`h~WRDyi5P)$LAVE=Y&tY4DcAhMRs*P&d0DU-j z&pbg#6+}ZqC>N)o9)#+p?un9LJAdzJv*+Dso4O~)Ch+kCdTmI5Rh4get%KwKT&O_y z76BEMuRO>T)vs{P@i5|yRrb5MG#^5 zi&z1lp;re`4xs=DbT$Zlxj$F0azRrg;I#n(hyYSyuqYv4wk}1O24CRB^gE#Ekbm|> zrt$FoURHMabZ6oZj6p*=+`goKynDFY>u3DN+i`qRehv~713iJf;#k^VgWUkVJ_Eb} z5D!Cld`;fOes6?R;rwh=1^^JQ2%(t-;@H#i3fSoM@wt>yBb-Cl%?A+m zHv58|-E{CT+xhhqXxOQq{zC`H9GdvhXzl#4CL47~`-O67xiYolsy{U^4pjH3F z9ZCcP)AHUF{VCWF5EltO3XRQyAWjmL1%J4%A;9fB!{rx>4JJk)1Ry@;17O(-{rt}o z4Grja^qcWZpdSFQ%{LyxPwX3?ga}|);SHTI{rrbO!3Q9Ax(8xx@eBO!j!26C2VGcn z{R&i|0Y_O2>AAZRg8;e<@~b;B+0_e2=va?y zj%=x4#M81YOn8Btr;mDV6V=VsCwxaCpGrk`cC0^H8uxeX^5SRekd@&$iQF8T8R6Zz zIKAisnQ1-s&t!c}xnpuQEmM-GU1hw3bFx0xWXfzkjFgYe> z8H7XxE8SFOY27nia-Kph6+eq0)ze~LAsM(bEOOOrbrIn z8?|Ho!*HUg1wVvN(1fFq{)fpBeOXUzm00Ua0kICv$QEI>2WXxOB)HXAVD7FItFtcr zt|s9FdJf{$=;gz~EaAiJYHNPl0X+S2r_yXCs=E;}PyB<9Z|q!nIbYd3thM<&Z;H9E z+9e#z)7!~@LM!QIo{-b#{V#T&OK|APT3zPme*8>R+$pcI@xe}N^VJ-=S-Us>#2Cng z%R_Itksqr+&$@QA#}Eu!*-0oIf8S+M+Egx-PKZuH-OI>_CN9GBCt}f^27biI3wdfF zsBGgWb3(QQ$kR^!a@Mes_NuUMnO+TAIwBP1Lqs=H(hw*^)P064n98_zqM^HJK-s=8 zB~pFM#FnfsVRs!nJ?-qNuS$r_tHNRC0)J{~fd?ifSkx@3kekc|8M1bS7Q%5S`os+b_#{ZaB}Lz^|G`N~@S`ccm6dCSM0M>NeXh?Q4jM(?oGj(WJLF(=7*lE$ zjmJw9LJJajTuqt>Ie3Efm*|{Z-!c*d&eeP8NGMqT^f&75yWQ1;%>H2kSS9LHe~og! z8%zs0oKhL)hbLA1o=YrE}Q^kt$;MOrLDG;Pw7)GZ1 zM8_`=2?)eDTh8ZQuJmM5gT&{5(L30tS|NGC@fFyV-bO;p6z{9)12}2T7fBik%!7SE zOz8Z_BRdbnQ!(6$H(|AGmH*I)rdom@Pyhb8C1NiRB_Rszz9A_i%|BY!rCIyXOPs_$ zS>`J~nf_^Dnu51ejo$vn3PUTck3p_a#R?Ba7EaM`a!D|f0)=AgAQqeuJ(Isasct8* z-i_MmZ)^v9TDX_>+;2z0U9?{rOX7RCdv`^V8KMocNNIIN?oHatd)fzcgjPcwqr~0}eaHrcE?jyeBnOGx0iGt`TydHyDM zNWq#uE|c9oP)ZI$logU}Fa}YmDsGVssi(9a05=u9sw@p~9?-YOVenZ7epmzPA0Ufj$_hcKP<9A1PGE-H0AJ=Ss+Lux&jFKJPM6K-xxEB0m6?x`NJ zE^D|RT2GboH8r3hEe&R1>4Sl5*}W2t8=-^=))3-i=RQ_Ua~w=+g; z&66fr_=_2b4Iup}F^z|YIBLv#njmA!kdcpjz1UyoM13{KB7GdQkHj_=i4p?!FVI+| zAHC+DB`)lItqLU>wlqUJTRsM0(wrgZ^%$~T<;XYvX`zP8RQF%wdHC0Fj%NoxXsN%S zig{bxBLq2A3stPlPBOmWr|j#2>ceyzrVhexgrOBBhTiKvh;uqaLI+!%c11 zW_C0An{p}oF?Y9jW60MiLJFVku3e7LAzK#3rZ@P2VND5dd)wk`p=r>jU-mu6Kep{@ z2t>K(q5nty#ilaoZ0y9C%nhBmyf3G7Dw)oBbHS+?S<_lqvLY7}gOlZ-@TT}P+h&1% zB@*g;mTMb#A!)gDY|SH%ZYyI}bqK*QxH^5AyR;5ynW#6!wZOi65U@jtz->h0rseOXSksqj2i{ z@3=ZbICn+(v&UL@TEdeyj=-;c(<$v;?HPnuqzzWq(KLc!87-V{oAF+>bD;Aaf-A$M25BKrF>-&D9i;7&QZoot7M8tFq?u*lnNl0**^l;GTTs)jZiCAjO z8&7>E^5Bqq$N)C9qds5`o( z2U2A;xW)$KwIHHlL<+liDq7mpgH5oC)GSfE_HgL%3-3{`?4fAANm&7=wrJf$40e*b z8T~fBm>I{Ds17~J1p6vn+tf1vl!Cj&*Wa7Bf?03MiD<|@E9M!672pS5V_a^rr9*3_ zDBszRHA;KV)d(*hjpoORAzGwm%^~n@%&D=D6fO>cL!egIa?KR4Ya->EMRTT7so>NF zWq_mAc(*;HnbSs9v}t;U!i)1WbD90zYal}Mi1o zg8Sw!$iTQ+4=xn!iH;su8JfvZ6+FJ9Rfp%5np47JfsC=0%BUu)#g3lP+kr?pzf*ED z{fXpU!-Jkyh2j3wc+#X$N*VS%%3X#1qzMy0tmjjkWmtiVCLc7@d}jD` zbLOGQ58zec&1;@ES`5b20aMD1#dpP1>>NO8jvUijO%z4njWb-4h|zaEfGI(Di!Wfr zPM!C==EoQ<`bKueqWdqR4dBAMoPtf*Qn>F22jueZciL$j~=AbtC7tj zFg2UWq222w8yeSLA3(!`lf=RnzNkQhB5IDv>P{m_x{`LUmfADK5OxJxmHVB%2HF*O z$$CgLk1}sU@D)gGAAHlvBh6j7Jr;)9wVBA!q8OlKLc;b$P_9~sKXVVrTf=l<_RhPs znKKk?Z{Jzb%gsvPW;ILj=Fjje`H;D_j}6*}=QRorYtLjzuy1+s(VNIQN2yC?8}Nn! zzx`Jw|fq^T$EI>y7u4kFJFS$V>zW`b(hT{x)MD>Ke(b8{HNL7X>)AV)KPB%fZuD zwk^z2QBjc;%YIY5Tx9pUS1TVIMiP_>?vnd;iMG*|Q4G;|6rK)4u-rf1eIJ;A8zuF* zx8uoTTpZR;d1OsqS@Y&)JX)8@8NfvEoaqyuV~LX|CFV@Hx%cs0+|gAIcL7cd zx-7bv2Jxo5XHZ?Tr8kI5*WF}4hf9TiF-4LvF6uAUIsu(iRPe?*N2LspMf{m^*`o?s z%s)>oKQWW8a5(?a$3fHim@JkyZ?O+xw#JzIG^F_{eXXo}OIGThOe-z^jc`#Q@jw zu~+A-&P^(>W}ZnQ4?(qc`ZN4^detJgPz6eH&z7HY>rccknN8}f*L97Fp`^Sg?%_`w zN@_Abto>I7B(pwBj;pnefpsayE-od5I6UPhR>q}SKM>GJQ^HN!Z3pk`ye1C2xgiYg z9Z4?AO^2a;W0FN@LJIQSWCohs_!gnqyih-)pBrVTK?-I2nk3;)hG=KY za#{W%Q1~;s1#QuGdZ!uTYIYbL?2^u5tTdoh-y0DGNE7$7fHBO#@)GVNAW|R-N+{g9 zP-PkGis!?me^5Bk&(1d+u7bQU(Zb#Wi%no6Ubs7NG@M94UJ0+4zN3EiBi^w>M{AR7 zqnD|dcfHU!&t~dSZoL=73fW0B8B^Z94wurt-RI-qovMT+ZUHYD**-{ZzbCD#EwmwK zvAhgxp=BoZU4HiBBJ1vKM?qh3b695Pu{5uYSZE9C#*AY8{&!1EKQM4);8wJXVh$quMR&d~#Of+FqqyV>C>F)$7H!^LA!V*&uQD zjTrA(d~!vNZrh5>_K*0@xZ3oSVB$h@3j{v3IAWetFoITg_N<$*8gfl*OCjbtePMj2~~k)s>TpJ8%z;s2S0@r}$@fXk5pd4VV%{kt%Uj z>#;KzwR_5s{4mgViE_f8)IN3b71h40Br?no5CL{q(|jrg-rW)bbuw8nkUUi%aBm0_ zOtN#*UBZCIe6q>M3yo{(2j2CY;7Y%+3EAf{L>Fw}Tzm&jr^uwr&C`(u?1UQ=eibxk zS}&I=uYC>xs)|z!F(?EwqW`TO)xhApx(z5y({jf-z|_TghN$(NXO^))OE{EYy%rRj zaywBVDAe%T%u6bu>8smZ=yd>0EyZ`4gW?Q{F805E3xJ*|#INS@AdME>h|bfY+oae2 z^Q?6k!o^hR65*AaBhSWhj{WyS;9l)>64Ouxm58;Z_{i#57yZ~~Z2ZL10;>7#t}C&( z{%=ArhQ%O8b*eL&N3_o27N_+CQN{?$?Ws;#2MOb?nd$ej|EGdYm-a{56czn=T{ioF(kCHzMB(NIaAI$Nk zQafk~%VU|`br8<(*z#*|)cle?M7|ehq;6v4tlUO7i7Uw(yT$N)z4^;M>r~vtShOTJr%kv%)jgkg0;Fgq zfI<<7gQ!8+AI=x9#WI4Tr>XvW<&;yki-$hj7t|>CgFoam!53aR+MVP)`x^L02^F`* z+ZE@xWlK_qySfkB*E|s~Gy%YphsPf8VwborZPO!5pJ7zPoh^ zFGdq46lb-8irS{&fqMSZfaw;y=PF*fOqceQXT2!9BWPNsfgJOV4*5?puvnie>9?1I#Yo`UX=5`GVC+@Z7w#G$XuF}w?4VF4cRnQK?GmS4s)wLV z2zn$F4SlDy-H~OH^#{-pohg?ZOdpargg@*1A5Kq@+m{=;cZo`*CMq|Q(;=SQ%3wTS z6wZcDKh_sQ@u{Z?gn+s&hQr1ft?LcxuBRX%xhdAUB3~F2FH=gs(-`z-i+byW$tTiY zdyh`I&-Fke{a|;2N94hIP8Jj1%ugLT;IZV0RXN#Dr`E5K_@Sxzu5LmHnKBSHVfa!- z%_@Xx!6K(Rmg=?IN=j0h_+c%)@6*|{27UgzqlQ@jwBuj%x9xeGZgG_=*d3oGRkQ;{ z$k?xVdBQ3~aH|ofjjft8uXgH~AW0zgJZZhqYS13xrhI&N)G6$ja|FW7lGBSiaF9Wn z8uH@2ST?%tHaKjH%F}G);{OZC*Y+9eZ6`>FEF@Y&(YTnXKf60VL z*}BeGISd5$UYjhGq~=04URj7GF5*C|aU9jaDnyEJXqkWk-?7=)zb=Kyt1rJG9zse0 zFm4h3>R9+6+|JH(=OXJ$#>NUE4`DX&>MT*RxbGXQUuN=Z*ojPM9HvCod&;;}Xc{86 zN<)UTXn;k82~rgkYR$a%iUS4B^Ec5A92YNk(#4bZ`DQi|j1Vv=ymmBgi2F}l(VuS# zw)oy$0)3|*S)5Tgul-n~`e{RnbB>^W>%nf3waoz5ku|4H_tzcPx;gi$Kgtp{ytSy6 zFL@>Lr8n$~!-9T`)zOvBx^H1)0a1BWZLY5>rUqQf4{v1D@l{sRfd`?*3G?7{1iLW0 z%eSo+>u*nRAKh-6VNK@w6Xa;x4Hg7l_4k#*8$%@`K48=VsD^QFD7l<}{OwaFfqs^u zW$jbe5V|G4gq&VtRQU|K+K1CfTYuIYrRW(^#GGj!*Oj5M=VnAbnbPV5136MK*+{!v zkg3iYGW6^H?Ya=rDPUg`AoUt%=S69BYTwbN1zkJT_p=}Q9PE96Osd2{kqW(iy!S+S z&6mp!xJ^?x4OSit4;3b0&sPVwAK!naK+8^zbK$%AED~$lzHaQimK1Izwd<#d{?|hn zD+l^&c7onY-$u9cMo~NgN*Q@d`q!P4H@udT#@6u%^1&L_-9=PG06YMEP;u{8VFq79 zYK1)d`EB5#M=ua_lTZm(+P-{K;aJh&12sj#Qh%*EQe6KW*R<1Aav?*Z+?YLG!$?&w zm;Kvxicw2;L)I#w!J1Sm*`klivBtK;XSy$z%=606H3gvHnA5gUNP1RqfwD#&-E|1k z;*rOoP-+&!Aj#4E7so^4b031r^&+B$FOi}EYm?W`_7c5PQkDeIV$`(ehk1!v+%zW| zkorYI#PZKTehW?S)sc?o1?s^dnV$C+J8KXwBGdTGE_~92%bwI$DNL|O<9XGt4+?mP z2DU+_v$Gy!)5!QCZ{;K*PefI=3v;AAZN!Zq9lldh zlzwEJC`qXq#318^(>7{~D&wX;VNlE}B(WlY@pNi$(L6&N3Znk3{ zHC=p{tDMD8msK6u0O|s0VgAK&k^0wC{r7RpC!A2wta!mD+~r-C*ITwW6Uk zJMEnQr#!;by&gl?N^lKYrpr*$QlvAjmCT|#RE@u=s)S*biNWdN+@g}bRo7YpDXy4P z&AkxO@@whzQv0($Xvi|f`3&LpYUU|N;GUa(#EHq zW$5DzeD;*gyhTb)@z|i(F|Eygkw%P?Ikp8t>{}gcHzH--)-Kj44{T1CPKU&KB%6pC z=3>4JDg05*-W2qO@~2onj%Cwglrn^`U&pvrE%Iie||jEiqI{aFgzYj-LYd@&>p> z@_6BHLH`e7g5ehnhwiBW72C#{GCOVd+AG(_-~5mFjou&6NK-Q zt?pWLWTfsB2%HIXeCSS^YGU?N1r(kRnp&T3Q2%&66TNma)anI;L>H^Js7*z(F>dY1 zqz9WX~Ah4pVyjGc_1(PSB-G zQQ>R%Jyu5X67F?%Jvm(}DQgr8J*RN zJ@nAI$p0benL<17D;0}-q591_ki2hznQ!~;cEQftn<9BbuTe8Omxqo*@2AAzsq4YK zO-Vw8be)w44^ssUR?^-=;ZjC>VvU_+U?UEQvnB$gX-+{6%F8ZcZ3Qo?uXy4}*9;B~fl=KmUzRQ;{asRZ^n+H#5 zUtpS00t;;1g~l4M2uMuL(Q^xzrbt{Ti?cQlb@kW*FtKHA)2j_HOc3u<8#c-e4AgHY6-dI#{JOX zj4E>MCy__j;xjOv_N0^1=_aT}v<*T5vcmCT;Y?Ue;N7!bai|5cV>UAxWX+p(tE4+u zI+w&WFCR0nrhNoC-pEs155L!R8P|BKoYiBwY*ZW5Op9*&^vpej>?@~QQ8OCC#jJ>! zx(UK7Ss-~iW-q|CYT%*^imKo{!!G@DI%M8bbt%jlD!ys`2%di%su;G{V4YT>PN9LF#I1{$FE8B56hqbS^i%pQ3lpO z?EkMO(Z>I65{=TF-Q8}LIzYn--~ti1!!k4Lw0DKRmbHU~>kI5a#sLZ<=wnff6EiuU zp6vS3ebRAWS~0cOHNEjZEn8$>BbmIC5vYH5k!K~~Dn;OzR9DZz?;RVPnjRYq78NT6 z4H4w`4WB!8;+LJ)^W@6+#T4i8m(H7EG)F#d$gc0g1xW8~uR+lD)g`i0}%?CyayHwN&QzRe)^nhk>hKtbI%eDA@<)q-;P zPf1?_jFZVz$6Yy!G9g3oFKolW1bBR^LWm+#Q!EOE1rAJ2MQ;r*r*CbKDJF%Z?t+DA z05bDW6OgOMaqP0``$dG)p30eAnmGZ`QrAA@I>>lJmt}?{L)_B%`AzY=OwZuaxf~Oa z_c}WGm2@KUF9908l-AAXf>rtTT!R4^fq&y()8Fj)_qzD9XZ~tbH#pN)-Tkg;0MYay zAo8dx2jQGU>w%;%Cw;Lq__MBZzhtyzdJ&KpOau9-*Z@Z*%YdbGAiqUs)+Qk@0h~=- z!GwI24qtJP-%^Y(CyOtwtp!}w9 zwQ<-RuXNv)Vh%Y-UDj-<^0TcX31y?0F)&{kB(gIMEr=F@e}moSb>421<>@lnEeR*q6N}? z56(=v0(AgyJMhlnA@sg|yu6I^H`sR|=k!?7Ezx{Cs{I+}h$^6(+__i(l=>Z*U=O^$j!~B{3 z@m(Zq)(aca1)C|n1oGB_HvTv{s{PPiV9VoERmU`fbE*5%t>#`lbmt+tq{$V_f*l>0 z9(yRoxuk)10Z*^=&o@!=g`4;FxXS_tY6dP};|lccVV}{-%K9nv+~#D;JW(BbYcuq% zkj~0gMR*r;^fjD)NceKaWppulKJICWk4%Nv+dnkg_kZR_ms+cT~j>6Cjr=% zf5Ya1#|j<(-H?009|Yc=eaD96HU0Aj&LhU~g$>A&D+T-m&1>5Djqc^r^oEWCVz>GY z+m`FNz7at46AlZ)i+*$q-*m!=Bb}9}haASS+P|-BG6PlWyXz=2^8oebnq?Y)fq&cc zu6MkD__$fdw|vqj@zdwa9ZwL)H40;GzP&BYzS>UL`c)ztuo!LaDF|{$awVD?X?!4o_iewpC7a=9bvdY`53+S8i>$&v8hU@?#)jp4sO649bOd z?jj?~1FsVEcpwu+0xBP=)CYs*p5l^DnZa?wM~0KeHl%%fNSMu|Q&HU~IL;+`Mw_Kr zT@u77fHO1`YZh&Ru-bZCiYR1LW@9z)=4MBvsKQ8|I>M`4M9QvmcpC!;Q)B3i_$CHQ z-VSz?w-`2fe-r{fUgCj3^`h$7aQh^s70;;ik76|GZKrb;$Wazc|bKvl{dpfz=!#+|D`VS3F&^ z`}~H(PMOZc;6E0o7LoY!6!7<0jpHB#Sl&rt#Do`CUCGc>;jhwS(J8^<)qc|ZdW6I7UB<(qZ z126Ps6IjF;RJt|;T*qd6h0|1DNl~THQT$^R&afUIu~U6M$M_RF#o#P8o)T3gphq*0GXkchjPz9I0J51@_cSSDUD?JERc>A%1Jt|_~L2`odFRe^x zk}i%j`bndpCr^=4o@+gqW{;Li!W3{^LjUXoy7*VwMQ0UG7P!db8*J%`yC&LZiV=g{ zSe<>A9^2|2PRsw{%v@j=XFO-pVQ~qJ`-&6kiT(7n1R52=~Ss$jlAn6&O z-WR68=|XD(v-z5lG60HUSL`3t*(V+ZJs_q2_FzXieZW}LEz-f8{k{zwPvA)Fq)}c& zyiEN;lY=?NBcJeGRZ%n2PB(Plo+tUf1sT|;f~M6zjlNJDxTShp7~!NLyJ&=GI=}Lq zdogaX`6Wx1@zWwI^goS8)?2uFIXI7x&Ncsga?S-=(%zfI#dm!x-cGrLF+S>K$eU)9 z0TDGxFW(d!=d+uw!##p%YLW7&;OBUEzgmqLn}+#OlpK9oV`N zYImgbAn}gH2K|v&E&Am_{PHMQ@fNLXqqA{A;!_Ar58;M&vKtN)(j2;PVS@mdu-fQPR1ive7Hs>UJ`$*J|?Q(bg2;apKiDF;EnMg@PJiBYfs4~N-}(n}1; zYk+?Ek7F1o?6s&>r9Z?)Io!>AYGh7<;k96iEbVK^u~i0QZTIM+XwO@-7l7(KRF)lI zXJbc`6kp&9E=_GrFJdJ_qSo6hE&Y}01tj+zWo(2djKT+-4+VUtXF^2*8<#|EfELx3 z8z+9plXDmjM*ipCV<5%gecHGESar!O3AfQQSCZ;EETz)-$6{}RU&q7k9cZ_cYOYkL z0Uq6$oq}}h_k4OC^hm6eY4?r@74_DLdz2W-r6)Nre+5?}3)~N_ zg*sI7kdkKYGou-HebHp^Uv*TBo+{W>M&)O-kRXXQF3=`H=*%U%od<~qrMGdYf@Zo6 z+fa;B$>us-WP+9qc41z+4qB-}^3PQ_mSL}#`5$1qCkt`a2$q0AG`5t4`^AtlU~fhF z6xV{-7-fSFOJY0Ps)g8|B4;BBZy=f7kY;`B=on z71OB?UR)@s=z4wgEN0Vsyi;SRTu9yc<0z%^6v4R4VnU9VkuYk6O|@z7r+|Eh(Iopb znhB&`s4&Z(Es9>BR%v2EPOxM_S~`8&S?NAEqgVGX{yGY(z8VkHF)pZ={`qO|02?sd z6z|J4kp~hOxF5e2wWtV0=yq62C!(98lp3 zKv2`^cz>PaJ<;PxbnfzJXLgQ9gR7V;3m;M!CuEQt@zs6R@pcIoH8&nZzA z^KMR}lFCRP6`Zm~5b-b#CaMd%yg~942a10fH+S#pg-PIR<9f}r#xLl`uw~xb_!Eg~ zkS_mglxu{#R$ZWEXpuZ&DoCs{Q+8IxlRlFb1SB5)6N z0mbFy&IOIGhCk@)px{i*UZU_ILUUm^y)<_O`fH_H5R5dv$QzGwg2kifEhp4D`&ViI zmcrk<;*Qxdk*80Tv>g&naFBE!+$d3S33#hylqZk)W;_x>j_*ZcYdSyu!I*S+UrrVe z&5j+l2?|@4uasZdJcv&QwfrwbkgOiP*v_g{Vv1?xa8cfbZ!H59^+JoU%$E-u1#BQC zuv+aSt2ST#iu!^`14!EQfD*NKNp-rw9XWhUwYb~FNI?@k>pe7**}CLR!4uIKfWvB`eP|ZE$6dYRg)mn?Wo}Sj>|w`20q(W7w!ACv z^U3i>-dsf9CDZ`GXF>49a?*LvG{=9>5znti*HjBu>1z=ax}Frf{}gHNRFT#(=!y-0 z7{q##y=W%U!~1SMglV9_j7D1o3Z?!yTsYAw_kx&ubi^fC2llHrNg-xEpxoJAQO<4_ zlE5zS#FzTCHK5Rj-uKgPrz|l5p>on#Zywzf`qU&SzpC@+_-9w!vTm@B68l2gCo&;4cUT2_t3*_PoaPS=V(VzGx}H3+4#dbF*jYYJM{JC> zb*Q5of+j{*!7mP}mlMkdn>-7AbLpvf_wto-(e$GiTi1?{$mu3~hVj}8kos7a!rSwi z+mxk>bkjzwLK?&@kBXQj245DTltBsz+PqGGB_Z&3pXF~uiSpgU%g_NeS0UDhcni1P zXqTT@{THg?C}o#`bbLsC1mHI>)FqqJ{vk1Uj@rdU?~KGwahv&`RhT+3yIka52NU*@ z%rPheuQGzzwn}3BP$*}a_g`0wq;o)DX?%@F2D_xk;v#yee&~N5qY@q~MI}$i+3-Tt z^vAutta^6pR4YteXe18(tM{lq(D9RNWIeZ`UziSo1b=U*3NUg!Z=KFdqzx5`U5++n zSGT8vvMNnL72aXbA;x-{l!;^-qJl@I3?dNm`E<_wtToNAl3Xf($yj`OjEPgdXGBnm z>!?t;*x(=|*dBhXSX#2|K#YeUpVA!ij!sa_1`?^J1Ctd1A=Cat0AA zQa2{UEd$tX*rV(FW)a=u3Nx^>Vb(GxNXi}7yCCTKEbfr34~l8bU}2W-QYaup6SI`i zTRvpwHUt7K)JhOH=_WPW7_EX*AO_<~ocMcm1R(4}tCX3L?>;f$X(|j>vJ2%Jp81&5 zsUo+`JJUMS+lNVuL`;-k^X1^S;V6Q2z=Ut5wwD?^U>=Gs@ouMm(|N7|U$lm!94cZ^ zqA4WU{az$TnZN^EzF=91ZUYO8NMN7WG70I4LWa)$C=)2oZJa#MeVRb$xj>_+2kV(l17FEl<*3u=b;6@5y1iNEw73^R`}_0%@;=d{W#i{}IM3qaGN9s&v&2 zA+glq-cPZg?F#w`IYF6GQ>_~7R1{Hu{t=%EbwBLWEp zCr zSumWLu`nJp6GKgFHdZDu)?_|ToEpcE!(z4d+X*d}Sz1=^5RU&PY_aXPoRVnwSf5=T zDN`Zj#U~eYU@}}bN2RLOn}5`cXkf_E4P|gt*YHq8E(uqYFCjg_g0ESy$huBfXNI@1 zHd4}sWMcFwui2`&7aBbVRZJT#(+qP}nx@+6EZQHhYbMx|5Qk9qdh^aa=)2BOHfouQo z4LWL7Nz51-`iG|`<<~YmC9Xb>SrFM^6rt84th5-31?>3HeJY%K8#1Mv#amUIjHi&d z#Pzd1B(`-?F)=mkMl+xTX zgh^U=6Gy5ZtPOoW1|s2;B+P2Gf|;s*nN9|)m-`+s4@lrraXxFr9NHTC#osd_8_#Gg zM5%4shWM`+&$F2#S7K3?Yt5F2e3xr237L*2bUl?rYq*X4?#&mIgT zRq`M|w&6cJ53!IOz0Ckt(V$wS=3`HxeQ+D- zO-C7@FAW!+|G1{$u%KW3WH_cxyF5A-#th-8@NYk--xf(X*w&UZ%7wV8hs&&cJ4O$F zl~+uR!o2+Cw@<<~Zh9J)qV}R$gZvZT)L!{k5~XXfqt)VX?4rhdF?)NC*3!aRRdo8A zY@xrJHQD3pzlw!UbjOup*HRHKl0Ly@htRBtM%zV>*x+c?S;^m*xa?sLC81N}bdgh` z^t?xakq|G5l{&7iU4HL{M&3e)0*eS`CS4oF5ZVL^^llKyf`mBfHJ?>+3IR=_S(4taJc8Ui##MvUs`42+Wf94vRkrU7>a90X zlEim!AFGi|qSdr?toBmAiRLc&)Yo{=X*5P`do!K|97c*SgDL8x0}QUW$tomBz6XCd zx%aQ&jmcx#TWVhwAw~2%h`@3>)DL_=1QD_*#_J^A&7@GLND`57#7OyuXdv3CwGCxO z2MrIqkp*jBpkACWq;^<|piGPK8v>u*u)&EUy&IF&dGV@nbP>&&7xv}8Bp84UcS_rN zI#sz{%2-U2q**-i_k8&_?%omQ2pGPSQ^+2--!CibMG5FN*Iq8DvDl`zEBbWFYKm8V z!o8+3Zm;|o1VL91iNvULN%l=;XR_)I#xdh$mev=Cn+FEoHr3i9cDCYO+YLPIm!b!6k9 zo4uL2yDi834knBi9TlXT4jw{ZPHapjq_;)rE%xwGewAhFC!PW2xi6m6d*`@}x>Hkr z+QRU~c&CI2!fMbtK8OPM$jqvV+_Dyp|qcEP#n*boU$p^+Zc9#eFctZ>+y{ zZDU3*)iHN1XvU$N?=7*QBav6ghtpI(mrFF~(Is?*bS}NV80!?EqiZ|YUnVh=-D+Gm^jWXs08N5JW%B~ss=t?XpPCUA5C*A9h1LMu2?-) z6kN%=THqJc>qyq`+EY}4&t)K->26|MlwmHVv}tShv$7Z2_VL_Hn!}jGj-zl!a2)U! z@n1dbk8qefcgp^!I(bqjv+4V|TL1AOUX~X-lUP?(OUkoG029mViG*?6>?J||iLafv zyet_dqM$oy2@=_A>D>W+YAHcy209z9(XwgBrSr{f{VZG()3Fr;RV)3L|E_uLj#vpV z2e@i+bSe&v18xu6C2-vYgof5YBy^W^s#IG1_@iyl_r0wq-39%Vq8xJ9i9GKy0HdJT zChrriS4g(tU_l<$9Mi~nkQ)V&5!RPM zhbK#K-AqWo77b?5ZHa^4y~LXAZ)Ik4W~^J@P5eigd;UWGfQU`@HQq>;bFFc}rftcT zrKSy|_Us~PCFr&*OfCI0!#$X#wKyAX^|~Pkrv_){s5oE}+|mzWUi)!;yqO2u?%ZMxuQ1-vcz&_n?O(G+YbsKavoUr3zWb>`GL6 z9A>d5_(ZScZrW7&N02yTh7WQkk9w#Ms4S)4^Cmkx8xg zxGjYb-ZP>MMl3`#bB3ow^@OcBn(wuO7#ctkJwdqF?$d%&I#xbw-DLMc;(SQby(l;3 z%B#g9iJV7`^enZEu&P8h>`cTEPhjvS6Wr2c7G|35;ASGT%SklwP_-7VQS#fEU~Nt7 zMg2f(O};k8ybB-xH-nRXXC!6#H?=e1_c^e9EvKhxx#Hh1(!6S6-{=p;DRcZB2^j zXUfhEqUMo?mg3YJ)_mKq|CB?XJwRLM)##x9jadEpK>Jwc-BhT9 zOktvYa^CAlhGn$PkOD=?9HT4X2Ie<+*^>bxLqlRqc_~MIbp|bZn<87}sJfE~(JCChle`Do?lIo7sKh@63l4hj>%0_;j@P zQ5>rx*nqM1%xJ=giVvcpS$FPE(kgEw-YSnPz>BJ7(#H&?G53|F(9VZ?NA!FNN*|R^oiwuVRO`dgnrI=2KQ57-b~lGO`C29b3CS zebfB-eiiew2MAknvlkb@o9dDm!-VU;j?a+w3gpam6>^49?dLE|dV?Wmc z9$%Xu-H}hhbaW?9sElkydx8>5n6I(F(1MAKBS6wlK!nMFtRWgSIe(({u?iR5!fo_` z?}4WVGPK4uq`lH=$!f}FLrd(MFW6YrNjfS9XkENurLCVl@mM2$Oa}PdM_t^n6cisG zDaX!vrCP$xm4FYI6;w72f(Aaf@T|A+9rnvmb)(tnnOQ=TaO^>&v`@(f$WkD)dbniP zoLP0<_Vp8)?NEwNV&v}DB>x1IGh?1;BxNxpGmzhv6-8n>gExO1w_g_t2pn4}NKJAO zR6Q$6zGy7jZe_lpyPQa$aLE7U$=<`MOg=HX`tXJ9ej{S%)HL4T87`AjjNSw`Go-y4 z#N;dwYP_!__HraSRgpt?4_tpApN}Sr@I5^bj>`Manma6%y+6|j24~@VKLGl%Gi$EWKy5@I0PW~C&d_U4R6lJiTqibj z2wgmb15Rx4{sk3Bf&$gRIw!?Cb}pjqX^*9N8a`WJ9nsSJZXcG-WR|aYpaxBCZtFFG zj#_L-ZkP%0Z4qNVz;k+>{%t(pxsogg7M68X5gEjHp|q{RCJ2W2X4sDzm~V^Hg3?41N^pVcZ&$O1k}L*)}m zg?=XbL7d=NnoUs{;e?~7w{4G-B?ZBjI_VnfHOPE~G$vD~uU4mkj-ZM+?K>MES{*w0 zBzb3t()lvgYYRFpp|`Oo6ue!bn9Zi_pP(G%lU15KMABz|?)VptCHVWXDcMq#1q!sH zYLoz8Ibpz&X^r7i+~aqVj=wNqQj7Cg^w=b13~nee@nB-8BfaO5Ed1Z@j)G*c{W)GoY;Gc2|_SDVWfidzEx1ZlQCW{;^v8fO(}#@8C=Ri>4N|4 z$ZbK-hB5`b&f8h1_e$leC?Lv=;2QO6VUaXC9931YR%}!~t$3dJl3?gM;qn95b8tvC0X!R>rC| z_Q)0?;*BqAyx}d^j6mRWm|D}KMB7yFigh+ix2h7rpcOn>QXyEO zBDbXz`=R85-@n!|<}k}a%hO+phOO9S*M>!h^~O@>wh89!;iszG{8P~9F^F-GGYVwd z_UH=h0k+5iAgR(ly{mCoOM#)094mL6>Kw8GXHLiFGW1}~L^AOP;m_jUoYnM>y{v-) zfT z`-9qh1#Ashx*%&i|bLNDFo?%oD zV)sK1hR!8S9evtWirog{HSaMHZcvv?655>z=0P@1Uzh}KKRRDfZUhinUa*f+Z7T4m zxjg`B&-MP@CP1|xQ`?Wdy_@S$`K9e2x*x;Oc%D^u>6Mk`$1uYkFMcW{?6mysW+-i= zGYb+c?ER&0D}njL(+@U$NOpQpMY53e4rYXyrE-^b{s>*;*&FGF?Udn_ge6=Q5q31R zSh+L?W=WqzSr}AJlQ`p}V`g?O;sKEs1)lbR&E+DLr!=-|?8+#vmLAUMa=Hb>N&bO% zBCBtfCVaGGo?@|dPcu99>#CtZ1F+sHZPB zxC)ol*TJ4A5PeedW_rDiRAESlB;KxK>RD%f@|i~+?;}slclBHht-bXPU8Y6{b56*K;Fsu2Y(zJH9$XcDIF4IRqyJ`ky_Ttn zDz>l9A#~&5)o}?cPz*`gGK+ulkl~*^jgR6G`|dDi;3*xXp?HQjBPi}dMWM01p4Jy^ zs_2358ZGO~!6t=O#_yOUr|2u&h)9t)iQ~yqurxbk-joc9`Et6&yRh4iP;mPSV_WhY z`G;dyS7bo1bh$|VA}UNO>^afjyvDn0AJ%Xej_J_*Rgjf}m3ecN^x$MPIb_n?9$b z>393~Tr~VN`S^I63xW}yn~ii#_C6fN0I`+;8e)ZjjXO8b`$P4aw!ItGrzFo>N^$kWxok0LN2v}a>2GL7{A=C>S#jP3+ z=daRPXX(4dc2Nuzaq1vXhcEerU7}p^^H}fXHYF7s>Cm8G)YrhwvRwaZ4sC^}J(vo8 zZ9_3ThM{r#>9CQq(~%LM9*88%)2ahBeH$ zJ2;2myr~#exuZ`mQO#{x2MlRpZfW!-eCqX$f**$PJ#*%GOxa+3_vHr%P{Yy}8uMU#VAZ8|QqmS1=`#y(x zneQ$nI=t4;$jwpL>Csr+o|?bWC|JS^MMb5@bwpI> zQLi^#rpG``(|6-1h3f5FG}7QkH%j-L5WlvcJs+bY(_e`#zL3a8+Ur(zp7@s-jwcF-X8xokNJ8%gl2lP6b=p=tP zqxoc+dQVxEVPg~It0-7Y5iKo~L@z>YKIrhK)wSO*{pdnKli9@r?q?r$aeQ^24)q|3 zV!I8E`%6?~{A^{raA?_Y;2pC(J!NO+3^_O;G+_1c@BYEColel~Lq2sF>0EY@MAu7< z5KH}0?1nQ=h$M_flEZ!nIC#bv1KCAntwn3GwH*j+l+^vF@wWK_d5(=fhytuOu7A8e zAx!peofB-VIuoCFt9q_G)sN5^ke)usa=Z$;A{0RvKE>XqiWHLSkJ`2iF)3}u-|t9L z{4Dka_$svefc`n`FHYr+DsE-~v4L~!QiMPy&Eq?>BhzM10)J+J2$7p+5}9mr_G0$| z6e~wI8>p03L8HatHJE&lKldAz$eOwlI)0j5Wg$=U8`c_fDynSL(mGrmUQ_i$CVi;^ z@`{0hT{rJ%(@Hog^$2!cVf;+SjQq3nh>YoLcqmw_pqlvIF&V-@eO#k;TRJAl_{BK7 z(xj0#MP}=XT8b%o2CKFd*n@!{(dCgiVTSUeHx4ST1;)G%RY8#6vqF8xgAK#9RR3CT z8ZdbQ#>Pb)K`+HHovxDQup|`z%~TVU&OFsI08|&(%rhfA)P;P&HC;2P#K=ag^sRU%DT=Cih;1boN8%C6?m zA>h4bIxupP;`H54mz(HGw00=4qg=URuOsLzV8ZJ*v&HdtYPKCaN4j4$a_{EP3U07m z5-PEp{6{7^jU5u@5sOf*h2%m0>WA(+OpcoBvKx%!_TqNDX&pyl4C8xZxh9k9R57K_ zMML9R3DvR-)3vG!DJ5!Je-pu$P)yBPAv7YhOQ? zyUZGykCLo+3D|$ey_~ycXkU(WaxF)q@AyY?iPd*YrP~_gzhF1Kx<9!$RNl4u2*x|&T5%HZhtqHUTdNl`ms*^kf>I}8oQ-w7iMd(K z$%ZuId8p&T?aw9d^VMXtyn8z(sI9L|F3Ndp{V0dP#LF47o!9=T zf{Tu=@?d%lh6-#|A5%YWL8{~PFLWM%(<0NvW>XtdFtVF)}i zV1b<=Zf+1*3oNiK3o+96(h#=&yzzTCHwatXq#$ms|C8rFZ*1}L^6|R<7ZNKOC$fcN z2Au56kEOw>x(Wo4G%@i21mNaIr{?A+2gA)l8=A-ZO2Z8L18#i_5FiNpi%MVt55~o} zUgRGu=PC~VqpANnBO|K6YkeT^SW^iFVSpplf#u;#2`~&5|WbkFg49*SYzV`m! z_SO!l&keAKYTWyZsK?qxi3 zk^y||R&GWKjr;TWEq4XZ`1wi0!98;=k1l_35svGJacdXjtI6bdJB$Sdg!#KWHk+pl zAitY;4)#zIK`tD8Z|1(KwM2iF9|T_CC}aR9PZ2;an-|cO!7F;#=;RQrj`EA`JK&8I z&>G8+7?2MD`wo8yUZ43L+kxjeBd{9x_uh#|G6VLD{!MxEN-rL|&-90W3|K$t3z`qL z^#>gVpl>J&i3*v?S$dd}D5iskw5;?ZC(B?O^ORjnY=o*($z)C56y;t*N zy8lP-uADT?Pf!;i>yZDhyr2B|CyV}6Nv+1O?>7@-Y<%a(!q|^yVX^He==V)Cu)jth zVdM%0=83GYfhYgILOFXX#KcJg;+Iml z4HdGpvZ?r7=`|)YEyZ>Vord1TH=~y&BHOdeKQG*&m!vdzpgLsI8=G8^@@=~Z`cDiI zNG+<)(o&an65Q&cipQu-G&HY44NRVpexa0;m4$625@Ngm%uZ&gQI2Ho3fU~?edQBt z7R2wf{NU_8mE=;S(DW+CJRPY!HLp)M^ji*!4Pg(|jBl2B6F%;J@$OTiv_oO)8IAG& zRdv4*N4#`y?l@~BJo48Pa8_a>zfPf`v73M2R9O{ z55*be)f(I10W=+_9nz@aLt7_VVX+KM_>WvSc!*n;6imzvW}&Z<;CWX1#jj;|v?%hl zmXx{0J^3+VqU9kshAvsCX?d~-U5UZ++-&Qi-Wjd(+?P(#6H_J^h>c&t0vV9bro2~3 zUWeP?_70z!8O-Z>72jDE#Yjb1*Vj3PWCWYl%fK>{D9_5K11{RWPesSp0DBy&9oPJ` zsRXeeBRw&MW~3gxB|?l>)!pDBwNIt~8!!Tl-Z9KO6)Ty)LONi=ds>Cz2XrSWBMt5B zAP*M2AEyLk?~j4~kB;;v4Z#|JuDF@yIhL)gtJ59f$(f5f`AGLt#P-DKg8cHaN+jLI z!FU5l*>LSKbjQYA{sHDS&q#4nXdQ44u$$qK%hj1~lhBGZg848%4Me&UEwnF{hw=Gi zu&>K5%}_067TI+lhPP7TF?#4Tc1?S}YmJJ6nX@93sXq}HCumXe1+(JK^T<60Ac zdnI`KJilvG)w>^Dg%-;M#q;^VfbhNbCEgF0bfF5E8FGmFV3}MKdt*-UsLUAj3l4;( z!3qALGS2?sd39s&4P0V$2~nTS})b9Lm;6$o~vjlfnsw1@`U5h z`nUpp9e+hP-Gc7VjuzGU?nQZ}LAyGIuEqHT?E_nuu%i*nELq(N&Xy_j)%v#^p;=8< zz7CfNv4T(hNhEGN2#F!js0^K0$qKGPXl=9uFK)^~E!`l5*H8 zVN(Mk;d%$Y&K>lc?Z&Kh;wnW`%*Psb7)`BS`GPhA*_~+bh`1c=+e#3 z_lTAtm^T2g_^@`A?cQ|X}C>mF9?Y#m^XdCWT63K1g}7`pBE2u(TCSON%AdMz zKOz}le2H1q35AztZP;v=nc)jsBGS?{f8PeG$)7*3?1C*n-ONRWU=CIhW5s&&#!!`v zU#wu#7-2*8>V{G7+*r4vMJOa8D{9Y2*MXqo|7Z`nQ*nF%A8`g&1j{*dXqb9DT?c+v zORCuac-|!sga0!>2p`Y7Sa(YwuD`v9fuj*QK*08+-~KnlQgFMoT0iy1zS?5ucF9K4 z!b88Oj)GUenItjwoaBTA3lG!|L-7r;CAM#&V(nWV)fX;@#$Yn-Jb5)5dtpF`D;+flCxD%(iUefHy&YO>#3u5H$z;We_$s12)%T`|fZ zBPho=6Tuz3QrytW)cCkN4f5qP>WKomantwI zW3*tSf~oh9Z;{Bai*{|v-_kr#p-rt0OJKScQH4rM0~k)r6y#He6ka{E5)4fO?@sq~ zug<-iz~W|(cKz3IzYYge8q?u&Mtq-`h)$Kk+M*)aewxA^|Eyuw3~Cao@QRt z@YzqNdAlx|%XJ{7)pM>jHCGYuFSp&1;{hdHN<_Sl3#_cp;%n$TuahrB9c<}e_w%5# z8HDgzsTOj9I0x&rSY2W%e?I8b+g6)gDWf{EI?6S7W3g7Cp}daQxX9d8oJB#n0ULW& zK@mT}fur77J-$z)mm6(Zxl$UD z%M6%NQdVe$_`**&nh39IK6$3QPkkArkIxTKTlZhJ7yb75ZT)2_U>Q@*(j7IdCv>#M zN4oGG*(pic;?_+OB1klC=~y%uCn9O!kGM17XTEvaf$8x7{Jx!t^K^v(aa0CLJXXf> zv+oy<6$F!I&yCa#P3I+vPD|R+ebV(G=-EIu5I;XJeYue!{YPnUBAUKU6rB^TpSNA- zN|`)MbVwE8H8t@fV+j%?H+*lQgLBomu~lx-o;LL}LpY-?AS@sm(HUG4#ES}`YTLM| zA&>ZEE5ecUpXa-knA4DwNRl?U_Nk!km|6WwYPi({1*B~)2BfA;f{yDeBHg5e=)-F3 zD=|4txVx1%3HOymJPaxm=$K1B1k%~YMpYVH`)7`|_ya*;RoYkg9);Q5tWgU5`a|!ekR$r#LQdIe zdX)Yx64(^8pTVYEZ=92lUSZJQB{*!!cp=$!n@p;It1;Y)u9CG}ZH=WO;Ufdfw1#9s zYnf;eojv_Xb5KlVt|7r|(x2hnwFVcHpy%n-TUihqtZ=dw2C$bzmXO)^v znuO`+b{DzmTPY}H;Glnxq~p+1r1A?q{Bz{}Zv0`q3PlicG*69I@<Dl#BtIPO=waO{@O7>F) zy`&Cwk?x4|;dpoMArv;G-z9tuvNWeM+> zh(8$(&1Aq)UM?B2#A7jao4m6SSZ%{2_hMSEu_A?5VKLb@lT5g}*ypu1@pp3eB_CN` z%6E*iQh;6w4x6Y^W!eP$ zy?vbTp9YrRx756{2}!cG0JnlnG)rj~u z&4gcY|3)U+w|kCe6+y{Xwz@g|^@e?uT3~yQr3el*gBwl4&K0D>p9^w6@;{#p?parj zPI6mtW99dmDaJCYbZQ%Vu6^i1O@A4~q42vyWf-;~p9Dhxfb6OI(`5-vsZ2^_#lP6Q zCJ{N!1!XU@oBTI;4;&ewP$}yiFO6xRE#}8a~9%2f9^( zQ$m4$Gji)YC`n2&_Q%N$DZFpgP=F%lwNaDicKh+w`tkrf66#@H zxBIUhKc5{LJ)&9zIgfCsLtF@sn0&Ag;Ep;^8tr62{98MWHd^f(0OT`~b@uXLSOINT z8e93odR}zqwKHwn4pCb*91SrjxolikhQt6YaoO1gq^OLrv#t`Zo)-}O8;BTKT*t=) zP`k!K`3QaZ{dFLVZ3me_9w6Hqak{FGw+ankwa?X<;|9OsBVJoaX%;wfsvV@oAi;Y* z9PXH=HO)~8oGiP9r2}ozZleCYO%&_8dQD42*sk55yknIcSxCp4Qc1J}L*l1(rB)LK zW6PKwXKiehr(jb6VIheR<6ECbNGzj`+tLvb#Y1T-_n{ZK5TKmn)q@ZQ-9h)6_%SHs zuljzC(c!n`# zYVYU)RMIeBL>I)2bdupIE6{_ur4Z^eWnpvWqHs;ZqW1t^=2XU+5PA_nfQS6phz81o0g2O`Q zF08=3e)}4vx-jB;m_RP}>Du27^K}1+{v}i1S&WZjcPsQfli73MM;ig3boY$4poaJs zq;fkPCbFM%4l3;B*EcWd2f7JGt8>8GW3|Q}a~bmY8c2?*)!nwzgZb~&s(WyO3`igz zwFiJdw@Fp___Dn5`RZF#)1<8;8ug1WQw_O+5yh6R7XRqQ#3t*qTylIZmYAPlfo*Et z^lgj8Z^P(YDP+hd!(07I-8v?BHU5K5_;1uH2cZN^yW#sjloQKHfvZ*QwH6iI)E9$n z!=3JPw)8B*NX<<_h^qOmm*5G-=&m_xHIm|t8-t_w%>*O2<`@$HCuW^4NDY+2nSY6E z@J8YN^x)PniP2QfG2T2ex2}vZV$6p~zbZ-iMfUJ?+U|pnTdyRn-2~wf%0f-z-f-fE zpl3sw@t4C5mZ#jn`Sb4DmrY`V=%`OLBZP#DSn<8RB+*aSmyHfCFh?St^s(po%XA2*;b!$81+PK?yNJM!k~!zbz6nX6buo znPQu}NO?k|Qm3cMrI7u^lt?bRdbsW3k?S+rbgLo!lTIIvZA=Qu;;T zo(Z?+XgSjajl4Gc*t~cP5^4J1$jR*rA=h`-9I<+ckoQ)afRovh4GC?0zoyfVGoI-85*x2{MG{fg!(4tn1eO40PFBcOqT$K_w~Xxs`LQgwaHhFNlWnZcDpr zC*}m`Eq7Nf%EK*a836%|dhN4u;De*LZb=Durjv~Nc#;`jCwjb9b;iF{N*J-Kr_O_3 z!wW#kwq!ssM^$-8Zdxp0y~Sh(Z2EbYoWA%*d{)wpIRu}2UQU=!Ocpzw&Pa4?mnIF+2~HyrIaD*(DW(Ut$N8iy zm*QcByli5Kto`tFf#u|axMf`NFyF}ZN zBvBJ)A<#}k3?JX(ANQbE^8{)(CrZW`)i!91@V}w>JTat*%tPOZY1597PXZSl=ZuU- zy}u?$MpQG^E`Q95R=G(2EumNCv|IB^a#hjxVFhBvowG*~ko$o>u!C&#RqUdec@|l_ z^Sj4CZVf!i3Nup~^q>(6_uAS5ocW8d#V2yM`A>doo19t$-6saGDJ!R0dG5QD z-(@}Ev$giS>^`%Y5KztX$-8H^t2JapiT*mV^b!q5nkPA+iQbli0=SZQjKt*fJ}~pO5|YBKL$6|S!Tiajba>3G`u%s9OkOGJ zu4(A5xdJcE6*ZZ+kU~nRwf)O9}I)tUS2{ z&1M))((YtUJ6>TpyP?}Tiq#u3)jr-XXX9j2Zrvb0*!Wb0NY!=aRHCBS0iN|t1)^6; z<5G^A^NXuxWrxU#-%#hL!&24|)9$@X(d}NH4<}vDh`qhbb%`Ffk*2NYOzI%cjSGJJ zkPk_@$?fYYT$sp%v~D6p47--^DzfNg&u&6Cj<=v7GXGPw-o_*R&eJ+;`x))ix~Ms| z&oSY5fvj;@>wsp$H)NDARTf^jhNO!y`tFe zz&02QHU%++zUOW%);4~TzoJ}|Bw1NOTVj8IIBJO=@0LKMOH1=|Pm!d{AphrAdYhM> ztHp^!-mQ&s*X!5iQ8_j0(@`_8bCDamFEVt+lq*~~adlM}f?6`l4c22~0Efbyt$>Jz zv5R3~GfV^>*BBW1vQg01m#pA7ytfzK7KaY7*p_JF3TK>df`>R(L6?B9NFiMm%S&j$ zRogagHut3)b#0TYh(~E?F@yCD@%va$#bf={D6i)}dOsdQlMtW&Ye$CQE{odf z@M22x#-e+9iL?jl9s=K0jy5RTC1Z$n?V_Bsm)G5dQwcKNv!OJo@6o9%CIq?F!v;ed zFb*zC&)NNlO0p2wyl=0f(>~ZRc>I;8Gk6l7n2o8XsNMa?2u7-j_DOy+IJrTL_PC)Q zg<5*3xPVs$-36M;o{~Qv7A*1QC6s2oCZkp`4Xioa&s0Zt7x~4*_p{F)Sh{WJ*7rh`NoG`Blrux0g z-k6MIebWGO<4%3eeb%VVTS(&9q+aPY9Hn2$4OCDLylhSV*u}16QO0@ zG}BG(ma8!2WR=sjwYDM`Y*lP)+vbai{TTezz1lo7H=xKe5)bv-#R%N9Mr=bnO@s_b z5j_-&m?>M%Tt8drA$yADKM9PL$eo3So7;M;-(PC=19>To-IQ!W=f zngTw0EPc!H)a4jXCl!{zIr6{+r!FwWLf19{_ESO>c1jIg@U`wWSlZcG6>9?oK);8b zvxUzI)A+EIM{tW%8=RsXE<<8ckN5IQS?CVqCNinPn~x*g33=?zF>xu-zWQVy!`ZpI zJ<%73)_-p+Y|>snfNn&Ujyh%oS7_p59~I^cF1%H&CHPmPSiq-r ziLkrp!VM^hlLtRMsE5AE7&U!^500Nb^3r%6ZrU9>k!lC=?v3IV`c~Db-9>@G&wps3 zir<>rXN05I?5xLq5Ye~h>U`@qOEO+Lz5XF|L>|l0w2>iQ6?cm+3B~_lpjkgRw>>R5 zQcK5vL7f8Gw(U9C-G0-}z}j-Zk}f`3xfP2e^qaK16C}Nqm_TAjm9&!A5AN^FO1lR! zV<6rneuRXzk7u#=<5e*>Dz%|BG;=yrSLlr6qZnwec*b~Lv<7&~8MmeE17$GOn5qcq1L`ycYIOhEf7*g;(dBw=XRW4%6@IC;%?d6!s0VQ#Dgul56!(>9;lg zCZrULc~x4;zlUgr)n^biq9Wg6JbDxK&4d@Zjn!qdJzVv5DNwyo($y;k&MYxsWQdCf z=iSjNwSK(6UF_5iM!5xnPpAwXqwUJ!5KS~c?FK_9UM{S+&?Vz@pCPBhA?zr(bPrpD zsrvjVLC%!1(HBUy*S#R=Ym<5*F7D4Vlo-zr|@qilArLP0SyWNe8BP}&?X^D?0 zbQoZ~GP1IYnX^=W%Oj}m=cesv)#6M^y5Oap?W#)KIx3xS3uw#{2}T%^Abo%hZelrp z6jOAT9g7Y5$xp0W3Bc@MQ?}Hqv6*J5Kyuz#`=}!e3z560y;KE9{KZ`JX-t!?8r9L5 zhgo^+ja31D-{*f@9@onm5qU!e9V8Mw28{i1776#LT%8LL$F=0rVRvSYcyQ^r`@a*2 zZg68I7f0b0Q!PE=REivWIK3nxaS3bm_QlXSn@FhMEaPq@n}GgsP~ z;~ge3{@jA-c*N1Gbn6QF1hwFAW+!%Itc9LX)bC)*?jeXel5@@0>r@XGBKPSQvdK=T zU@u#}A0zUvy)dg&kyP!9ZQ&J-HyiC9B-I+=JN zg@ne8&A622D{^X^=vlW7vNin?wXD?QiQJ5$-<7CcH_I&a@kWUUz3p^9xx zt#8e8srXV7n38XMToUy?9Ti>8kVgb(DQtaBH2)1I8c=>?vhL{w$LVz_Jg)D>RB;1R zg};@N0%Z27)X-WP;Aqc0IwpN9jtKmfr`;{=wei7^^+c*Kwa#p5Oy{pCOxUAQOT6@{=f{R8UaxXnlz$o5Q3WVP@nW>t1#0`$&<+~#2>4( zX1Bbo2j|xc4FG@4$#w*HG=Z?XY6gz`;I)R>*0q-I^=g-jfXDhK_tZO-5M#V#=e^_i<3jufp-{?WHSa2AbZ0eVw z+B0>Bm*_F0QX(jpP-q*;N=-Q8Rp!EW$c)SVuP7wae4j?jV)>Q;PYhHxC(Z|fzG99u z--Xch5*Zcl&x~(-h=I;v0S?uY*4m>hr61x<`>*^WDThJYVrzu8F|((bUpTiQm%i~} zCP9>plL`2x5q0Wks4_Usf$|NDmA{**aT1tHAP3C}_cDSp-%rKDxXC+h@iLz?%RvlQ zwTS>2#Es?_ige7jy6^zP^`{)`Jmp9_9gz&S9!SQ3ay1gD2JTx>V4WLNXwkE*6toQU zZX*s7f0G9Jo??t7TCT9D!9$=b|^MpW!2Y}su zn}c7tJV=sk^WzT zSYOv8fEc!WiOR=k6~xN036g2d?woQ`x0%T|^P$2Y5#`&ef&y~YT zLtPhz6?4`8)D>{_UhS&~oYNpEuJ+(B5W4;^Uf|}ho3=V}KWAsuNp!W40fR=z>8%|X zAW3l()`iyHqFs+F2+yZ*7Gf$#yDDO8p^4`w%}1hPFSMJyJ*dp{EMPzj{ElyzNHO9(ohrjtJW^$Ote$cV>7E-9H^m3 zAKDD&bP!O7sO2LBjkk2mQe1(8a>w_gS6$bdKZ0;xeOCk{+w^9;({6}Dd&YdkN#`S^YqZw;@5ik}eb*HGxsA*f~NP#SG3IWc!0_`()@wY zTam!*Jq+A@N>R*(F$QQ54B%+}4Z`0NuLI5Kw4wc-`hywx1}?aa_(Cv?%^rOmk5zaJ zJ@RTC9F#=(c`-PBpzl=k+&$8~5MLR*f@uX-10TU&PkIb($u}& z^qYgW#@}k8Hmh2E@6f8Z)K(oji^Ozo>e_AA?Yz+AV;@P4R$5-iQP(RHY)B9lwU6Ny zj{M%kF@D(GveWQ4lV~G56pg!K%8_5H ztQxy#L-qT*6b;7gxcHg!>a5U1o8Lu|`vrdI{D2he!n21#7mg-35Vk&kPU_mB!FX@k z{NRIa#@Ch9vkA1_qS=eDMJ7+ZRc8Bo;oXM&O%puFqLQm)`yD~y-J;F0nL|+6kqj{# z>fOcl9y26)iP(rGe;Wj+P)$AiDbAR5`#6pS-Ak7i&Lst4R;vDT(Vzpq2OcOC6x0<_?<;y)(Sra*$P3c9`lgrfc1Rn zWM4BniT z^C`a@eLt%VAgm!}!CvMe?PtR|7Tx0Dtx@tFJ(-oYZ{ac&D;<4 z84Y66dYKnWowuL_E<@bDwdIrY6BV)jmr-!gqHhMrn~tB_p`5&zE+u^53qlmak5FHS z1z#gA@0llgypSOzo_#f@pquh8NX;XuLUyn&Pw}sJA+2gZ94!kKBWAr4H(OIHZ@&{0 zm|ju_ug(aOXb_!|1>$lfo2 zjK!kmf1`n!{wod4`G4@=e>5;7GY7-})Smwz8kmXoA58q814S=pY2#w*L_jZQW9VWk zVrpz}VhY8_2j%SIWNK&&<*^al{x9!*jzkyZE#weBxUC!1%{_=|5J1SVwpT~k5xO_1 z8w3h_^A88k0SGh@q+8!^?mqqUU+!g9W!87+-~Q&Kwf7a4uB;oSGCVhcOL7em(Bxd_ z2mw%{%F4k3fP=GRgM*`E(bBSISb}>>$BI=$Ke_^P3xN2BCOC!x63Ta75IAF&8wCVX zaA^g0a02Fd58-$Z<=_C&!NCdo1?1v@1}q7*Gms8|!WNhZ1acBAPIYp4askuc6v$uv zIz=2X7=+kEK{+yiAI2pxgm(hd1|S4LC0GJ8`OTRJvH+iRY5)i>$ooYN5*z`8az!yR zcXxL;2j1vz;N;MbW@-Z18dSgzAo~k?bOqJ~@@D$Jh5RG53ARC<=JfFbZ0S4R!@63Dg$-sb3NLT=S z%!B=Bof;g$xP^2!bOznKDC_>=o^?$yBT5s4J9r?0T?OBK`7CRgCigmS@-O_{pJ)er zaQ8pb4M4&)wSLJBF0Ll4fdRQXf=~cxtRQ{KC~= zpF?~M|9#i~o*G!)oF7Cqc$NV=f^Gxi{Vnk92G|w=sA#7CyZX5s_M0}x!3mgV08KG~ zV*(pi@QwVf3ET9c>}S`}hD9C%=2bP{myi`V397QXKn_v9AnKRB?KE5Td+@Hcf4(8vTJ!5ew_ z>A`n+_~yU3^WDF=GtduraMkdC;?6L?F@1>O^x>nA=%>GrKwtY0zwEF5#b3K(zy9zf zmsaMl;hFpJpTA=;E#RA;KcF6Xrs`*pS`{2T^x#MSgw3W1gNFqy;pzG1)~tz(`=zHEJ%N22ddzxNcT5ybP0VGqoJIR^Zv<$V4Q zRD+W<@8_O^JU|EA6b$5V{i^~2v=)dqi~6Qb{1(IL4yM%u%B!EPHs}Ae<$w8W^ROFs zih%Yj!841rwm!7HGja1yqm%#n3%|$N_uMa{2f+QNUjz{Fjn9CN z9ryp^)dho~oo-=rOmuU78Gr#`AKQo`0ej_`LhBm9y6+W+y` zldqyUw|cTah&TUPp9md402ivQ`HOtpnR~tP2JSbAhx&&SZkCyoKH)L{<@cgJwEEH6 z?+hRNod@PO@wdZOkN`dbbmJf=IMgA+R#xJ2+8h$eeZ}6mzTC3^yp*BIi=NBhwbwiH zE3lD@*kb!#>R{MlwK~-nGc5l=8U=nwT-NpPZ5A@Cmf!nU_8)6GKWjnljDcJ1S^lJo zYf@oS(`B^XXHSQRc~~FlU69Q>iR|kmsyiiK^wU4R;xol`?QOK79Yp z$y?-76bpolj1eSzgNT$)QF)%vg30EpCA9gJJ73HZ|*) zoowmS;fSz^fQ6Xe^4ExyU3QW_$D=?VcSb>}eWCGWi9k{E^%{J141Gu2W>fV*S7Jg~ zT-3W`Y1$lbO#A^t=8~WGuSnF=S@yEHlq>gDTQkHC1gblCgZ{p3){v-c*Sm1n+VCgQ zLCP)j0h;NZZQ_8kxOx3nIcwqKTp0JleXjX1uQ9Z2pI57stWb+tUC)e@7#m|WHqoTW zy&yKCa6zpWf-4R9jy4^=2=3t_Vo)96y3l!wPj#lw4jK{!tif^%edMxlp7Q)@FZz*b zwKWE_-kHJOpH%GnMPYPzt-uNQqyxn90=5y_+D4mcL8A8>wpLHwFQqH%K z?o!-fA2GVH?C;yeyQb)IH>XrhC@ZDcP&rrSLhw9ow&)?yos)gy6u|lYo(%)2%c{3x zhhf0LtXDI(V0KI2uaxbFV>`>^N0Lsmu-rXT^0pmtnU#;VQ-+hbTlCme#X!A(VgU;A zELPgTJ~*d1Z3kYUThV705#`YmWvM&wkY1uqR4bo-3S5Z?7egSaOzd}Z-iwOEodkZ6 zK4V@rSsSgzUsL4l<8wp}WOmu{w`MXURl{B87}ecfM7 z3D=1OE9s9Rp$)PC*AeATPZ8zhk1U%46;`m#NDXuC)ZLqvz%)huAcGh+!ly<8HPbdp z!*eenV|&*@7SGit3ug*Zt-y-Lvp#ebIw&PFL&ZKYl8;R}z=$DgK?$qd%*LmTtH+Av zQgAQwE;_Vulk-a>xhG2MH90H2>S^UprLkA4`Rr8Vh?QSfE(i|$ySB3??(!tb+)q!G zd6a`g%12QtPecp;Qtk@d4vlFY%w}%API!q54oLC*oX=k#4U3c+se4C`zh9gkXF`nS zXVHytr+~h{pF`U10gKz87_K?wLpYVbv2=D>b2Q;O@J%f%4h4po6Q)lNUt5ux^V0i3 zLXz+O)J#y$s^!iF%V1@+J;IxG%WZ>4h^W2kksCwBPFmz zXGNXGiD}j}EFDqm$#7f83TLqkpZXnT$jZ#qB>oY?*&QZXV$ z?Bu+|qBeP|x@Sk1Iu4<)R+#bh_KR9uMMHx78cc2@Fc1f*xt8QQ=e%2iGXmQ^cVLJ_(J2Ct(6hLy-{gG(O;=XQ z^{WCFXrNIYSf`3`-efUXoT3ZpcJfXaOSaH5sHyLeoqECHs=^+h59Ma{_Y|7`Bq}!D z3!6+;bfWW82tz@2CN+5^mA83x#yCS!D+5d!5u~Rq4z*`0$k_de{d?BYHZJ@==jzWg zZQu115Xpde>=29V;rw1~lwGeL|k;kjcfp*DyB3#8DW%>NE2QQc@j!Dd^H&5cm z>Z4T*ui4ySA&}nnX>kQ$Y8DQMx0e@C^hYgmVeQ$U~q$RUrx+Skv>*NovBXz`CeE*S~o174%a4# z2O}RmMdTOA+)GQg6EvQe03;Y3J-U{xi#CM#iLr-*sS<$Ry z_7V}avuwz&a?vh{!s#c74Ptsrq*F8+%rZeX8asvjltW}yQ>*<6k3hO;Cw`vyX~lqq z93pIQ5czGT?AGb({lNaVe{_9{HfHdWM&1oN=W^l%N(G1)@vyuyP`Nuup|0{ob4*9c z67Y{t5AhkiBDd3Ek#EBfTgQ{tu2ztPT#Z_gff0{%WE0NgsRgBTekC!3252Gq?WT&z zma12p*NH@Q^HjCen<49adP>beOLVg~cmT)UOhXdaMK2vZ9pp)ujPozE^wRmMK{HT?99^EsL8iS|@Y8B;jYPecU&eAny-dRHe%ac!*R$6s*b=?Rt>M*t4fTLNHY4rT zE>tB6ItEO)$p4v)MKO|C6U4|Q^Y=+j_`Jhot5N!@XU^Tytm8?}(P~Rw_%m)9WIF$$ zPq7l!ZwM1>`O++Dlugf+p5>7ycA-KH7GH*G;cZToXi}vMXyp%o{0_S!sE%gVNo5A; zX}IOQ)oK+R_5GMyA%k_<3@$boddV*Q+3(dT=e#@6dz%`4f)R>{9{pLra(}l7c5>)) z;y7=gM+{fC8q`h3Xi9uheIl_09u!_c3z{1Hj52?8e1{(9j>s;%$`DTnD6Ju2* z+|#*vTA;3eOZV*gF30C=O?i{B3?cp=YO3?yydp-@=)BcSQ#kp;9My&Dcu%Uyy*pG-HFAWU*H z(x7I%k^cAeZku0ou{)zUQoF3pCAZ=WE?y;oz@^;ISoT>K2}i5ZFAU-ZQ17U<6+ghu zHqjp?rw7moJxr%Z>SgI;38@2gDd@IVubT>xsv>H~=m|%EpL_Np@>E8zN zXk%(bMdA$?o|G-XqY5-^sr@1@71gk5h6f1QNqAOb+H3Yf(3KbRpVYGZ&S@@F9nvIn zkReSB$5;`p%4tS3-^#!TxTU@jrz!pV#w@D{6l}(&@7vg!^T zV^{8NZ?D%c`)I_5mH}my;K(oiIru_4OLGEM1v2M<)p))mB_iE+iv-H5?lZpBKdi?` z5kZZU0BA{OtO1@!U6|9RClQ5X8BDX4d{^uR{j_G{^91w)qPqHY#;-ycItheWDj9{w zNdoy`{7fo1>;;A{K1hHWH)O?nD7?(v9fk{9dak>-)HmroW;_J(sK+h3ZFGyIk)2gl zIS=jm)#%orAr?v16{D|cOMQO;ql{a!wi2JE*sag(5hl0Q8Uheklgg#hJcVpz-{JtA zf(Ib>K+Gn<60vMA)zY0_^#G_zD0q3b+e2r{GaZ|0C?0uc5R!wZ##Hf6ckG+A-<|5o z%kg2+U+k5~Q%Q_fujaKYJ7kDv6?*0uJ@0z^tL!b7{(Y3O3BqS&mbcHB-W(gdkTCrq_9w|+kdQoCG3hbyPBG3+jH>D-- z&*q*UM52adR#*-^bOESssX+QiM>GI)gY&L&p@!i%O3X08iY`r>Jt8Cc+HaaN+u?I_ zus2CHn|XnDUxEL|T20uyzH;)HFL#H<^(H$dnp7#t>Bn;dy~@r3quazS?F?m`viZpG zy7hDpS0Fe%>l8ZvB=&gS528*_tPWLXXSOdc#y=P?d$2vm9hDuvmBLAb+F-L}JEGH& z{1SJ|(zcjq7A~Napm_+8Rd2qWu>^+DYu$A9&ks|Pqx5<19HQo+X3^Ojh+tPcAGFN@ z3jY`lS#O3o7;7+XB(n*qdRN~=zgiDXu#00G)xLB@L9)NqEN&65n(SSBdfumY2vpzi zg}29M*@&O><8Pe-e_XFOoQt=%b(d(1p(VRq7wne1$@q#%BroZ$;p(a|v(mdFoGV0z$HXlhR&XMvU}Wt6I@o2n)NZZ$Vqr z_*FSsw;3=kla#xVPHBgw-0t`<1vM1!UAa&xPT7(ow$#Ogy3xX)X>FhX+`B$Jc|d9J zzApo2KFv}WuAPxeJDE%ay{QTmfuKMiMzpfTfu=iFV`^mauh}%S(phjQAAN)rwTe?z zqzIq{Ef?3S0Qm?vAKLL|you7TIY7@4Cyi9{bIc+O1`@tkF2A7GJ1JHQg^Tvq$HRJp z%l4!{p~cO3sONY``>{N(hC2ZlHZJz&-GA-C%)H<~yZuBLz$N)auYjW(`iR?~<2Rtsx;MC(b z$e$8O2(s4KCY=8YHtK&Y>hpO0{5r73yZjjxk@ErjFhfcf3Ow|*@M)Twn;{svDtZ)7 zcqK9ahc^%zN?h$&vMaDh|E^rhtO%gF%V>kH`Dp95`Z}1d)M(mnnAVp}?DaMi>FxxN zC5$avb-Gq4GhKUgMW_jf-9%ZsT_M~j~SAzLG$3Y2GJm!~U z{gMgcgQmT#XljzTO1PfVVHVM~&H{L<-tY8wx?Lz>zg|=o59dsSRP`iA$o^-RpSx&G z^TxZ_DM!VJYQVN(*@?JFJ1VkKQ`(<&T|&i1M~c`oCvoXrwQwj2V+|!<*S! z3JvKE`oA)2)9+%#r)tHbHMQ~2d0v?fO7Dlrvl{cSyp1jyjvv*Bmp9t}nn2RJoX4DK zC%iuBJx-ltU$Dq8e~`+%>_P^qHL@%8rXDu6fghae5zdh+IKW<6A-HM37yBlHIx1+3 zBl2R`AjC{H5*gZQoiBLjV1sE5EiQhGv2 zT=fk{Aga#QN~X?1x zv3lW=DW5X2wt!ED@Rnj3QMS-gw1|aD+fFpdCtG3_MmZ*fWM`JM*XaW`SA-4RE>7xFK!Mu%gV9t?pp1mCzqG2LuoQqR^n5{2F8 zn1!&>*j7SkRjJ(#*(T(E%tJG2>Eh@$utky=P!3MskJ%}!zFElh1aH#zeu6Q)?H?Z? zV;yC$7V~JAhaxKypctrfS?_8skq-J|al4m=&MZG>QTWX?tTY)C-s>?ATa=>Z_XItG z_l@2o84i5YmccJDv`nWtH__`F&Au}N)i)V8JtSI)%-2SXMh=0aJ&Ws}y@7AHc67kB zqCU6a>vLfcrunUzy2ue>Hp-ri`U@upYSJ6@@Y4rpdvJd9AHq4i5s%$&+Vz#b) zZh+TTbCaErdi7FBOv13rumn)Jmpo+qiuFWPj9e=q>!?bdM%nq+10@DAZ~>jh4hBmH(m!$dN0pHB~ls=L)C4 zl%F$->PSzTUkJZr5%Iu7`tWSEMd=QFO3{a}Zs{4fsWR<>;qtJkMx!JLN0jFTd_3D~ zDE>pmGv3{(-)h*^a9N{}>W-W_63JfUdc`iqvm*_fg3rr=7H2ip;v82ARPm$-$Nb!B}Wxp8n_O+27Pupm=^stdJ-imhz4M0x&ux1eaXgF4Pd>3&YC zdiU6W{1H)IF=nVD$H<#GJ0+#hp#Oez{@PmR)q~#8iPzRkmp?Q%_@YFiG!8h?D{1Vj z+xSmipdg`hhtSy0^5XDG*p-135(dI9h!?g4BDh0H{yMD3V@Q<1Z_~f)Sj^H%yeJ0c zETz4UR%S%niOu5Co3qts$NAOSRSM2{qEOF;;95J1o@+e>8N6-^10i^-B4XWw(=|^* zB!1vKsD~_~Gjt4mdve&k2`A^z0HbBcj!zNp2%(|qit$BM;o{6a)JQ%IHUhi>|L=Fh?RMd z6~N_Q{zS;tfrHcf93(EAXRqtU{w#Z zH4{xgWfo%7i#U=EDPTb-@Tauq)U1;&=a1zzbJ1zBiNYCp=DWF{d<)C zG~)Xgb*;NrlYMv5@*A(P(<%Wl277zUlOkWhtAW*OlZF*z*1k8ZzI(mm+w9Gz)r~U3 zNXtdu5EXUn&VrpoE-H})C6WYW{x5HrL(#mNaifuxna1FW_Doh_Xj$jz zx@oLIdDbOOUvM}>Z+#-{l1WO`CYB0b;!L#BIu&~%)#4@OZF8D48Ep#3a!9|&#Z~U( zCNi_ntoIbnvkS>}!>^z4-z4^4bn`-P5w7XfRY+oe%llY$?H#A8Kd&XI%E1>xHIu=T zFwi6oYj~2NyieDs5>#s#>|7SF*=ED>V}}i@5X~P=tQIi+M-Y@xt0^$8iMU^Gtd$Hg zWpht32fj@{l_tayO)^`S$|86kCIt|uVWVUv($>#L`J22(pJHX;OYby&_v{Qptlwjt zJBTcX(yRQg#v_B{Q*~DXZDXR*$ehtK6V7zHX-;q728TT~YNF_Ed#>q>{U*b#}1Eh0#rsH<1a)R-%Voe?DYU4KQCIWQKn$97`>-U`FS0q@%`#_-~3 z--|&(wPfCwddiTF__-sj!Aml$*(;PNqyCiDQz@;c3k;q-ai zLeUhC&)wV#{d&!QrxaEJ(2-e=JJKRr56YYB7GGbqt>sDfYIrt{Q>7y|pLuDTBxVpk zd$I*b27R)|gv@+GEO&NIv;|uM)l4<8?%T_)47L{=D6uMjYi$Q$(usfMDejb`cmM(V zRk>yYWGGd5YxhKtc6FDq7+O_1j=F>;2|ocxuBLm<;PqbyfF4}(`nZfe+rMCTic~sK zDuX;C!8RHaQ6GEefRy=y+$mwphNk36$O%f6+VI|fI=SA;TC)MsDS%5oj{I@foI|n2 zzY}7Mp4^{xEu$1Cb5Eoo6HQO-0&_^fGWxE#1EtY^LE1IkI zIfow8W>BQz2G3ytkSIG;m0+w|%PbNJJ{sO9p*CcVL=*iOzHKNEpK(}fidZp*?F)l7 z7Nd12RVw6PDCmOxAhOlkfT)aDhYE*ZAowXdSf0FD%gZQvLCZFVK|$jaq=l;rn!tQy zowSntbvl=v3YVPvn28g6^laWIu9{#H6pigw#+LCsBdDL~)cZ6rU z_X^25NW-+XHrL?N6tU*^dyMd-iS5|Ow7#J920HAXmP^RmeLEc)aaV)I5z~?R;)DDrIn_L&km)$ZqJ#L+~JiUw2}%<5j(Zwb~R^$MB5e%u^?Nfv-dari3H2} zj`Mo>5N4Z<#Rco$+2Qj|d5kX_L9Q31Y)DwFF9+|(YI@*|1;^hwhiRhnOoIEgVDrgz zOi59oXTe;SBt^>F6RQ=mmz!m4$zYFB^cYi%a&f4Yg^Nu(be@#{6FqODy$Akx@6oml zJ`UBlqKN0%>oJxK>$V&jITTXJU6AZUt`gN;M?`1gL!t+n+tzRkm6vn)bzYwxw0t!1 z0IB5kSmWX(U1gn+5{st{S|+0OQ-2ul+Tuxe_I^ls1_CdT!Tg%LQ6bIoBx}++4&HHi zu;MSKwNSNZat{7Dcd(m%jOhKK9cQVj{j0=*yc+LH{UEJx3;pD71w?j;x=fzTIpA)? z$a8unH)Br^`tmFGHiY`W069vx5`iVS7%Adg=}MJ?FH-rgM1L2kYrRJfys_miRB}%_ zie5iEX(=~Eg^t=sPEVQr%!nJVzImW8ugsE1&0oQhw!WQXJZUuHI|@>J(gU^EScu)s zg+;@lS$=KHaC=2yj%563tIRH!25RypUt>C4ic)DFU3wa0Mn395`MGul8>3%Ik Y zsUg${4Nw$2jw2#XhqUc*@bv|;J7|B-=7_UT%C*qXQPu69@zt-Ib~DeX*(%UIsAl{9MQHBpDB8=fmA?#GNp~~S z$kq6N_;1@cUqkTOs5y5A%qMi7S@>i`aO3FChQuz$reV-^yC_+TrS$2gSO2#0JH#z1 zb}GsVGw(}ZGLWtR(S|*D#d^IZfUA&dQK=^152UBr%00ZMOqS@s+NVK-)pIv3_b1A* zNldb%kYrQngy~Fvc#`n>R9Uh!VbEO5MM_m-O<>w^<%&1#wR{4sTSE|4gypWkHWNqT zj3N7ZSbohv_LAtqF14zd2pREx?D<0lmUJMO|7l{a_^n*SBcI>%3L|M7+iEOjv;&Vv z%cAbSb65xxDx%$X0B%}Lqc?;;JTOB}z8dPTHd2CNgOs;*`oWN!dEm{Wfto<~xztcc z7cu19eRt(|dn_WezI`6dMUJc`O>rwX#{yGL+2@NRvN;1yw6e{^hq8f?R*2HGm2HBQ z3^jq$**Qao!c*&LAE}W-ItDf{;j==Cog2!UNFbd*-DBDacXTV<3mNL(mVz&7;B|DV#V3Wy)mIURGXIuMl%BBr|$;X}JfW{Dx zpsU&5Xp!a{l8*RvX1V@Vt=sfQ(b@}EWgEEYUn((8TW_u7_>H0nwR9N0ajRbiv4 zQ&_ZF`OeqBXKzHZ&t~Zr9*rtoiZFpaVp$(FT|U1g-t+pn^=_btu8ZEbG>#c}87BJ}asC%N$Bwdgbk-8D$m2 zvfv1*Wr{=_iUhj=)Y9gN-^!yT9wf!m00}s;PQzrA4K@8NSe%vhG zBUkr=Ub#5y=?+ENSl2=Q;)a_bgD7k#xaoDP5sxL zeI+_Pfgd*vINPm@`;NA?wn8Rfow`^JbFo08tVw6xlz@oX_eVrTpj7Vx(|!OtuqXi~ zMorU3F=el&;D^c-gtMHY++XC5Y-roq4?BST0@;VoFAZz%r&cT&rM}`X*rzX`9a|f7 z6Pf#G{2d*g?xb*O_1^yO?0A(dH+VhFiIBM=L|?3lQIfIkjS@+h7Qb#X8^O&Y6hn2? zn!VvnVvTED5%<29?)ItZeaorpCM9K(5Wm31#vJ>+Z#wPu{d-xx9zy5&1!gzlh=UyG zCAWWk8*IfR^er$FNguu+=beCLF<00=6mh>O(`MB$8mj zS^a^*Trj8&>dX$Tb>X`_ed*?4-uV3~j=9pkyOb0SvS2J$X`{lFS;<9!FY{GGN~cQy zPA&<0E_Crm<;tWUx<5qCG}>_A?cg`9A$MYFzh6X{nvp}Th=l!tAUo*kjAl*B+E9J? zWJzeN5wkA*y11t`y@~cS;|0tq=q5+E@m)QXN(u~bMSrtC zB{^^gzB~ZE`+};tox+-u@TY1%e&URsr;pJ-R22R9x^veUg>_XsRPaXBeLA^ghJ^xu z4h!>|5-D1-eSlL&6J41iF-v_QPtSH>MJ=n~RSFe>?wKI(u^zjvA-QcSHWQ$e;`Pvr zh|i|UMuQ_~<=0XuY2!Fu*;&x326)8m&hU3au`8OG0kn0VM#1Zut!#vFG`Xl!X-~+= z=pG{nKKFgsX1Vo5Bg)+QNf@MzOq*Y!vX<;J^p?uHa+U~H&S~23E-54I#>S{eBQ=x@ zw{mFpc;X=Y( z2-m0RgZbq1F=GS1bP6CxDxi83IBwa$*(IS8M{NtfUn(5a^%Mz>LLO|}Gwk=Hp23iH zUwuc2>;FT1&BL2B!yeDcz9)=AUc{CMH3e@e;j>IV@)_!tbOMv**eo0nRz>`w7is(I zV$)A3*<@vNHxI4wnTnZsN}CHVK#Q?)X0;uccb%?hN0YVZCC*0$LV*rZrTh!BR$kIg zA;<>K9_jg^f)zetSK^yVTIq~M|7sy97j>+u)d!mCmE_w4s$%HY>O0me6|@b0p3RRL zb$6icQ6hGZ)IQjT$5e@#)pC|FeOkizB@nMa17#IKLQqHALM&@~>s1uUEwf_V>@f9;yNOJ{s$^2D}WC$yM?&_PFp!Or=HzKx8fiM=6dI zIwm*9L!VHOuBLH;$r?l|L!nOI#ZgWmdDbvGwQ3=S|*vmY1c!V2M773p&lw zuP>v(b)JtWN7zY*ekfV z`&OlA3)y;*8zNm5hrSsg&1C>}zi)El1yV|Fo!JClouN4G>VxZLp0J(2Zqz;RO>Eic z!{9cEL&;uWI$knQ!a7l*^!7d0_DE66avxXMgei1zr5T_`EnkGc+h~E%66Ehnv|fPM zd`mwgo^MC62){WS_Z{YWohNxjBX$RnZj-GXo25)^Mpk|O%5q=)Gs{X;x43#23}~FW zIjFI$twD3k4k;(IS@X+fJdYK`KaDpAJ#f3KK%ww<%LpJM%BJO>!3wZfe0#TiM%rm@M@mwXG45VO-bxoRnvL7n9{IkNk{>y-h-sbupp{^iKz%kO}%l!pCIQjEdMeiNV(dhs|Yy{yLuJPg$z zYi=VE?vIPOl~2cv5!hzhzHI#nV_P0R?SqcRbQJ5_kHT<#?8~Ev07Ey_>L^dtAGx^{ zN=B@bH=;mLMfz9MA*>IUL;?}iQwL==kZDHG=w<7avSS_Q?t-( zwteZ6ch$xAaey!xdYOmNX@;Xa{%@S$HKT>ldT%E!^&(aN3@Y)f1i7DL4AJ&z{Dsz? z=3lov2c7@^L#Z5mRHF$KMf*x+r%#Nh+0Irz`>hayz)7p-RJ3=~hcqTi^@2YZH*EM8 zBW&$8vbkq9M#8rHmT4ET!6e}?xpWR^uHIa^?A!)i8EDHO7_~mqFP;Z4)KXZqCxacD zJT%Y}h@laD=MS*>t3UnUR122>rds@8ZUqwoD<=#4e={xEI5?U9w`lSIV_K+zswCg` zlb3LVfCVAr6poywCBU60)D4Q+G{k~QiXxNl!{nl0J(oue}3+I z&-9-1n%_S9Jihbn&YtoDZ!fU!DLV+P392ACu;df)Ye0GEYwM#xfI&Y74+@nKBoM+} zL%k16K{169C^CTPT=c)+5)-yr)X0vb#lkL%4FqE4)d>h178GQp6m+0qz@PvHlm0@9 z5R?W;wdpZ{7qIaw00V{>NC>_n-t*m&XNSOvCHi*dBgH^6itlyR58O3&4J7W_|M9QEHFN+U(?`JJ*#?c-V}O^B z=vv4})IdJxXCsHeqJRPm9wj9SK!7J08N;KxtL`YQ=RRszzDvjS{t@tZ58<9ega$-{ za1JrhFZrR+riVa?eF_2j_;nxacP|MF5&+NO#j*f*3>uXDt&C$8#`#?{CXWw!2bdnz zIDiBi?9c00Pt&mDB-pF#`wjWUs|(oiHD-0a?(PTty;f2Yc?0-<2N@LLBUEHat2RI^ z;BZ5HyQT6!{DuCsudbuLnr#mJt*n4^7Xcvs4G8G%?l6oRF|_bL!w31W23vcm zW8e@$4-ESLm;z`t2L26)uV(c|zbXd_&0Vrb2ca(YZ&wN1B*yWxl#@__v4|Gg_((DW zkKc|2`UY)0a0z((I$>1^z>gC!Ru0hc2ow+pNqSo45hV!#@{FLx}ISKuB8|E&G_#@I=_85@Aa{p0$DO<9LkLe}$(1u#ottn}D zhdJR7*>MNK0OvSpKVZ8EVCwB5rEqaFm+R$T`Jv*TJ_XB{sk8d2L{}#H(rgk#|A%6O zsKf#1X@kx=C^8pedQ8eE{3RTI`ECB5d_$dBot^dIHVN!z1mg5Fn--dvKl@Ibf)z!m z71$1VDnsKw-U3{l^Ba|2i3OwlEBfKoyUZ8Map2a`4oF__m||)$FC9XDiqRG{1-0w=)8wNRn|C?iXAA{C(^q(> z^?;?7|4zU zfPSnP>?>l#k9TWMvl6 z>xk69s?R37#I!#4=mGm%cw0Jrx%gF^Cr3yYC7cuu5axL0WHtTZK-V5K>HZ7m>nOZN zY(@XBta6R7<9%HNC85k?$XhC;01=ub!t38U4*mS!L4$(C3v6^x@y%qwz`Np*0A2WOsxY@z&2@HID6grpaQH*86dB_in*2DUs&0FUW+2)m@l3L4)1%-@9iC1uoDOxSGei5xwsvS^&*86rAFPZ&r?jpwE-I+g zUxj>-LL991y};#)SzQ?MX5&=0`Ue_PureI_*a>I|QVm%IS<0L(E7K5t4wXr~DnB2@ zt250ma^DRnedz26k6f{>)n#HYAm+(6^&ui6{{Ho)CPHK{rYS5#o2Dgq(NR1en%U+B z=bovlu?!XAge>DTCxGKj0}MU2x?7oYtVb?F@|*iTYAz67jxPDP%J7w#yWp5BYs9fI zhi{b^A$`Ec$|CbSJT<_#l_JE7ubM`*YSqIb;>8s$VR1Kf$g;b~L--bo zr3jQA?@9H0Ol>8#oytUETh})+J6@lTvqsPa?Ppf6(giN3OAAETMIXHnq>FJf zQI^#Mo33d|`m}Fug}A}3dioFUpZ)W&@G@fdK;5oa$Sd8ErrSvzatvA@?U=21EJ-%! zF5fgoS$WFPSr+70qW*&g{#}?|~{=jO-EK zL5}ehiVCt|$jh6)FE)+vD1_L{jM>oXV>FoOcC;X#B4JASZO-2O9k^2Is2Y@^_W&hY z*pXTLeX{byTYo!gm)lv_#p)P^2-=v1_Q9uQ+nVeHc{}lHemSQ zu8-kZ+oBJejl4R?GV2O6ag~ints5tkve$n3D8J0*JaO5q=p&d9tF$86BpDIYZLAfJ4;3oAe{3Zl&Kg`k6^6msoMbgET;aR z&z8LM24CY>mt=O6ZXwX z{oCNuSjT~_NgqyXidV}Ktqgvm~AIJ82KA8bwzAhfGG>_Df@aa#xZtgZ9E z7(0h9QGhPXrfu8yOWU?>+qP}nwr$&ZY1?*Yz16*{y9VE&hVcg?V%>euK3acW?aHB# zTXpmyA_vIXn*{Ezt#WQg%6F5Q)?tnAEx4!IsaCqJ>|?!{TaMY&>On_rf@5PBfhyq)EH^`LtPSKKQva+IFH^=W#D^N75;RemS<{jDJ3!lbqEknfhn07xBQR zG*2H`P(6o2Y_=EOfr;T{Y@&yc<)~N+;=;0}?fi^q_Lq6sED&N!>7W?< zRE9%^yK)k&wkmx&QFy#icqnr#rh4BCjbJ#u`3SykfJs|?LJ_Zrz?+1>;N=SPH<(Hk zG?x+Re3(*}#}X>pZx*q2sx)U*K&M|{xg4&68ljG0(x*So?8MS>NxS3AYs~xc^H8ER zgBm}9C&r8qZhISzq_@yI_TEn_%FYEo{$+B2KldxpC{jbc8o*?$D%748Q5$}j6hxiz z1Ff_zhboueAaj~Zmj*NxUXG>?rCwQ@cNg3Yr6{#H_6sMiPw3v zV90p?RqO>m^6))s?RdBnT=L5+Dnr_;xl{g2?lErW2{&YV)oY)Y!3g~In*KRn>Iy7q z#&UD*bZ>?$Ra&2fx=<>%F>lAng>uu$OK&gr6{6B6(a(=b=Ryq)EQTbPYn=jR~Q0Vcof1mYnDI5u4=i>V_Ii%akVJ9ZaV&_ zjMKVZBbQEAcS)B@u1`;MO{zHZlSWwlJAwMa8pY^#yKITxqTg$If}u+hsZ-ven|FQp>#A-m$1fn2zMZjQH(^(Q zkx5_#BHMBM@wcU7$qM-G%0BH(n2SG|34zN=>fpDQ+uSwVk@p5{30^3em@UN1)X{~J zX`rMV<)@U>R%8@%34^HAsDyLPM5jz~sHt098!f1^S)D!YWlOter%wbk4&xUPjw6dUL6(km>lb)HIW*-5J48 zVi=vuOlXTxjS8Ra4V)e$`&micr3+Z}h=fOuRsxl!Nh_**Vc~L+IY=ySdOqCZctgBc z-C=d!LAFA7fgdw(Y^=UXlZyLXA|iul z$Upc>$PFf1WtOqdzI>T2f!!)XD|3;xqWaN5!8xFzc==6p_Mo{yYTps+UyaaJDO4r% zkBlD=4Xr;y0UTk395T+zBqv>pKTd>kv$|%a-5uSja9?;8x5~E@E>Z@usw>cvAiXKL zV5%zLXe~Q`y05+VlRIXp-(^v3KCO+?qKaR1syy4S^5ExKksX)Ni&td*dM~WZYrE*E z(?*+4(gayAy^21;e1b}x0z)Y??IO&hTHr`M?Wr3s)Wbcg?ppGAM0}RA^S>sFdLuwb zrQejO!}3jZqk@gV1meGPX#9jkgH;+gu#66aD`ab9ya$NeJonK7`Lek;g&Jpzu;y>X zVoYBNyz9i)ga)2Oi$QdlhjpsXsc%auPFrM6+Z>H+sQ(qlMSKC4O-2SAw+L^cF9AV(1981bQHX+@ z9Hof$-mbxuqddSo9CawKHKmsmj00{`F^XzU7+uuKS)9wSW;?%Tr|eeA6?I~^nOsC7 zgrAvSV@fx5|IAf-IijZl_$r(scZdaVtK=b(s?5BiW?&_8>b*+(PblKo~TZksZKKtqrFi zF?87il<71ShTsO zRAs_EXI+rr8|`^W?plGp-oRx-wR7u4a9WDZ zpM$wt)&dEv)wF5nZB&kTI!4KD$(38m3k$u4?ls@m&##74RQCu&uO48{vNl&bU8)Xk z_~WVxRc(_Np5`GUvRs(EED!wq6W(ZSVOlNss%tnyR|mKEb*M-ifd>H;y6r{=Ma9q?+CGBf3Ur2>7fRGT+(?&7L? zYJqw&;*C19=zTOs?)oW}Er1w_HD=?+kMsvI1z3TJ$qI~i!6zx_FneKkSV75?4Gy~? zvbDArXU`#pvN@#Vm|{jYBy7w=YG+161@ze5;HyQp#v$m3s8?({17F=X_7BFLDssQm0_IYaZ(qMMXyV2oQGdY+ z^9i$$ZsP9^(b)^dr=_?Dw8MA2A!#6N-f3p3T?;ayS3&8y_Bf=%xa{50<43vxJ+aXB zzKfr?qv2Rw*QVvd8&qAal_J+ApQB`|cNA=$jUVPZxsBZL1Ku5Nw!Wpl9sh~R(COee zYxH(4p2b&=bbi1u%X0Agb)p4#TyJuL?>Xd)4@U&veyPV++r?}__Cb$6-O;f15$U~r zj9ZD@s%DYbU!F+k_4yo>h1YVkBFL+w<+u>3cW#~bMx~+5BpH&lFr7#t(571|!@b~w z(pyN=P(F0hVmiIbUkZ3B>AAK50NxJV08BD7z6-LuC$RlL!96_uBNkB9nfTWV)oMOU zi;J_m=N-p@SI*BnL1myZlDstKiSO}A|&H1D*qZG#wxA@I9zAzU+hy5Z;) z%9we3=^t*AH_~q6$i8_q^F`qp(xx~!eAX&vX+26M>~@hElx8cm5#wGLWi8q5!TL0-8e?KXEu>#kOd9pWZWjIp!GKw9l z?Z)~78#;Us3u?`xsUh<^Jec}>wOvZjSVMYA55dxqBP>-%O`tXO8_k#2vIh<{Dr>*l zt{d{ud6{i?Kq;7}PlKxG$yGS`qtK?ekv`0_UhmDSA6t!AV{R{s+Zp<;K*EVUj9SY64 ziT?XQJ*2&oKVfY)3PkkCb?YjMvQu^|$jQ0o_c^t=B3JkM7Jep&gM6$v+(wYN@y+gp zG<8bn`?mD4HZ)sz;}hTgN$DKhnqtXM{k+lV$a45jOBaV|m`j{L4_mDX+D`>~rK}9R z!0I^AuoeH>s-hiqTC=Wlr5iT6aW0%#gr@Y#DA&bs(#W8X-YQ{*cXJM8XoS%1T-uLC zIlS~rPvRrmOW@L&3Zbx5!CYh8n#8(E1i3j@^%DCmZc%IPWw2hU;nz*+uTgTz#g9{ z1$jiy%l#_HqE1YP+*%4nnZUl!cXgofN{abJLrR*$EM6#D0b=}-}A&j z_`JKqz0y@<_SbgOkT|vCoGqpIxR~p|cC#ZRb5|0wW?w&iE#0OlsD7E_CVb;oJT_A0Z!%+yiNx*Gy#++n2#< z8rqw!eU!Mx->GMgRdje^Zj8d;JbLB89v;E#W7aaZ;w!PJUq$Bda2WcP)gz4ZVdT|2 zWq+&MT6)GE)8Xi@@E=g?n7M~kRzC7dlHn-(OFdBX3kT{l13L0?WdM%&YdD`YEihyEtAn%d}+= zOZ+`>^w|PVwR=3NSM2X!YB=7v1;Bl6lo|;5Li^5Sl~}QCH0zo)2VIBt1v3r(>zw!~ zG=O*a7cp9A`0X9YCtJ&QsReHCJ{TD`cHS;>Y-%&Q^FR^i6rU$0?WxkbCI<9m#@6GH zuXwN;O)g1cagFWLgR=Fuo*AN8ua77+CJ&?I_p}erwwAPaT8E;K_v3x~U18+?=>S}A z+2aViDU$|GImyCZ1zRwOQFP5Ld{S`1h-fA&X+q?+2?poOx(4TSPVIwYQxTAz>WAG* z8*5yQ=^xTS5S`r1!*W8KcUtjLo5a1c8V)+KkbH+NbddXluKSU(Es3e)V~fqxe|AWt zO^vVQSFOgOSd=06IuYxVkfwQYn8`_Wu-NTzs3O4(vnpY%i&KXJs_GO8vfB}!UV#my zR^CYQ08R?rhggK%phPo9tU+RYE?va^n!ougD4G=F=3!@Y7#~1Hjw>&q;5<199j!@WKv zPhC7r?sD11_OQU`rIj8to;Kx%XrBWM4KwHN!{AB2)Bic?S7lbDg+q#&Su2z5ciSGc z7Wo|YSIP#LQ$btqztD^0Y(f4LV`Ke~jE#-szp2{)VQeh_efpm^Ggfx?KmTjSrUt5v zeAQK^#9ypnFnsp+OtiBr8DSKIApmyNKgL!-kY6zVA9YJWf($}9Ph~zsljlE>?d#nA z-Eq3%;WG2uE%Tdu^xAO(J7Qo(R&@~M9Ar*_Xl76cApw_XVn_k<=RY7Kh{pg$FozTC z8v2P>1fVsbuwzFeeBFJrq`&})NvaTJz-9Y%g5Mbu29O_4Oq}fVV>=nG}i8gV+NX>jIKC*kMSf zpN71Hrt3#I0Q`iN4hDi?a0~JJC1e%iEczy(zyKh(4-+zgu*(jDAA}4A+H(Y+c76gB z&1D$IAN}ydfB^ilh6SMcXWiP$+vx)uKn@;ZC*RN-#=iN1E;y@WXeYBG z$X<@e!(#y1$U0E-xv)opiM-@geR@^jMiA!{?#DMXV;`J&M+YItms5ZS*_r|`E&3?~ zl@-2^n+6R96A$Dku)x#+n1%)z;@1)J17#cY9Q36g=o@bT2m<0x$OSON0Z~WT!VLW^ zfVc~N8w4;!behDFO%rl(nb8+JkTkAg1_%JLwCfwk$EKtSzN~!@k?4Qc)oRLm;351A>T>2n5ituV&}Ra)bDA zOYXb>4f$?c#sK=40~xM zkU&6r1^w|$`fZ!~9evkR_<`T}HRH+Ty}9XY@$Osx6@tF^?=t#bK2*O78np=qL~271 z|7C6o{B9TqV<2yj8}qYtnMc?%Eho_4`n4t6(n5|6;J_SOkYD42cv^$8-{0PcNdL2l z{d1WC2oWTZ|2x0$3VRXiCE4we^idPIuX?^q$$}tXyi}KioRkd2FHZrH3dH8VC4+B+a_Kub6%=XIZ&Ee(H3-O5uEtxoTx{{hvc4ZxeoJNH zQ&%_Zv#`h2`JC|0t>07<@Z@_*oRr1~Ja?5OBbKVCC=Ji#3Xf`2$?fNs^c7nFUX#-A zRL4KXz&42X1*fCmn-&Mt;y}3Fu&YHo{pfbwgkMOWCZlRu{6sM~DHeiEb6_(hITipK z%Yi(dO=7;EWel|T!oYkewmVjP46D<4Nd~P5VnZ5^4z5lgL7FT5Hm8;u<>A(7-=xm8 zOTyjxVh~Ku??S7SWj}wk=?_wEfPJ;c8(@yM_7dNR+7-=%%gCu4mlP{{2hZk+LaYWO$-|} zh>az=d{AQULA&T4V&d`Y)4_H$HX>?jp$5&D0f|A`mtZr6ubKVcoa~_PMSIJh>vI%( zH{x@UXF@XO3s4Q+1e4qQiu+{TBuZ71=2}BuE?)7=>oUhUk{Q3YIC>S7s*F`vykYM7 zAPKK&<-&FTT0<*pJE-~c*qS%|b3iy#(iXL+XJYoXGoNU>1l4M;s z#+c44F78ZBy}tdAm${nu!c!)To3GtWk88Uc3syQu+ak>i;Nefh##!$iO6k8=S}Pf5 zggjx}s4)b@#<7~sGK0p(C>|}H@c4Fa3^l69;Rjz6WIr4S4|raBMlaUU4JF5{ay{0! zfwTcYF@%yi$=IT9(+-%th7;Vteo9XlCVeQ?d!h}{0Rtq{9ACdT2V0vC#D6QyPp>JJ zW)d5M3sndfVMR~Ds9shfKAdUUK9{kNGXVisu*Y!*BvBq7goMZ*`??l?3I|AD-EElr zACJ~PzqErrpDP9bfvN<&BuOwv*oT&K#(v)cQ^2RCQ$j(D$-|VbU*5CAYjtb}Qx_c+|VwP!U~}Q!;-o zzGG|$A+1hhO{Ii&X3A8ijbrmvx>d>LS7@#_!d`-HB!b;xJCoo2$%jdG3I0*ein}2GO$T<&v%o_NG=8+W_M$*w!_RmS?Pbjf}<6fl@ z++7N1pdgS`p?OldQ^64MxX{yDloQSIE3lX*14=w(?c{$oQ^T}If4>tb1r(=F6WnC= z7u~{oH}`S-Oi{Vb;h@i@6@WxA46o$Ti6=`Uf+c-IUV%G-`N($^hIPWes?ecE-NTFa zPE=-`+V@iT>;`8@Su5L6UU4H{`BWzm-dCiXA*tNpebl^WQLj=tSym+L>3Oa7ZGLKH;&gKVPo2OyUSB+aa1{ z;H#O07iP0p4UMIpmWpxH=1^CC!fy1mG4>*$vR1t3D3^v#Cqk-{(N)Qp&EF@YCpsbA zvP6mChqteOE$^VDymSQiuaTr(?=ka|ir5y4_k0-;YXYPiBAj-#3kcVn+RFA2Ff&QX zTxzz)rYtrlE0js_#O~C7*|Xx<1zHO2bgTW=KUz8s+Ye7Ke8oAEuws4tTBF(YDkiT4uHz zt=A*%V9n?LbZKUjsB8LBMd^0XKD#yNAj{n-I5{JkVxoaUZ>)Z9)QarkhM~$jx@B7W zyt_tZQV8rr82^bJU$F6`_`O9~^!QWjXzOzZ{v6`_PW~ENWSJV4Of+Y7A0f#~yktLR z`Odbt|G();J+TU6vgU$M&8MKNi$^Q5MHr#*)ff*boPt|JWEo~%pRKcaqiflUOQ*Kx zLD^G06D@T7620-%+0g~8fDL?8TlC*KN6DhG#K6GmB{pA%>EGg{nT`V9$+jJMQjDZ+ zTK6m1EW?P&`%Ts!dSaeA1wQpC=@(fG16ScPT}V}0W*SCQzMGAu-s?p!{>hRL9QN`4 zR2nBFon)}z?6i%v?(CVhz*+S*+2~CfJCF~WYJ=aRt)*fml zY+tDflJJ>7l1=@g=0P|4)4%>}OnGBhsJZ?kz-*h3=gzHV?h*S4;7f?OBN5tVHoMAR zFBV#@8dcei_?1#MV*hp|>PWDqb_uN+U(r2!HLSDQc0$#zePmg^HGrQnulTRub(bdU zo0dIV)p2dCTAPL{lGJ4y52SDtPi15i4_wBWvW&<7-Y7EOB{CqGJpDoAL&1mAQ3L&h zLvp48CVOlrD)prfP$6*R;Y+vvbd#iTuIrVN)FAn7qJKDIGJp#NxnI*D^BsD;LOlm= zxpRZqPw95*#!Pz&ucW@6qpEHRQM8*sd%=;Gzh(@>A9aMQX)6cbMrbdeJ?2^|;sQ1UP8D4R@@*%?{d z$ujJMxT4(R7E#NhkmgUw(qt?$bXXLXM?$QpXB(F0tydq&!ew(?z4T05ize+`7Mb{ionkz}Gs zzhIST*W8q{?#iCu416bqSK0xYv?pu0@K?n+NWn&0K%j$sf@3OqgzD5g zc?^J_X@lpCOuiKe!Ca`JKj6{t57SM#(M0m{nd#z2nJco4FiM?8bP2A;BAr8d7eYe#+tKqrU@h;D&PE;*_?uU{)DhTd! zn0IC|F}=QV#H_c)OivHNWU&0BRtJ%EV;#)0(;G44>FO5{)&E%oxQpzk;=#9R%Z95B zo_=C$Z))l8O%x(s4vHS0rBrMT;JWp#Hz}e{hr_^&Qr`3)h>cRotg>4x%)dq0B4yD> zqEc`Ekf1|4KWs0Lu=zg3X0?@;OCDFfI~XlJ|2V>!9d-$gjUf#nxwci1YpN-3_-%R9 zXwh2L-dS?rek1q54wfnOcr-?{astN1$fXde6O&ZP_~dhYa~((Tj`2Gk_i{8pf4+M> zcmZA>oMIH_r@inexDt(Vr>p$H*?1ISOv5yl#NyKpy)++iI#N4bEA?MZ%|4g5ToEuP z!tn*ir`+rE`n3Ea2R^-7ze@-#VK^rr_g{b0M*=6e7V(nSR9Y0@w!+iAEqixCekZq- zjo%i~|BJCaMyCHcyIyJtUtI#n8l`0I!NBT{{Id}JF%HyFYX5VAI8YK=DxJxFk?`u` zlU@#wBq75$S)Nqv+^l1nfR)t!3SEZy980~nyV0rUGcV^5f@Gb`5viDV3EE+!ZmL65 zp7eR7B;^1(Tgx;>BoRUFrVHPn$E17cG$7fTHFCXc_k%gVBP40@Z5h8!l1kMJnfy3- zKF%~dDWc9d(ZD|UI3|ZyeO=85nHObIfwGQd-DXzbq)5L%5`v}_QCJ=F*ZX|34C3EL znq|u=sWrF+@+#ZFS3aHeUNPoOed-N(midmOeGnAW*Eg_icQ*?5@C9dw|? z5ZF@G;PK!1i?JTGy2^AGDp}^N262!1v8eehuSw{pq9(l2A<63OZ*3ln?Xni-r-+lp zP8^`>F~TWna#QIxNm$k54r6z+wqPkqxrYXW@TIm!IW#yqyckK=6-$xT40`G4R}sz7 zcs$*rH-&@-TJsP!Gt(i<=6%B1cOzofy@W=~#BM!J8S4I4Jxe_ppY1Ivw2zlJKWe!y{Fh2lQOv_rP|E^^{K4p5j(H+ zTD%cDr|D&rl3R@CUviq&yQtDooW7q+Na-yk8z6Sm-L5OX6#e!Jc_I=#c7*B9uV)lA zz*%Vz#;MJ=MpcbbfQKbwdnXR-S4iHKEGh2_Yf4?N<8esvETC)!-|G%*S<^`y~| zKiziLq)PAtbu_k!ZRn#+C`KZq5gAi1dMYpg$X0y2l)kHX-Tl3_? z|5OcANKeN(>IhWwBLmKWJJD1%zv;E%u=e;)-l>v59*;WrpFmv`Rg;<7uk z;S+uucKcOH?`+Q!*(i`XJxeC2nl}~sKEh@-H7)QJWF(%nf!sUru{Gqh*=cffu_S3O zT*IQnI!uhH9nM2_l>vc5{h(^S0;>@-YpNPaHZwEAExwV*hGwqA;U)17);vol1YHCt zAkDAXOHn0m@>vmuBS%$ateBzVqRy8hcV6fI)p`-sHOfF$VrWR}i0=lUTZkZYCiu?%&kOtndSu(Us-zIP$k=omGf6hnQQqK#q0j8@iL&(Q^ zkuq-SMuv)ad7NlHZ`=rxOEn4L1)n)sd6h97lCwbCRZ|QT`ds9=EAcUjmn;vY;`;~L zlbYl%5ghBi)`$)8OQ|evFH}LEy7#CI7q8MD4m3I7yJ*A5ttBCYyo$M?+GiL>DU?~8 zlt&_Bj1RJ}RKOdHe0Ib@KaDVuo(ydUY>7 z%&|aWfZDzn<@F6*4`sW%l8`0Eizr7wvu=F}y4&&LD+$^a>B>tmOHrB^a z^oH4-o6{9GG7>5)IPutW8_0wd{XM!iCYrj@<;eQkPS_Hqw`ORR_0_vY)8tAltYce3 zM8#tWOHLYvs`9mRbi+9zwbNF+lV@FuE5!I1792b`kiCY5;zRs=Q|k8~*7v)2OlpQa zQ2=N8JibZI*4XlxOF!r~-(+7a-&1f8dc8D^hOR`!>lY%sksCosp(ZWhl%B^g3Z zH$B28-Jy1Ee;>;PvyokwV@esNRL?BiY3?BL#n)Fvc{J5$yvy%7lmyze)w`-7Y!^N> z{2r&7j|{t_e$yS;DtHiKUulL@{394*)pd84Z%Av>{1%k((&nvJlcp)J%+#P=-RdvK zvAt0wl9LNW$jyei2XNxNa?5q~)VO!OwY52_UY+WRXzMfZN3yM~Z(gl-rv;fO;fnF4 zEAFF8(zPNwe2x;eSvaBP?3YRoabc>kJOeMVV+2)YnTK~cn7BkspI;wrkJFi6weig^mBfnGTz|6U`D{z5rR_P#;Luy=h%+v1 zJaoN4xMG!1Jet(PL~_X>W|D``FO|wwwDKCfLSAoBPHD?Icg?n+JLN0raiP#|#B&(+ z;{#eg&l@BDu2gf~wx?^E4KAWA`!wJje>T|b%l;s%>UCr;5unv765gKMpJFs)NHL$f~#K>hbNF0x6 zT`&wChfkNYCpo43xms0w(UVM(OtTMQ$xdg4m#WE7#PHW(@?~0~cbLd{*KsSK^t958 zxh^W&0;iT14j6hRgiZRM*vjvQmiF+1o!X7`2B*&KISjUQyxoFT!I>KZ9umTjcrd{N z{Zna=-p#>($f_#Iy3G^lUMD3QV_MQBbQZ;vum$t|19b(LpM#|wb9+|R3$DX~#xugv zWu(pDy9>|F82sYtrM>I33f2GE)|MOGOxS!g&^_O0t1JCvs+M`OTu*FLL7})*FN!5R zQ-f={d1adZwfjL&UE=HePhgGxKY=x7j{gDH{sFZA*BbOc!5SMo$Ny~!`d^0EkZ-y~ z`3;@hqy;l=n8n@LkQ9xq84QE|I40*O`xDTLLm>rH00Au$5GW!cNlH>sLLvSC{F>RR z_3mr;eb3x0@2%UY-^#L}^bG1X(3)sby&-}_J&^p+xHcLDm{erY01|+&uN28D^ba`H zULWAt8{q;)$gk;Ie}92GcPZq^!FKdKMSgD|Isy@7@Hhp(F>1elJ_rWQZyGUH5x{aV z7=cc}zvc}eW~dwRy*2(%5Tkh88}%{x-pe2RQTluNkR z(L9JCPe9sv1`-_XuR4^#$Q$+QI3NfV3=9gm=NDu#qpjo+;eY_~YOZ;l8}KoZew~26 zGoYA)ox9!PVZbkbDYxQX{CZHV0N7x|J$~-Jkl+CY-!}liWNIAX;XK&pc_xs|w|)gb zcI=;h0;sP?OMe81@!j*E=${mbh!0$tkb(IfUU_8(q+>8)f}TBoWE&v|YXnsk2$7B- z$6(L*g8Tb<0E$KEi$J$G9d?xR8dI>~gZJ-=S@=+a5B=}q?|9ulj6mO#0lh}FNfqGh zYgjRZZ-BmwC1JxohOZj%Am6qXA#WnoeviCA@JfN?j zj)4Y#3kD1tYIv|gpMX1pbgnZs$0>dMH#_1Z^yoT1nA4yaK%zU8Jp*wNoL}JncLCr% zewtByywK0vP`_IM1c-T5$RQw|JzH^Z=QKCM`UmHa=F>pW!L!?IjKads-2tWz(0Fwvk2EVfpY`=Z& zzoIe)<9t@Yzex)4A^gC{zxn=sU47;tUlou8d}AUIZ@0+N3+}i>0fE2cJ9sp(q5FLV zzjpV(aPPa!ztmH|grC3FVw<~Dmu)I{Y43jO1v}z(dwkdKsGmmn$OgfqbD$S|IyL)# zFb#-XsOPued8#}#D14Zf6l`_>f@|kxF))E$nM4f?uY4d+YVddGJ@FLnlpFBx|KM7r zK>yxv{k|FONra!|*ImwsP2i!}`L38{fxh{g9uqksEpV_Q!@NE~@BLd2GXnSkd>J+O zSzB!YfddLw6g=R;c?ck)In16KA0dA{*%mbPcgPQz@g2n08vbr*AA$uW0Yt#dKX0k{ z1hBvx_)T693Bu9g@$IV|2ru|5F7WRds2(o_cK8puFdPI_fYA@Yj|jv`+`wMgSKHp5 z_3y^7ufpCP0Xqx>Q%I;z-}U|1OI493ODuoGib09PkIJPr;h!y-(v{!fOlF}o3*BX) z6M0&r{HT|q$ke@n3z}C<+op3+3u~uLjVX&WxiaO)h848_CyK|*1hFhjmmck-Y{S$_ zs{*s$0ybL@Bo-aZwNv`1=d>bLT2pqYs|Co)%bIL2Y^D~=))(bb{{ypQt_G4S;ZLnN z^0z2$JlV#Fc>R&~@!<2NEJ}zuzn5ziKz!yAie8}Ai2>5|q!`VhwCHC%f$bHU64T#covK=5CtHVHOm>C%OkxvWs>d_;ep6mXR zJu^URU-%esi;DN2d(1T7$V`$np51&5VE>Dn%bYxEuzpwUqMa%4t9f#yV;c(hVnA2O z_&_puGu;vlb9znEbus#6JOAp1_N0uGF(^cZ`AmXXFTW^vUbWg|d)B&~v)m-{!p1VE z!y_PG;tkZN=bNKxNH>apJoS#FPy2k^H+n`ELZmYPQbIY*ZJjd&erGA zR)W@Ug^CGjFxlq2qFs;Jet~Ut`zFWQJ>!ORKchotamN+za)jM0lMTy?e_tuJ(R8zM zBj&n6DrZ&>DA8ZNNJrv6?sBV!Y7Yy8={NQJZURKcnS0xganlJVp?|gW^lcIud55Q> zf89a!HT7**7*7SuiLxW);{4tQ-R^rU@a%HZ5q&nsM`H-)3@&Q(cW77M)sUS$U|gX; z7;h4~R;HRHZ!DWypoi=vP|P3$LYgM0&LMnge2{z!{dx zE(qIoUkpJ476%oAs7dyx#B#ua+HJ=_;Z)WPX72Q{rL{s$Vm-0@Sd$*CG$=VD@*k*esQ! z7mKpr&3uRq5HJ2DNgU^E#MDl{$ejNxVXM znG%GT4yvFuJ{;s_U-kNQGQT~Nd6mc}K`G&@fQ5QZJttD=-Z$S98Ro%pJk-65%M|0* zEOBJ!Y!(x->dEuO^4eHF1hwq!S&8MjVF75&n6n9 zvPSXIEY1}Fxh89w6${Hx^tE_Dg~u9<=Z!1am5_su8}!&|1~$Xg_L?})#(5aq!)!O4 zf+=g~7-k^vTDsG<%$RP0!~XN4GcEbmv>#1;ET_V}rMNck?5V;~@>0OqalFj&9V&R& zU(2|<48Og8L6i>pjPmzG+qd8-XBL3pcJ*KdT@Iz6-H%nMKjr2?p@q8G3D1CCPr^#f zB@ikg3?Fn3L)}IS@?%?JkMa`lF~$o`iVEcCX$+)^C)q4mOT)Eis|6O*;WfUZ9GyDJ zF4~stbTI< ze_|bdev^4}%wMW~>{Pz2x-14Q3^ymmKP!_%VJdIGTG~M)X=n^wv$(&}EmJS1Q;I{Cn$f|wxUneia}g9P zsyk-}^P~-Q%(yzqTkt%jG*9=lfRD||tr{JZwQSvXMwfjaLu7tzLftT%AIhIHS{SB{ zgzXco-StPH)P}9SF3yR06?`8Q!Jm7vu?vM7Z^4R<=X5+*$@CP`xd35R5737eY+%MkzUoYB}5|4$dw9vTS95 z3wNPQ_`L_31^g%<*W#%q(=Nr4GJ#WC6=!j~L-l-n@3^PJ)xpS3=rN(h@pm&;7NNDS zLI%5}hShz?ixGB`JhHK9yA}>d_(*iP$CXBS%h{0IElL%ey|i9j>sbG;q)f$hNu>p6 zP{y-;dz?OT#KPTC`{aMq)T1dMliIrI%qvi;Qd#t_zY5L^^K3!E(I`V8fa)fL0>tP8 z1KjW6vmt*6yLPIh(MTqva}42;%RGdXk|^uMVCZ+5!w_m_(ROF-f8fg1R7BWdiek4o zUUehno_5kd%4r!fC?@V22riT2J78hy*QOc|4c`^}5Gv|e@44qZbW$yVB48Ze83Hk` z#Sblk0!iT+1Gd&8LQEl%EB=-W%^E?*zNR*n-{Ib0SDNo#zX-%e&r6o=P{VjtLsQbv z@rZ#`wa|A1mZNg)f8}Mjf+UV{AJ~HI=aJGbm*r{WPHx~oWTknD&@pyD{0XIE0?zn$ zJZUPmUIJ)3nM*y)wCk>tgFoS%*DMn)-E*jy1Fd|x)}j5>;$dPbBU;jK%&^O*(46*- z4-w9K9af5|Ct_K+czsM3goak|7Dl3zX6tm?tnTQ$U1iF=eZS?g-?DUcC!`+0R@%nv zdIdosnQGrKFBsV(($PvZNaW+`w0ag50M)sc(h#$j|wW(%Az6g@@3|_U{G!ZrSl92|J3N9qhBRC2u+5G$5WOkJd2RW=w#^{s{Ul;;6r8Cx%S^!fpdQ)2>4PY1c$XZ5dVK<8?S1<2>=@)n<}q~s0ISw)lBAS^rZ;_v zv4_!9kTZHhn?}DJ)jag7s2+m%_>ngx#mY;UXbVA&w&a=g6zUMKtqmE~SA}8lT8Jq4 zee|gi8e}cB3T1gXt1+s{)q+$b{k2a<^95Ds#PVlj{Jmu7pzMSmL@UmIm$qM1c@>nY0(ylwzioe&r-})Vw$LsE0*Rp6*VOPaPsO+t`RS8a; z(J^P!{e+ne#aDnF$Jq@+((mtKN=TNlQ9XwEX%z$aFF(+qKZx2}4)j&Q6vhR^51GC1 zwV}T(4@~id`nIY z38^NEb=CxqQISf*UN>3npnU^j*9TFrt4++yO?js^*K|szZ$s=e=23FwGf9|JimSBv z0uPt?fP7T9|1=ixPE2jcNOe|mx(gYeUn+amF;e>;b|MkfOK43pR}fVHS|9?3CJOc1<^j6*5Nfwr%w-(FyCj(6c#3r0j9a)H4CbGI^49$=U?{|X{UP1zKaUuz@sER z(|3hkG*ThQTVURdxuF0)Ot`@iw-Rp^h!nVpQ^~Us(iiO;fDj~k?>$~r1u#y& zM-x|<3{wMxOY7#}8Cdzr>o)A%?BhDybSyu3lT88)NIu4cONq!|+p?G}iQ(qmZoih=ODQk}}C z+uSUZNM?;~uD7>#tekQIX(VOAoN-8X<3>$v9qL0LkF1HveW&|R*uvCZc(zj;`(`Nv zz|xp2=IPjhdaZn82W2P5uwC-IZk%55Gu+bDn;epG0Hf?^VMCKc|qq zi&j%K1F^ocr#pZ6o*X3|XvFoS_RmotIF~UAEn1=2HAs!@2sLTx23`KB9y8Dw3ASOB zyUFWp#04rTGCRFxz*&3R1Ok6oVoyz@Ig!<{iuQZZ2dfmT8bel&2(RaXos(;FZ>cQE zZ#q?&5y3Yi`uFcn(xi#TPGw=%qU*c_W?FJtk#P+tgdQ`|ZhnjV&^;aHX3HtB&!}JY z&(VhkgI2j~+Uiz4(5qq~ka>oC?DY||3g`Y8W9JYg3b16+wqLtn+qP}nwr$(CZQHhO z+qSKFn?Df~@fWkKbyZYk)yX_JFG*WxHgH}}^u1l$0c&Sx64L>b7lWU>wrmM1UD?T< zM+>z0?JpJsQs)%Dz%SM>?kR!M(f$yYm?j0au_38Qx%dg>hx$8G%J-pY;u5n~SU7%Z z6Y}P?OkK1MXs=Rr*nAcZ0*hTH3R}jSyK90J-PIc9gXZiNrCFQDc)B4xl`>*568Wfc zXO!0@fNLsmng7VvqM@JH1DR&MX-P4ugDpWT#v>l>ayQeOqCKtlEZv0Fg{eY(=f8Hp z`#ZaLtVfAre+JMt9L1W^rCRj$1E9UxmaA-dIaa#XH9gk$}(; z{HNR^0~Am_r4LB>w~9B^sRSfQ0+!5Mvlk+7!7Q3y+M~^Gfgd(RteqJ@97w&$?FUSe?@b_UtV4d1 zXW44WpcBhcV1Cr8=;0QkO!apNs_9=Bx5x z?$8gke{7u@h*lsNRoGc0iTTM0g>w*`Z%mJG8dlt%VtTR{w|`Bdn`OW1A3dCOO9go` z_J>=VH(JV58e`vLPrQ-=hAqS4_-wr)s~8 zT`o+#pY?|i-8GZbs*^np&StPt@W*8HjsFV*WPf3Kr?mLKZbwjPpRvWxu`vxP0UfFm znw8+&2)>a&%H1ZnvrfkUo4RcCvZMw~jmTH>T&(T5s;GNFQ@nOHwELn-%Pl-o+;^C_LN50+5pbdh)5uNG<)* ziSw%*sImS@HF=!7!ZUnD^DH}+Ord-DEpC--b>w_hqIoiwn@3f&mCv1s`@`0$8}0Yn zAv{q$+K>h#v?aKd(Cp75G!d3yQ8wGvR^d#)_@B>`Cqk+#eG z^1AXnMYI-X%i9qM>-WMa#|x ze^K}_5ZZ7_U_QKjyQ(ri!jzJ zYU;DaV%FOF6yFVc>-YT5jFkux(3Owe8w^^xnj`+Gno}qRo5u$;ACJx4PxAS|eTs=x zqMdiWwylncNvc4?P`7|I7KUnTmwj%UaI3*gig3}ODDMJG|cYo)v%}f^^ z_d(Hs=+{XpcBN?-&VCmY1)e59C_!lXIH-9~BHVpfAZNB5PdXu*rD%Ar+RNHXY!K#2 z#u|<20(9ejPLRfWzK=yes-lMF_jCyF4m3muB)1 z5E0bE;5UA-3SKU zt!~5f6uA7W)GMYhyuzNr#tf(CwOvX7L3^b$jz4!ccj71D65fEU7J$g&v}>bYZ$fW6 z{gjG=<5cq3xCdY$)-MOUEJaW4QqMhG)#7c26|KBeQdN4~FUlGvan~EAwVQClIP^nY zu+=eW@=p-=E236I9j4y(Vd6EOqmGG>J#w>ai*aS~`NGh$?&W~B%wsBTi2fUErCT)s zO0aMXkj(s@>DBN`TO%)DZ$A1l;$HS!oO_J@Au~T@28iWO3l|J2bEb|Fqci4Ape!>z zuaY?@k-FBo%g1gzZFLf<^ws6Sj_mlX3{VJBu|4AE@K7)#W~$&DzGyFL)=X89&u0ck z=f)RGI7zpDS5*(Vjp_}N%)0J`&?6U*7EI0h0*ub2_!-Z?QO_rI9+8VIbuIHrdnljI(t{7}_y_5>IET7`C%xeYn+c-Q>~RxI4rJAqPaR^pGU zm0_>U;8jSpleMWL8w^)g;-lOd(TMb8kJ2vj`t9O)iayKfBA(?c@FnthKpq7f?#4{= zldkwDD}{UA-=dv_k!72YymH6r8Z(iIsB)n-@+EY(Mv`mRJ)Zd@?42}9Yle{V(4FLe>Q-i zHwR&7T-DB>Mj6hAHB6rJnO5PWUrDeQIl3^9+l)h-dz3E2Zd8CUkdu($4Pvgm1WmMo z3gkkCQ9?F#9O=bfg<+E9Nezn0y8o4EIWXBhB`)ly*kWMXgmy!i2`kBT1n~gX#wWtE+W-<#-i<_nK9n*lED~pp7Ds(oKCH}J4eFzu!=nF{T1OKtt5448{^OFXh_Jg{2S+-S<*&!^B13aA&OTpk z`M!(^X0Fn~AyHH6MiP2*yOdpV_NOhL_7aeuS6+*k6D(6ea5wF|jcB9qs)!ZDEE(s} zC7+k^ciwg$FM@lc-=us(?yL{h6QuP{C?!lmX9V2(&q-UBpYRPg?F<6ZVlRUruU6{_ zaM;?f=zaZyFt?1tE(yOtcPfpP^I+JQijq#{aDT4@qZcX8C`Q zs49UfEp4|Z!=8&+0Ql#do+ZGZ+k^vxp&5XMpku_t7lVQ(!OLr4{L{o16?H1fDZq>H zUqt&n_xyTVcDI^T?{0O83(BdndV^r)1-=0J4Fl?tv)46YL4d#m z`y2f_2;m(AT)_LLLG$T?409lSZg11Ast;>I2fDGbP)C!}JU3wzx7!bIY8uoE2Z93<*a@hmuOsJ| zUy=hs0Z$C#*Qf2nF3|M_zvdRk3vvQ#Kfv)tg9S9FL=VPS_w{3RdKwkHV#SRJLFtp_sdvev}-VXzC8^g6!McW#FMg>J}iY;Tu zI*AOisQf+m4;K6F-^wHNBZ2@)NI?PS^9G#bGj*NU9iI;H%Il5Z)1__OFw`%*#Pzf~jj!YL zqlTd5q62uke0`mOt)xZ;*`hqdechc#X;x~b@2aMJ%e>nqQC1eh!xK`|`inEAo`I|y|j;tu+4K3ahm zJs=ar1H_4X_v_Rg^g}=NA%}{#@yT1gK?dQ%ptNVBZRuAAf#p9C0#Nrf08j%#bYANd09bG#M~i%f`hgjj3=qaK z7&l{Pt4eEirdx-+f^ZQz;&MtW1Ox*A+|NT|M_WdDfs6b_`XRdd8!}v9hq`fV3qVBz z3NPH>rIpv4?`!WMLRb$e*UKDA{I&Y?S_l*jCXg+DY6?H|FptALUrnk^K?OK~S=dVA z&O(*@03A9-xH-p59=7mC*+{4wzpK0e)>)pyV*x-v0gZ)<&nfLJ1ebw}*_suc!&#IT zW!n@t({1X;nbKRRusQng{byCuh3>JBX@RgGz8bWcKlnI+N-e1Wl<-27r%GAZQtM>T zW@0kv)~F!y`r&>aWLMxmkR4V)p2Jm|WllmPkVJ=B4=~M-cZ_`UNhE!V!SA9(NE>-0J8r4F!tTek6b{ zIiN(KJJdj-PjY`3l4J3^|L$^EifZm>#*@<8l#8R9$~4E0*A8<|sfl%9F28(`BiBNE zT~jexy-VGp#m%6GYD8*L3$VD56#>r8(}L5Po`matY#vJ-#dHUQs={SMPH& zVdXyKmhWw-I<%;3ZML?cuin5>KW06@0G6o#zJ2#~lYm`Hqq@f@`>S=uhS*)ns2rD9 z#NL3{>{yXFc!udIjX?V=xBRo*MhTi5pynB&I8mykvgk0N7lP#_JWn#aEG@Pf+V4{6 zKodK76ShQ5vZRqlJq^U_9a24OG7$n?Jm_4|J($`wp}8XD`RKIE4xTylwWAp8katTn zeGti$G#~0v77iIwGzG#Szk^)1`G=ZKGvfYe*1SyNw|$dWjHHGI;gx8Ht2;U+S&m!p z>`Cvk{;V*k>Ar2LL3P3HjI_i+b@YdNvJj!u$Q9QHEWZctyu+@0)9$!w9KExas6l&o zSGSHgivH2(QQ>*O^6|y~B@+LS=;0xr&uFs!NHG#CDp_NRiwNL?)?4+= zHf72iU({xfP*lyb54*dA*s7PC`gQDRy7|$3=7J_G?IjCrE(XPAZgP)8M&DHRlix^EkqKZ@I~P&N@IGYMyB#vKjA zF=q?x%6n}rl>f5NSe#MWse0|0+edDt)5ai`(vYyJyBKI)P*kfeN8_r zTGj6hcZW^QKKwLyJ?H>S=N2-J=Sj~3!Bq6I);*lmEC88~qg~+p(`Jpjccoj1QfIAz z8^J~jZb^+Nk<}c@Nw9id;yKwwcpp=A#+NuWar4{BaO4=z zD{M*8&8Fl|(@?N5ReN<^naXBW#=1oMJXk#Rj8Y4$ z*g3x;S=+AXX2qDYbh)3nFFlp4td9snkUfv^{Ta6!MP-On$tTz=;E)uzQ9ZJIMA4h< zJGRcz=I|a3cdsxyzFg4!e0M;4TO1&!npEt+!cs^gXP0`jk!0!`!L77vvfd?AD`BTt z-o0`UZ%i339r)Jy@ZGwlcfJ?p5o!Xpy zr0JWt`D-~mSu1mA^L`AabRxN34(Zz-jimgZm3%k$Z1t?}aT!T-+s`bL$O*{tLu5$8 zvs($v>gQ_M1H^S)bIL8nRJ!E?#H6(B6{m@=E;~JG_n^L*hPqVlJjcCKy}Oy)DYk&ne=i{gvv~`9pmA4ocI33DLk8uP@wQKBuIEXvhj^5Fe{>R) zm3XF8&CvIeKEb)2`__bCGyGWTn)@#Z+2IS1omfY8>g1LJaAqGSk$xWiHGartL$aRP zygX+4v68;sr1v@E+R3u(`Db~hIVf^t=dK~ZWWfj5Mk5;a)ivQFGjS1ti*C(WBQqU_ z(!RC#pKv2=2`iN)6+vTuE7Ga}J_qIH`Ca8E^e48swk6zTesf5d3*sRqAV+bhr8U+o z=UMC=N3|eI!dVtZMnT{+;)Xc7Q&2nkcq!rbMC=uDuE7X1C4A9MkRY{>c3r=i`;=KV z{p=+#ac=aUI7DF}RyTk#_twg)MN`P7v-`oraiELra84*s`D&m3Z&``C%F5?NLM6)8 zY{p>b{aS!LyOi=txUu~F~l>-W8>QFtC%5pY{b2wzor|yL4+k$7Em|>0+ko*fm_eeF}hG3y~31O z};T=CRSHavHqS~DtF*@HaQbzq{1uTqF}8{ff+;C&uH^O_6MvcnISW%8g%x# zl-Z|8M1lyz-h(@^Q_$g!P_+zV%OGX2JHtCLC4< zzMoLP&#_-DyI&$r_F6YW16&GAg0@$6%=~J_7R6fP>>f;uuE>hc2JJF9!3jC#q0|XzCckaK)-1rAr8R$3uPxbnW-*luMxQj5sV5J|$Y2*50>YM9T zH>Yq(Z3v}rmBFGT6PIq!suHD4KO%XYt%NEX`!KGLFZ^j+oy>?{nMjk_8qwJ`MXOM0 zL^OI0wUbp_2(_CGwo&3}(kmdc>wdeln%BNq+yGnP+m+}rWf!;fVoDy=Gy$AU$4kzg zU9#}1V|t7J2B$o1NhO>&J-X7)M+9O+R(8d{+883XODR%>%6D@G&4 zhgDoVm+qp>o*4*he$XS0iCSuFbY%THT$${vcndiB^K-)PDh5)qH z?z{6$zdo>$p>PL0#JWo;wTX+oKU@#W3)wafh`+6Z+)#_Vhe!1uC+n5(kpeP0MTO5D>_2PK@uLpQ{T~-y-n7j%-C~P_Ikhq_K@8W5~ zo>?P$@pEK|NZ?B%+X+6T%T9t1&xrvqlITPxR6+-nxG-mF#}6E&UZrmuSEnQFcRv3e zH=PVd*#Sfn){w{hpdklCy0mJj-t20ysh=03MUg%2AEbNXpPY!ou`X^!pZ9JC4mO~o z-!=zddEifsw}A**d@ne;X#A@ctH!Z*D$*I?Fv)lraf25MOK!4_y4MOj@zg4a1x(1J zNDPjn9M93V+_rtbXu~&r<7lKzI?S8&baOl&-0%YddhOhB5E&Ag*&hJxa$m@Ejqn!I zElEq)XO;6;yJlJEfXj4Q#oyu^uXi}rs5nHDPKKUBF{>_6tWGh52aZ{^G54Pa&#cw`DQBt=zO#i@8 zW%FjDKN?G%R_GAQKN(sbp~wqQS>+}2n~K4Osg*Gh48#QMixF!CuW_>(;W-TzOGO@g z5xAVk{1AEci7FG)bB*g1oc9hl)>`<2*#hZvotK|lkh-HUnI)f|FqZH(eLE?Aw75$u z+b=my@Df4j^@6pE4+LEr>3rq4K6lOutam}0ls{O_X7qelB2Tl!qPU*j+9h}|Za$Jc zca{Ujw(s^Uoi_Fpe|!eqWvU64q$jf~W3V5+@#s&o)y5EcVIXCa5TsqlTW&Dxz$)9w z({g8c&|P*JdSN(!!mO%B8&OwYk)trRdrqF}S59kI4J7=EAcRGmse&e|qS@5lLwJ9k z;W($EXIv=2QF+u8&N0kMAl|d>&M9v+9Wd&3jdAQ!RCUQ;K3TS71U{9gLLS2>U0-jx zCB(5kY#Pk{fCg~M6BHbh72>)HyYGmc%t|xN7+S zAet8ozjg{{We4etab_;` zwp+uZ1rZeF{pPUpk5cZWMQ|mYB!#iyQHI}HUz%d_RB)r78lJWkVAs1F2tV*2>@`x| zfrjTT7nhSK`Y$2)^7A*clbG=!HitWmrEd}?-BB5(Ayi5j+IHvTJ;~aS%SCLDqnkC4 zleDIq%w%M{;5td3s7+5zqf}DtT#@)>3bU;KS9LQvRRigrBA_L<*?R{*Wly@&nkb!O z+t>)Y){W6#A&Ax^NUb#*!6b#;1PK5Mg|eU+0yw5v1wfc!WZ7q?9VA_LxQ`lB z$N+4gQP8c3uz{8_XvpmExu6>+y&CE%N8fAi<1V3^=|BocFA%q1B+*A_(yj$%^zZ1f zx1J~d#9#TdA1qQ(-df@yRm`CaHj4``AM#u9F$Bl(VP9K2u99ct(vSgr*?*vB%}8f~ zReXy>IZQD6^OPyUSruzg8joS4U&==bYbLKwon@;TYZ@~ct~e)56pg8tPCoY$hZ8@w zve_t~x+!xM6>wwII9e*XzH{378|M4t+>1AAi-+V02bD)rbfPlimf7fy4{-C+&lJCr z$wK|AYs>XEOKu3hW?>Qb)9m(TgtcnIEM%{AM|(?p7#^jP3)xm<};|pDAkO zvA5KZ6`_YZD^2GHc;{c24HEI(k0DE5C_C}Z(l4thXdl^J64XKMNULj){209QSn(bm zj3^A`+k))R;-4MzG_l?}Fec%%#skc6gm5Ly39L z|MnM*eF|$oY_AX|-%pbNbSKJP%kr;-?*B=rnusc*#nmpqBQgot!;w1xe})o2xS(=L zDn_QdZ(VbOE0M4scvIHL+~ViWx_5SSK3z1^#pISje#Bmq^_h8=3++DzpR}NsrnF*f*R*Ak za{-6xx^*27GS z;sA!8Sb@M!0UurkoWgtzYCo*uhL)$`H#CDrdtICVTRD{sVq4sy6&Q(6D^pq$K)=?1 z>TjxhtqHmeZtK3f^jF~t+niPxTGXF~g(5M1`v_YWv3pl56qXn2yR3`?LSm&t$y=ZaM6+sBbGg}n4qef1zGvL1Kcr1Dg-W&0DhBtV}3 zo~>Lt_!SOC@I(!kZ3+6!Y54x%#B!kd`_c{Xh9_Cl!O*ydfc@sOhOF_|O|b3KDZ0qq zPC=NZNdg+yVHA8st(|5{l@P4MD3cG|cEn2!h)=a`tFe87<*OkF%4_FYbEN0BJ4u}4h z;HE1MAIVO}B36ZoZO5z6L&R4< zaq>#PuJ-P(rH#tAtccu#(W}2FQ_ky{;)3y-US6?z5X5iH!3&eVcr(top@?MN(=jyjX%RQ?ryGx(|k%PQc;Pv|>&iFL?>5 zY?4|}oTE;BBqwO^%woSP$NZI({Wkwz@~7}p*w1K5EZD$ba^Wo(fA@~ZmL<~M@8kY! zqkZlclU075s|zN@rO?1Vtki(a>ZV?JWtq}TmkAQP>rfoCEpf_g|0t*KGllxrC%!x; zod00x|1Fd-M?`8YoAdh=^19`WJ(FYs7#v|CzlgErZ?mQOG1#E5V$~8!a&XD3JOuKm zK+C0#=S_DpiD163Xu}63e+o0ZiJmS@$yEPy?K^!iJDg`OKYuE z@|xZcTJzif!$zW+?jIKzyP?`xM6f7OZqe9DY@zyzZ>*bVvgVyw+mwBDS9-}PW z`8s%U2T7|3G3}rxi8%8T()fi}SWg-LF>GbbS{ZAJOLY02ZTE*0^)d8z=swmYE0r4z z1O65Hj>U=NpNBsqWs)he>@6tvES1GfOE|WSmjc!IQN(OuEX&Ae)_I1GpHX45n7qrk z^}EPZ64WzAiuhHFS7zDx)FVqxq;@kZz^h_oE{D7!Pudd@C}d2J>LE!I%!Xv^I6NI@ zSDTX$F-Zf^8-T7YW?J+XP zsJouU0|wWNP6tlQMHjF;LrD&l9wdnTs}NB7Z`TPF1PyGQJ^~I%-Dt4qQZ@fwSe}Q_zC|A8-K;`hoI31M&C0>|DCw=?< z$hbXU4$-lA0OYw$kq6>FNyjo}0A)UHvYM&nN>owY0ReD>To*#w*Av#z1pNqq?` zA8Wf@Bvr>J$K?DO_RClS*Gh@Ci;N&A?N5q!@+ly|v_tXmw0I5U+oOpH@j?TAd~iaM z^|4OkaKFz-55l%km_<1zOP;f!CAG2t+9Hr}KMx7G>U9E5bOUmQ`K}iMJ0xDZB7qt4 zM0w1Ny>c$$feANTdJV&;SY(t%;tg(hA)+P*R(^v3-$^k6;=(9Pxpjx&V?me8uCI&U zCm(sf6cfwYGVa-_4=`KBMn2~THH}A{F)nEuLd&u#R|TsP zSjHn%vEV8aiEm2p*0}Tg;&h1SQhv_;$r~Mne$Q4yI*OTK_G%a#Ln=PGoE%p_&pHfVvviW#88VM6_Rv7K!oOK zJ-A+X9DjYQZ#C5^-Cw5|89&z_r({&t)Ssf?P_PhS;gvzKhT#waBmk3~qNw=z0N}}} z06?G+8X7SL<>|(DT?AYd!%z_;{3O4@1;(KbVg)vnuI0`0V1Z!goxwmkkT*27* z_2K<;Dp~+0;D*8LLOFkcHU{G$oVvPWxsgq7{lLC`S3yG zlW9TZgcHH;cUP zLSKN_0TmpB0|EGU|2!K-tE3SE!9M=7ez``1qA)opF-yDu%KfA&$|LN9LmZ(dfZRz& z00QE{i^1U0&_F@_nCAFq_w8Q!YCd1*`?|d1qBHNwK=>W$63vyqvLfX2PV9X!vTXVJ zs>})JJ;MOneQW-}`4#Zdef)Xy#R>SwfO)TfCmwnye*aPGi$8(iFOJ`!Z@ynIH*#se zxF8y{J7iB*XLxf+K)<$S=ts5wEBC; z5+qn?7~n-m=jA8J3^Y%*z>g2!Lj@b(r>O zG&c^k97r){cKQ(QPTZB9B6)WWP29dbv(x4d(Sdzz=lWdb2K%*6SN!+3j@kd?q0zMwfXXm<7F0_GK&mM*RKEg0Kt zKjL(clHNV912k=X*0cidjw`MdIcO88ZStgXzna9(=dm3I-M_FkDL6?g{e$3cMdXk~Eq6kFBh3a!-HZ|1#X#z;2=uGZ(l_e87cw-!fgx6_o8 zND!fKG^BcUSDVpeyHN48DwMqq5)Gv^9P9@Qlm^{~>$c8h#6nG@U>H*A*PnAQ;$ybV z?l3s3!;&zV^k!_`ULH)XJt*4taE$VlIHAcWVi-hI1uM4_g}ab>qZP$4*JCuT-f&qC zzFv4=E;+nJLl`;ZQ#YWW=r?Xxc^=(&PbkWx^YKrx|B5NN6{?UX2{OQEl8rD4rN32z zfYyH-IkwGVX#orlmj~M+k(4&OmAcJFT-$46xgREHjNZHB9)eHAfQj%==L6hlCzE!-H3q)sr|{hN7NiDkJ9 zVZ8>`yjx>kD^z9*f*4@-RdQYy;>zyH(S07ELl8zgTRY`+%Yc4TQIwm6ebhuct(W6{ zDz-ZovaS5>e##%l!d{XOea7Bs;Xjz#uo14eV}@40P|TcH)A%z_(KS&d5{e!uk6jhQi4PulPXB zY$ko>r62E{cIiy*S}`A5QEmc?=!2gK9@B!8#`$9S+$8lL{uUAy)IW?pD2yVmrvbG(e`t{L zg0t9?WxiEcF0DgzX1P*Z!5AfrnETF$x!DQNcy<>e+W*=wCg!uh$y4*10*O_th1`43 ziI#Ecs69q5Qsi!4fPVXW!4ri(IwL=lp87(zB4 zOO5c}lVl&kd~0SG|AUlW6L0%1NKl&yZ0Bl$S7J3YA%HWR6cp@Nfv#k_xJ<7c| zD2XY}h-(U58RkqmNFSrM7Qb8J5(5o@c740*BzY5L>r+9my@iDvaaLbD)y%V*l6g!x zz{O_Ihtj{$pglIE;Bztj_Oy|5h;h?pog~Eqw5E5CTZiVR1>YrO(q{IG*m>qft-WEE z-oDM)cFs6UbuMxwo8wlh&b_=Vn4#nT_6>$NoqPk3#7pjMg=Vh(h(C+ZCoLY6%>9oZ z=P#uicj7xrQRz1=$@ykpJ6d)w&DOYX4Qhu|yq>g5VzXO*@I2GqwYI`{BMiVBp#jwS zio?X{oau+<>XzU;;Cd^Wx=ZisR!I}k-(Oha19Ew6aQWwH^i_pVE~?OaujV&#xeuamOKT0IY58FYO z7jA`uIa*jr)IdariGHKnbeK&4t%X%Oy|twTV>P*HW2SlDug1W!qn?pjgP3ki1f)l) zv3=Pl)HN82O}yy~*dm1gXFjDAK7-+LmRlA1`_7vWBO$5r)Gld1^hwuV6xYtHU5uXf zb~6m5QZci)l@rZA9N^%s$(oMD(McOIj8`ZlZ{xw7~{Ow{_S|<3!RKzLm{K z7%_=izu}fF>(3a|FJV=A$E*_Uh9ExzrdAR+BF+xYuVp8F|Dt3D-5wM+(4?~Q+1|-6jDEE~Z`dG{WxhUN|mXY`foQL$31s9D# z+e$i?S+?Rw`(I}W_`CfW?FSCOi&Gsh{ENl0Kypi5bTtFWQ0=C($3XOn4e#+6_{l~m1jO872P`^g-XjI=-Y|5uWCX=GvR+lHn-X=iu~40L7Lgt%#-R*k@kQSLW6G=o>3B zn@$|=@21U^L*UGCZDy8nhr5Nes3qHa15p|A*=thA^N5^aOZ5Lq}?? zjWc^+cse2ww>cJ7n~^#yky{I{D_m^5@*A`+!O9^GeF|WHY5fIe_mKER&*gRM3UR)W zHq7{vXN)YcvO>A2#3#;Y2=!d`aU67=d}fVx`&{9}Eb!La*4A2;@XJM6eQdvswXmwQ z5p8naG{dp1h-@!3FZ=968#H6tKM&mW~ zL94FKaJ(L^;y6xh*Z#AhMRm_@{*euj`{G~jnrIHrm*GANum*<|8Q>Eyemro8<=XEl zbIJOQR+E*>`}m2AcoYkZd3D)H`u;uiO_WV&bc&DI{oBW57wqHU{w<@G0p+K3qRz&s zMzkv~j{b`%?L{HccyQZaREwXAK#Fb&Q`4%CT z4~$Ds@RBWl7Z<4|-3wH%lVe{6O?9IOwo3lz%JE{JOUdf{GP0eE8S_Y+Ft%c>x(v!g zEZmE+zPQS5qU);=()WyjNr6CKb{vz}ugm zP@qjO!Vnm1suG8Du{Vg^hH{mzNhMVsHu~b!N4EaQ+zE@)1zmmBWOwu(PNp)nXwM!y zouU%v+S`RUxz_QDKbnR^F03RjZx;ZNK8+s zH^5ms^#p;m7VNr)^f20 zO>r-`hCCkKg({|!+_z#kS<4HgYYzmv1)Sv?ei)qPxiIx%CDgXztiw9x{{0E*{1K*` zNtyI-h`LoLaQb6s6ILFvI*FfCHY99Cg-5cAuQu5ZzqNQ)gJ+Gu9$WY52(^U zDB#e-&Xujys$nX72#Zz*xK9l?cuNiBy0pIp1fFU&X^MS1Q9Lu;5(hcRC0@ZnLep?w zlrkZ7y6xQgjQR~^^s4MdQj%nseURXIqdC7X1n0n)?Q_&pc#JCoYkw4#$4p9LCz#Tp zpP64v2Hqs@PSz|+dbocdVLta$m-%#5dEu|d;{>kWiygLQk?BeBw= z0<}4r(6wQo`y>l+7gX|aI}QsGo-|<7OE5jT{%A4~!zFqNT*qqa5m6o}ltZ8mNz8wz54mJZm473V~I}6Ygs3OMoWr>UjsP-aq*o zzEm9Z#N!l8O;>0~%`oe`^(^crmvenocU1Ot$%~+xEI23g)OnF8QIosWaMJA}qZs9h z$jeig=bPq6Qf+1!SEQOw@>Lxwdf#Ga7{vNT{8#g`VgzseW>!FxTWbui(>2Joab2f+ zBN+TqQUMdYsHQQK`(xYOyikoagG;cr%Z&%+XO6qMV0#wI4gn03!ryr-r$JRZg@;N z#WRH5(?B%ZhH)n35IE=Y@~Qf*D+8LWFVW z5|Z}vZq(CtV|J7>;7Gk$HN>b)Ov8p(#>dIkyCCA)UJ=6>@pV7Nqu~(bmk!>n^dEP+ zN~R9f76j3}*Xzj~>|qF>c2Nr#y-kbY5VUB8l9g!0lswySBv*>Ai(`aBSF71SJ&dyC z=D8@jB~9D+lP|{^$Fb`U05l^Q9K-IfCu%r-^7Tl5p7wki{w^LWQGt;N06%g~0RD@_%quw9z9&jnSd z`p!PM?89ENEJIVeWbw~rmh_kV^W8Bn6Ne5dugxwLjMM1X%^QE*+fd;YzFP*Z1S{~a z6b0#;YEn-bwMW+ooF+rV==LrW?KdZu$?W!llLxyWyEIkY0e_In8?Dyh<)#xhtISdg z^9OpcSNjOx`;5@Bd>Pks4%4L9E0a3@hq80*(FE$&^i#I0x~j{zZQHilW!u$d+qP}n zwr$&(J|~%zO!8(j^Kt)ywX@f?@9U=VeVYN{+mKnVzV-bnnk}K_0fnFB?!Kux#n**0 z+PjrHXCIEMiS%(z^q;v=5A0ez>T3G{6u81ZFj=~cf|b1Ni6gQ^T*m(^@lgVn(K}(v zSUWju+-%_Z^sn-exO(z%R1-7~M(dI(^s#MzxxE?2fZfe`qvVt;u5{hT*y^MnHS*R2 zn{Z_3MToVr9bLZ7@y@-+J$X8{sSHsI%79m>;I8(f3p`j-+KaSO-w~%CKizla<5F4$ zdTGuL*_%BY@2{X#)yy-s?YBY`FFz%*{SoA;-@Fe@z|ASo>-w~O9-#@r_>2B%Hu5A& zA1=7!@5s-H;|<70zyV*AJbf2(0g|lpgJ@S4v5(VQ!9sUccDZ|H#V;0IIAr8xhLp6S z{HB+=jXfJdE;IK?0Lv?5T{DoM{9rS$EaU+<#gQX=wCR>D3cWoA^SVIM!ZMCyps!Y0h`u z2(g>|fgw85Y{t2n4oJfW-caCdeCIHN5d#{|um~c<^meg1giA5A^VRF&ZXXEsmz~T0 z4y^zE?W#mCS?TdZ##dhxN*hIPcS_xJRY;q%O5>Yz?s=$z(y4rYAi8#DL;ZGK#Gs(= zv+Q1JC(2i0qx7p%f<+8@#0}|E-hvH&ZrYPAMIOdz(mTH0){tt0Q39??(Udf9MK7>r zTG-3LMNJK|jieSk(b!*(bhMm(qnEyVWO}zSRtx>bdao~{(||{~Lh^y_`FDWs?Jy1I zkB)i24&NVA+@~QSk}St1p%(N(ac`au7DB<|doV-ll$k__gVlH4OUt>zx4@-nYkcU+ z&~W6bQcTVE>sa3PBO+1-v=qEB$c?}rQ2U+*m~B790n2(gk5zQ#YU-p*A1D_ zxx0r~O?;D_P{sYe>x)8`XFU9hH~1GUte*#v|+9<>YIyWE@ykb>ylldu)b)Dpxu%rN zOS9GyDp-O}m_YNUp=f26Ef!zAS+Y+7%ZX44g@9n)%otIZ325aB?0ca>A~cXhD1+LJEFC2!S&d4?18%$rQpa$}VwRNu{$~CsYdGMaS#6 z8E@Oj7tvwy?yhBR%d57R%pFL!knXrzLR4!AC6R*KetmrLU%7=w#sp9R|3N?eSn}U& zEezNZeqU&$2dqJD2D^U}FMoi^+xqa;wWWUt4DC71lKT~N0Rw)4_>q|ODc0j7@}q*r zzhQ;CB!H0%aqr6e!6W8|iT2SOZ%Y0_w`FTBK>5XX{EtcI@bCesiHJxZJFs&@1Kawp z2*~~5K`%gs_DR=;5CKGuJpWpgzSUrO-N~qzMO1|c7Zy+;1q}WEu#Ied3IgQVm!b3_ z2YNTT_2ql%`T;tS$j>3aV!?5yjYO@j9FaYTMy;lb0u+{xIU_os_b^}17 znCk!@bc}NZ^$!Go$lH}QKrjET@A{X@R|OLGQwN5jZH#C;zx=jcB2h0;v>(u;a+AM0 zT_qwQAmAHV5D|m98h0Pap9tTDz4s=)@nx*hZF7ZYW27(>>{5Aq~aZ6+n6wK8*#GL#G ztS@NvJB*{h7626+Sy^_ ze7wIOobbr#$T5R%zahRqd_)#+%u7qLAioVhb2hs?|Iqo>)Uxxdi)v$%sVV&SOKc?W z{n^p^9{91n?kRXjeAV*=`C5<%Ir0M^{mk>@>gX|d`z(U)?!g{FczprYVU``I2kh{T zw}4CdUE1sI{@8x~(7yGIeXFJXq}=~_3YA|&4&E^D+^5Q-t++2Nji+|t7ioc zI{n}O0m;jl1ZREuR<8S=226FxX`FC!vCRIUzJ31K*Bo~20_c|jfu}un&k{b)_YX=t zCPX__X}l=^ACJA=a{k<(@jYp?n@GHI5Me)Z=3i>Sz4ng~?73T`J~~v8_yK_hn+!eq#y{s)H`m9( z4O_NAyTjjI-&gh+lQ5=otXx6ODKI|jXq%s1ig80qZYH6B?Aurfr}L?_fhU;0CRZdf z*oCYopR#EhFW>pgzb7kZ=P3S#_iJ`Sx+=Nqap?+6PYmyr+j)03(55dw>}U5NJD@~% z?7ZlbFz?cywK{>YnyS$9&}{S97BxbZOI9`C&L19BC)0~2e*vJ}?4<|d`U9dACe63{ zW9oNXnTUIY6LzCSmV1(w#B5vptbVBx~Xi*wbL*^0;9@N6Vq;sV=HkT_^F0b3>o@ z{0O-}B?B_vnSwGl5GK&lj}9Q>l;{w=yaWJk!(-qg{ZG)V0gT57S1$q_GzlEYqGkY_kuf9C-4j z%vq`3o5Me=n===up(p>I%9DyMvAjR2(;?o**`x-XkY)MBRR6*u7elDPyU-4lmP9h! zs!No2OR}meN+`Be(R>0XdULSf(oW{|Dm*F@9&I3qGI{f~O}|uhr%=HdcwEO^(98f^ z%@9dyJ`!KPvHNIi0(0M?UYA%w)c+8M#AOMOqL6aA&L1CC<=F~nbSPo>APJ>QU=!?4 zq%QOKG89Q7yOaj?G8DxYNob|x`ZUkoM{`75TA_vy5$d!Y+hFAEk`_#*Kizw3Mh=C# zr~-4wy}B~Vc&2!}*z-o5%kkH7a**cw6q^@B*{nyd>G^f;lea3UktRF0ycH4pB{=Iq zCY~t}*)^=8QJPp}om7QV*LD+(eYuIfzN2TI{FXMX1%GLBHIUt%H+9b!K4b^a}cH z?`W?{84=EGQ~p?mq9UwpVyiqopWLejArs++I&V_K-1UggC&E+900-9yXd(uRDNwVa`!;$_-O-3z8HrCjnRhy|}Wx!ONKR@6{$pMTKN zzxcC!OWi+|5^a>yFPxy@z7=46{;ueGgDHIt z+xi?@m~LuMVdvRymm9*pAXMZ+v*DB zwum=zXsWQ}%-@sDZQA-p>+h_nTjA&N^=R!6TI-NkyCmm>+E1gx zLfIi!rWn<1C~yp+X}k|fJqOhziaFzQ%kKqVDCWpmjjkf{$A241INV!MuGB?KZ$rO?JV`OsF&Mzm**t0FWj}gq`T5g6hlnb`|m|xxnGasXY z#FQkVE-*F_uW+DsE>9$7bH0n+((1G+%G-~ejy|Y}dJMmXzDN@J{4F(eC&;1jDnGCG zHpKWcNRP>@7`v_&8~YlZu-h;PbEKB=fT&h}r0 zLmOVv&{vJ)_BKuT%fA|E_^)oyJ%mQcEeb(YK%WANrsQtyO?U>(hg!h7MuX}g448iT zvA;x13AQ1~&|6l~Si;Cme9hVLc74+O8!5{bkh3B|R`Y<#_G6iqqH?)4L;fk|TL&4q ze9#3p&lCqMZ8hEkVHfRf4AyzQxLK7({&Jaxy2&4JJ%{rsiP!N*YRMFz5|r^5Y{fkT z*6w@YuJxk4JN&pmX)$p}#zKGn_a9WT&$_D0OP$>7Er9$#8Dq&K5gOP znK`(g#YlMUV5zZHL zq8O>On8NC!6oh=oRoz!)ZR$=dY&;*II*r;O3)4w*-Q|hgpN+8i@;$ZngH;eZDpzL- zzz4wTA1&wBg$*w-ZL&7ub#bh{5rTi(F)`MXQ6dvmF3H9w0?!4ns+F5lJxUHc*kd4# zp#=*ipR~%GYsi@$(xP{D$T*;tjCV~jG;61?a*d);Of)cFIVL>t5hy!v{{FJs=H$pI zw=9FeiK*&%(HYm&Nj%assj7)uQJ;TvDEExX?c8@J+}dEHc(4G^`ohwC2&hQ!rzyra zZQ85$(NwZ6jAm1okmQ&aK%f=ut{rPaxU+jp(S?Uk_=BqP%u}*cau#YZUWEOp12=uv zyoSXncV5w9R-|8Z8C9ITL46iawMATPY6!(~U&6qfe)k|Id2S=+d(Cz%SfMMc;GI?U zyJBY~^Es4C)bSW^sD+kPac1&e-S)#9FV!AT;=`)Fr%{61I+)ffE0I;oz8W_)m{n{- z;udwyLxv1HKaId$F(b^qa%; z$_EPXD|YS68}>0ads9^Eg>0g8BsP4pNmH>y5;r=a_jZsDF`fmiw&NKsM`ay!nzgT> z5m>=CAX;z(8_XtmWg&R(CR7P$FNopzi`*+#fV@Fo1ajYk%I%+WO7=$e13)=K zB3C7A+S8gGz_e>prWe0DgX~M#E$9qfaXB0EZ(-o_#^17rSJA|FyLvL&4n@tfM7(;L z;EJ<(bgtbh?1062R-&rQIj*o%3j^o8zat63eksqqI!}gG_;H9X@`Ej0Rn&pDJ&_EM~$_TIkoHu^UB4!-!R z{$mxSN{eHR;47OG-4K>+zeV^*gJLuFM&&jRdurixRMmGTa(dz0c;<}Y;a0%1k64{V z;jU`k!i1z@-Y>i&Q!;5dB*)XW?tWja(|Tc0;tP^|JIkM^J}qCo*x5uO+C$(GlO^c$ zDs?!ltFxgsD{R-2w{cZ$e7(#u_#m-yQ8DkZIulf9-_k9gwyqdKhW`+eFFfH$>+M0? zO;8FgHs5UPy1cR7Y{LW;3z=8vEvgX@76wGcQDm)E7{V-ROtXg9YqzM9+okyKi$`(g z#YrfeygssGWZEJX!%2X*7stIbkKwnHbJ<9H>LO9f&!b1p5%Guic?t@_p&(9xn-?DY zSf4y{ABt>{*zcZxW)pXe99<$SV$E{RYZcbl_O-lvc$9Rz-!T>dfbKpD>&a8*FASAs z;^Rb`FzjS)z#TC0iRPn&zuUo#^lgDysWu2|_J^|o+woFs=7FUDiFNbx@=`&bf7)L+ z+>8h~o+gxE)n;Vh_$xHAQ7=&|bm_9OWUDPHqDcKa7DniBxSbYaH)yKIXwN1I7=0e( z(%xae0gDB=0lao{6#7vnZB_yL%w3L3E~+)cO8ou%-nMChR>fjeu9LkE77adW5@dvP zpe57Crpr!7h)T-VO|6xS^R+;4@S0K6uEK~*%Fomw>5+-)Z0TL{Wo2o5ZgnHjgKkmqA?p&qrQ()Z`>zltRFl^|g5R<=oVQXAu3!m! zl7Tnf);M?P*zkJZR^)-g>7`YNIJ3H)Muf?Nu6Ssiz%ZNC;3ib`(V^BSr@O!bR~aqClx4{WQc_6mjhagqcFN0 zjyFm|!7xzF{VFE#a152=8Qgf1$%Y~K)(XtJW>nV#d?5XDN%dMf2f~@kDp;xVyWd27 zyY~kEMqXG|?vk=u(fnf3R0zZ9`Csn{s3N72Y&N8?RJ&G0=p zQ9GKXG0{2K=xWleIpeXf;<;;^rVhVH~fkgmrY3M>qRvz;m=U3~&7C zWQv@3oRwYT9h>4yXEru;_v=o$T^ zw{A{S<$mH|g?2MPMg4{WRyo#JzY>1Nv9<}u+4{=?c_R@YvwN4>i2aa6eM5};7EAxa zpCyo+{B-d%P3M!6Qi!qhoHR_bsV8XW8eSh7Zbug9z3nI+x@9GmYYQAMevLq9N&&8H ziTOUb;uv*m<72g0Bt$nhm-l8(A0pY&pZzM`o*?VPj0ot5Jc{z;>j~ z*3C(;$bq9-gDiDJp7%WaOQ#?E)q`d>YjPR+-Ki4(#mceM61340H-_E>8;xs1St$5$ z$GjV|7+;}r0IM-u!SdmRlZ+x|CrE%ZQ^InwbmvXn6H})5$vSb8g!e5_pHISQQ*jtW zq){`!Y44P)czKZ-&$1}d!5EmI2JtsUqj0$K@E_w`CV-VD6zid=>@FF!P`b93xb_=x z)cp9t-P)#q&cK~{4yK-zulCV>zWxXD*dG_^*x4+y)jT3IKc9IF+jI;k-vRIJkxCgK z)3dDFBawh9@!!tO$jZgM-vPo3n$6jK9B`j5Ml-I3^vnW(cnlM<{X3B{v( z&nj~Vxs9`J21Ty!82*(Lw8_aRA!?x{*kP$UXeOStkXlL+V|(`BjU-Ru3W~Pke&sV91jhIu@3=C%oy%* z1u$l{Ul=QMW<8#gcWeHX;i{$G0tZD+N3r)p*2t6^ugaM_S8h37wFl1iOV-W&OO#gH z^O_tT2j;*7(FQqN<3fMx*q-`F85oC;Pn4pIowq|P`QM>{{O-6MB>=GgMf)rM%NUE{Zh;FzSRX5l|FbxM4DFzdS(brR@e z&#FM{G>YJQz6_Yk95)gl{s`Zw$NmvSkh!r3iQOYOK6-o1B6Igeh0Uu>%ReHv&s(-Q zo{?0+svthJ{rY-4hL-F8mcI0~uviij!}Ff19X}{3@??l;#G@_Tl=+Bo{G$sxJZ;YO z7Hvl%X>1t6goUS3>NwKfUBXlR@QxWA7+WrwVuZL*qv8SbkO{ce;F^Qvmo%kFLopoS zDp+zzdCg@OaIu$S=!*I@N|60>h6-tX)$cS&$Ie5W?kyiTWzg8vLuULv#SPWCh^U5W znOnE^&n9G-{I4I_(PjxIHQ-0hgG@z9X4qmpF#nP^*3OY{j8j4RJ4WiOMP0hVQjG11XpT8rZ6O5@Pa0V|MWp=c6i#-(gIhNy z^cd2?(pQ__QEN67%D&RH)7S>z(ubyBRvqTj30^Md=_MCO(gQ<*w@SmnZP)QDZDZc( z>dE$WpK4CsM!<1&9>uysbaQ3BTY&G=DvI-&S6ppe=~NYdcGRT-Z94V{%uH@QGEU{m zYC1E5@$(pMWd7E15y-b1%1#nBr)1LNiXYD6ZsJ+#6 zo}qdwN75ca;)Bjhu?!O;xmaAiCUNnK3LmrNy+e@~chw6CCzmQWH9MAO{NW$=@zb^l zg%8zC$_E?!DFNFHXrYHwueoZ8rRgGN^M-U9B_`&T+Ef)~6LXf8+1DtQ5pTXuV}FJA zB8ae<;Md=0$zd&4p6uE=~zc1tc9_3M4O?bJW$^ zo+aUQClW+410(FZmlmLst1C|L#F(Xa_aU5vRTV?=0%4p;(WMkjrXMe+4^(|ptH`#p z={5n*I9d2rONq8_K^-;JwqN>Z1JsIR^|cXOJGayKFi1$d+T88G1(0rV&JVE6+;Y&k zQhC;kbsZG3R;M1EV{Ud=le&&MNS73z5xcRL5w}-8aUqvgr50WLJ1k9;k=!@ZCMySw z8|rOll7oCVhAt8m!gLat9o4@EBU@X9&9M#Cd25{RaqNaU6XZXpTWkDc^KXB5|DB}Y zmc0(NNosij={Ikf?+g+HYYKCSj(L2d_mD01-cD5+wi2l`u;U*!ZdqMQxZhMOIA9@= zb$73I>&|ArzGiVo_?%kd!r{t)aW*wMrV=u845&)LI(tIBhUmmqqfvO5zH;o)$x9Oj zgPo$A#U{l1DFh*z)P%ozouk8E{ZmcyjJ;6^0;VVkt0UHor^GsrjA5Zib ztfQ!l#4cf&Qz^D$hD+esz8a(ii(BKC{ty(>?74=c&6Z-CEwZC^IHy*duk zFGkKUB_<{(G)e{`*dg%Sgw${$giyx-vUT+bI#xumkGxR^K2mU`jA$2t#wG?32LOd2%xb{Mmtlzv!2T;}QJp zk`BC}ZoTp@0Gv`P)HC=d@K0daSpb*75B>p(A;{@kpZ3qHGZHH~0zEP`KNhwDBKam- z)*g6EFd@+CF+j(J#jltN^_xunO0HL^SFZuc&rRTm;zjMbMv(sX#+V*7z|H}DpiAFQ z%MWf633^sp{y@Y%9~ZdS?n2LBUrY^@6Yml}m?NNS7O2M-9-Lg<5~TN!pKqUI5Wc}Q zxtgw8>H%G7ub#=QQgVpa1Yu@ou3aM4T+PQ=-#-_w$E9vBUxu?E5%(^yFOHSIon?j| ze&trCzuX=@I$LS|rXIl`lsP_DEpll5!549Lb$L{PGY~%yflII6(Nkw;UQbr8o+&dh zAD&qtQ!h9i@Hs?-fBsLXmv-OvKdI{(_|wDNPPA`MC_la*3v2+ex`4HTUA}L5!IXRk zpV{Mm9KD<$6kfU~K47P2$9H>j_OV{H7pLnR>ZeODH#sjdKOXZ1Z}8`CY!sgxh?g6m z05C&DfCw0j@d*vR2l@QgIpza-#rm|Z_=WMja`gILRtno90Kom~^TXZVVc-182OH6g z-vj;Z_zMm^WkT+EfOnp84|OLni!l4s0`MvM+;RJ<82^cQ|M4aOV-p+Mv5DUK{uzLC z3E=SfLh~!G$AYGTaR$}IzWsq`@%xUe=Ul`*K7QQMH9^IoK`?KnN#Ezj7trPH<8w)^ z0G>p#r~(rbxco*uyHUyYWbfaVrwOFGTtSD(8X9@g<83_0hd-?er}8l9(UET~{oYc; zg%?o&QN-(sr3XX`2XuwL&JrJ>BLlzs%`!Fxdwd_W0Y+iOa%U+3%%XgLaKI9emQ`MW zTol;r4$C`0OHe%$ejvY|`mamUbtwZ@zGE_lkrXW9V_@)|Y>vvs(solN?-pH2L z&3o$YQZ7ZvA>Oa`5m~sOr2W>2$RcNoEB)~0la@UrrEXYlh#fI*nGL3ZU-3!x3K;iW z6^vrs9AD^q8`gP~%a9%$3UP^M6~-Y@>(Z{&GIr9qo%E^ize(o_YBieUT$lFS%|HL3 z?}C!QijK!m`h_P=TdWO*vl<%ch{9o{#Sh03$tZ3;Cgw!z8i)++Pn)D0p3-)z%IwdB zAD?_MdbBHn%5ImsB*UZxE6pl+RMZ;7kv`8WkQkRPwi(t=Kzb*5XQ2AV(C$!VdIN2g zSs)LNj$*EejGTay8#m%528$Sy60+QsMlLh6M#0@Ryo5D;K0fz*PLVQrbwHJ+6haLH zzl8Nla^P?127y4)V9|`spjs}Ymn3Y80lW5zR;DSmcZoIr{lLMlUxNvrqZN~EVPU2# zNM_ww*w4Zu(I+x>ZJG!?9F8<|K3Oae^==9}$zyQOx$L${9iQhRBP&VjI&rgVW%!c3 zb8|&u`Xf1v!vBn%W50rr)A9)v{8>C!-#%0n|1NQ;UvjHu136T`ROz^!U#C*_DOSJi zC%ri!;5dlh*OY!0=f5(@5RTR^<)tTGGv%+>?Zd60pX*zYycYx558*pD^Ye<0MBUq3 zO{ue(3+pR?)KK?DCy&u^mP)CQXgNlLlLfr>a?}6XDfkW~P_&oM{PwwW`88`yD0Ay* zl-K3j&@wTP@gQVj(pmVq-nYA^ZE=(3Fmq%nC|#kPjfW{YGiI(UkANNj7p7>`xb40` z;sk`=M;5KG)}lBbSC?aCPd5utdDHMmMt+P|tZ2WYX^9D-bQZy_D3& zU%R3t^9ZXpih;oRGPox~Q^s7yczTkvwWoYu^X+pCENdv9WHE5<#x3Kz+4~Q4uQQbF2S3~=RJr*{X6ciqB4D+bSxYQ)#grNEjO=YP}%4hF`NobP<~}d z+GVq&K2mML;cNJM&(K_by;MyQVFRav?ca`SVuw#t0Qe0gv`}G0uM@E0UHVR&Q_G69`}d%mm@l4Wy)2<`&YMd>~1Yl@l z=IH_0Ys6g}a(wK2!)#vr?KFbB`Oudh=pV1kNV30vivc5;w3hl|6xX)0(>GF84V>C6 z52-Y$qru5ORbzij1ChAkx#D+zCEs~IS=8f{q7X-Ep7Sni-l;bM;+DeTDPCZub(=}+Gn#U@T{|2>4K{SD zggmL0f@1=Y@Iq~w$gZ5&k!l@r2g@2`;V(SoVd^0x7cZ|;s1bbisddN8ar=H_R>8x_ z&DpLhNa(t{V<5jYF19i`Z4>JpDK#`x;uuK(O3@7e^CqeOBuu-7(!Cmf$XkxL(%{(q z+U<=7os{e`aRDD9fjX1$ro=R|fK_7TNf<48BesQOIDNVE+<4v$%K+^msJ@v4CiZG9 zBP;(>=|8jOi_yPNHGr+o^f5}M|JsWDieRiq`_nrYzvJ4KFeZ!d?t75*9-C)Z_K66i z5innd*vHxd8~DLRS3q?ddmu#UZBjT*WJq&BxFvFw%5XNS#U3T89FmE|tBWwQT&_Fk z)7GW)LEco!5Xa!1e|q)0e6hP&MHCs<%HQQ~5w5sml_}-|i9S4u{=WM`#n+oiKYymX z{CYu*X~jxdDz)KFTTJom`@+4?5O%Ba$&&;%yZxLDEd1{>Y+Fg+)n?p+OpD&K*22T^ zJ;B1#levlMRbv-lvp&x+j*Zn3dhEQ70Uz6<*Ge`-%FxzFZY~ES7OmbecX{Y64@^qo zOWjO3A|Ggk179@rbqSR@N&+uq3`XGw?3&t{U-XvVu2fy^!u}?YWBUX=-8p&+i4ojS zSq8y{$aEE*cC~%TFqiWiO(IWPF|f6nN)gBHadmXDoPR;qE8a~Ty-q2eQz_OEhYm_+ z+DYU~j+59dwQkM(>0f|5+yf--d@NAQS`CnSJX_zFc6QzL<5O{!dNn%}8mR?o(MA6< zHbK^m_S_+ugLO|uOJY!la5{gUL^&KV??L& zY27&L^;tpz#Ujk0YyFZWPA2FWzf@2XgyjBJb)df4v8vFNpFhrWSfEv=$_ z-OmR;h5*zm)pK#XADu357R}_{9A9aL83t2brI!bRso*+0K5m!l3w4|z+ zPv%c6Qu*^4z`=9T;>ao4ysq4fIX+)#b!eY|j1o;0phW~MplSt*+Yc3CO}msNMX+T4 z`h+W2{kxMIJWJ?&%^-1-sAHQNC!dn~9XP{wFEpmUD)-(zO5|#pQ|HYbG{&L}<`cz> z`Egu7Y8>64bGRlK$&y@E8q`isL0?qjvncGxN!?Al~Hz8E~w=Qxy+lOKl8*b1rV zqP2TU%{#$jI8Z)^c&->GLj1J*))RdKC zqhJZr(Um(*kPx?t0yv<%6Rh(Zc9!ZZA(X0ycLP&S<;|tcD;r%CHjDr@i_A{9x$%IN!P9`MNW8$+0R)GGMa+OULbS zw;*!3EoP;{%o0ScC#GBJCvX6J^>KZ6KfF=Wy^>OI;Z3DmUJJf8lvvv|rRwCNARn*I zlxvt8Mmfg}4`j0jSl29WPZ_jK6lUI>V^1r}$h*)qgX;9T@4%SQsY*h_-dx^8!y_0c z>w$gnyXXVMx@V^EZ99Kv^Osy8NJ~8F8G+5veo~)ZpUh&|acn9f-&3Aiq;Z-Q6vXvs z{~VEr0QaUnDSXH;?X;Q{g=1&PtUKEe7$H*rA4$>L)H!FnT(|RmPPOIig z>>ZVgxyam!OMojb+k)syl7e$WtapZ(XzZSsh_6W)+% zc?nz#DDcmf@h?tS5i$z2N)(-+EGtCbKivYaKklEw>xGso<%sM!X+OUSa=yH03n7~O2Aj>hd4?0Eb1cJV8guB}{IA$W> zA@!3tn6|}(Wbr&j+#NxRPF)EFu-%(|?#>UG5*FXNRgScG=qh!{#VBQ5@;Rr(BnV50 zBv#Vt{g`x_nRTFu9T6UpsSMEeMMdm#->Cl{+0hhepKj<}cSj4E%!E$NRL~*kG!5GQ z!KJM?9FYjYDu+C`#w_aT7@3~H=r=xmm;(E4v!l&R%H@eSwk_G?&_RFs7t>I!Eig|) zmgfLfyyV(oTuCml%?@1YHd@VEj}hW8LCH=ZsVOZv%T#RY>PRBKXh2pYBNT(KVzHyk zlMwqai+YyFHD>NYabn75l6SJ3w=7^&Sy&6(h)4Q$ysLPTsU<_cF65l)>RL}cV2v6 ze+kC}9&33J7<-rFkmu$}5zIBwJ0(49{$k0L`Ve4eu5b@NM-LDzb>Hj$ zl?4;sL-KiT;I_ej)pb3vvY!HHOV~9|Z!C@c6Eo>cw09}MT6CkR6CXUw6E5Vt&kNwg zQQ7}MDay5@tWJx_TxxX&#;@bM9WEEk2T|v@MTmba8BA!vIl%A|>Tsi4$P{8W(tutMw2&8%eKyCX&}rW5cl(8!>4- zO1m_9b`EL(8}&@YIS)?7$Ko>9sjuCWI)Fce=r~z?j$Z+7r~PAgS;ySX<1Ir{cgp#I z;hB{AOuny*6v7Y_cxd;vt0Tz~Ru<9UL7aMmGyeC+t3yn%L;T{sM98Gwi!Pdo_w#gk z(pTa=pzxtFmm93T;NGOcKZDdUMV6R#m0_D*%=^>w+o~zFQNLpwrV92XJd*k;u0_sy zoie`T7R36Q@b07)D*;*4kpDuWs!KZxmuRT(uWm~SPqFp&0jg?Lpd&5H$624!M7{bF zteR&NFuhi!uD)5=Hr$>g4OG|&lv&Cjvsomlwh?8#QlBz+~j+yPMkO=Ve`g0rFhf3Zl%X4F*b#HJZ4a<(n zCFr>qNrvJ=;*DYFtbB1Nq6H0`i2DxC&eXkJeZe8$+zpCY$>=~0D{r6$m6Q+Bpycg$ zV>PLNpEsB`*lGm5NsJ7e8IfBwp7{#ZEMB~2$UWC zBg*v3a#!oq*D@E|U3F4XhtP64Uka$$`WsgaqFM}p{!QC4hM8JT^!oFNP9GaXQO-<{ zTcHe|eByMIU!TP@wXiDb_RC&Y0bWJpr6`N~1nOK1RZKn;WG`S7TQOF^hYyRL%mh9W z!VBDtAe(tYSuo~o6?DFjy{0t*sUVzRd_l~i6%m~XnNT;5UTbxH9F$bM?ZJDLtcNK_ zE1M+rgJ)nPp4Bh1%C&L89mZ37xmt3mjit4>(FZM&VH=;J>)^>&*ADr(Few-=_0ya( ziW`r6*UxpLMHcdlU=BES`kiAac5qf~G$}5^K*)+YDsn3LLn#RYnJ=En_=Q5W;s4~HF zCHaqF&s@JUYYX5*KKRaawiySSsZGRYaqVF_Aep81{mF1L4DFQCUbxM5U>%t-D-vdS9lnQ;UOb2*%;yC{`zRvC^P_Rig63=c7!Xo1yn>@hG( zTEzXTqwZpN1}#G@6UqOSK=|YjNRxTE$9kbofLWf!uT~F0zvbh%kEkRGwGEQy>5lIP zqHUWhvS%6vlPH#;VgqkxpAJx&26j_}kuC`!>yFkC)=7gY+{Z5{kAFtxKP-6=v*wg^ ziu}E6V3!3#g$lC9fG0Q?7M!M}-+_&vrv;#ASN6fDV_{*@+kNSb-MG?fCYnt<+Kfi7fLivM7IgTojQ6@Sookae#d$w{8mRGh zSgsE~I1^@p-r|zn9gJCNn$i33V|{KCE%o042$aUA0gRX0-#xIQBm2!sDM^8Caw{p~Ud z#9@g&exsh5CJyz2jHp2$aH3*HY(9|TwJ4SD_NiLpN>UkkKcMr`66kYN+A49-G#-6* z^zR0RDTg8J!CGGEqW#^7rlL~V$i7=)3Y9LH>4A55+G(4^y& zJ(%r~A^Ai@n*UbA$;Y(L$O>z3-fH=~l!0+#)o={8z1WGrWSd0T4fMdl+fbdEs##@@ zj2BIm%m=uS?JzzCqCeyzW3a_TSt+{lY8pEXhR=1UlU#qAnc`p7M~P>1(v+nQ{9S?J zp)(Ejw3#Mj&bWMHXB=luCocxG{BKPjroilNOex%vu)96ZwV)R_#VAia)V3Cq1?6a~ zPNd6+bShDEkQ7-PZW;tl9MBwF!ztsZj*e2zO58Tq?lqzgdUDh>J!% zjs@rF)W5&}`318JwgUtyAt7=5B?&>^COAh=4+%62W{{Oz-5RZrh^-$8I*_Y=F-~_rBVvuiyKm~qKQ!P?gzo*lOHYsL-)GWFgfGtwSi#mWECZPp6F}+A#ZPllNZ$1l!*%6If_ z{6h^Y^eGAM-zTny3b_X-#14$DZ%59rCnE;92s#4sLyXPw$7cr*n}Bfl)3=M|q1|1X z767o22mv4=ZV|X)G2ny@7=SS_KFNgpa!l+>ybypC1lrpLkb$XXWXySG&M` z<(9$xABA7PHQ0L*5kqqD@vq4RP(UZAaLUWx$w18rKSqurhkytD6!-TH`2mY?fG1!s zsBdc9%cy{F2k0;61H{*l{8(~75O~lGJ_0!)!X@PW=ZA(k!b1SKJ$cCKfnfI#h=pu@;oIvurYbF~Hq9^o zUa|cL&M2sex&Ymu{fYn|3I++k*w|8benCOt-JcuA9}d5szMpzbKYd?Th|iLI(taSQ z*!L(PS2y2-+gBl&ZNB(6kXKg-9^&W;dB6?dVheaUP+x1xf0MJK{~~7%|4q)i2v}U% zKT|SZQht8y{%RZ8-S7diQ~ryd)z6CT5Bk5}$TOYVQd|fU(7UeuJX;tFu)C8JVB4df zpd+IJ!oQmb=q>2!$Oi$zU|e6M^E(B-PksZ4@*u?E&kw_WCP4l_M+0T>mjN9r^nQE| z0sF#FH{CCY`oxDN?}0;uK={m)BajIpIz zUez&KpZj8tuAj$hQ=TeH1QsYT*VH>byI{sUKHI)ZK5DS@E)j_v4nl=327#YsI|;Cg zve4p|u7n#9(DRUW2&q&iz*4SK(WJ`Y{HStIL&KSZz_1Dum%0TIP5Q=oLU3wpi^Gcq zw2IoWEYl;kk%jvVW0JHA(qy~PD-9PQx_!JK9-VE=M|HDZT$|iXFlZLw@Mxwh`vQ4M z+h0pGr!YFT#tp?Ni^lBP(x7z)Y-CW@C8TrY4!eAQ?~v_ppO%&&3s>XaHjj1T;-*p1 z?#3uj8XO+|A-zm5?WxLEPTogaZxCCtsz)jr*83{ZGjZwVl*jZIXiL>k9v*zKj^)xJ z<2r`d^NIA?9jONRhYn~!&!xuiX4c}w6^6mvy(g3=V6 ztNHyAkM*&cV-ma7mRrsz11q33OqO6pU@6FBs=vu;4UMZ@%L|3ZTXpjG-Zp7G*8P2R zW}YY7J*EdC9{$!KT=J@UK+=b>659FSwwql?@#Xqz)o7^T<`07A06^?;v!#K1bRiZbspJP$=bV(||41|Z9$i)Y^dq59EybUd9#f9^}8MDzkf}47x z-e3P0TjvlfTF|A@YumPM`(4|%ZQHhO+qP}neAjlrzmx9tpp%nSawavX8dUb$`&*%f zee`kpxRf&~ktfM9?doG0HPD1vR7o+Zny)NUxDYkF#T`XapS%5B*PF(Wk z-?6)3kr40JpOUba4zEyDRhE;s>+r3! zrF}at{ltdH2k=g6K980HH?qp1ABr7zyNx!cMD$Ge|8j!jQ<L7vw+BWL*{hy)$xug zj`OK-XwyRe{dudu4yn}xWqX(yD|z>p>G&4m<9CIQy%QMxytmLQh^AeIneKL-q~&Rn zodNUa%F+%VIUdwbI%-zQcHGtQnJdQiod$e=Ghf;)8o_J!CWaputy~$5qN&)X`glWx z;X5EzT*-CD^uK~Qy#-}Sb#R~b*%fizt15-BJ0EGD+5B|2`18ckXLgx6&cpWe;s5MR z!@Us_F(;H>mVoH&Vu%^-{slDA)5JIIKuYg@v6Q&wXyYlXd|;6Hd~@$Kn+gQrl%HK^ z;Dqgy6iL)AP&h;*$<#g1a%0>4gEq=)W$W578AkY7@amB0cfe5*-Nx0dv?xL=unXLP zp7c3-ROQYyDO0+z2>;j~wv|d-!lqG}^}V>D>KNqUcRmo^M;=XL^t$uif?k(F3$*%A zW}J!gNaGa}fQPn(E@-&dJytFCVru%$))iktv^tv;^>@@TE*B31qVg1en;uhe&c?H? zttSGLBt4_!-Ic@qBf5G)*sOUpu%k^xjWv+DZJtWarhnzJv*w>qQCM6&-3b6?09k#CoUJg1v_1bcfod%ictz4b!ne#KH0JQx+^0hk>(xa`lty-yoyuN zvA%BA&<^97aP%T6Le_85d0b>uq9PMz*)HUwX@Hqc0|ZLdyRMHNm4)2-8r;Sb+_8S~ z1Mj8Dk&QH?@vzEu_GD`5Cn0S98C5_VCVZc;HaOi(yGJEGZUobAz=*-)#BcOjd32@qO106af%;Iq3{=phQBi zTPCAoWQ;NxIZYkXZJGtA>t_4DmC?)PxUDS)ct8KOi7^h(kK^gMcbD!eHAPaU7Ct|H zagoN=qh#taZulrkR=7TyM@D+8v?TftFBRLgPA7V2D~8i#!I>nr<`WL{c z;h;MA0{nb!Gp?N1@pgtJm&r(d{^l?N7YV=qDMRh+AC89k0anyn>?rm;;g6TTksDh} zuFa%;;-tE>Iz+I@lFm65Z6k`7!W5Yz3nxrPLKVh}+ z5_XoiOPT2``eSm$xSu6@7?_Q_utoFpP6^2bXNV<}?ng8|6!0_*r93jc8(T$qFLUmQ z9eM%|Nb09E*rBBK%~)2r52y6R&JWQfF8G8m-drOmkGb?X+}hT(e$!6se2WrRnMsyR z*w>A^g{hFg^N3G2k!|CxBQmX5z2SXvmPLilHC~D{l3zk3Ta;~|Q9%)#{&vbZfEi!> z>$l529_^THJjO?)v*(MSG1Ew(e))}(Sn=7dyi_-on;UeABl5)YA z-gPrBA=qX?{zagmZ}MYh4m4a*@}=VBanR9m5puGP2S)><^zlyC`P&i9t;5a*1}0P}~pQy^d00n-r|QG=EE+9DF;q zUeKu0@go^uWuR}PrQutJ(N;Th$S*Y5OJ#pJa_~?Gnr~;bxuw3MPetccZGqBc_dFIML7IX1{)e>;VF=O6XvC9=QkYSKA7nz4h0uSTvVd@Nh@uh zUkNjOte&$}v3ud|&=UB$Uyh!tmZ4K{ihq~U5+Vk+WCLgAI#5nV^|R}0_smF*e#!*m z#QM0b!WJ|)BM&4kVNV>gJ@a%`Xf^XS?HCg{M=Jtxdc7e;M&3)CD^bOKeH4LPGAoJ* zmhkf*t#0kGb;aFSus)2(w>mQ^eic77&`(acIMhiwT$)5JLY?%J=2M7ydWAf2l0W8 zG`N%g(#rkopqrwB=vzw)96XyC%RJMpz`q|kqRC5pjUsk%A)5Qp)k(dc0TspE%m$ycKH&HRsNew^di9ucxL5!)nQa-6#H=|)h zU_Z*^6x(#c86r2^VqR4=sIx8=B_pjkrW2C$g2vBGE7AnInl0yX65^qJ*+A8m4C)LL z!ApiyeVP6JfOp(zwcPtshi$w0d{wQ@emui{;#$gcxrX?(*`@c$P~0zjs~{kNf}R#0 zcF^#LVYlSRe8u={XDBK%A=%)TPBAI%LEV)v0e#%!d$c{k9HzOx{7PY;^{&uor`uT| zPD|kfGmlQ*k(J^Q@{bI^#6EinWX;+JH~pXW-XM4-J8kE-cKJCVcm~}Eqo&;N!55}$ zSD1)B(kedp&Lqu}NA%A`EnA|bN@|Hx$es%#r^xi#4nzlh2+`y9p`Lx4EyQU0I&^Q+ zo<3$<<*lP}ju!MV34zSw30Vc`3b}@h@y)qbIVmJtu*O?4-hOPj)9OGDGb7Z2sstCH zuG7b~tE5OfJ}&ZddB*l?nPp9oPp8w_l(^W~LA9%}xhyE-9n6v8TXW+1W?)_>wM4nS z99WB9yLTb($x}nuqkzj-x#c1(DYG!SUTDh%U5#Av8L`k{BjfnB&UY^gW1qB2-cg7^ z_C|S%!QQ}zaaA{mh)hv(!J)U~fSq|v&_P=fcO8`vbRw{w#QPbzHjb1#q0B1;Zer-k z3nnMl4JjM^07U|0XEJtd6N6mG>A@jVM|Z9vO_{eL5fj+BX&gF9#MvftpN)-O^6q1f zE`ODUMf|ze4?=cB;8si+sBCUx2QPNg%3EzQex|5n&vPdb%SHxTZ`q({ZQ4%Xz>jkx2yKdZmaNr8+#xhvI(qs+2$S_` zps`%znA=nt>pF}f1r>w~0%V&hU$l9*AAqhRz`C}EL)t@TRkelYAw70fN zcy=4_lAMyG>4zrl?9O5nHdS)ERP^1IvblBiq&p zNyfoj_x(?tF8*+fi?s_^?<+Z?GmHy6T+qN4GMSKNXDf~HG!{iV%U`bidvYin6@qwk zdGWaf6VVwzV}04geb1-zj2mz?RyXIaMqdT*R_8`$Gx3NN7}gDC=Vgl8iH6_gZaLmm zTcO|5x^-au5T~SW4zDi!G&NRte)H^MxNQhGz1Kd78Slg#`y$!!qJ>%zWp za(n@AUOmemMPF280JVuXwiKJkGeUDPhi_HsU z?4pWLoVxQaXb<(s9fsaLUM1*J#p1B1n3lQe+La*gn@h1mN=~;Ti%of^BL<&N(BIIK3h#&gw zU@z~9&*O5+*7I4ZSCrJ5GZ%5|=*{GKo51@IX;m|8+`&Ft52PzYbDD9XMtLqnO-gHy zMkd9UgSWoA;C`Zm*WZB0zqkfsAuZ47=Q$G>y$}-sjpS{)tZtC^u|09bo)Wu7u$v^h z#C}%^`IK&RWuyZS>av%oyP;z-M*!GOT(2$R2Y6941P?Rj7+ch-AQDOX4*zC+7M^F< zIvUZ{L8}mzuc8i8$4C>EJA6#W5)!Jol|&$hRgq$$6hvM zdiqH^=(}r+Wy#v7XE^QEb<@%7>-U8}g4AwXs0)G_vD6>%*g{Q^;eaJ*ZI zk#_k^&*{e@jVwWTxamc z$rM~{L1w+ktY71+y50s0u@5Z~{jsh_a?R@VlQj&_OK}m#SpEARI9)T3a-!AtI@R;Z z*n3YLfqCs>=`2b;US(b?etSVLKjQUMji~u2Ed;;xP*-(JkJG3dGWT&6A;37>Ri3VV z)myw&+pLJ`S@s&SA6nnZV8x6}?h4g2*{}%n&M{nl_rO&!c+v-yKH8OrRuTNhByMh| z=b<=@t3DfpQj*+&(5HFOi#M};S+xiaBY@-t6H09#^r7!xH*u-Z@Kp%|VWU=uWsK_; zebE~F(q;^c#u!x4``(TxrNBkL)Yl(6zO~0}b~3#_wP2AJGb#6y@IrOIV9O!UbZw;~ zA)jvF>#rDNv-vfLi2dLMRq^K0v!dG?9a(>*8Fr^#a_tN>XX0 zJz!5g4Lc(=FNi+}+Mi@p_Cv*s9A-@U$%f}z`s&A{sW2^l zuEq~o*!Cl%vm=-yS1;#kh<_MayOY>gOMlbhS!N#}0ToOMkvOI)Xoq zjnm-k$w|ht?{ZU=lO_A(rl?ZGQntUpA${YGqRhx*L!N%l+A!-nC&QcCWwz4UFLZfzwt??#-T2VC25Pal@S6oRBD11j^)#O5OgcVx&r+cA zBP&BKe7P_?v#st}w(Sy^Cy;T45nU{9$bGs*+LfZE;xj)1?OXM-5zU2kckj;`W}O)T zUQ`LQ3|eqD;&|c`P6kxyN)1Uw*m~iuGEV5lew-*;A-7#X9+eN7hGlilRuM{tNnW|kll?=AbeKkEGufeB`{><#cbCrf4sIn5ehH>kj50y9GKckLYE#Yg&E?ep78rjPKSOh>WI@E6xX!^9QLn9&;s z^W*N2$tp&=k>5{HZ42@tlACY&=r@;M_DUOxwppJK><5{rGv1&)6*ggW9LEQTJ>y=f zG4E40)H4ih-Q+DQ&DDnWPiGQsaZ>Nh_!ycN^)UMp*ze9ptKogC+5=GQd>BwS1*cKp>!KSQAe9W3SQpmq^~b0Nbo7^YjFX(rP^u5P&ECm4Nyjf-Ai7n z+H)ovdzyTM>w2#;s&zUkmkQLPrw{ucTJKv^+l1RS@9r!hgJWXtx>M(WH=JqO>*GzP zjc10m7g_=%S6O=BR$n@ZaE`2*{b%{@o;(Oq)8<4U=y^6LQRJzGz9UQM!Ol)@sZw>T zQTu0J`*c$3L|r55cfWl@x>XRMEi-OO$)hMK3#YW+jSC0oj!SFT=DR3{TDn_gRjypu zH~JVxX*e{5Jq7kkf!X98$Cer+64B>$Q%RK?o0WUsfRs$18@`SadWQ120nNID@s)pi zVe$9>frqRN{|`K5XZl}S$V9-%#=^+>KPd74!b3(jPIl)1riW1Uq88T9CXNL3qSgk^ zCc-90cEv&C3=9nH9}tTfnykD&u{=Mr zxGOt6KavccZ)*u8&*lQazyz3%fq`Kl4mkJ%mn)lkibe+jWi;uB4QR<0N|xH1Dht5s zh3&;IWdscnmz9;}pVdU2lSGZb!!I#eS_*&;t>m9k5<@AVt}CddD2pRNNLL1hz}~{_ z!qf~%(f$vTU;!J`#K>G{%TNNEzQ_V({ZarJd2u68`58EtezF5_vn!FO`T1vXZfpS= zi>QE%9G@ry6b?R74Fde(M)r>$=D%>Io7Mgm&ced>_^RT@@}K$@XAAu$#{7iw8mNG*3PpIf9!G-zmb5Ck!ZUV3W9V7}{D20A=8%1+Ip!MDAbR6H$?bD=@x03PNysU}$M(X!)>b{zpp+d+yin>o+Fe znei(OUXc6I55xE^ZememdU0r3cwq4ae{u%K=BMCt&(&q=H+!xR>YMyCPto6Rc4c^X zcJ%QV?W-)qFRch&aY0@wzT_v5@vTj3d3JqwcySgd|L+5QQK&50uhGAs1M?63%ujk0 zzd4iuN54xZusYc^ya1ap&c9elp?8JV8xSVPv;o7hfa>LqQVDsK^JGirfKb8}ebigipt zbu&-9mc&|cTIuKbdPh9v`^Q~F2Q#2p_cwai5`4`Fn4?*PIkGZi2%_h;hutX%YMGxa zH{KLz-R#2WJN^|0TUb*8JEFT?#Uy4y z$Ysl|>IeQj=FPt~PnOJnI3jD%A-)jl)8ynb}oR^lWk8xdtq2aM+mk2|yq zBm&iRYVuNrXI>b)zDq0XMB&xE&eZ;7Y8R7$B;F*g^;?D{{IqmiwY53w6r|fhJjqHaBDiHk2I1;6(E`_W@A#Ag)?r|o}7E%R@#E>oNp!!)!&!hZ>e2hVzOFj zK^CV{tlf+$NsE4~gyeM!-WLWY4eEcKkKP_Rf$g;8MQcCZ{rypf?tGY_Oc&SAa;Mb7 z!}R}lHMs)59+?{VD&lcInSZ3vR9864h#4GnEg3T3ZCozaaFLIl>x}m%22<@(6EjzX z?e3y{C3)t*A#@IN=eW7SVE=;#iKb}wVQ|?ppF|IT30650QcMFEdK;c* zU#vszU$p`tez@TzR;&@QT~TX^dQOFJ9-J)X2lCm_qA=+%YZC^M9bfzp4kQh_ZmV;w z=ooxzc^1q9OXAiZlvbi-t1B$p4_|(;Y)r)|2vMLv_$0T##2XQW5$PaT^{M2fi`0Q8 z9BC7I)V4aOz&0XgUV z`;51Ta0noYX^j~2q)bt6#!0hKPacThAS?NA*;Ykmj-gwgi`uEf-MmkJ)%+Ot>8`D> zJ`PVYiUpbk;#(Ary-g1qhm+7m2AEvz(oh-w1sYblXC9owv_J?|h}$=@IupX~0~CMX z#}rgY^P7DPafw){vheD}5$;2NW{JHsPRuJF=ewyao=T#~fa}9m40=%{R;_qU5y61R z`Qg(!&bwt?<2g#mCinXB2b2igefyv(4iTw;^U0<7=h2Zp;o3Ag-sLDb0TVavxLO64 z-B~&RzQOUc4fG~`CW06Tz2Umdr65cnbw(MI>>rLr9WCh`8Fj4h<+s8LEeA`X=RAJQ z*|vmvmvvw5?3k&_VtzX=b_5FZNMTrle}6P`xNPwPYv#C%^}6S|v|2NB$urXBFcMqgG2RldJ#Cj#?`4Kz48aAY#B1J8ZxmLi0An8W zL;UB)r74{;^Qy?M0DXAeQ^4FanSm|LUTeol6uzg{J<>)3xRIhJQZn?YQ!!rqJ{gUZ z4FBW@UjDObS^{G*N&O}+V0ZXoi2qQ>sX@pSnz#N3$r_axS17oxwAt20x8+j7I6~p>C{OjT!Hl*#BR}aL`z|`? zY~CQM4uX9atUnYp)5DC+9YGll$HA$T0`XL5@try0VUBu^q~@5;#b`HDD6U7v8f1^i zpD=DVo}k)N!2L2)WX6TP4m&RmYx?pc#<#!ig)gt&98K>rcj|G(E6QbBilXA_(kh)h zAW@OIHdMFiD(G@ilK=xN_%= z`DI!I&gE46%+%un?*rwy34+1pj>FDzp<4K{lSa-eRN8Lc$4Nt08Y~EA`=Dt?~ zPb$W~t?7Etw8WbTGJ5zt@#{N2YZ28F6=YNaeJ^5eXf8F1R0MH2b5}KU2|jHyWHZ|5 zM#ZUHnS*R&0juCzT)Hq{8<+(kCdxZ1Ld1+>n~!?#q$Dn}#?imt10_^h$%?r!g3{-8 zwp|$&OLTNB8&u}|TmH^4%jX|uTP+Pss_M0Xm8)L&%7L1hec$$x?SsJU8H*kW5v&)5 zV6cq`7&t{Ez_aK^t|ezG5LuzD4_w^|WWEDIi|`>+@1RC*L;;;6%m5kMXV?f@ig);Y z?;0s@u?AY37}O_cU9ZhS2m=NZ#gm3Kn~USQ()hhI5y~ufg)t^_mf>VOo?uKwz}z7s z0NfE-Oe^Gwr6?az(Z>;C0`KzwKYMRtr!o~E4>$MX4z$|+$+If z4{s49q{eu0)yI7^BEiI?L)8AT#=|e#V8YE>t?Vi&RbDq% ztOz0Jvu=7x-bQ^?MX%$e9e*RrMt+&=L`dCBK_`@FfUFwaUk*3z?$GF~Qy ztotG`K2meIIZ(X7oU%A*s!Su4t+1}?R~fOk)v2F z3~3rwDr%(l(1dAtmAk5XXl0kc`#q3U7q40$%iPc=61`BE^Y`mLIBPZjSFJTKoV`r~ z;cj!&ckih1Fvi8HNpuO}#3$Qy^fX#D6phFVxcjd9Rt;RQ^H;6XkGYA(varV~Ny7=x z<~?FIz*hRnt*LxYo8&lF)_HVo2z<^s9j9T3F4TV$WfUq^0SqM@x6L^DV=-qF`ZApc z8+8NW=}emWo(6#lcEy;+aijPLNr;9{)p@;Db`rgbZCidAWv6mn^eGm*2}TgOcDPGQ zCPirpVt#YLfCGXFoVsw4`#Wk+m>_Zud|SZ&qol?er|k0^q7c!${SS(M^X;Q-b-R$W z8AMEb{7wPUk+m~X(=(0;7e-~WXHhtyI7wecf@o%9i1N`sjRr50>vZ|T%l#mCh}a)A zAFlX2(PAk&x2hB5Apx*BIkr4vrn?`$mD9+B1@1Ago|EGkguB&kR4_K)~ z0j&XpQ`3@&F-t{r%X2@4TwO@)Ud-lC3m$|O-LoymF*h`L`|IQtxW@@#Ap7ACSWlN0 z>LZ>?@<2^Byo?-cB$%5@jhpqQmOt*cKVV44uvtY#XkmWbk>4ndAve}=4{fvhx8b%?hJwv)@`{;DIqGgyB=k{!yQ3deN*~u= zmB3QC5Ez*t%`BZg#s!cvn?dHn7{m=!7?1~3^Aa>)rjSW<-HZ~kiF2o;_32(3moY!_ zxg<3=&x042-)?2%wjJQ#!(7&}ot(;#_U-9%nu3(=H5&s>U4wL$+Xyb64pLq8yVnBj ze>ZcP`P*L!C$AuBZZo^WTGVnI0lPFU^KL$@ZVoscTc#J27aqzI0BzpRng8_IyVKme6ENu_&*_Fl(!v z0Ab3I{!w#vShD2TYWjOM*}QTpAa;=YjnqQ*$;9L2Ad`a$QGwOXdcso-o@B8&zP)NO zZ;};|ENetOZg$+x%EP(gn+1R|b-0_stfTpN>%ln8Rm-`>cKU`H2x@9+ITjT4Ov~*G zvwKNw{KUN_fn4pef}%qSI1dQby-)8<_0s;rupv2&QMXpCRgu>>l1+tqt|a1tnxN&C zp5AZL$>MvcvzNn=;86kE4MN2#98h`sSol~|(5?mSEg<*Qa*jf?u=>5PPvHqiV`qBX zyoXQC5IxBZdHdcIKZ<=o(nGXHO7%6^AMjP*Jk@he=#ypa`frcS!!q5Xb9c(aTw|MW zfo({SP+ZlVIa6k++mY#| z7Q_K(1s2Vb!v)0yqmMZ0u6G(i+dcm`Fk~o=jkD7@+3I1%7$&V_Bl19J)y2HmGy@iS z0=)1Dm1^e71bk@r0Dd$I?xzSyfHH|Dq0xyo>4N-2u#mgwJ51Gc6k4BN3G*sPpc%NK z7ERWP@joI7h6!uH)y>0}O;(p9jYvHAf}L#SOgJrnWCtNM_N`l^5_#(UdRrFHqky>&`S&qll3)~%d+ieD^n0i zlsu$eB}VX}BzjN~p~8wDQ#o(G1<$v7VU6Dk?}E8~g(l%pmacy#bCA(WxJ6pPcUv zREuFve7j4F>+@7ZS6JjAdp0quZ(-X`_zaDIldtV4G*GRF_1@%WI1UD&$@I-X(GTXz zj-w8=1W>!RVN|qBZj!PDaU4b)@bZ3lWA)B}S<(Ai2zBCZdz~KYjnuzt+J6gai z2`3}il}3`P8QbAJf;p`p)hBK+DN4;uHIH_~Q=6mHz#9@7owQT=&olCL6bdD_g6|(= zv0zTV;9HGm*0$kXaWg-=?|`GXI4DY1ORMY&y25NbrjzUAltE+D`B29g$u&Sh0g+`X zLgd5JFM)@~wd;-fp(6W8Ms=u%VG~<7n~M# zvmK=reaU0*-A(pSiMZu?w7jIlz&#mq-B`fwfUIDN!6%Y?k|SBxG>S;)_6NM&1Rn1} z3g0tmsK+Xq7{Dbn6I86o6pbMFy+(%1e|i08paTo9<+9X>&oLA8=2kGc6H&Q8ugaEb zmdV`(GL3_7+HrC#XLD4Bm$gyt(w+{Y={ zr@-cFIsL7Hyk=|AZ{xEK4kS1<^J;9Cd2cTb+S_kZ=OdtW^cyoJTS0545 zk!a|GFy6@Xc15xsoX+aZ5VJVwx2URbPOfJ|Bt~miGlrRhsuFnACBqC~#B6ElWlsEP z7EF{^f;)B0cXJ;RzBPt@b(6d>6|D4rvk=B_<(gzJ1IQT+#uHfyM)T<>W7{X>(_ODH za{vmmwXw%=`tId#aw3W8Q@amk)Q#lPb=3u>dL+b62(&;4`B1XZ0EGhgJ3gkT7Xa!d$bP%%KR zML;#7_L$slhaNH;aDE%dU%JjPf=7R;5Z!y$JrrpN+a#Ccph&eYA}|VG-PWouxJSSr z46dZ;eAJLPH?Wl0fW;&X#f;f`Oln~=PFiz{JNq_I$d3h4A0WefPxdL~OVK4}dHf(^ z-%R5&%>cS?Uq-y7Mg3a7O%UL?g~LuTJN76yhwt)aL5J&FBz*Lb7YQ!R+@P0&OgQbf z%$>~R$u%%Ry?X>BHITJZjOe#0NVp9jeMDDDhg`i z7{iH$LQ>HCKsO~BFh{^p=*;hi@_3i@D-R*1p|qSSQH|o!v>Pj!>G2zJm2|@;K`4Ui zK^d0Q(bBi^jQ26_6a5d?Tk^ksN_B`pKEK4!1}CcK;^_15~Q#K z^o1Io1ex->6Z@xaXcm()@n+}r5{bbOl;9WeraCaH;HugYpY!+U_w*FKLlkew~FzK8tM#L1@3 z8&;9Zw&!}idB6z#Oh!rQ??`HFxB4O`f53>$8`lxRktircuWP|N6QJvim6olayUxYJ zuVrB}D~!C^wkuA#{K(8y1jUIfR&23Je+uosV)hn`py4&y2f^jBJQEgb7J>Zzny2uA z1^FqHh~hXfP7n@TX(XZ|hd}&l6KJ&rnqZEYBvJIUYzWdCd%+gFSWOwme(?&dFB_vH z<0SdGIDK1(@N`$-*1H*>EF(;foxii!AE2^&gBJ^D`l+~e-g6N(M&A8ffdjLt_2)|O zl?*9FY**#ju$|2?&eA7@uR06Tp%4Y(!<7P9Y|um5fBW-Vc81*~kHX;npanG2Pd^WL9DL;F0V^Ta{4lf$U!`VZm9mfr% zMCac@OrYI!UA<(5>&VLbh^#8vFK#29qXitQNC;NCcJwM1#gK8DdiiyDOGzvth7GO% zS;TKqK{{lw@$XuO0%Lnk0}tf%JQ*C0XN3G@(0;i6R8c;U^+NNFwK=SOPeOuwAbWx} z_(Lx#r88|rJ`(Z-!F9gF@8wM+5_Rp9N^Ub;-=*J04lm)ow`oHR>rDWoJ>PrnhJZDO zo+m6)O%%>oSSy7fp(hzN^Qs_&3yCh{ zwb=*aHi&17a_E*@ zQw2aDfWrm)nQj|DIQAVzFg5e4BUhf$R4bAt$WJuJx=90CAgtwpi;-Zlt7-(1C5@=& ztpyul^vK`Ho8}XK&M&4-Qo5cjWtb2QDbE2&<-!3MBFhjq`bSmPM`XcE|)+vN>m!ZY{6}o9< zyf|`A4Ql5htLm2Zgblvc0t;1~N084z)Zp_b=P=G|E?%pEC)G^}0m;Uo1Y8Y#=ecuL z(8|%eOvaStQw!phevjj$e3yl#VH5i^iW$8mg|bg1Bb^%FEfMRYx8GmTzb_gUeR2B1 zg<>6C*`+9E3`%f~v~M8m%g7#Z2;@MyA-Vxpg*IcIBV>XY7T2N1jXjVV!15tF4dzD` zB%3a|qz6hsGYKt8KyBAA-WwyvtiB)J=i4o#)irL$p<8zo1A!4v$X zYmL4-dGwWe-R~Qz2+Jc(e$*cmSrYU9HT>4i*OUA7T~o=*y_cz1NkleF_N_9bcwDFEtSyi-hZPek*e7_cMCUfDZcb6T)`>oQ)SjIy^<2U}YG%oUa=H?`Y zB9OYjQyG3em9_of@02#GKAgpi_yRKl$(r>SJAz~P2K{rSYVfirhy9NfRE4)R>sIVK zEC@e0U#?1Qmt5#mR``5WtO8ZWK|byjIu^%%iQzE6WaLDS zWdEAq$xHDGjlc*!zl4hUqEBSykB)*ASQBsVC+(US<+@rSF-8B#OZjAM3!QIULkmsG| z=;;D*8o3Mj>85N7+-F^^^`s6Z_tHc*eR52jU-8A?l;m&s1bcDjXI)#T6nRB3*yMiV z14w!S&*67fRh@p`r686L?y#x;qYmCRGP2O;wE)^3th?_0$VF_{F?J#pVqNT5f*r|9 zH-waOm7;fm%3Y^`?vp3SobZ{L0Pvwq?0V%}_S=?R&W@$0(z>_T7dpA#{Mt1cg%LId zf4-selPMly8G*=evxA=%_K_{Sk1Kiq*g4A%o^Q6g6zI1n+~n)R3GN~v!CpuaeRnB; z+PP<=J&-EGZO+u3(gBGLV#q{Cn?&el-EDq-X3w{%GDLkGHShe&PD% zzz({eKbK5y0_r$ddA+r>ASkPq-mk|c7l_TraltiZ{lJAjZnEM(e;4j>I!3TXZa<$+ zK&uCn{%*$^)r~g&_GlO(ZrECK`y{c4EET}EFkLgGeN><;j~z`z_r25%FQV1l49PMo_a{+t|e!Zb$BWvP9KZqDJ)@5`UAWT~LG! zwaJDcL)%)61=7Esox}(~I`;t)9=w!cu*rtXuyDymkC8j4z&p47M5q|;XGVU5YKj+D zZdf^IHg68mxK`b!H5zifj}o_EhxNMrfdEFpykDbW)2&+eN=ZgnhHW}!RC6&1*c`(a z%la_Q*UbF|q>4Xg+_VlPodWx(V#4q?Gpm(vqS`5?ABszX2_|l?!*7o@X&3h1amCZx zK2(*ip*61~!vk;ZtKrN&;MgMmxuI=%k+`!zzi_1LoNF>X0g18*`25}V#c~pv_cX=C zD)yWcNRSSTNh;q#r?p;MEWwqQ#gjo$!P;^fct0?TJbF}{aR4oh?GB0gxZB)YR!=D5 z;$AXBo-N5jqXvPkCIx;Lk#j(%Anu8M)jL4$gy04Dc0V-2^VaU)Ss|`}x+j(o>#3jA zIcoSiJ8Lp`5T0YaUW;K#&CVaL=N(_i8HaCml{*Ey{vaC*6J0bY2^|9(V ztg6)I_|%C7w{*;aEPh6n6M2K*(?zX%0w=%y^{$LeQdElv+BG{gNzbrCoUS znS)8TMwa01rRp9?a(hUdA*y1n1OvL1Y3cw6a6U)8TdmQ&TJycN0Mtn(q}#2rpp9T=%3GKfF;JBNT2$MKsi>-bRsc+xu7MZ>g?N z3V7neV|;+ZzX%Ax@?qkL@+;`RXPmrbkTQiSr_lxWO}vKNw@QTzMxqj&ek za|?0KfIE}+Db=W%l6u#oeK>bKQs$T6PI?j6eu@^1A2VG+K0LV~OPb$W% zc?OwffpXRI!P^b`tUa{mxN zM=-M7YKnBe;b;wkE0z*-8sf#8Cnu+_I2F-D#)9@3irzH~bSrhJ#z!xm6+rGdN=sy$ z<@}+yRB#xRB(|M5V&AtJOZlSo7A-dCA?auZfBEE@1XZ|-N75of{80-IE* zq8tlV*!_?D;eGq>@-?^AifR>cc--Mr_rvdt{9kWoZX9nP770xj+6QEZ+RVRTviAYz zz74S_w)`36>M&fFmHfp+%^RBQv3yWFBDlns#-c5A(Z>3a)&)FVF4u5_j9c|}DG2UQRP zkL{5+F89U#c&%V0+bV>#Gqw9optm;u(4A-KWLXZ;NI>4odi}N~7blhSHpt3cbYy#5`baCXO@~&3` zzfec+SUrIty&>EjhQsqZybUR5{B=Z^Y0vsJ46%mzGiHd&(Z=f; zCpa2eK%%098+uGR?{{B~k|%s`4-;*6>Ni^>5Aj&PeLkFxv3ZAzqD`cnk`s)LF8aC2 z#<~Qt?AmikNRC4k=w^dMXy55d?BjFN@Gyp${`SM$VTlSnkq#5>NcgX3oamM}A%k*20 znxcHg!UBZQNprmI`|6FLF7~+Cyyd1u0MiUmc`jBIS-?N;KvO|c$M|DhZ2(jGx^jSq zth0L^-n^J*y`L62_v!ZboigTPBVq329s%9Q?0? z*r~EYeC37rflv%ab7qbLivEOHQQY=%VPalYg3MzjEa4biI9%cB%e#`Uj}t{T_#`C1 zNZ*YP?k-888b(>wA4|hlURu!NnSK}m%XJH)LShrPkZdmY$&dil7ii3_53n{PSgp+) zT64d5&z$fg6Fv#SfqmN9+9C?TeoHqycHfjK9*KR}r4qrZI7xti@IugI}jHi{jastnnETOSQkPJoxMY44t{;~yFnZ(z5XI4$j$Zrnh z9o9-do5gx4v?(n^2)ec?WUA>wn-uYC!Jo@ z;$Z@fHZJZi{=2krzo^dVY|Lk~JA-NFEyg7MNabK~UQP?%s}`e=89rb#1dYs;8cfm^ zGbL#nEB^11w~dXTGLNcq%&Ea<-)}JkQOXD%Ws*hVs%2+*JX`gn_VyhAtrt^dd_T+z zh9Ih`jg->9&8;k6Ks;8kU_sz`lRQ6u5I=2(m?2XFZ&_>#AuTmpwR+JM)$Y4|3y?++ z;*OHA6}-YmSWMN3WwEN)dDx4+UG;zQt-%2q2TumFPkFRKZz3PMty1xq>P^A)sZs%8 z!F=MinbV1o|7KBf%3ri3Fktpvn>FH%u1)apfZ`_EAxVegviD8IuhsWIlO+YHTm_s3 zH^=nEPgc`caXG{!dlsw^$kv57$Li`}+VR*WKVy{{65NM2GG&+1NqJs`e z;sOChhrBLL+EToe)Y5dvz4rsh{>cO<39969okPK-l&4Sw@y?5w`OMpM84$;}{nsp| z@Zk0~{8o>eMaFREu{IH%gTBW3l9B?C#YS5rE_6_sS<+}n-Ald6#4HEOGfr(%vHE8#amlr{zfp zt!;@8_TemgyV!<*utpzDTA!eF-|UXcR}ruD{mHrYGXA80XjZ*bp`YQcp`uuObV&_K z5@!R4P(cRQT+?0)OtQ70zi|v-4}wekMDFl`@VWK%oR37e!u4MlUPV=>%i4h|S`hgF zDE^e{2i)IP8poUv_{UekNl}g>)nD9n%yUg}h983MOYL)=T-e;Le|O!`Ffr+&^=0 zcY2R7P{wJZl9or+s+ax;@P9%gusu(>W)7Q#Tq8B;`SVO= zVdz3>cG~ify#^5h)aj#r@iS@_(2g0LPJh}6y>^=GQ9BhWs!MTC&dD$jl54(ze`EaV zJQ!&L!0clP%;Mnp?y~hb8yD7fc1HhtaYNYKY{qp^VS=7$c<4!Tc~zuXpDqpLou87f zYZIENw3XIJb0Zx(2U2SR?LMNvUD!?2CV$hj^bJcm_dN2}Gx&um4Wv_XMr=#O6UvE& zF1e^brE!DWTw-`IJ5-V-9c{OgO%8J$IrjVSO%Pjm>htKjlt$BGF(~qC#RVt`Veaqk z?bX<5(et_lqo&oAn*uqp-yzZSrJNPY)fZLE zFvez%VNG$V`PvIZu;O)jeR@MO*P&ZKuBh*)EMcNw5g^w^Pie}??EYq}Vilzr)9vd& z7 zB4&3_c8`juoZ~srus^Twk^mUMnF~NsbES`XwoS3NjM$*&6KD!{F~u|!;CAD5H%1wP z;at6qF0)zU3Z)41pQLo0jhNYO1j3goV1#S>taS{9F}m!g1fQTYS8SnD0S!r>+-wu8 zK&=-UY9>%Hv-)+!_Hv+qyvWOqqpgwqR5uA-Vb*9>Pf_4J}qFPU%v-rX>o4;r;~Anu^YDO+-foS<<~5SRPqgVBaLg zRLu$C{ii{rWq?PG=i0|IafhR(jw##uRZjVuUkFLL?-DCyW*+zv*>Hlu5;4I3&}a!f z_KF%$Q3>gq-la7Xko)}at1_N0NN!0B)SpjKD1tcpp!+mSBcN9=)g|)*BoYZ_I0Dpr zb{O|3EELHJ?z18YbuI4n`n1|Fcy;yv{jYY^)kExkRGxZ9I0U^spF6>4dUe)(S^D0i zC}YjAUo&7S{uB0V&}<%E%s>Y5TtL0)$R!2QuUO;P zZ56lL^|%*{betVatHf*ax2}%s%9PPES-Fkbb75<=j@P~?^+)A zyn2^3`H%a9@cFk`8Vi5*4JRKm-i;G;-Gqp_k&_e`!JVpd5a?jP~F`GT#CVNja{aaXv> zm;T1G!_igKLct6BDMypkeG}!TjOhZ&KWB%+SAHjoCW;OG+YstwaBpgYHBM{*9ACf7o2vy zutNI;qRXF;xe_7u?Tf*b7aGD$8E_p~y|epWZ|ubK^A4mFYzbd&A8OXGn~lsC@>wSO zFaFWFmI}}_=2?hG_zVUy&eFR?CQuS$Qg7h6YDha|%ZKSY(Wi`0#>6zJ@39h@F2Xu} zw@2nOx|gbn0NW98q&!scDnhl6{yGA1tVwU71Mt8_pZ~4^Ry!CE>!}$HVNda1)IV?F zxLlsKAbP&03k5(BkYHl{`p>uQ?WH}jFSS#gsFq?_eV5npV<3U5hG-Cq265bm$F_fNs! zbvml~6|rh3kf>5x<`Dr*2(Br5zD^WiGN9eC+KKPLa~}U%*UIlWsShgtCY*43RlapG8QYR}C4`{{UuhBRE#m}F8Xl1aDzF=hlNNQP{ z#N`w>1qJ4aOr6sPWov`lLegM&p|kQkNk}}|dTZGhLdfoKW6dUxME4D1`8sX8D{o$7~)%nD{;`yPHuFJ>~X2!sH$cu*yLU(csdgRT42p{n2@^r%+H1( zM2EA39LMv#`jp0TOhFlQ#Y;-__V431l*{~cHJNf}2*b3pJgdn{2#MSK0YoL_KMaZu zeQD8rUKvY+f(n+`7l&mKX${(orc)kX`2KppTW!rf)W1estPitxp(EOdx4Hc|R~H-u zXD{Hd;_(Fv<~06MdnXiYPHkz&w{E55pGCf{F#t=pCMSjjq09ngqtO`Gjm8iQCtg%s zhZO-aXFZ<7WY;dd2zp(1#TD>5km%Se`eI4N5jEB%BAhxQj?p!qTz%p2v3#Gru@Pjw zd#2`pCA>ohV%pDf?q)QXXdH8|V;RLcx`)7{ii@OdWa&}dA`$g{xGJ}BIKPH0rD@$C z8naf84W%h{Sg#d%`&mh!^kdzkorHEV?~qP&9oW@&zY6e8wAa5Sd*w#jxoFm+ID+cQq1Fd zCxs9gR;FGvG~B?1Kp3_Vg0}kGZAe=}3AY&UKoq)cLBABW)@oW-30KY{s(I!@(>bi+ z+`cfpKn3FupJG@S>|#*qv}e})$n}Rcr}NgrpC~}EcjfE;>|d)0E;Tj?&uy#NV)^Su zJYHbVw&YY^$#{015I?twFPV!zBI<&pA6{qUtRK{b!(kP>ljT)ib(pmcj9Sf3&d%@sp6rRM&tG;;ilZnq%L zjs^7HqbbzEyzbSd^RedSi3pDVqfm4zHlk}NpHJy}mOH`!UA{}jKtKISPSmRC1K}w| zS0u^HG`>1_odOiKH6JNq(C5n=*8`3Ns?+38cV{bsyQt<=%9GApKKwnEj~mq>Cojkk zr%ARl*rlz3h;j<-T-}af{J*WtSX~wSAv!CQuN{fUi-H`kr z5tsN8E2GhnV!|OyIJM*ZFq^h*t})LQ2IOwU@sr66M7hldckxb)$&$S>Bg;*s$a3-NnJ5Co;%b|3kp%l^ZfX)055N@5oN^Wnq3%7_LWf)6BHc-xjdA@53_<+?WBwd)?~f zFt_im!(2Ov@@Ya=x0X~h}C$}0%EJ|rzXp0yIR=c?F`E#4^pmI>e^&cW4e zd7bf|W%6|j2whO&(FE&yCThy%7S6$-v|OSr3Z!gC%0UpcUDv8`6X6%tz-Q5O8b|tp z`&kKPs#6(yk0iYU7$?T3gH3k;HcKJrslh75Frww$!_ly&-9#*P;!`T;B(ipdWIsJ@ z5M(TLbXk3l=HEjRB%d#AJ*6XnmNzJqE8ukVtcd5V?FPL132>aB%kZ&l9fd%2LlUBN zFAPO8-=>PZItBfIqH)H<-4I zwLc|~o|rT(P%G6~wwM4>BYz&_PgdigHMR(?;#d`>5&l+abDhBfm&7 zfnuB;h$wwYgy~IMW_3LDjj3IXxOMAGIXjMxx0l#+OVGaeB}Xj})@vJ)SkAl!;%&Oa zh%poa1GWwtQb%lG&kZ60QDK>51qSH6&)^;gofFTHdZ;yP$)mOF-!?`a^!`cxDfozP z49jjH+&THoXjOLMk*tMrQkwqXK`rGhEV4R(UPy-0+X_V6LxrQPsso!pk@SF4F;yv` z7#UXwoZ!-#0tE}2A~d+pLkSEb?BHF}H%{y&rU>((rSns;|2M>f>Hm#bu(AH{H0l2X zv0!In{9gqA{|92xW$aM4vr3DzB{?p+*Z7}ak;{F#e!kvzQ)2v|WZ`ae#p8X~yr+Dp zuCMD)Hde!Vs?od}uZoVD*pXY?Touln5E&Plmxx_JL{~F8GBW{TP+}fPOpNRZg2k!5 zxeJtwSYG;0`m?&1R@TG(AfOu(8AL00H%r?D#bXN>t5|H7{+{`RNw z>>wippe&7S9>BP;y@VEbpx-6Ak+lK1{)f!w+W2RGi7zDgcMq)aTTF;LfMW3qzd5?8 zwL1X@QGn9e-01EI#szeIEfW~m24Ki-tsIci&AhORV)3cpk{DasI{ruh`$trg6Z^X; zJhA$X4~qGR+~k7P?gE}grN#9}+?kp9!msqhT?hC*|M6YD=wJ0`3HpAfBYR_0%lm6T z>>u{w&J9NDi3m&SnDwU_>|Z`=BYQ1FYdZ@_HTOqhb!_p;ALw6>8cXxnEc{pcxR(pW z@WZb^H?gs}gj+By@mEi3_`UX~FMan{7!rE3-Fu#qsR`ghBXbQv=0>LmfXFIaK3o-rY;6TZh)USAJNp(NjAcABFq&7JaCD8(R(nb!IySY$I^OUJV=rEsBG zU~1t{2=HcErC>%I1YH*cs`t7&AoK*}j#xM807C;c^>YI+-1_v2AG66g&z2EvVIv@R zO{CGXxz$uA^-et^&_C>E;=ab_T=5}bgDK?-+rrI?eN(0FT%yK(q5ie`t;>P zUb1!Bl)?FT>}txX`{sx)*=D-qtXZ#wJ2s4}Jv#%iGJ>``nUiD;##M>-=>^y6d;Mg? zcto5(PH^!QZ;xxaMokkGG6pr(x$|LDdNx@`n-wpomepN!mB?y0(rtq{Q(;O`zZmhJ zL7GMlyDae7p|m{Ie&&Qqi4{@Rb!9-Ww_?Dj1FoR)bHe^$csSX%s}j5(ldr-8Ms`)Q z$0=aRQrfr%wJpgAN?4nNE1zUWW+4D{PnXul$NcYDXp$XJKM`2&WH9k5tOn)_?^Zm} zv;_;w^&v<>J)%mXgy5f(8C3FB7oUsvk?y7wL<{KP=Yhb%0@tZ1!%T*c zW_1=*!>^3RvGb8e9Fv+;-1&-%QzN6b%xfHHuT4rqg=$ZP9U%cZ_cI-+^M{;-C4zlN z8J=%&g{RuWLw|^>(B&Ae8SUFy-#vA)GxmlBy{(x`f3?IBv`*(7ojY^_ZZh6m`$((l zOCsD?!?CND8=m(-27c4yZ3%edmD`G0%b<&?LEM$`_NVfZeOB-~n#g1(7lO=h$&mP= zS+0yqFy<>NWTu-d<8Gz8pX4@MPecqKDLTBDvvdyWuZ?bZtYR_nzadt+;i~X3DbeVg z3|h9s?KAVX$J|FZoYLZVNn#J`NF|HPKy>LZGQ43}iK+0@v6vJlV8mIDApPxhZo$EP~; zauT+d2Lz#Ak|Lmazl=A0w^B$r1D)#?4QIjswp$!hbp3mzl?PBi zTF}$n+ED&WPVG$V3;^7?F?h5J6eN5(9&51tO^@J4Bz3#52GYwxdnUGT+gt8NG zSpx+ZFf{OmN$cDh`^~`{*|gdi!d0cau2CQ&aSKrD#PK*T_xN*)DpvXkvE*_IDaPSV z;NeU|2wrdJXo89jkVje%w|gm(##41Y!7rh3J4!a)ajHBo;rwbv)#z?ksS(95KHT6J z^BuE*$}8$y9e}q$7^53es}Hgns43mCOwK8(64oeq1^^4yF{0sPKS^_-Ti&J0nmqN?O~( z{|wH_cHS*xpVhxa+v?GBs)KdOIp-#;#BE1>qQkp1jb#4&y|UgI6@0wrHqVMQxz6T| zNgJ{r{_7N>m_x8z?f7e2_ITf=M-gG38ul0`o`V0hEi!)E1lQNgxG!LUTvi09C!jr3 z{AU@VJkb^msSnB|KJHeP$lMZLVEx?`3hbmNu;64-==C{meSB~5*o8_-V<=$D_KZ7y zyKib|Hlir630of)Pq92?P-0zL`s1=`4$PMSFT4_g8r2(q5i;kqSX$aJRf!o>n>0)e z;Zo~LIFtp~sS)1B+(1mcP|aq{RKceyxfe@{K*X>_7y22LE^uiV8(9^PHzH)Jtd<+^ zdWDFwqEX}IxV~oRB>DG59$c*wY-r;eNOp!_EE)L5XS(zJ357SExKZ04Z(^onZ1c_w zIrkhU7H3^(>!Kn z<>aLdrL64$$zz718WV-JI6eYS>(pWu@7t?txh7MMvuYGxKbPnS~N@X(j34P9(_#YE& z8e{$(dB4k%@Q3fzDQH9hZsW#&pSrc_5%B0C49{Het zs4wgj;Ibh$3C+(@OWFe$*UqlD_mOd6C}t^d|Btqz>@7i3%P##eFSi-Au-iq1Ox_s- z1+dm8p696A><8eYRzw;0~`;{qQKpz3d)(^^#fQiY~ov|HC(dM@UYQ^G) z1jl%e{?|jPKyo0sJZZ85*O9aT?j8-nGvbY;>Ss9av2-NoW?HT_%z0^+PnYxA)HTkS zzKO?F=jUVwdiB(Ykn;yd4j$GOd!@tqhP#creB-7MM-zu~Swl~%!P;C#T7?_~wh-eg zW!!G9W(7JQg@*G#5dz$u>K)`29>d92th@)^g7QY|tMrs1xqCM)?L5~8R_YP-mWO~n z21)|x+gt53OK@A7yU2Z3Qq!$9k*wu1R3oL|{E3AeM;KEe!d~GLQRGGy^lfXP6J(!J z`}FGy7Xyw9G#islo-7-Df3w=ZHA6` z|H>Z1WI-Q1c9b$qt>?D*cfQPN@3FTTrH-s_=zkDG_Nq2B%Sry%kU=g)2MlH7o2FBPOg2pNY%vi98g#iwOFIlLcGDUnPVh;~p;X zK^1)CbAt6jV2WpFrcu|57hP1f%s({i^(Pd^O{_;cnem96nGjD7KOW~;;-MhOnLG;TfpZ*;z`CWdABPfY;Wl$jYP&QlTDc5q;)0;17ufwOHz z3uH@4TsGbd09<+sKIfiG_5=o54gyNVFzS@#`DZQ>(r{d~5$I{~hZ)DI+?CCyE(1Ah zH?U!l59H)SHh)pI`I>g=9V4NyE9Z4Yi;Z0B$Dk3iJZj6Ek=?CA>D<)d#HiXszz?V^ z_fy=pL$|^Fvh(lH(8E<8mEdhHvnuAne23xe-|H2_$SZwuUrT)ygs-ZLlGSTXo+4j< z9KGQ7fa!48z!iCY*sWmt$cpYa$jG57fU}htzZ!sER(x>CsX2svv7Hw6DC6k>Ws~$z z+51o9>M(Ad!#gfiFB2q!fLvfdv8gSSj__kAY6y`W_y&yL-{jlB>UP&W1sSv&D>Et@ z{Xy?223Z1_hW{v>mh^Q_L^1UiPH|Aw%~nehQddg%x?heLpqK7e#T2=g>bEvNF?NSW zqIV_ESvW6Ja^xwp&Z}8_wvw)Y1?kFWthy4jP5RU3wlJaal!}&qo20zZ}iQ=Z79 zb58v*V*+|h0F{7*|7yGuNy0Ml=GH%Nwd)|Uj$p*GG|C6QPXiWn+&@!}*`k~mkW`0b zA0NW+B9mr{+Tq))<0V$UhjrB0}F0eLHqDy>{KJ5~b*u~j~hRgLo72hNGB&5--jJXi{OF7#-_KDIvkuo3pU6k5Uu{B`6X2&|=hw9xO` zPQv7PyLY0A!K#+HL^GA_)n$GY_MXeP@5;`MASYk1ynHb0!b{2rW!}LCb!azrbG+Yn zN0)#8Z^p^4L;P?SP$~&Pa?(4>MyiFds85?XAuoTcdURLtSa8W`W#@70tQc+`0-JlRGDg|=_^OoT*Np5Y^M~0s zsA1!TUaQaM+0j)^RpsH@RjvCzyG_?!Mv9$u$_A+?KYagmz?TQgw)l!2>mbY;P{APS zLdlFX{<+!((Elzp#wE#Ro2=S^-d0dpwB#02d-M;qY;#oy8I>SHiXr&wnwqQM6>qw^cGZvnjzCVaz(7I#Pm-FQKf^#h%hfee!tDC#_-u<^yA7`8; z)kPuH_Oq$xzh$r4v5~Vz)0Bsg^aKf*n9&KW?YRSyP#j_HbV`5q0R`CR{%B7zBh$^N z6K5YKFuWqWh!hj?t?JZ|?{ysu^~~lGoFTvh-whVfEoiBq?O&VFf{dqOv7lF--Fm_u zgPdz}=J3p}|Am%fLQon~E$yD_P*||oD`e0>2lHfVay9u&^O*4_IyG9{=2ocwyM2D- z!0&^&)taiIQYFi|W1rJ$ljAaJer*LPH|L!}*7935%o+g$zT*ONUN}CLDTU4Ypx(ad z6aj}x_U&Aeybe#Z^VUD)AGP1-j$|~4qG17*G}B!4vNoQ)CMfk$?TDY*AGHXUcb(ty zg*A0O)iLfk&*c0FX=a$oXycw`c@V>K@spyh81jA1<(-Y00RdAQ;YNep8CUxhO4{^j z3DEQADMsas=A)t(nU`Q>_|Z4bTczG(A&E{7Mo--AhpeOkJXk{A%kdYZ-Z!9j zmZtV{XeO9ZMR+*l{!7Q^^>qHo-}U3_!YyXemb3a_LDL!v;ivpq0;{r7iyX6iHH@xg z&cc)mgRM$N`!|)To1=SrQ3e_f*&Q$rbtQ{yUv;r#*KB7@><74yjfu z??O22DTH`pQyh=R4W=|mTm+A4bC0QF<*QuQGvHV_Q>@VQw?yhix z?9!urWc<$NYp^k3FM+j3cr#XR6z#rTg{Dv3g3LpGfwpz#zGuHJ8eB(QA-DSXH4R`=KrHdz%2Rz1V>9Zv!zXrSwMeov9Z zOM=73Qce{3@UKn1zdkcR-(T-OnH1P2!}cj-4zw|PgUAdsGwhUIwDfn5Wzr8AvEIiM zq*RQNx}>^~1eW<&m}k(pza}Hf4?E!FvO8=!^z|r7kmXW#q^p&P7(MOw3S26|Cbvm# zmQhb2q@&7@A7upe>tM$O0H`RvG)Bu?Z`9;asUhI7pgb zY3&`LccV_lDmw9*jR+eDt)OVlepgzEe&&@tFiQAnaB`2jna(iG=p7I*hn&|{Gdebp?hR?Sp$%D(6l?{#BJwXB zyrn6{@b4o-!3jZXtWPeq%S)k|)EK*G&pQ(%LP1XEw_7h1(lGpri%=y-tlci7m!QcU z$Br*~Pd%wFdRAC0!)@Z39aA}O8OB2egb}W@8M)9boY8Qm@7v5acSkDpB-hO9KO^rm zelIqYCs#_5I|(P`eKgEM;-ggN7@A+_u^U|o`<_6O(YE7Yv4%(CA)Qz3s>sJ(ncO$+ z>br=vX(K>kaZeY&l2gi-uiJ0IY$f1uB-pw5VaTN<* zV-`d%rMy~ikA<%ipU+T^o{kwk=lD;oTl^Z4Ge0TM<4D3=%^>I7EJvyUgtMF{L+;m8 z(L%<3B_LJ+X?0p+&tLsy=^vE64z#*Y1pwyol~RA zfe|yEC{}@hpfPbj!@L7PCa$SAAVH@-e~e2q`C7#0|B7bEMO2|n|KI^gb)U!P$`XW@ zME!uxhi`1`uNU5WyWUwxDuHVmtr^vlvl1|C(87V+AjajP&Bdz$Dbx2>9|R&D$hPrw zFA%}rOnaG2&hsNOC}1$ZQwZ?w!-u);nUzB)osgZY1YFUytGIYkq~BxPZJy`^YAp=d z8%fIjD3=|P>6;ZeV}vM;?+90L9o1*)`!%7E%d4Dxq0+(!B^twd16|%}UeHdw;ZU}n~R3WIRFZECL{&{Pomyn*du23D# z53DH)(P49Xe_=@A4P_$|)y1_ZrLJ3$QS;tgGG*`jj_FS{zZlA0xRD*pz=#0#B5I^3 zDgl}1d|BSGi26bn?=&3C7TOwp(T5#0bj_AFNP(mfD?F(jZ@!pP!(lB?b|1weRIw89 z1^3pMuX>FwUiX&r!4+d~(tk>~Ct_<&QfD;@GL zi*V<|3HG3XXZ#m@(y@PDCOL#XX@MDQoM_79R+;`}y?`eH=Dr-=@a}fbNo4aKVS(@> z49>~tzBbu0-&V**-v(CPC1H63iVmMZtzZJSgpfTTX?dxUCq=buDKB7jfdNB>u@(=k z9y3T$S`vR~nwNAh%e<waOvywWcZGBpeHNn|!9_!iGFV=iHr$+?lW+UN~iEhwvLf=`oLg zfzMQ}OItO641+-c5`8@~@o(h&u?T01Lq?B_1`RP$p>opnXZM4ewEzK_-pVz3k{;B9 z0VDB5A9dm_=B36O+COp)RkbG&mC1=)R$Vp{A0?E)_}nW8e*x}V*-JLbWm*Y%NqXFaOVJo z3W6X%%{?6nF?8BU(EGq#6#`Z(ybzjeQ~I|x`m8w%sii0$xv8LB70pF)MAkscKyEUM zdE1`QVPAAo98Q_>F|46Rfk564OIOLbuIB!nT3MQIqkuUtW?P_7)=hMDcje!>3ON+9 zz@>`3dVzt>9$}&18ALV5VzAooVTR9pt=8(CQOeU>iM~LxJ;~?MCEy(F9pRE?IZIVn z=IIM*>^TV>ZdifVK{c{zb3t|Wk^84<7eC`K;E-9n#_6+Zi@u<~NyDAEgb@wefrLkQ z?ft@Q_aJFsx~Ex91*&wd;dJ5~zB_*uLHWcD5+2|KYdB95yCT{*c2N@FsK};z8u46D z{?AM%W!d5U2_Olc2+mYn98EdU*7E3MX4V4}y#z)Axbh?7kG#0$U6384 zC8o5Q?ENS^gh!XmouG0E*aQR8HytUaGRnNqkZ8gng zbCoU*wl9()!ol&7LrMJ$@{4x3f6LBoVfp@y$ZD0dYADQWCUBI(xGS(jIB!ef|AZ

Lx#b%}{a+(;NBZ&ACygQBRD>EcAm9)zwuu|>p% zRCXGN2Nd8#k2kdiz$KppH?2J;qu!1N4oTKE)-UG6ObXS|-N6g*61bP52Vp``(c|Fx zY`M9nf1NoI61qDjK0Eb&m9{`Sat*j3{<^$v5w9d2cD_0r*qNBM`T7a|Y%>(j|8Yms7MmV-Y zhn5?0pan@~znp^Or$qs}4(Twlxf+XMThIKB0@GcIyD>dsD_#gN;2J)g((1q3lCMYE zw_$?8-*%;Zx06wAb2pR+MZ*yUzUXQg*!9#m&QAx)v}tSHW_8lHs!X{lMKPqP;zN7< z&8PY2>+W4goW{m=+;ne_B&M)zP-6ZPLwMsz(S8(X!2@-_2k5*E9IG^KYtyak<(nUk z!_mf>g5lK!%n%$9mG5>uG#+CD6!MjL0c6!YJ|iaF3?G7JXQ&Zb)6JG&XO*}+6C=xo zBoSl!&TsS#>ZTi$w6zM>Cf(GC(UZoQte3U1i>9!4)Eyi!o0`1>NeS^PTiC}Jkn<0H zY6$zmIl@!w+#_`k#U>^Z*PR+zLFHzQAw`L=LJGKErpw{4U*67x97WxHEJv4b=q>Am z$zy9GzSzi|p5RD|RSgxW-R&HA$+W_{9js0yfVmdqO$5al{~=8&e*Ky?wZSXnPGQ_E zj|fyHTDnhWS~S=z2uqHNek`fytv^HmdrqM!)_w@{sF@>X#Bg7KWoEP{b=<0{jN+{} z{&|cU4H50Xu3bjtYn>8U*-%!EiV1F)LAk+p$;u}`*^BfaP5W<_-!*c!ms}bi2DC?u ze-ex`aUhBkduaE9jfhB>FNW&OjkF5F5`_iFbF$NY_?n&IW}Q*u%Eeza>Z+m5ZlJiJ zN5$-dS(Y8gOMW8!KmU)q;F6KTXURg>Kl)R4>fwvsA)nHx}D^2KivJ38=#VUA&Klg zF^i7#`M((>wX^96o06(_sE<3jO$O1LvKK7S3ai%63i_$L6u~T`p_R%~J^uFOb~|0p zH;_#&Po|>bwcr&S>Gss(=%{C{TKec&)RW}9wJji)DO>I}2@gBjJ~YybS>nsr+@1Yr zP-$40*>X_-*-wq@$1VcXQ67jK}*u>qoDTjaJSUYjdqqmef1d6S*}`o{#Hy?jW3CS z8*%VC^~Bsp%>8EM9Ld>L)~|28gb_ctd>Fh<^HMK(9{&F!>>hYT0op79w{6?DZQHhO z+qUh#ZQHipw{6?T-fw0%n@u*E`U#cFn^daKbNJG5=R65IpP_qIi^=p1b;Y5^^HyV+ znjQ({?tCp%@(5oWh4N`CyK1iofo$dirADD8ANVeLqrt~<2GP!Lpc|r6`%?bA`rmaS zO{4XnvUvXWYK~IF3!*# zcYDgL%iMzBPdthL^ooyMVE!;f5f9j)_S5BBDgT`-T<=Okej^ZN?IM$qa<>sRVoOVk zAV+^^&MQS2GENGbJqU^!CD8_mH`^l%YYUgpENjPPNCb)c2bxck>v=}S*~}F z9lQEyeYwSLm!15091mYPW4d304^hkN>!v2Qo@5X4hfqfNHeYr)x5_i2lUUSO9rA7f z{hT<-$7B9c$n&e`{PVb5_|u|+`+COXZ0K@M#)JE+L2}IrX_J#-Q`s4?eAkyd6CS*> z;e}K7`s4_UIlcR3hwFi)x`_4JtO777h4&nV3kM@<1od(;+{0`GrVqJc;;{!#LM}v_ zLNsz8BnkI*YTsT|vvPzjP#o@1UU{7B4?IC+_o;sAHD{3Ab30=6x)@559uAmF5Gl{4 z*fCuLGGK}zNeHjB{l`JH43O`cZ@AiK7%#InESlk~L1*4}q?|=zJ4)^|s2A2%K{Iz$ zX7gMas)-+?rfBua9Bj~nQ{|9uf`^$yXj|Rnk_ptPX`8&Sc{zu9ssA9Dmpir0ZdJPJ z$+_Hed1NDLk+LohMXd5rXx{K)jVMGSMzA6dHs;eGy?6gqU$eb>Nt?er@e8%_JE^`P z4J5Dh?Al+djX`GX+$f3mRpq4UIVhHhqBFY+KgyEgZ?#l6|?EKDU@#yR8mb4mc1 zcI(VB9cdFKB;u|%pMEsGH~W|Lv`Af!DT5IW82lYV!hW|q?+9r-5xpM}J9Qn%R4@EW zLr+1PpJ?7`WIP`e8*KHyzrr<|D8A=&s$+9A&_zM-w&mpHZs?q6-L7`(c?h%2&SoXE zv`7)eh6p4lf4033dM1c<6gV6`hm8=|uh$h>1d9H3Fx@WyikoKZo;S|5mY1&WItaa4 zX}I6#lP!VU@byjWSsiDY_3GKtQ*&A|X5Ku?P3Zc|dUIGJc#5cr>n9EiiQwnUH0d4B zxt)XPR<*Gv8Di{kB%P642PM8why5T-ibMxt)_65;=JR#o+s(#_;Owk}N* zx@2xvH9I@1WZZBfxgi*-NJoHU2z2n1+-5*F;!&y=35_P#ptenJJ^#4! zG8VhXK~@Bfa6p|?iHUw72=%73H@6U0hXnqr*kk8nlhFEJjG2fS-W@WioNP~2`9Gtq zW&C~f%tmUtl20mO{M0GTs=3Z%J7CI6r)NaEhOWE=V;hs7v%AyLP(bxnf0Ft%9a3MM z-oRmU;ryhT#A%^6KK1ZodK2eiKL%UV_9uieJGy&ErDhAl?_l;N90m4`=>uBj&Y=lk zb;f)9*=feTb&pGnmVqpHVl_kSv z-CO$YrAC#FeKg!}c|dZ!>xTR#4)G_i$zdv5jk98o#X1RbHxp&8w{CU17kGO9d@uPl z&X*<<{;D0u6W%rA*olkPY7UNetk^7qlZe)82W#WyB;99jG=b%=UX|~I?h87++8qkv zeaY~I?Nj9}4}+`AN=1;2U!e{0rfb=8Wt_xUF_c&PX!eM4e1=BA=tFYDs|e4EdnEbC zodkZEJEQ=$$igo&HFdU0gNu^fKI=O>nMQ*P`>EkaFB7Zm!s2|LhRIl<@%~HI5X`E<)qH zp9|O7+Lw1YzYB@$5b#iXzdPkcM+_-F%TWEQJO z_P0};sLn0a80yiDlrw&lrnk#T?iaW(W8DB^O!P3)dxxK-Unamp!=WQ7&J$W<-z5y- z5a_xKFu6Zk=ln*=2i5A`sJ~{T*a?{4k>Ie-N4oa|O)D>yEX_Ws6RsZU-=>msm)joe z8O1M|hPWA#VzF54+D6rOcM+^t=^3m-q@bF5=#P=m|k~D9qN{>8-!mS$AiVipw z@Go9fkN1ee+fm*1*Jj+&2Bfe`zWQz0D$#nmJD?;7SH)-we%e_&dp+iKjCY1T3Y?dB zZ^kmQd=kQ4aCvM^vqxNHm96|Z6J1E>H;j+rSIV}0*aB96k9{URd!u*|$%~tIp4Q-N z7e<=}$<_i>G9|w`T9d)BFLvnyms6}A3EX2&GlY)DGgCl#B!+FufCUZ}5<}Q3#=e1I z3HpS81v9(A6w^EErqvl*GV#CEzaGFL$3NlFz)*blob1h<#ZI%WrI z86sZ&uS2KrPsB0tNma66f%h?Gcdg3^D!#`#Ud~$qD+D3Cz8!GaNqGc*OWVF zt=sMN->>Be!I>k%ns3SVu6LlDQ6$R&97N119C_y{zv*BtiWDXTwORg4p38&d?4gi_Q@@}`#N6+>f!8lxRc9e4#NdGoNBJXE}xkX!Jst* z$4%iPyD%=lle+>jQ-7tT?-qKY$|8}IdNQ&*nO0|&ab8;DQRrzUy}t3(``P5qu%HFq zVrO*KM{Wd`D>3$0zflEbTQeg^+_ht<-EH>o&R2DjXeF#`egP1#qxq{bj6?2Um&XWY z>)8-6h(1s0H^H*i`?k*Ds@5((aO}oBOfO!wjPn>dgn#!1QLs3OX*8( z9k)O!kFuwQpq;hDL1f{q!wTvbgK2Wjdc`VAt2Ru@UNe>o-SL3V9V#8N!k1zEG#YoV zoDqK8+>2>=KWUE2b(u&hQ^pdUPc4z$Q4i0+q9dREjuR~3NcYH7^QJPmB4`V6ZS7F!BW}@PcGL;{*XfhNICuj(o&9N|h zj@w)WE3Dz8&=Pd`bTVsi=6i4VJ+CM>6WDi=2Xi&F^2w#}KV=$(t#BXNbIni#J{*!5 zuS@0@2?2ji=Mht?_h*FU_B;r(CPuKYANJr?17G^d`YmO`OlxITpyv7psApChD^w(< z&RyCvAk%L3@c-g(-|!K8E1M9Al~KPNvW3O8==#t<6{`8nAa*hy{WGY*xXZ$&Z|yZ# z9D68iUNhyWI;e!!oIGR5197*Gs-G7KiziYTUh?#oU)pLUVL58EWVJ@J_w|-0@d$3g zA#3pd1=>q^=WFnzDr^!KQs8aI!Z|~_lt|Hb4D@Y_#N;7$x{=7R-BD6*X0?exSm1gF z;EoecFR$$e`fNaI3TZ>UpFmR64fx50^i`N-wXHT;4)^AP_^fcHErkCgU0GY3+Z)VXa$5$-pKK_EJ7qhNA6YqLG2>0 znxF1Uug!BfH`$Z=8C6{NRw64_%!K5X#w!Nx5e3(l@~iX}(q+a?Vqf_2!bgJ6f!n}o zAWS%-z7P|{ih}8c_PDu=XbKCgHz8?nf&6|@^H}gq!!xsTIB7ld6doxb>3R~TNg}!Y zEQE>$DMAH+6ZWXVzIF(ZAInTK=4GDndw00N(EJ&TG4-xI%?|k?#-UzUMGCzOnA2gxYHVUcE##SXfz(Q_!$p`Vgtsg zwNE@CHGvQ+*F%0FuX$M0lb2s-MyYoj;^p(Yf02WQ&>ey-iWz*I@0gcszOVA6cXb)( zzb^+FWZ}wkpj?BT$Tt=4#BDEcA0KUuB!}T}0zc^B`-?YtxP^WjwDQ+Aty}dE&=|lNwHmEEBGQgOGOtr6>q2CSxI4xJOtM7?H$xc}&&99}K z;j(2dRNsp7r{-ZB#6MvgMjllvVk0k@-f6m}UckQ!pq4S7#n5q`|305$EEA;^TsJZC zxK+=c2~7PA&hrGn5mz=(_WUY=)SPKo#oz1Y=wdFAh#b!Xh=r;VNI&U3$xTlgn`tWj zeV*eDac{%fQD_C}<=#K)#q>`wJ&Xl$H7pnPzA>g9epr0A`BhxIK&4O z8|741t<2XO&{M6V%|R)ukC+b>+l#Hrrfa=$HzxG=-=L?%(L?x-grna@S8*cH_V!z* z)7T$wtF#FWJq<(^H9J6HE7_BXaLfpGC^K_QUeTSxW(1}Tp;RTs`T4`aYpXI&o)Ssa zIfzPmDsJY&HI8nTm?DUb;18XxZ&xnKY2o;j%O)%miU+WmuDJSw?4SLy?Ux&!Ul>^BgPZ!wSh$V-Y?sJ}PPU3#I3Pn-`+Bo1gI&?| zWQ%@M7k~VNkYgY9S^Mj-^QewDaWxEe(i-K?DA)tXPNdR^eunehw;gOpxVW;Uvk9Sd za;@Bm8u_Wzk@q6`r%%qFa5}*M=db@0pO~{e4{+SH%3*brR3_iwL5WLwhO!Z@lY9U@E9ZhsklMs)!xTyf%!rL8e zL^X_~FIY1g>ER2}nr!MJH@!>Lfk~h)&8UJYxTG&(VJ=Vrx-UasW5@AwrvvfACOX-g z)PIbJE;hJapppTWw1Hx7*KjOU#diKwnu*LX9nwKS*M>~82Hv2Mj?PFKuopCK_KmZ45|GsU@z zA3r!fR!T0EMv!@Lui9(LG^{AT#0@W5?3BcOu;~Gymy0QTgHsfN@>opxDi&;C3FY3T zLKjB_`wEBLz@Q3mV~hoVjkE=bG$}O&yr^YiOw#HQfym`kf`6ga-QiI4lBz~r-^-0f zzG(%&WJHj9DFA~m?Y7Gg{@te39;m@cbhSH=Y5~1^J3S_l=WPJm$CFny|G>q)EADkP zkXq-t;qY+tqz_Dd$7mqIZIXoqoLc8}Tx0Wa62>QZ!VhENs)FTY2`=e|{RR?YLP-aA z%y|Kwxg8w(*9zG_S$zrhUc@t~@K+**L8_rQ3f79%RCC9m!X7ervkcx4R)~PnZk~RH z1pjQIFhXdKY5zDbn0aK1Is{jGUd5V|fD?yoNHpr$g8cY%o!_eq-x=_Ur{4;ZPYP!W zRH@bxD5$MU%YjbRsvciH*!}CdoITCA4%1h4wVEK0n~#hT7Pr}(hzz)tLO{zlXc=sL z}9elJvbM zM^lVhVC2rz90c2wS;&sy#xxiHzPY}GpuT7F%n~f(3!63YyHR4=eePA?Zvqnj(;-d6 zF?#cZzH&loy~!LEPY}$3eke{?17UG~JIAgFp8T5}6+7G)3EsTbjdIyt@2%6c;-2eat_R!SJTKRsG~gP!KIyI1%3OoA>kYtR~y^ zy3jUFKjl|Ak=sISZa;Py(u3|d53Tiy;SbFEMU?hbDCqur5%s0hlICEpr*vWHxUf=d z7n}7M-jDvS)aeJ;;J~G>Do?T6dAWQ9euAmf;*;A7Y=s6iB&UNjmsa=2&%z6Op^na! zmg(?k0<1;*e-}Q3CWtCalNNi8e+YR~WqsP%cd!peR@B~uQv+1WVmGQyiAY6UsQH%e z^ThVT+Tc*BRQ-{cc&@-ZE}#Tttms64>qXb~yTx-B-=}UN*)Jk8f}N z&jfM|c7`zNDX&ZUjs5RwI(KiJf{3c(#~~iVlij<1-1jnATagQcO%{OIK4o>TYfIib zj}vSt4NRXwzR&V>meC;|y0AyT0n(*<{g*$JtB7-G@|O@5qrj`8fCPee)sy=j%)54z zIaHG~Zwe=y(Fx3=YYV}~##zh9R&-*WHiR{|7H{*)#~dkSH=K)-G43eESsHMfEzKA> zNc0*7EMrMmo&qHOrG~56K5gqpMHolwzx-+*ecVGpkg#XvDsSf=(n$)eSBD7W2l{T_ z?Y4Dt12>>+W&GL;obV>rG!DP_#xua z$UO!Zzcr&Evp+-5Tq~AehkFluO7iYa>QCqZQ((Jf44EfN6Wqe(mW}pJ;UJ9{xIMAz zVMF)+X)Trel5eXo_2+w<2i0w!vuMN`<5Bt@sS8f$m0J;cd-1AbO#eV6AKi*jH#Wui^cy#cQ7+Eu@U@d z{m*oVZL6^ZnGV`Ny2CBc#ReO9vo(LM^&jA|&|vG5<6={FxaDqkGhI`6QT1qUe7#{^ z*Hkr2NRHUn=B)Va0>HGy%*=2PpfViFnz_D~0U!fY?QnENBqu`fjpm2#-2OG!$oP?O`o(|guSp*Ns{!LMJ^dfI1O30; z4!F4c|F|8Q>%bg8|J)AOxBs{uv;T2BzKaQ2|J&_Y85P?ZM}sIpYG`wHa0TQ7Ji3w% zlyd_x^v3?@c7#LE&;GaDQBx9o`rmGcPRxJYj@f^1N9NBzw*#&13E-dG(fRcsw`1o2 zxE1`8R(`eSJ?jJ1;addO%)kCUF1s zz%0<7nc3_2?>wucs}s;h$Cvhtzu9};@2x8k5N`mP!zJ|#SvR5DxvgQUpV7#pYC`j4 zQjfMa}PULdD;+KDOk9=$7`hr=nX`ObKvM#SGxb78*P7#5n#l)vQlFSq9?UG zJt@hm>F=s0iVq+6pv_yqJKyE^ zW4Rh;*)@eMYz0TJ_+tF<)*Zw+4_GYBpm89ptd<#vdYl!*u^m%StZRXVJ#ZTnP|>VZ zhg`XSV}jGGGD}Em^FcAq56T(_#>W=$HhKiu_UVT4EN)Fk+*;MU_A_2uP~XoXkn5-M zD$5dUm_-|!6@0qS^+f6;ogQn_Mo+(f7S6j*lbUt6d!gqne9!7Cc7HnFXT1J;k<{Yc zoJC^>6g?)S0DD`?IOKx4Qno-vf(K<)`wOW)Q7*9iMkn~xWJO%@F`&K_8za%GZ|QW~ z*9l5xVWf8gLx&j3vv(LbLJs(Um!ynD%A8KOTPh?gzP^3)iTm~k#; zvr&Sf4IaZ3$Cb$wUPov4(kYn^-YQH3!xVq%(@X=Ymdd(@q74M6;Uj30e67oS|NBD_ z7B4Nuav*o131^#lyuw0YK*y`YKyQRev`6CgcS!g z!d;d0qEi@D@(g1)1zLwK2<~(Wl)=!T9=j_&D6JvFw=+N5Cj~dWW=x3A%dGT8g4LwS zd4l0w-NvT3VxamyK=Z}d)&(N{>y`{AP0UG7yG`m4s4c&-<}8LU0;7cl<#_n?t;0Qo zBd>85g()9*!^TX^5Z7z8u|=C!*MHFb%WLzUHEGT6WQ>+CduQw5$D4qh1~L=PGof5v6CV!s}kKl<=Ykc<#wU@o?FBFgP^#fNqng{gC;coxmc2T9&a8i!WAUk7OZzFtaz z+?zA#LN}0pkdS$R`2@ejG-2;V`#c+@rFo9h_SU%~^GB;e!TE`~t=LTy^N~`b6HbU| z5kLZR2fS%`27>nkHSp|uKfIqAAMpT8!kM7c^5{uI@N~+~F#Uj=?m!|XdnC!5-NfH& zILz>fVyYX5=e3{&bfz|NcF@Dt;@tc66=%~AX&95D5T{a-?S~zCP#c`y{zS>=VpzR( z>CQ0ohosA1hsYD2E~59@s^TKnySIg;xloMlF}FIODe)l-Ia_VfdSEi!QkEX0fi?y%K#>n4P@TZ`Tad+XleERDp8LG5qBzV60qa>W52hjx#y#`k|=mYag0y zf&JyjV?=S}zLRhvnZwvwMZ9!!m%s3($w^MnAUg4m$|*isMmYYqZ4a%K-sfF~xjvcd zD^?6zg$^v%*N1z)XQDuwL-=Q$Y)mF&bLyV9d8+Pec|Lhjh@l0zEoVwzcd-lC@vhOG zGW9P)cI2h=$&$O25uGrgaD1n{_W>cZ)2&y+(F=qO>t{uOj@XpWq8-nvEoR~7Zfg)A zuaFcM-${Kln+}vCqDrffL`Fz*^o>A3$f=a)pq1T-^qaOuC_8nUmQ4EDLXwEYpSIg) z_?TL-z}8~3NZacxQ^+I-^q=ty6+dxFHES&1(3incbQ`CK7ZTXyau5544Z=y}h=f+8 z!y{g*%MT*?UroA)g3{Qx{`zG+HkDf1D)Z-Y#=MnKP5uz_vR(DXmL^EV-imV~0 z%ozgLE1lXE&&9o5@u#*PJe$pw%-+a&Cm8X%hKWvk{g7+EdSh!DrR!fagp4X+XVDh` zqZpfG0T)rUp(YGdX2hw87{S4h@gQSiJ&Dh)od1@GyCWaG-Cepl3wl($bnY_)bBM(W zVGb&nvp~MYyWHXbwfGuO{nm%vtSoYss?1KMAA%!~6^@N=RFR5Q=EYkXte3n47iu{e zB6DRf3WWFXqrZwi25r_H3->N~z1EZE4y}?n9614f6=ByGqktl`Sg3UMII8zcA%cdn z{y6;DyWeYGY}esB==OR6TFQcjmikKA5BcKJQ-|8;XcqddMSt-oQDJU}Pvt4eOy2Pl z7P%i6vU%_*RZWQscO`B!X0|_7*q)`cBfbI|&Fz_tor)$%vk237b>f8l1FLu8uRJ0~ zGm*M1I&D;bAGYvpDGco`P6U|3kj}#!=AOw`74kXNWQxtd+y%t|85&xc1Il=mj3&$_ z?^*PiFS*U{k~dST1m$}u?iVCOUaZ%xBj&!T#)}a!Ip;Aj)^3JD!7@$4Eze!_;=`&# z1>L>NY2?@23N#dBV=&j=pYk1ah#;Hb#}y1gUH+8`tY!4xkjEkhM27RUng@GJl;GHx zP)mLExSVJMeyCk6@FeN_KsUVAB?1C2sE?aCF`$v#rwcl!hU`)Q(c-P2eN{RuRG6~> z)SW6L`a4gZ?5);G>7&afOMax$E`#}wx9a$gJc+cBH>fGGAh}!RHYjWrNTZmF?c2x+ z!a32JwlH2D_cYF5hjxBi{YjWw(n-nrjfZYvIO)g?b!rrKoHr_TS0c)Vyh&3f#p7bg z2cxbqoBZ?Q$&+5d zg}N*4B%1>nSEWy-AZ()!5jXJW>MvbD=I)BN{-{$g$_N=3r;+8vS|=S^SCeSAp@*=% z{}HT#!dZIy^H-7Cb|<~h&iez}VA9B~!4^8@5otT2v`$5#PH5Xa)44`H7M>3^Pk4 zE@zZ30f-`)8+k42bn0o~86F=f^RJZ%Lr>taQl~|<>f9z~XVCRNQ-jVF$H(@q zlJ4$c-WjVxTO`7PqTSZUa}p%yw9hGLb?nW14COkjULjP~xXDzqvDE9%&WkF(Ktdg* zGnM%y)Lqke<_=S>qbXUnE%G6E5z*n|O~k}IVHh3Zjp4xP*#!ly$;h`4ke;~)GAKp( zHup^!&^;RNk55-b+jRyY2}^6Z4G`+i{*s@VC@^jdKNl;>d zUOk7atYH1!40jwt({fqyAlh}71A`Mcg*tUo?tQ~6QcH-9Z?k4nDMp{vkJ$)jwQFZ@ z;=~DCj_5$Ev0yz`5YDdm(6~ zhoEGuxxo`pyQ!$pKidgEXMF|@udCWhb}$g3LPZ*Zm#7G;OAa;Ah|=$TdKz?|=-*xm4)@s<4FXydV*1eZ{| zu&JEYu}alAVXlTwSmPcMo83$;CCv3te*(&){VV5J8!21-!w^)s6LJZCsfsfECC8>S@Ms)TCTkafo_B2sW_G%G3o2DYI`3S zaa9H+nXr^NcG7KQlUQWEGlcg%1+HopkB$YCly3HS(dWf7Ys5sxXqFQp#^jB|U85(e zB!oNN+{5NlnLbln6cmk2gLaH>rVSu_yYHvSaqH1m=_E7AL9P?r!zjd0J6dIG`>=Ms zp$mv%V7Gb{GQ_G3=Vhx^Cc2bC_XK)qPcX`W;A;=x-|=nGNnfZSc8?YZdzT&rV(EGz ztfDvT1bh)8y`r$60-E|As0zH_Y}4+Kbg5v&SX#yi0{j(@a1eha**K0JcbS~Drqj)C z1_~oxxjb3<+Goqn@btbXzasjn_A6wRs4wC02>t>cy9vjOrVVq-Xl+e%(T)#m?w#{s z68@*aCI0GtgJ8C@<5zJ+ttF~L`^PtU=Rfkq0UBd|+sWs)wO91@+utjzbnw^s+npm6 zBZwQtDQ(Tv$4{4AQ^5ajKwvb`l(yJfmBYs0G>DNsU~1zjZ{V+-RklDv&*Iocb$Qm?#@>e7Yl=KTzV;1%Dv6Zi^Z zvtD7d5Zd>V8a7x($w@xm4Ms;bHSptMm5}k&OLg|1^lqtHA!rXv{upFLw(cHQyBh|$ z!63iya>~;eFnTV;Sp1LX>szxO;20EN?%(RuAo(mYs(s~wK*;UXn4efpZJ%mWj`!-v z!X6&V7owq-XpH^R=?k&vAt` za@b1b#FQQUHeS@HGZwLO)HRO>5a&(hLwipm1!tPsSQZ^A^(GDOU-SmM*N`3mTJ%hj zs3MjmeiSw9erk{oQF+~x)4a(uQgcbOf~T54emp?#M=YYO_V8WyYc~X!cq{Rq*zQFk zwkSw0HHe$(Yc63tL}<@}g-`Gv>Yu6PH*3Ns)+}h9o*WdK-%1-*O4|puQt34PD{JvU ziNFs$q(8G7ALjwsJ*_8hyfhDo)60~w>l^+9m!Vk>YrL}lv7^TK$K5SZ_g*~@Yw($g zA{XWn)e2Ca(ktB)TP!O^)Gmk1rt|FYvgmi8jv}Ddk_>z(bMz*BepM{G<3B?gwLP0(JoRZub zm^>VPy}~&FhFIBD)GK1D7t?WNn9QIAn?ep-G!<02)jZRT`NEwqzTBC9&x%f?s;&{n z`)L@j<=!DjiGAjzYwR4WW{Gtl$M)H$pqUqTNB`77IzCWRK5&#QfeRx7*Eh?%;1kC{ z0pHbC$6KR@R;+Z`F!A>aR%=TTE<$E36?4DdB0Hl5tx$)^(~p!N1=>m8@l*nu--sE!aU5%*zd2 z^t0ZG-mt-D>yU&DTU8Y6iL0henfEM_{M9L+nqDxz174@BZ)=UMop1CX&X7@&BnKo9 zB&~{WaK6TpER`=<;AoBq7P9CBR-in-IuC6U6n#31LQzVn_`-gIyjI_1w4N_yg*zt|V7#I!RQdF;oGnc?C?pPgE&;83zus zPERN|Iv49^eApU7`e~i)-h#CF(@Ge=Z;>u6;T?oE`))r?_$XmBQ^JEX;<{4YQwJ7S zX~P~r+9Q76a9JQH(ZxBv68rZU?6R=jbdKqVtF=M$z|*4c!(^1vZ`%@c_icdPbsXy_ zIbWR8-!y2x5#r3v1O1M{Vfm|}# z(tB56%eljh!3}>&3?@;Gv}OVrl|XX_%(vvhjWq(2V@IPKd$Vb>2H-wUW}wMaGC@BY zD-tnMJ5*(x)W98*{#6@5l0xBxlK8tOJiEC!Dic(Ph)lvuPYWdIfE4*`G~ZHAZXj<5 ztBJpgtxaRsx)(Po z<6f4CFA>XB9K|SC4y2?(es?e?1}Q6$qwPuhO>G7EnStSNo28FWm^uw;S&0OXS-M+? zy%oXjt-4cLg2aPfIihj(8s~Ray&kxWd!TY%d^oPG(RSm3z3t9%<9pvackF%~bu=<6 zl=KG2uO@KZfS`}KuHAaj+MgvzS^{ramF7|!h;!?U{g-n9Y>2!FBPom}sqG6%0EGvw zO^wmsz(Nc=weRZ$YBA>M_B|g_`5Nz|tKyA1qvHE-qaEuXMH!IjNAb>pEM^IOu!XXp zvQfH~DMC00IM=GLK(bKqg(620!mMVFv6!C}osW`FEsW6!;7iOvg2vF*%D{sN+y1Xv z=Hxf-Iueufk4fvEyfTfFUrlivCZKT!o?o!U;WD(9p^s0#8>hrnIxG$dZfoFR{%yZK z969Cv*ea_<-X8%Se%lBd0Hq$$C&^1e@r-uul{|C>9}%v79MRPK7vm19TU$IPB^vou zA3fC~4YFKrxdYvRMyU{RrDV>EmA}*4xzn30uhVm;?TPt$eeHTi;^1E7^ zw45`WKg_p}h*FIs9q0S8)X?f8UT$#lzpv)TbC1Ofy zL$K6bJL!zlU3*k=P-O>B?&ep{ir%pH34fXu$7$hV&q96ah}aQI+5D|0T4oO$`&c## zvWKvxSmax-GT>ueXxi{HCjV~WtM-la(!tA^Z)t=lM4N}|WvA=Z^89LWq4CwL;`zF?%5?edcE(qM-?kH#z*+G)svKv!&v@4-AJ%9AoU#C+@jpl)6vhT-$DIFaMQ zBk)}yzPQ6FXHDm+qv&P^=k}VJWMVgMOq}lUSzip!jODM+v*h*nJ7+(JV!|QWO)TJh zWq|7*TN-gGvI!5o(8=~2J(pG zw$t7N)1KKU0?6V<*tzUWn9&bep^kO{0%jLBndK<(83@4Q5Gm#ucs^Am;ncss=r?iG zGH%zzVtBKVQ?-k!{*k)@!LeA$Dl0LvyA7=`j(mcR4Ez?{FET z0qHh4N6%DHCPbmaSZxe>T-7>Ke?*A`pG@KgA=v~0hyQ*l#AsK>jq=tEZBl@e@pzIs zI7sJ(t3;2_NIF86)pV<^ULeXLg^CbewuqSWeo5_FMmj%UY3QPTc)(b+Jr*oIMLns~ zVSMm{70S?ub3clVpmb>?b~ki15^@|I9L3WaJoUC-OE zQ5;mLQ2FttyillWPe%DW7GAI?LHWUW# z^PQpz$FB&16@Ehe*258L0-TPTwfC2XzpxF>265{XX@{}n{_S*^UMhpHS&4N}mB?^^ z+1*8H5pas$aoc*gruoG@#^Zoy`fSeP%RJF*<@p2|sw`2vX7d|JM_W9MCtLcsK8q#B zwV%_$Sv$4A7$M>{#GOrBZA`C77^JUtfpHHR-;-LM|B|eV)#LHR0y&}u9)gXNC&G(Z z5F)rsucu0Jm09vIK7i(Iq~yiDdz@0$*U8Km5k6SdLskec;HLt*PFb+p$!w0q85ZAq zJKCI9D@MD#GSxzrAV^Kmh9HJ$(LF3(xkXnVl^eLhQuo?2y#S)8!=^A zBJN!}#fmLofDFWN=Pno^;+SHXD+u9b&H)+aK2^%~$U_=M<96MCBQvAn(i+WGbfzV2 z-+If~7}k%d$dXo&l?mo6w=;6e5n?L7^R?01;iODK$nxH8%7YYm*+SA zKW0?SUD$`Y@tvLw`^F9U*xd&fnRRB>#ef7`2d zoUGLLatkw_h{pKS&@CW6(((;VZI;O5P};Rg@Hu?{;*G-5X8XR-K`cyidgkAo9bS#o z+qLroRHndwC^d95e#BmY^{xQ<7J#9?k;N`r`ui95=SVDX0pr4Fg{e1h97-8Ed}k4@ z@v)D^Dpq`ej22x?XkMQdo_~V#$g};0k~!Mj7RRSd%HLo9v?9j+Ov_6LM_|Va)2@%1 zsPKy(g7gzZ$jeoBy64uVOuK0KC~g5W^|g+g{ycrBW z&GyaFy$Q`0p$7gUseEVgkJ7s`gX|LIL)y+&&NepcaBwDoNFn#SA)p5uOHV**+9$QO zioXk2qNbezQA4;I-bQ9Z!Q&q%s@*}JhkG-|UtN|XPZTW6+p;l~XJEvV12Lg)S#vhJ zXIybVYYOt#=n#CJr7`}laXq2ye5i0AOg-*5oxl5XR-~JSnL5vJj8PoJ53){`OFRqh zI`9L92K3KXBro=lB9^O`Z5=Liyxu^Ni$hzaAnR}U;I}~SkMCB3GRB!!0mK19;zD zylbh!&5j4?szf6;g3G=s&0`TM&`weYB94;BNUPzjLj4uhlT$$<03Oo;S<%P`W5A3A zjz<&xpt=qJG%h{~#1^$j|1`T1WvNbcCx8KB>Yb$lB;&9^|q6+!_iF}Z&S>L$-jJz%tM|Jm|x_oN~xpa zV$mnJ3Qq-6`1D>Csl!FA@C8DQ|2BOoiOx&T!e@d*%I@>d@}mJ-v$LX}2_C{P>{qAw ztKULZg(45;Ae%Kq8%hOR)jPkFg6JU5{UQxgc18<>zeAc>*`XsFA*`NOn%8IcD7uV6 zF6;sh7s4Z61^Ji_y0oXAuotdmsY>$6*o%Z?Db4?ugscmcT-IsokDNi>o$ySyS)d=X zJ(!9%N;bVuyJGg@@ve}0*MPfhn%4TkV!dZ}oA@cKM0@jmEg1na-*#OCEK{{CL233C z19aiF@DA5w_XfT!y;SQ9iO^eR_j54s7^&K!PG&24yVk)PZ*!(@0tGs`<~3GL^;4o% z`4*`XyQKNJy%3qQp}$hkM%@A_&kR3CfR9t6b^-8Wh|Q9u%tW1`k^>Og2QR9$PT|LY zf&WI2r%%|4e#h9|W`cGe5r@B4i^>?LTg!8&Bs|75#zAJr_ni$pC=)OLSNW}*o;daP)L|X*q)?)_o^ma>dq7)2?{CI4SIDWRD#KI0lGZl9TyfdBYzWfmDkjjA@QV3m83f#Q)7?4mVRO{7eqPinXUo~%+8`p zPMuBB*j(?gF1__sW*C8w!V@CYtA}F6ZOC%rg(c+~k6mllHvq!i9<@OAfBN2s5tflx z2_^KaKey>}jAauBSlK->nrTwQ27IkMX8O&vqNmFUxh92-*ns3@WA;p2 zPv$BpcQW*javkO=mt>f>bR>M<&(i6jy(g}cES}0uIHO2P$J}5}nkRUlqu-_hzU&mq z-@=z6)kb3?ywE9Z1Kx~-AT);0fu%)y(%j&5vW#%1bp4ZN5m};`J<2t4LydG>9kTZ? zmiu6R54rs|rfmSaUb^IVz4_pvUXrFarsm*j&j!e7h=7}`19UK#P_YRmNpWcNvK$we z(lELFcR-!4RBH-I0t7;&}D`LM1aRy(~b$P|5wOeaUw-x;|r;EpUcPE@Ke|?+%tuE^a(&|40p`JYOY< zt0521KwP=1I~0pICpmcLMtmO&w@!KD%OrxBQQZL2hDtTjk^n) z>LkK4orzapZFcAlpWxg}X4CrqYhawGA@5s7ov82OtNm+O1XH*%OI~Rn+4bK`Y}9Py zrL@IBl8Dn~8N6vMtVstRdEtEG25X72_*fM{Zg-hp znfN)pk_Tinxe>a7CQNB-q_cMld8D4}8HSb=!-U!ZO_75f&t1WCgc-?_1+yx7EuuTx zs}94B3Pika_Ba*a$ep=g=O4_+s;HQeK{hu2Bk3&Wu$TCp*!EZJ8+3w&7q+S!IJ+q6bPubW*18vG)tFxDTF?Z9j z8CeFge>KP+D~hwS?Xsb1gSrehgCKW@+V|qtjMe)zq|0WcyiXgS^?-S97WoeK0Rwa| zu=A@ua!CcJDw_=0^36&5c8w(ZU9G}UH=JBUcKDY0ZNU!L$jrS^9Nfr?*Kw zhgDBtn}v45)Y*_rU(P3B6AYD=P*poWd*U|5DOJRYe|h8KWXOM3{TG{&ZQ;LQ=$kymP-!;(=N-bx*FZPMe^`YDa=}~=R^prRN=oHOz9*U z@H%jVMRM<$bsg>!44I&HKAkYMVbxom2|d8WwOO%sajOi5j6Bvnq*CEFNa`k<^eXFI zXCQ)bp_=B3-vm!E61y+Rx@1C0Nh)+`b(t{&Yu;T8mEx5OvQkQxPVr9Bo!DOB_7l!& zkfk=9^9{+&0~f(e?cL2};8U@~B~=6L>~VlMmxuH<N=8E340P4EYTH%kZ0!w?Iamu_%FWji( zbEYq4q}?-kwFo5r)<>G66t^Q+DvqgC&S@&q-&}k{F(+~Ek+LR%)Y=pxRJj{IcRFU(spu#q)1VI9H zizm+AJmy7)<{^u6<$kHwT&Dw$1kRvB<+Ss-oR?*;?3iFx;dEmqaC`P3QI1v}1UIsf zdc9rwxG>%59>d9jg<&b2BcNX`k*1Y)o&Csi)9|`bL)iQ5MY2n$PB`}`mpFdHCP+_9 zCeg7=6h1;!NljwYap3)wPHM|KZ$g{<<_7Y8ehmcNS9Te`KHyUJ)Cg9lSmwIwhKuj` z4ea=MHREck;mwmCBE&XO%Eqcs=lR+!BF;qzRRoRkX;v%Ek2uHX9#m3F>uOt&_b7Xn zr2PIjh;Yn)Ns^mP;mIs{8(#KftL^xXa_dRMjZgmW3&|RoZcA%vK=hu-X%x#9;>Q^k zVU!`eV+8&nn42tTUg>Lil5luC$+!=!HpN=R)9qn&V{mfLVM2mbT#renP`vBL9$eYh z>;w-|v}6mamgjO`3P9o)q>7kKrh;P2G@@?O&PE-&m%X_#Z0&Q{XqP0cUtjl4+)pmm zwpB%gt{|mB(P)&M0l%PU5ETUDg7@>!fMyIcDf)#==j2x4~ecPT&+D`s2u=ybI^!B~wVHsdBX@KiDDUE*wl$ju`S|&9Lej+c@M)2n- z+Bpma) zVMjsZdoZ~Y>{vcR^lRM%5@RTKfRgvj&nQQBKiuPbX_WS2R=%B#D4mjD&aW}7q zxwpGT>;o|MlYw51*a!mbd`S5Id$HuUj;4AGa_AQlLOx-OWy&HBB~o(P;0xv`!|9hN z-)32~*Fasu5u(s)Ly1qf-$jI$Z1w2XPHM(E;xt$8x{O`d?>Y3CH$=eLc& z1HD8`G`j)SP6CgMXgltTx&W=Z+i!X-U!HLE6AdV+!3U5Ggzn!*ree|?oPKK2Y-K!!d zGR%+$y8u<(_7(Y7V(;Cw*LArbTc-VZ6ddj%P+{yK#UZKp=(#P~skQ`cwRYEa4H?V3 z&bZQkeyt;(_3jS&I8p#x9wH^B5w|ytNYcB)HR%dW>F`1nLn^qpjsYK{K4uys@Pq-W z=vV=IrrMf*0b_U!(fk&7%41{&VJ^pdW{ycP(UmuH3#SavbM-}{4)?Oj1L>+9{4!?N zS^i{(+$rDwafTJ`Y!iweR3Ecv=+72^zQbYkX0`zO z^mO}WYx+S7I_#z`XjJCc#3OfB*VF_(wDXu^UvyQcSZq@PaTN|EZ7|8QB>b|34LyRfnQe$u=SlcBkQ^^yoi-bb|G7H<;_37^l#%^nXqW z=h)tQzwjR79pe4FR#mARPG?lot_%x`P}|s^7F?VI7!?>6m>z+Zg;7m1FfcL#p`WYo zjg1Lq`H9e`ytovI(DK{(fz2W30XYHCGXSSyV5IMj0T8~x=E$U+pwa?JAXWJOcMxgy zKM-kWJURC#m-N4bND}`~h@|u%h=lkbh{VjX_^bIJh@}62L!`j}4UszkL8MnctGw{U z>wgdlwC#)TA4JkM`szLNRsIK&g#K$l_`e|1zHZO|f=Fw>z?mJKU#(BE_@};4faJgT zagchD%%7px7KTK&Mo=Jf5o?>AZ5;sF0RKXi{A65y4c*o8+rH`|Eh(%yzr9_*lW`6V zAEV#|T#vq4hF@?-=hQamfXvEGPVb`@OhlQ!)E{jBb2zwr3{aXz+xmAA?rSvG*Jf#H zXJ+K_7x#S@{g*fHua>;Bl6c06FVx*_Lt1utcX@F(2mkOf9$j>n)Gzo~XO)@Jd+zmn zZQ8%;2fy>*V+RphnG{?A9FY&-YVgC}o?j7<-&hiAtJ{6)(V=nBJVSjGAo}`-df+xS zcCTMP2WhSBEI$|8U)HZ&^`FdN&v-w6xIBohi-c|n*)U}f$2D8N`h#>xv5a&IL6!^> z(z)aD8%rGINkAyYz(C0@F6AvCSCD{ne#4&ZNbB;>l3bB{{-DD9aP)&e-6UJ7y2L0a zJ}jBG62Z042p_8O7wj#h5Adt;t+eTum473akgC?*O<5LVjJ?Par5Hkvuf5~OG$E)S z;am`vJdn%OH+28>@nl#WVMNXqP#OBCZY$T_1?=GjSu$b+M;7e*!-DT?xSr@z-(hZ! zxbVz4-l#9E94v{3vWM=+Ymp$h>W)zurx+y`SwdlMJuX&(AHg!Px%lwlZO3X<(2uzc z#lx*N>O_vEa;i+&$LpbNfr-T~eQGApO|h+zdd^q>RpL5;+m*Lk(boLCxy1hSbYzGh zsexz|+<&ZomEeQYsVvnb&Vdy=$G2AZj`LFgEIb&aYq*WI0#W8*47D_L9GARoWvI{K_u*6IxPcs8*iDGbs zZy$627LzKXYSx>9{$*Z4$}AJ>&$8Ig6GCStYxCaz2X*JOa*Hv4il^?B#Y41vnt?AP zy=Rn>!JQCs7t4Aq#6S(3h{)kO>B6O*@qKeI)QrscJ>p zjQP~Ifrjzu-SJ67|JmLvjZltisG=ZO&%!G6^H(>zqMR{(;GVS5hP^=+Fjul`cztF$ zALezGT7Mtwd*g!^o|98R5ZaXn4}7aD+*tX$?J$%2P4_=e|&qtaim)=_eKw-w~j zv!z_{4FUN0_}sn#5yu!g|LjmC1TQJHn6--G23bt1#S=FWeXk=SpoUQUvn2lAAZooo z36_yOD(cCmy(*)>p3}8c%Y6 zd`>=9^sLgK9a19^c!hLmW_^{3^3yR1=}WzY^AxsrP|Qx6z%H6X`HnL^XQhjhy8XiW zq=Gt&fuX+#b4R!)^(qN*f&hFK7@jePFkU+g$NhTU$s-m+61U)9-!d}rg!waKtw#*Y zszx6CD|AdtA7-P6VI1epNo}xGyWR&S<|hV78`JX1fB1~!+an4z-1F5lzOB&v39(kKvGIx~5$~P}7~;I?rrAyjN#yKijQA&|MDV z=9o_Z1s@#2$cm+gY|9kw&^3`wnfZ8-(?`$^Y&;1j#GgRwko1LX&zcdl%sncCBq|QFOp|k2;!*6H%R(V@ ze>;F5dTYWc0W#h_uu&0@`GNV$J4r}6OG*7`Z*M3Iqk3;N+&L}N@(Uxgb)iT)q7*^P zT^oDT%q#td@ZW-l5`Hv!Z0B>cK-E3gJ*4OFTKFZB9CI=r+O6bLy@Rz-oA*nyI2?|> zXU{)3Ec~wGdRSWw+Y}nd?s1M>J2NmqXtLVNg_Jch|=s^FCr z^-v%@|nT8xE=`Z|rIet(zROvB8Ltt3EQ4yvwQp-ZA3rU*4%?){xfykADH z9d;8-b%F)PkvC)1eZz29&E3RppqfC_Oz<(j_eaxVr9u|hMcl%*FYXiJF|4c@E5G5J z6xyvDl8&s`QZmf(KM@WImx~_J5d7tb6*(*cv&CfC{36{d5 zBD`iVSY6!d>unP`XD1I-awyAt5-P4tsi`SK!Bqkw@G*SqM>d6xH0TtGtOGSj2qtB- zlWbYOfu8TOkK{MyLL|^9j;x(;8oEC;z}$2$ETFWSO`o+snr#a_Gz!uvw7kM)+*43V z=3#e^F)eb#vO$;k6)_2viak%iA19U+fXRpQJt((i-cMJyqD2iT zqwS+awx~bruAkJc^A1n(yH*Pjc9W!k{jHa4d$`4<$gfhJ02sACRac6_U8?khU(JU? zxg(>dBks9t1L*QmvM<*TIFNgRx@2*fZvpdggYm?PJ)$fL&u6)k z+IWDB*h7j}mCR-}wHyyY5Cz)&)(g)FrV#GEKU<%@UmP=uGnu~uPgDn~tiBq%*xO$z~ z4LDkKu8hrOE@$5rj)RyMKxVw6SCnlIB?P_PqeRu`C?XpI&f;M!5XRqJ8XFqWk#MO* zZWmZpUbmX}*o$!KiNSym%*T$qLqpA=k@641Ax3_25BXkzn#fa*wvpA@%hyuh5)j7u z1?<T0B8}2j(046sEj*))$xWmEsTvU&JD{ULDdlXi~w+ z<2!E}It@9rjB@At{&={51<7B}FjsmlYGa8gB4UoiASnfkdCpGI@fqBw}M?Qwmb#J!(hbWz|e zWxX!Xc%uM~O#5QbENjVc-$tA|>V2oFJ1>!Vawc8Km8@D8N=IyQkiVzi=FytSdkVsz zV{Gp%ZetFJA#9T}wcm&p3wR68QZg}@?XhoQ;fS)}SaHcZP`kO^U`n-eNggZzS-O&xo`L3VI-H@{2k zF%yexD5F##avcm6nfy}d!+Eh7dz9+jL4Xcf5yvyo=e-Us1$%FzCpk?&pKLIeZjXq9 z8@ZemoeVfMgzKfAh%j?dXNDXBO4Bq`ubl~{1MVi@Y;)j=s@f$|c}aM(hsLuPxUBT0nM#)I zu^3(Vv3SU3Q7Tsc-XcjDHtk0Ws-{{%)P6uzArJ!==AL~t$+>a8cz_x*8R=j4OKTx6 z`_mnlTq_l-B(Ra$xxLwjS$9eE{v;idLcW3p&EqBi2S2jjhG~u2+}ZRGKmkzmkJyij zgojI9RSFl>LRb?nN;cMCK!3j{pKZOOk1{2#^a&btuI_AsV=Rg{9(2Y(E6<0EbA2j! zFhpU3!f31Ym{Howzo4$6!yRbPi8(raxEE+GT!=jD9Sb;n1_4Sl6I`}BlZX_hp_9_w+D}g2s&J=q|LStmcESN zZO#N2>v^n$7`X{rz39OBAek6OuCy5Jh;{Ab#V4af3C=DnIsdwW|7?s73-n-3|E4Gl zX)VlV(6@G$tZ$%?h?)L)i*xhpc%T5{H(2}N9w7d;u>&VYkbo(Bbj2R`w1bg3vD%{sp@b~x7?Q{_BwC-}WA8#kOJY~nJj97|G+x~LXqke4 zHOYw3S3S)O*>LC*cpbBK&h+r^J45q1-5zEJ(VHeB-`e)?w)0i`)9_4b$1L0{1UZSV zp>Tl4wu`SdFk5TXB8&Z0EZR3`B^`C@lc`Yg9TO$5=3|1e6ZjaN+qz=6>I537bN9+& z7aGEkIgG2;mxqO2fxBB`rs{Hrfn!g#mGlV=U!@gW^v=qJPlkc)HFU?8&QGL%)X0T8H24C>pYE?SBaIz6LqD6FCv~E|}tgJ<(JZG`nfn$VN~b7@zxoh>6Z2n)#JZdnk}x;&~}G z`dD2?RoM27rK{etUlNE$@PQr`Gm=6dDY~RnxOmOfm4EnnyDkWU_P~f1ugb4`wieWw ze1n|RZ!O>?Fe_g$QE{hybYI%^8_R*beIT(^f0GMO28)k+!@d?+Q@+A;0SBoOtDz^Y@7C&||*oi?%*mpxj*~W|c<63|Vy}vEQ9x$Mb~v*lEd6AskY`$yz!6 zCOeP^dU(RSn2tU2l_!HYyI>b9&N>Vo7ZQcWqlV7QAeoGA=rZXqItB*;+l5JAKVk>+ zVDS8YhF3j>uJTn2IJJ=UmCC9^Wj+3#n1}Bg<77rO!qkq9ZWSa*e;IvBdQA!jAz8NC z8c7LNQHRu2P{?VL47qiAD=6d}(Vq4a226myCU&b34n9be`{#!;@$PRM2y~Eq06#bVXcycVpGx1$>GT0d`6z%^)z(?u=fsSKNw%XjsPt@t?rm<3Piez5qnk9 zI1aGv-i(=Oz7I4N*;GHQxUSMyThAjQ*OYJh2M|Zt-p0%sZE^19C4HYvUQ^DACaOzj za62-npY0)I$efXR-w}n10yhN}IylaMO8zw+^{?EVG*p{$V9kuEvfq2T_pJ<7ew4#o zE?{3^uP;LP4YOvv9V;#jIXy=jS{^q{^?x_ijYm`Sx{gi{#H60#i1NoAWB`lz-P@(? zWnb+%0Ims|~(}uIGvb9})axIX(V$K4S-SoC@ z5E)+V%mh=O6K{9>ItQkCo>yguD7)h-6~+jijTum~`Cl8@5e~{~xflWc0ai-*mypt& zzvnCJQP+1Z`4zIo_lgL@QgZfbJ}M7*=pz)EFAt^nOtB-XueQ%x5R`25~ipomVof zBol_wfP%Np4HN}v-M?7l4+0#o8$??6+9Y)Fnq_LMu-QvMt_Slk@gY2hoNH#_*Euo; zJJ>;_6X*_V^(hFoYq+Eh0zKbL`1gH!zZ6C?{t0~L0u;G*+)+u@XJxbG`OgeUuvYWRg@>WwX8c8>VGvjcGG7Qp z-kxcjY_qZ0{q|%@wO3T?WczVK`%SR)Kr=eRND1Kk;23HoLdSGb$PVTzuc zXz@r<@RV6|57mVoYYC|6{in@$w!!{6vVKfZo~p56`;(*am!x!PfhA}s1*Wxkcv(UG z+!da@g9eV7w3l=I!nbL4m%|CE_D_b3S75!Y-FuITVsLBl*1jX(*bv&ySwpx3wGtIO zJx0KSvjc#H(iO(mnx;X{dbEw-0lz$n0txrcmC7r^XTunNeV4icgs|gHCP?nscADU- z&s5D%PZ;<^`+t^Db_;4RCWW1^==et1*pXDIdo$frjZJe5DmFng7V4 z@S=Bx0|*jyfM@NRjNxdwStQ8=oDIsLy`J`K1%H5F!)rYb)iuN4^T^3Pb8zikNWzQ8TstA{pw*u==J^Z>qV zGh&6%zJ|q~Xj*O(gcNg`jTg1koUA?2a~T^}MgeT7?kNIk%(qr?2oEzy;F)RDK)G3< zO7co9&sG3iVzm2zWoej_U}33kQoHAZdRx|>M0>r6gFUSg#YI*hWzUH}9&Uu70^XpT zq1BJ8@Og~Z(O}2k6}FG_B^yFG9kIY`^hCQ)W2H<#4x6%El4O~4@$zLWg=$X(Z*3}i z@ottVzjj~05bug^m~F8It#dRH;$NUb?a#!bfWWeU5alALpwdD4;W&#(VJ;)3yI)#% zt8?{?eUD5SpcjYXA`sc{0Npi)d!dyV04n{{w6eJ6JGf|fjGC1%(cqMnx+Z6 zudkJH)DGeg*?Amdc+ReH15TiiMU%N#aVt-1KL1^6b(wui=Jqfp(lIeysQ36WPfW%S z;k7Dm1S@NlqKiwrSkO@Z{SD}A8aK#t9i>rRMDqmlXr-uO?&{W)_-`{tMtKB>peFKvXgHF#wJG& z(;ma#hlDb!Y&&tWL}?C_^Z(37S5JrOFT+G7`Tcn_GY7&@jIi_*h)xuXO9Xla-eq&z z+)+zMfH!4-nWF`)E%USj7#g$3;?9 zpSU0LLpd>0PK65GHiN&HAlu!6!bZHlRojZ2m@z45v887gS=!f!mzBMFHpCSO8xWd!1Me5?hyM>#=bH+|kn zy?QG(=i(3x2QoRTead|us^M|Q9F$c7ytIjtDrk|M_UeW0j7CQ*`QAlc*LklL_pzDd zo<&qZY;t18;)WE%Q(}?e(3WQQ65qLKmW2JDC>Hanr;JXJ0hzO+bMZ?JDBdBUG;m2TB zj6W`SG+E+#ikNU?jQ&lPsaB>IDG+|CG8B9C`PhK}A{v;BUgf*lAb1~Dkh<~G=qUaG z8DoSXbsyU42ulFrC~^tv!<&0gnOumB_j6_y7^Kl*ZU{d}~sO(Fb zY=ty7y&8jsrV+82PTSg#{tp$~ce7Nf56cvT1bR-a;nrmjB# zFxZd}?f>f3ceIsf?z`R}lf!0((HJG7`aHQe%Bi9*lW>-eGhzyD;1s<3sF0T=JGv!V z$8yR7yr1M?6baMM>lSzVVP%M@b3UVNG?(U?IGM2spRKgxIq==RX9DWy?Y9}V1${RC zs&zoi?P>`BWxiC=uSJqGV~92Wq?Bj$(DF|U?trs#Fx1bs#{wlw36fb9YcLBdBtRdW zZSHPOkn{_zflrE5?^qdS3B!gs-358JJgfU9`pRy~7+|e*nVFIl?^1X8b7w0>%J=-4 zF+-v?X!rv@BMOMCRWL{0(D*mS%}}UEx=R6C_&$#twuo%f#(Bc)kEiZi$K(M1tmE2e zgzxJNRD1jj07bMfCO3}`h4q7(D=ebC!}qtwkwqP`njbsu(PAkDO@v|x{M&@ZARc7O z4y8U8YL#3VuF#~kdyni6m%f2_u2FO?Yft08`P8dDk~ zlZjvY`gtb&75(X4m!gx^&>G&OfNRY=y&kih3jK_LV(0ljR1jOTNC_=N@p^4akT-3i zHl@~s9K-G^v14Yj7a9gkdcbo61+=5;E|*euxWJ=?)4dl+mLTiR-J8UfTFN~ti}hsr z`lO_-nKYHB@_F_MN$2QX_ckTOK(0`=2EkaA4ZwhNKyA``aO}qyE+Udl0Y2?YteFUi zOlvxYm!mix@{IslBzXP`+EloI_y-(L1ud|nn?)IV5fz04a#Fyr%BxX5qn8r zCOg(ur%VhdJHq~mM|GXP{rruQUi5-c+I#RUNEyD-V5i3=4w`+ZF*+77tZ?!fnvCl& zlMOT(JPN8ZFp=DkA>~1HB}cS^hN&|E69T$o8S)~VHNO<436l6(RV&v@NZ2%zoxJ6f z`tJyKyJjQw#^iG7f&@4JtHY_t;=S-%0vUI8xsKi7u^9+p5x*_}YQuvm$vj`JsRTsp z0&Xf^XP>#=Y8o0`w`#^)d{&OW7uh40mFyK)v0`ee+15W{$+Cvg zq8Mr!jS9u8I|7P`H8s#MUT)~b)wJ)%nf?;V#oOoWvq%0sEQAH;$g3gDOxKSrs?$qm zxzZU)p>@`T(Z{Nja&K3SMJt5r}o2m7N(4_Ad zOl*&vlx6&n6x@KMwV8Hf;LBtkszCismIY&6cXXVqUeict#1`<94m?|B3@(7!c*~<< zHELX3ll0nl&+k6Zkcrs!y9y&MnkdT_6)wGYF=uWUI>oz_4I{YScWmF;7!e$_pl`Bx zKujg~qMi6)NoJy$2%n|-b%@&y(;7cTL|1<5VlWyOQD4O!y{8TlZrk%m0V6Q~&Xh#B zdoTg)dr)zKF?i|D!^w)R*j(|{*ukS)&omMvJUbH-2-*-qj5Z336#hcG!pO)sC=sDfkFWM-0@>ZM?7XW0Ib63T=2q^&2SXAK{z0<+gWVIV zO_u4V7<`~|Qs#L+34&gy72UFUkB0B=Q26I2VMU3%?Foy-y@coQePN)bxuwUsPzx07 zq|d|>5?15ik+~rGiw&*szj0@=0l@>vYOhl`2@c48mR-nW$_T@uAE)y@xWnZeJc>{A z17Ho?zitEK9kuayEZn71lOU({%U_pD4D%cvLm8Sk{$Vr-Od1!Hq`$#OnN%J<#gIP*pthX*&s!jcn23I&{~si zcf1p}aZjrKXK!lId{@}pC1Yn<>DZg zzs(#B>s#l%-m@6|%ImG;#q7FHKBENZ;vc9=`^1*KfTl4xIx`UQ`I=DUQvC_%O?YD_ zPLcCcf;d(q3Yi=;Egr&>Gsr#iLn~j6j^ya5BDfF8`g2xD%UsI!ywk_)5_lwb#%FxjH4@tp77gdN^JZ6^=n%s$2W zoEu&A@=tvfTb~cIOjbf>AmYM zIQsi2hr(p311dQ-_J{ndf`18QmKmE_NH*4a3}Vet@FAGP-th^b{t{K<5E=7dM3%PL zr2FNNAahfy496j(4-7Ud1&N?M0ZL#y_G!^9gM^Hlvj zIH$2jv}NK$N>5jR=9+v8h+f;lNbdohS*hEBXr0O%jx4q0xMNMH%>=qu`@{C(j_*i0 zERUs^6vC}Y#Oh7BFlKS_uIKlPblm5~0l>67P*$)_FNFq)bs>APi{Z`iwcfjxm2#&Y zcuudlA0fubeAP?wf$kMfXU`u2EAlX|wQ<2(4Og@V#{a0GG}F; zsL0y&V2n8i(t2(wkEEC7Nsr%5EzL2ndkE5%qu;V)5nVnk6U#Oi0MlcX(3nD#$=n1+ zFmT3IJk(JAks!dJr^@qqe7b)Xy_KF_hQ>9PO;9MM)rDg~d^6YuBG;m=R79f9GaBDM z_Zc-60lBqSFY&n4J_h%d%aE3J|4oP9xynsX0wh?M3PFi5=M=`?@d zH~$xEUP-g*ttVrD%L^fQjnJqSZNPKMr*@D(@|H5W)hoM;je2 zSAItu&KjtjF<-RRO&F>QC%y0Oizdh0h~-Ld!nj97EhM_iiOKGy6<_hSbA=sN!Bnm= z1M?MnGRrtdy%pKLlv)q~6v=wm7Srq8(rYT7X@-B0>p$OfI}m!E`Rl*k!a&l;9&FN{S2Y4O9tJDx{o9SdA%8Uu)!vkpCjz#EYVTwtTi{| z29X0%d8FE1JlNKclj8<#`(wFAG`Tc2MBliEI~?=iJGxWY-L11Pd_m46`pj|KFyH_>rIABd1fTeJ z849hoU0a%`G-=?aWQ$2R1L=*dUyLhMK{Qh#c&^*hG0532|C}67)9aP7Qy_#TSY(6!Qb?`$yYn^dB=V|$D_@-*` z9GD&~sK-)n1?uIj^soL#&6~%O^ZO%0Fk*alm@*^&43PM*Wn(O(@t4Ip#v> zmaX1ZN0_(>k0IpU56V@@p%!=+WlRa--M5lWNpSV@#B}@Hj#e^rnsXZ~D3Wik;>%9~ zwy3x-czZqzo%Kccp9HP-~*D&z)h{9IJ5YBw~77=p~hKOq`iYKg9xj{v{g8C8V z({~YuB`N2yxSD2tpm>$Tymt=vwC-C`d+mQ8vS&O#R0;*6F$FCb{g=QaJrm?aUL!S2 zbFybgIBX6cK(&J3xgt7b3Kx;uP`8GoueF0SkHdiK=U~8NVs-sF<{?X4;HOI`H^59{ zT$Y~3ZvIt$&nxK|a3nLk-=tI01?4Uk>Za*NEFDa8{lp|`DtA0}QLVAJ>*qw-InBEI z!By3MtDkMN@ySBGI@0=|^5Pi!_Z4k3A16#nGTwzwkj%$p5LWI5weO*GCzb7xuqM6CK_JxbTBQ1qGW*Qh@!Tnp|0xeR51FIe1b}2NA5eMj2)VyDstVY8`u9ZuJ|#oI zrk+&DASd-t{zP=9EuR3~-9&Ws_-BB>Y0f+9(<>P}gjAqhjfm#!IK9>d~e`GF#=!Brp zZJQofN6DG&`q{_W#@<2B8?y>*?77`6J9zyL?CN1QIEHX?# zVU!%0a3Gc&GxpZF8vN7Hv_cNwY1u>z152qIeec13hYPAp>*3{yybQidicaKr#@+$q z*ZW^vW`#-K_dHwwzpzM*+WQyrO5(9ML|}VLPtaQtSOkFI_^YtShh~s2te=H&&SQER z#AcD_J`t*02%wu4;8jSze_#ULY=~baVa!fb`BSxD_0_AcLw9?>cKz2kBGvuDj$C&Cy&N%>2aq$#p0mtSEaV(P zp4u{{)x=f8oUM%%{ED{`)69!+k|^S^Q3!??Z7uIg*SsC?`qNiJgm%p#(i89jW&fQi zG3l4)Ofs>A`CCJ$C{Mk<$g1VKGEWsAHhr(b!i?BwuZ}Z(V=aYrUf@!|8Iap7Q;)1M z7%}VUcKI?2u-w&Wf#@0r%;J$Zj(4#a1U}qejh}b_ z?3^{QkFlb-z&r2YE>!~%xy66A=R>{-LgPcj0VR>D^?FfZxg-kpjNFb|!do|IQ)*ve zK40zwTiwMPdqBxPIjMlBflsRMC*a|TH--Phn|Z7|F>@(C6g6S_nNqF6)wytdrX*UjGU@ZIg=nZIg)DxJ7deHdPX1uspsQsY#q7lU$+t_Z0BacCy`&JWa%m z_!5J2%+8uhKz_!Ca&rp!eJ(QJpVj})Bo;Is2dRCk}x7%pA6b6^FiK?#f{QZ zwLX&4lU;#pXd5<}`u(P0_x;#X*yw>2-|}B>=ozsxSq(rUG?nUXz4CceePUY<&nZ~G z#FTMwy7}0jr4jA#mex_@Xu`CWsRx<4YgDsP1(WlqbmJ^ga3BN0_JIQ*E#MhMest7r zA6lUlToPbdHY}WV9?tN544pOTtoCG#XJ$QBgTdNr+#@pbCOm2uY7+Ec5VgBVM z5bjzX%S0`QBwQcFc)(3jq~>^vj*F;qK9z8APLvmR<$E5U^|_579&&RN9t@KRn0c9` zsv|eU5k{_4*$gHEkG)rC2_bqTd6O}tLqcfPmYL=Cp`&Hz?3E4`=yf^Rw}K574G*0^@s-qc|z}OCLqaZ4c`BPMM`^O?O<>=?wS3VE>K-jqUJ}F&6~ay{fCl zK=u*tbbRzx)Bzg`YEma>$TKlWJ$PElgRzQ7q6QOKexx8a@xHMzuFRct@iBM!gv>`f z+$eay7?E)zwT$F7+OkGn{wvc2pC)J1SGRDX^o?SU=2Q6UAaL95a@i=4eGpCyOYe4O zovavLK-9Q%47D*SO}V3&{hVQqr@_lM+Bi-H{#hedx70s{hMPJna$Ldr9fL8c%83q) ziFCuIW20pw-Pg-9pK7bJrbpxZ=pXPj>|Ha|`yY&*4eQl;fC4^64f^n!P4` z40`(x$QoPaSK)RMGY8_!MuULuRlb6V_55db`KOd@HjZV~25%K@yatKkUDNqK_J@Zn zW3gUFO6mpkI2+C@Qy>tlP zc|Na^*X8mQgi*LIQu())nT!c1CEGyIM-Y)^liy()OQj6ZNA61;%g4tg6{ORJoVDTn z5dVPv;39BPS5$CCRH`ju`~65=fa(@8ELm zyDFKRn8c2g@P5QZ?RbgyVZ>Wa>tU5-Fub!-QG>pAt6cmhsrn($jTw zCt`tE>FmKH5<$E!(|cyRKx%o$0~K|x8&=Sin>Mx~-R17^L;aTn-kO(fika3lsGvtG zJLne)mJgEO*hj8Qin^%DvoFy8)mS5cRa!S&G=+b61ol^|1jrE`Kl?x-==Ep$S?>Qb zDPh0}h4U{8fQ|o{i<#_-*DR9ZBH9gMrx#^I=~cci2}6^U(yT0rvU$?C`%(lPYm}5~ zS5_jTgJ|mFKPk%D1ypN`%gDMBZ(i#nPtqvt4{X%=iOlX^Zu$|(6U~);Q3p`tEf@RJ z!yEalQ)UMn<01n~b<6wE_>3*C#HsnVub{WqrYJKg6LoKgV?iDe|CM4ZdoOQPU_ zBAte!@d?z5xI@s9bzxOUQiGMZlkAUXAdhQqnM3J#8%x{!2^cAqGIj}1SZCAT*LDmYq3HH&Jsx^{Zjot;m)fd z91d%b&`##uTX4|I*>$;-I|184#{+^gNqAkmxS!_kMRLn}h=_6;1=LBk;;mf!seeG= zhUoI^QkxXRbbzA^0BE|I?TP|u9`$duKeP5Na*q0`yH;+`UM#Qpj|_@(WZ>$d1Kxs& zO?(TB?{%;aMP8*Qzk`UZz)J0%=?n0+q$elj{*b>Z)RXDnwXBNQ_A7leF0;#Cly%1c zS^1(;mxC2_R0!dD&_MTE^Er6rSIn(8$##btr!!Xi@uxzFwYQM%F8*H_vzVs9tZ z8>8uZDH|>bh?>shIuHl@zJQJ01w{uAv8LCmqbZ0NR@G%lwtySb{~X9>7v#<}-kd&@ zMvs7OBvm#OO=<3t76Hk1Cja9y2d{pq6ND|^;JcOBKyQe?b((gbi zS2_>A)eBs=StH1XF01MuhN>1{n3P{V`KBq$svE5Z6fsu=t+U)yagWB#jOf1ar5~>s z4uv#Smj`vyub;LPdw&pKPez6iRA=}ImU#v54$OZyZqtuC@eE2Yk946Mqn=&L1O08B z{S%mT75%ozecYYun_eKZXkv0|_*0-Ykoi$IHJty`(%uI)v56xxb@Ptq-W_`s*}_0m zAFkb^OF{j{=}AjHU-aPsHAC%P^E?*8SGNc+lMM&>X0bJ z$Rs%TpyB7%prA7f-wD5foKKdPvV*t`me9DKoz>;{VMYenV_FTtCi=S}DK>T}#i;&D zq_CslS4!EP0Pvwrpam1$y*2w~8%^LSTEX+64s6`c?gLi(-Ml!$(!EV*eLtk(iCi@! z0nyeG)3+)-IhW0B#6Uz`DNVv6xO#Y!xD#^8%W-|sqCa3Ht*?m6C;`;%tqoS$j3NYO zXk@aD{**6T1D0TlDcVWtAk6CF2pj7A4NHA-lX`kAYj~*_aSp+09d)|dhln?=vhj5_ zDL>JdK*jurJ7VKxJCn6kAu0`1BQAqPMVK9#IfaHWja=w~nfNlm_-_H6Xf>O|ndv#I zb2uW9j2ynOn4oxpfkX0MxLr@d_lpj|LNIa1oM02E!#4yT61P@RL?UuU9}hRHdJ0rCQ}W(Ce^Yfi;dL zg-H03Q8x8?iq>jR(r%xpo~M09+$kI~4XIgxpz&-K8IwT)osjMtQ4m(?##LImw#_>~ zC(e{HhuK(W$Co5lj&8>M4!CL0XUPM5B?oDB+hJEapQ_U&=ajLRTN*be2&g`H3u^)m zu8x-^X&0XS2&3JLS|#f32W%7wL;RzDZHI`0*E8Gw9dA-;RQ6yeB+MPAfzE6;hK^xO zv=m}d8Tk#>b7%Ig9?fA0t=PP1s9IGPn*#~Hm!)_)tba@nQ`LYO4exLo;+A?6ibb5% zfu_{WA@2-ReZ(2(?Gh}$jRV3Qj3k{J^DoEyN#euB=`I?^Swy|$@~bq(^xEkcgtfu9 zLMQr$KDQ637jnpff7vPycgsaCvEkkx!;3xeHO0R>t!giIT^L{ojx$mgm{vrQ0nyfS znk*Zy>S@GZ$BIXxPVGx|e;=r0dHzqA}qFY>=ii#|8g0FKXemh_OCqk6_kf%K?`tUuS9Mup(9RKFc`7g;bc zzL6Fcor|Ovf#Mx~Co~4DGS6X5bBD}$PrM`E*V)FIA8s5BkyY2*t4Q)H*TDukgaF)Z zx-Qva;{{*0gMbp&XI>cx@R%@-DRHP<+2c4-ral7Ae?|_aKDtC6hKwW`zzEM!b$eNP zW`_-h{EAO$2W8u+&xNR+Th3_Jo8PEjOZ~MjHzk$4L2}QHALmO}AcwV>pA{usxRFH{ zc@7G^futH@!zE15JM->K)|jB?9S#gPp?|Zd&H&uRD8-X#cyk~xmn+vu@7)y7+V1nb zQflz%x!oyjYf?7IF0#!^B55;+^o;rQ(vnTgfp;DjqkD$=!=6OT7k_KRpssiA%Fenf zP1hu%1HZBY%(n>nET>ePweoB{HVF>f_1t=(JC@N|y*did^YhsHFzs=5X+YZ}S9D@2{Hykd77S1kPQu9a}F$g<=h zj@;jAykUuLyU__-^IcT+cZ?%ObeXz`iDS+bTftG~kE!L!gRo61HMHXI3!9?dKrPu* z{Ye({gGAotGtmpy32J^eIp&_AQ?O3tE$5yWUVJ`byk1TOri8VPU9xr$^Yv3{7;kzR z1Ik$UsRunI8_84d-&XKvIj0Z2+8#1Gj{C$q%mFF)IqN$-|0h2U^Ska8-P3} zNIJI5{prOJgAiBWuI4SWIL8lqd8Xr?aYVQWe! zLB^xNP8;3(iq{E0 ztjle8>)!j#RV8HRr|ZN%`$U_*PwSyVd;#7c?k^*Yd`^X$?x2BO1tEbi^IjSGSUGDp zG*7&8@|r~>zIBHmysj#Z6iU;`pRk`jUbg|IY!M;k!JOD#V0gIx+AdA1)QP_RHRHgPwSm?TS|CcuH6JGIg@-l2W;(F-@uRd(OBE6il-AO&{OA!MN~9V$Z}jU0&teua~}EbcbinlY_hHlG;g*Q9G_f8sPl9-M$3*#ycx4!9&xHx~34rewdR1cBVwk`kCMo!SRf z=;lYHLYQHV=XhH+x9K|$bbO0Kr97z%tFJ^WWvQ!y7qEyLa~)(_hKStn8EQTb?tXSw$`UZ`g>wLU6j)b3LUkbFXAz#rUqw=AX|Rvk zw*-fpu^lsS|BiJnoP7dY!d!gxmA`#gVNZx#LN+2E6Od!PS-kXj|01j2e0YVh<2&8T%u>XpP`X^5PuiI`4o7Ft&avJ=kJ}HHmUYp|g1N zKxG7lIMI`|K?QY02*Q(!s^i+hLO38mstxFBd)nB8-JV_^JT*jE=Yr@gTQ=bqF?6-$ zgD>4XMSEoo4Uw5J70gD5Gt*K(VV*=Im+b8dxf8ni4PyN#BO{H5hd~s?5o$%1q=uGW z=1|3ZZGIBp1w$;(@)}rfX2{Xkwg*!9=G3O=S!Gt+p@O97SsIAC?u@!Fe%x^)j|Et-qr(=Y8fxXWNhk;a zvWwSyu@1ya#Emj$UVT<+sBRGntg_II285LU4n+%R$LsKVZrwu&w85uT68?uSRw5ZX z0VId3(cMzA)#v9^`w`OF!Kn5{;Zv~s&2PnkWyx0`v`}g~oEdlJH9sjb!?-y{wN1D*KX^-4;wqHX|&jy=Qnt# z9E z6;fC|Ax{1khluOS$@|_`lO)>|8LT`Uz;yKs_vBwXcRv=EI4nQvZOkSgs zx!BJ7P~GX>ditK;lz^g!JtU1tYC9fkERjB@)IJLC0#EyP#L`osko;FCT$br8kHmYJ z)#?Zme2m?D%;eEr)vBv{2Dxr|8GSWP%(y$+AxQnHeowD|Bj`+oj8I{#2dQnQp+!)} zre^(0^upl=EL4?cuy8T_#GBz`L4qDCHVM8@K56^SPbI9ij{)Zw1n{WVZVlLCF$3r^ z-h)5D9S;#%F1UFw8k`%=u+f<>o5J23q2|%)mIc|?9CBQMKvj0D!*8Yh6|}L2u*)@2 zt`ePI{(V?b;;4!cVnM^x3XI0`bV^T5vc*p-GQO+bR(R4)N>}l^zcUrEANhc z3T{p!;Kq(_AoZC<>s_fS4fAM^cd zu4g_Rb%RG1BfEf3GW`?+1D(8+uoi zSSsZR^i}`^$U)lYrZd{TEXtTX%_vqmFPa(WddYByUs(Q7XtxG_Bh?o89S3u#U!^t{ zxLa$O-EN@hkY1bh&qD;ztFNow^V@ znWJf=S&ki~sA`oZGC1{XQOc=QYSiC91O|89_iktKJ|IU+4*!tqg{C#19%yG?LE{!c z98MrGs!fBeo%D_4A>qT(HVpKdi??FE&%dNG1NXTml2jXgjke9r`>n!pp|qM`O0x|O z*d?Rit&IKyOcYPEFSnY+(0L%-xxq>O@gniEz0MsNyHrw=5IiD~fxF;$+u8C&%}VI% z2_ST#^zh{BgYFJYZ0tg!cQRdL94i7Y*IGn+1iDk&^`Eb`-CMdvtSF7jBhVF+>Z3I( zURJdPw{6`9#(NrJNwj6G%C}|3E+kW7yDLtVt3FF@onoOJ|+XP))}y{ z09sj&)_-3+F{u=)ANo371@WzTS?G$`JFd1%*) z@oQbU{466P(Sn?I#f-{k|wcpDQH#-^*Rof0AJTac|gkwEpW0?Wv z?Pzu+@?5IQJX!Rq-%x)M`DJvuuuy@dpoerl3N8@LHdp#h!-{Wm?Kt!)5C|4bstw5y zsl=cF-9r<>9o#Yp2ZCH=j``OIHyDonLS+5#_vcb~5VT%7&7_60)sTTh+#;2O#$?84 zC$p_ihmABx)_TtH!;nf0FWs6%B9lIPy2hD1gNI_EX4*-1iO0iZ(1gW2m8yo(b4_Q1 zn6X&_F(iis6_P05@~!H)C^dnb&P0YgAklzzTf})Nu6~A94sib(s14&!?80edNrsLL z_?6pJh^NPTehj|d%hix5U{(u*_xJKopDNZS2(CfU!JHL25A9g~m;Z)w1vQED0w#>Q z(ubGiA8`T!aYe=plJ1iiil|cM<|26XQffnwDAl(4(_6dCIB2_l7#uhez4BXas2Y(T zA4@00J_xj^Tg=sWV-RIFRjwugVILr;d3{+fsDvPDJ`1}7hrGm`mhMhI6?a<|peT{} z0H}^*LLC+&+RM^uxv!RlOSxQKekD@a_&<)F#H~W<*koF%lls4FfpWH*>*Qb&`}#%v zii{=S?R8UbZtuj!@@)pt?gUhY^#rg6`(v+3Xx0w=;&DlqV8je2p}_)Z@KZpNXBSKaiIQ9-9Vl->bv=zNFL|rk;5&{ofmKSS)$U@ z^-e3Zmgn}(MsF#LM~LA~onc_5forA_jUP;UkNSSYL>_W7zE+bg02WhEi@Vt~M+qp~ zP~980NfqrFj`-K5d!5X0Ew|0-u`9}t$um=<7i(=acyXhiHMgB0hTfK_@95vGFqU%E zQ>%%u4%!y2TrssocOPhFnZY=y@TF3L6(j#S`&KRwXp)puPXlsyz=sWpNUgO>NwOEg zn*gS5PW<>rotNXN=eo#YUXY37cb%2NqUhzCZL19v;-hINF8P!CY;i<(w_|b||Ih|X zu`xbt?+SIlnRt`#6a5gE*i<5pEeqc1WEpCuRWr}8?hvc(-d;~f-~edwiI;YWgUG4AU*3j0UHrC*Tkj9ra) z9P1JNKI8l8?`V2PU<^O`RC)kPEMBH7Q4!nSn8P%^h(r4#tV8MS`>E4#J}$nw-nc5k zS=FpK-S>7LD9!k}iJAQ6%XWgs-lM@vE7JS6tcBRbwpd2ZG*nJ0*d=;g4x-S; zkMS}&7kQvN>8CR@IUFSTqH31Oeb{VE7NuAIwo0xajjHyn<~ps8ge^J!@+CHg)5p1T z%ssH0$5So(N6uy#iX1e9d^r>S5!0*#T~zcWbEv)V7iU(Qpg6kp*YJXnV7dD)3IV14 zwjHJ|)`pXLD|8FQ&8@g1zQR{I4S6^+H+tonl6{+#wC$8Y{kKj_eRJd{p#hX@eZ(|% z<6O1d1Fpwxyoy^9o&QPv;UsP!v*2c-;|3$W{T&qz>;c`;-^dDoJ!J}3|{2# zBt=x4N~>D$PDjFlv}AAB?Yf&Wl0a%Qn%7z+fY>ZAhwdQ*K??fCTK#)>0yIA#{gOnw8R&2 z>I9Vp6L#wAq9E)gQ6XLU4tf#D@LEaEGR>!uv8gp7lhWzw8DW(hVrdt?f(n95DC`NM zjCC}UTO~j7P?zCk3gU+YOX{}FK*ha;=SRie^I$$sUCUai`FEGr&khfCEM;F^4i?*A zre-f#Jwil3Sx^#@phMsx+@;Q37p{8Pkl!f*zdu}oAKud3@Yf&LLqqRaOzf|5b!wE8 zID`3Zq`_!x_dj2>vZuy=#ZMP)1Q%1t?>8n0$b8svT6tKoWZnB zS@c`u@oj3|eBy2OE? zeU{R0=Bf)OH--Z$ljFd&7{GPvNmMt=(cs|5Av8KYicbJ!Xh?`eBfWWjP!eb&Y17Z# z?td)7dJ9dFs^Mt?SL66Z^0I$b=uN%63(i9^7YH)Je1dQ&O}C}}0Ml_C|0v5i#-;R5 zYKS|mO^;rx*b`tT_g=S$Cz^-XD*7^(JshmQh_4)~&&-zkECZ-CAV4tBS@Ni_)Jx!q zQ!S_Sz*L`FbxjU&#-o0B*qUb`svv|0C_tcmc(KtX;=~F(rf(T$elgRAf@_1Xw_x7$ zO4CV;fu+^bylN~yH`B)RS&6n33%k?r6%S@ey) z!y3whnI(|#v472wj{yy}*~-L|3<|71_?*X-_}uc6%~0$DUDW9DQdEh7qvnqPeyW@L zk;(~KGRHkK;Y*VT`1*E{gnoaGlf=|^kjxr`r|QpQ%f37s=-N^aJ{bAPh4Gcv>7tNJ z&mekJ19Kek^g|R~-<%jTL@x*OquUY|e{_?ozIK4DNuuNmM|jLRN`KLdFb14BgY^G6 zOK3j~fTTts8R)7pAaTEqC?^#zFs*~P_yaRebL}i01s-r3As15l&niML`oKSOXZssv zZ9#HN44vRQ&xoOETgEj%Rr&Jx*r&>H^_rU{y~J~8V=sBvz8U8PWcV{ck3|x64JUY? zoLSZP_A*A08dU*$c_=y_Dh@{V%t*I%(=jo&ot?HaR)50V~%nmW@O$DQa4XD@%usDU!7)bpJ;T^p%+5GV!FH+*Z7(z&qeCFJ@OVdA6-BUg96_8=N z4uS@e2}5r94w+uN(OwSE%37Kk3zaarXMh9A+U;?We*Ng@8p^F@1;BK2e>^%mw*#R8 zr*G2;I34rxlG*ki%I+??-||1M^(R!HP*q4+S7#ke>Fo!<=Ixz7qsH zmntGx55L!+cs1%}2*zEjBzVMl&n4`Yh|l&#PP}uy z@D|;8Py)hRl3?Y^D_JJf#M_-xU9vgo7Qwp624If1_u5vH#LPZ%0(Tbm@O}Kzj4uO2 zv@?*0GoXJ+Q3pRPSw8&0A6r&jPYHh-*jEA9cX!gwA%q1jguy>~7Iy&IbT|I9o%bt~ z?%7ibvng@BP5;3bYE-Pm@HS3IR=Q{3bTKEj;82~uE+}428xY!*7YNZq_Xiv`dDHh{ z4N|0j93pdv{11P+-zk0}g9@Or2(eWM zsd`2HssqMnxn-ScE!X+k7u3ZHiS22%v#~YAYyCua^GjEAVDt2B0@lFIUgk@~%i%gz zf1Y3kcK`GCT=L0#3VY0}n2#^2isx(LRU~T~C-7r_S=|Mxwite!ui$G(plA(^{X%cc z_%pp7Cd1(t8`HX)$-TC6Zl;XSD7;zTxXEF3_LOl7D(oT~=nE?8qj?dJ*_&+;#mt}N z1a0o=p;}>teVAx=gXeB6c};TGbO*E2#oMWuN&Z#7c?qZ8s!zdyhIsI{djR;!lX$bI z=pbr{2{s}G{ohc2?%vp3zY(dL?#<`FU#dyhj7~Qacp!{No4#gpI#e|rtp@ixG29s$ zTRD?v)K;*S@he<#tn_ct1q{wd2w=C%@v8%|l1|Ulu>m>X+Z;j_TY3eNiw<7VP*>>! z#uaGh*0M)~NG3{%ON}{_(q|>1Cl$ZnGW7DZ8Q|$sVWbs%Gt<`|^#K6fT^_L<3hbqy ztC!65cPv*ihe(YEEP;z<5teYGp}GfRO@LX}Iz1Qow?DzFKzj`XL-#OH4>x8@Xb=PQ zD)07MZJ8&xQtfB@3(gsH^#4AeL2&5$qb#*i}Wfx?81Jc*q=G zKTK3z0RT-zm9rt|I>Su>vkKGjY^B_GsCPx_pONgz4IwS;lJH=2=FHg6_~Fk|940si zc2mGBEBrtJ3AP^&nEita)Ag(E|PP$V9$&Y@ZhkP17x%NsxMi zTB7%JFx$egJJ4ID&zuBCt+#j)zzY80_16PO8Q$sX*u)r%Cy&tKuYmv`y+1R+0U>ak z6haNA!x34~4a+?u%TKlHm4PE?8x@s5D&R)O{N_o^iH z9jf2vQW_|hGIF`DQ)X($^&zq8q$PT;Y1l0?2*79qjU*ikqtJxwGS&MM!g);(r2szN7ikp}%SBG;&(7fT0ck>F>;09tsQ;|ts3HtzNB zpDqhr(8$}l{E+uh0Zw_ZWuo)8I7Zf9;Pd`)F2z5G*s02s z^meY~sLy?Ee<}4(yK(IedFB5%Iy1-rMQ3JYWMF3b-{{PYjBE@H|4%xzjT^AN$##d0 zb*b_7n%HPdOl-aJrrN0Fe?ZM_+-GZS`nkVbPPX0ZwQ9>1@Wv}RyJ>}L)1q=Twq}=A z7l!bEO3X|R4*mzu+{nNPn1-RTKQ=Ck6A(Is=GsyaI`iLfW{^CfCUAyEfFGf>{V_ly z*B884G}DtA04n1PzeoTVD`8}4Y-n-+j_l^_%8+_a|JCJX)w$*IkpB6Q-2Gdk|FD^@ z;Xu-~G=Kq#pdz)D9*_X2{)f$sc4lr4tKiJo(82&VriB4)lkL9*pv*1q|J;l0U!Pqa zG2F|+$@nGQw}N_h_LZ7eUYHFlASa_Lp(Ch=N4@wi5aq6a9nz-FkWUa~lpAn~rH<^zZ1E0VqRrZGiDdnw?TxnHylVcan_m z<=5hy^yn!S-~XaEbO``C?_9qrs=2u<9~MD?)X2>E_5j8iWNbYh0M`a^!j&zw9QdR_lG?MJu49;wwHJcB}uF4Kxk@5X|?-^Dn2N#e{_AlbsEzR%vFC!Ad85~Qfwss5iza6-Y1sv@oDs>ud zSW$L1n?j+kDVT2hMbCm*GX@L${BCbwx9ae;i!ebNB*Vcb=Wa@e4H08BC=rgFj2L3r zCEXz(dO}L(yP91O)p7Sy$fd4O+2I<-q_EC+mxG+PKD0_v`k%=$zUmZLihbd~2C+;O zHn%|{>yg^JZLNRvR*FTWfA1pzwu-BT(*IdWds&d&e;UEiQm~tX>_uY>?Q-IK486R^k}`VXqOe2(fz$ z+jQOKaH{ijSxKIEQ`>}o+C1KJ?1lOH#pqWbp-0`$7%;P$Kc?lQ^dQ`#S*_Jbd8>?> zP4d}2xm730O8wwO`>b=*Q%BwlLKL)zCN>nEFo_>D6~Q&Xl*n6T?q*7wZ{<3%CpHpq ziMw00f~XYM5A*lHM&Il+f$~TGdDp(PFM z8qTr_e01`b$*U@X+mf_Hc4e3f-`mB*f92H1?hoAn58qMenJ+a~RN|J|A1IAD&E2M{ z(cCO}MZOW-Fb@Jaze_bm(k0PfV+H>7x&VVJP}q?kvi2?vUU4qY`Bf^<&qWNbg$G~? zK2<$j>X7CZN7pHiOwWif?JRj5?-%YHYhJ$p>;0TPEq92uw8I(JcOg(`-Z6MO(pEVjmkOO2tk6nG;Em2N z8(ZBBlH1$y3YrQ%s}HKwLlpjK%t);f)lW0ZXysPr$j>my7yB*460QZ)Qg<9zMSV14 z7Yp;dPtfmyEi?g{$Em)M4rEnE(OlogxS3=y##GL1Vi37tUW241=%)BPP@q}fyOY@A zuL9)A#nQ?qYO{j^dwF|8XHz-fAfSq25*w`Yi`98+C!5&0$H^vn#0t0p7yt5+ zRTFG)W<@ZWmbTo?u$QRV%J1W_Dl5~_13T!v!sg35vsTF;Fb*60y4I=f8C1GXqJ48K zsn5L5d(XB0_vX$IJ5vi^0vh~1@{d{d z9u8z&e6#qG2-CA;t=4@p8g~}?RBZI!i^i#4>p52csqi1{zxOK{NlM4TqoRHi2i7xG zwv-EYpYY~6tTv(lpsVcj>?w!yMM&tl{Gx>4`{+%lvn-X(N+?*o#(IWz;#pNtU|0JC zo{nlSRe;e^}BL<`ESEgIb{%M-{$*k8!d|?iE(Q7D)!(v~*06RnPjGVH|liH(+ok}S7 zbKbhtJ`9@xHDs@|K~3`uLaFRcBqd%Dt3LvbZG(*@IlH|PUY@~;-Qy>|o_0bPYbXZ0 zbNfhhj$#Bjc8HK*;D2PU507?_u4%#W1;g#D7T+fZz;MK5Arq2vu!D)=kp@L7ccqdy zBbJ78iz7}V$Js{hUO*l(J;#ce{-E$Hapgv6qFbZ;_0z(~++?r93jfrFzP?6wFNP~z z!H+Q8R^Gd=Qt278d84x1IFOv?oRch{01$ z!cZM2GakzwH*aumg3l9xS~vzT-mGjM(;`&SQ{m%i9#JiHUp*`a7SsbHGSb?}JM+$- z|GD_kzx<5AR`{z0Cu(wzOJ`RP?#`;cjFh#G*#d(|TIi|pK);HZ9>rsjRu)SXnc}$) zW0Fe{2Bsg=Iol5%K3b)*g0y@(w^z+-O3l_ryV%#@(oVhPo?!tGvgw}l_a;oz9(xRl zCZr}!?~dp0${PZ|*&2%fQ9cFfiJl-8QMl)_EWgX^s|nA>ho#_)H4(WrIthoKR^v3F z=Ka$3K|?+EhgM+FxhKE%aGt@m3*Tbq@+F#I$NQzKp@gNbdSTVZsk+Z)5AP0c)y~DJ z41ji{j)>VeBgN(7{s2i=rFgLn(Idg2NuYh7PZ${D)Lhy^+`SjFRW+po-$$S!lB`+F zo~W7gvBoV*J!3#;O{hb~nk|`U}DN=UkR$Rf7cDOPuQD zG5cbU?JFmjZmsC43AEM`!yrn0DJ(bH(^E6XNFCkH@ zIeYL$dhxnf{gV#)sDduDA4%NFP$L4Or-Q^?VywgaUf>EkL`k6n3WyMHMB%TAh{Ffz z5%pG+Yib0+Y}~?e-K(xC=;L{2{0=oP=jV&$dTR1OeQdAamFrWG2}FbQ-8^HUGO~e#SayUXW+bDeJ)VgPCBe)D^ar&Ks zQS-~7s+3SOPD@jCbaN{QmGA8)HvG-F`Ejd9!0{~_bQPZniHdv;;}@pWNf||RDvsi! zJ!jdQfB-GTd9=L{l^eSO1!|a`%g%s!!8IyF@x~iW@#>?S)*Hm4C8I z>$^e`!SDOgrZq2H)B@gug__t7rN z=L>R;0SGuG6N=wJk(?(wCy%y=QNdIQ6SrWBozugI?F`8HQsyCQ}G_OylKnL?u@ zL=d}LK+f{eNA-=xcKgK!Qg)A}UvXPiT`2RW8@B$+=nVtX9y!mfv+k4SW?mqZkPU_@ zn#0`&P1y$}F3f%2V@KYlMIBx@!&)(~fD! zVT*W+VE55Qpx&iSR;4R?E2!J$44B@&i&ki=DUxy@dp>de`BdE9C3hQFaV|@!_qaj$ z?w94r*|0mT`_A^;3?5%e@&L79gJMba#kZ_-Uacw~#m$?cr+~qP{9|y=01L>zCUgL? zxQ)AJ_kKVX;B&qaQ%125$1W>`P+j8MK-tQA)?SL$Nw4Oj>X_i!uS5c zJ<|Ch$=>2i>hMME&217M$IhYX>dxbVJqbi}NZ+9%i4Q(l0=cPPx%NE>JZ$kW~YH6M;2NWMph{BHU+Q zaXL5`pX_3humz=)tS8$+Nnz4XiDTEL3qNh=$3}LBYeh+%u&cNCVT$5#7AJKK^P#wG z>|_yqJk^W;vBZ>S4CT=UUdJY)M=DV&wC=+MyOmoR7Ay~h)M8mCt9HKV<^wjs$h(Vm z*&zl5lPMr(zzKKFcT3R?Ss`gk{dFu~9%-UGxo7iA*y&CKVkp_7w0T@nleeS(ro42L zz@mxS4d&fq<0)8W+h9~fJ`WwUvH{5}5*9s8W8(#$%;H##?i|k>)PG5CjF;Ck$D)73}vqyFk<*&8&%GmfhZOWTag`*8q8~$Vu#$BgPGzHJyA12!5E{5W`*=w zmV2oq3bz3IuQ`=!2MO)&bczW;sXTfKyDvUTAa@2}Ca4vOZBgZs0+sWT5RIk^RTC&& zl`s0RD%oUqZJ?~E&_CHMmTE)0F7WzR*{7eSoc=D^>X|^UPvwv$O=L75(RFLrL2STQ zfIg@*p~hmgo1Z5f$TFX^Su>ihnvzZ(B&FUC!WT62ifH6_E^Ni_c?K)3>GP*Xp(Qj* zb{vEb4UA*&ZIssXl)DzqAB5eA>(Owhj67ipyg#tQBh+W-!GLkt&ua@Vv}&cSq_pi& zgqNvrD!2(3{dyZpv0Jr|6+{k5$VKwkmt1*ACYn{8(9Sg28-B`SSGy(Mi>9_CMY5Kj zW??4y1?l%-k~J#+$*%OGBPVH=>UZfp1rY|?to$AkbhQU-INNahWoP581m^fEPQuNz ztVhC6N~egY*ze?$6mEDe(Jm}92fCUlqd3^H9>&BA;K_X00&tIJ!hKi6n$^0qi4&Uj zVW4!PA_19yY~83aA*?HbsQzmN*3F%LVqqn0Vqwrd`8?fqU<&(`G3hNoQ#?E`2ywwl z2+O2UD91%KoO<)-Bx3VX=-4KWD$;nd^XJ=aT~+xV>AjSH{mF5g{-9{H8$H}`GOxJ+ zYEYZ60`=9q&>)1XsbD9IU#>fY$15wd8&&CH2BzT;rvay*HC}1D$7mn2UiF(9-Xu%> zPZm2RbPdjh$El|Elz*0rhafqu3}7(|uk*i(NlYn{e?RXOsdk66gEqaCS!CR(^A-t; zhdEAE1-9=Io)??SC$q|x7jDfuiamjs@Gw_hXyR`Ma!D?Ry5a=p1_`*EP6*C)*cyzk zx4UCu@zda+b1?PcRrupXQ_SveqlgH$|q0Ni;%@!CpQM!n8yCcDLa0wrX+)%zMIgD#$ zE2hEo++^bZ67b$s;`_71yar4oD-KE{V<%s1p2+U^2V&y0?`B$vq1y9uz$!z4ns~uy ztaMa*kFqr$yn25W(_D+)9{3zywATy;wm>r1MABlK0EcOQ&OY|}CIpY;JuS6( z#}*(}YmS+d)B?(D?sNHmf+wB%UmZGt*L#kQh^Ko3iTu=xH!(cS|pCCcbFw#Fag-E<X~<*CAMSq@%rv-yX9N2I8ZNmfh$S zaJiv-1$#4s$xi08m?xq5!q-&(Vot~_+%XqC;{*0w67Tzf%gX}NKhEX^I|fy7UW&d* z)te$PY0(79D@X@|%zHtMT>3>7Y?u_8v$u73L!8|rT~Lu}p`X*(T4PzWtPON7iV9=A z`uEP%KLi{j*=Ei@4-i`tKex>3hhl@a$SR!7bcbSC2wU|Sb3k?fj*6(a@PWt^wN2${ zkULrX+$ZAUBgt+{kl)3xoZPTRTpx8PrB}3K!$Wx~UTQrU+;Sc;uw#vl@SpA2S+k=0 z6c{<_K>;_VThW}`V(p3odmfR3sk-T@~uC|xVKUwn7i5*LEQv3A95DHl6(>l$>=v*Tm1-s;Sirvud=PGp7g43&G4o*XpM<4YVQ4bV&UP%AI6|yPr2*gf7Y{+ zsl5rcp;)<0DS~jtIpgG0HZyX3%49+Au0{#3H;c3HO?Y{|7M;`D_9P8Ng*9rNXlHNU z5ES%z-;kyk_X8cK0XBl>7ri+Xz4(-L^Fsecr(O16jGg0hE=+(1W7|048=u(DiEZ1q zZQHhO+qP}n)_xbTRlCIg^?Fw8^7&l0^g!<(82Jzwq83co{?F9W?m0dbYB|Z$c z*x>Ug3b$)}Da|a0Nm4e6QdXuIwZpCG^?*sBgdVF2^? z-cJ5rd}6Y5=d8FWvWV5CVAitC)TS^+9<%ULNis>QNz5}%aYu=Hrb0{CTG_hJC_}jy z#5&_R*NWKc*qkc9jnl$z6U1$=FXWBnrR|n!%-Rup-V{&O-wRJF@`nh+TPkCPPS7V6 zF3+1^d8^5;kv<+BAFul7%Bv1BdYw+z3q2%tX`us|sV;FO{$H4{5^N$igh`V!3FJuZ z&1w?xh>@u5cbWFG=%;2b50h(cmo2ZPrz{8zXtK;H_FIqJC|m-9$TU0}tp`xsokn;mXr_Cvv1@;x~M znWL2qA^9{q6tb$FMw+>D*Co5V%H{rTC8qa8fB~N%j7EgVx7tgVz_pj#-#cXR6+-B- zbIL_8o)`%gZKblP2O?6o>3YXFK^2!XEc%oYSlneGVctiZaHg2u$9i&YE=y7uc-0f$ z;*wNV5wR-69w=uZ)x_z3h^p1^PHQOE9yRf05n5nr?j)KHX%mrvl&PI~bF}vkX~ZKE z;rC1mJp1^8<`Q@G-$^HMR`k;)M$?s7sl%+$RE{RdQ;&lKh{_XeH+a$x;2(JO?w0`eF63<+S8QGIYB_^1aEG+! zBKDzU4EA9lz1gjyAobD)s7H)8-OL(mLmdpGF2Y&o9|)aYnf0yVK{($JYlv>OA0mPs zTe_$zj3P9&gU|G<*kLO;Sb@^%cVMIP&=u^Z`#D17uzTxf(Qk^;cMrDo{^iZdPp4MC?6Iax?gC9?xDBfXHhznafWngUtFwsi6bMQYdgRoWOKQ~C_3njAk(Qr=e zgrw&NTY6Qxa!aCcrQXx4+eCfYK{0sB2@a_gSu^6pNl(yt$^0d8cgr@qqosV?pe(n5 z10zo5Znki#JSeL1SE)N`Zl^qb^rW&#vi59Ad$vZ8cO{{y6O1H}a-FvW6HH-e*&FcK z%16FBKb4|{P^0tSxBxklm)@=w(I-8fm8A{4WS4;vn}ZRhOME9S{7Ne4*p>AVrBFvn z;HqL5o<#2!Z$Ya60R_0>cf8k{pXpLhMAz!&#SDOXmniY~ukR!}w(Rzh#!J+A@_v22 z5C-@JQee~1LDP%=RR2qtCgXO;fSWhaY0A-G<&}IEKs^0U6i>}KeEs$I6rF2;@P%G` zY84l?yD(&x?%q$=K2p7udrToV$`}-R9sP6*aYiN6l#=i!khdV-9W(@JhOrxF7Jx*(Dh9x1aqk<>lJNOOtXL50e2Cn$_9fcs{lt?M+BASW}?}<#g1cPN+Yw4~rPi z{AZ@y5W&#RP|~mLbFk4*4}EsQ&+pFTS_Qu)AD3TQCX@04KRTqFTJS=4g(w#=^U31Y z7F4&cKICrF!AyHs8ukR|2|)PX@PMVsaI{3a8WOy9H%-BL`WX?10mO-$c*oHq=osyq7q5&2iko5#K*BbDt(t!K-v+5{E2p=-s91jO{_(zI2C`Y%jE! zM>@`MXiZ~Te_#2X3eQ?lV&xa4r%oX~_0RPqYaz~G0uvM%I0_=6q9Z6+m=`qD@{^Rj zjbHdJ#*_=nV0ZGb?KO6cLDKtCH4;K#r@!SF2pXsikhveLLMD*aNweFF*Y^>l9j};) z%LEqf27DZde45QtDOv@~YrJx_B>WhiWb++7Hj1}5cAc2qqeckCG|_~)qbt@R$Jjer zJQQ*?f{H8KFi*c(z9KQC)ox9 z{PFPxZkI5Ul*JYqAVClWqkV!7zTLVJ8!9H8_cVH-VZOUmJz6I9SInI_@doHIOrTuMW10uj=*OQ6VSWR zP+U##m5k0rQ*y#R!V0X5PM)|l03%aF6F7H2#$p{$LKkS4=_p`Oe;{`LbSgrY9mXl@ z&JfcP*j47k!bGV`S1|Cl#?WUo{TO+uSIgRw6uE^W5;0ur50)3r*SuQtCvcjfw6iT) znVlZKwb@=_yazr#eGHzF^2zn1mmI1~G$5|csfSO(TJ7ZYbAaq|5J`md9NbDPeJQ&} zA>)}ty#cG@h6BSt?>h|rFQ;3j8f#QZ5$y}ZRF6H+McRP75Ev8{EaoeQ`;0ga1IN}N zeMB{hmQ;3h6L;ygW|O(*|9u@_P+Q4z8@1W@ZTHqkIz3H5&&SoX9T@J}=DG z`xH#*ug}mv7An22kF>4K)D1Iq(|LNRbK4JqgmB&lkl_k+?NnzUVB(L)(A}>mnk9pt z+jJj_>}_1kch@iJicN15lKwwKLTf+9~ShM&E=Q4sONGN*KfT1n@X2`;sw{ zJe@Ar%y&Z1Yf;s+Ty-EFLVR7Z|3hAeDVog>YlG}iZ;J;<8xaMa!5U=%5=I&XT>Wb; zi%$h#^3v*g4*rRg)lVe|y1L&4@bd7_i&w=1Tu)lA;Tt})+b%U`Vt_4!=ky4P?#t&UUPDZV(V@0X_c*@b``w@QRZ?Q$8X7O_e|MGU|%+8pm(Hf zY+!seP3~c&-vNHxz_yLONlr;IPknd9XNRPJ7^e}T_$b9pr7b{rcC3Z6-_`W(x>ew4 zi5|zwgT7X6 zDJy{U%3VOTM&vq4FmQw}>at6ot{5-nrgodoQGNQvQ!=1#bd4rr0a_)Kdf~kwp9>(J zaU3Y_aGUn>G8-%>#JENgid;?k~UB z+jZATTP;h^ych@a?U?=#_H`|lSf|g!qkT=0bcvNJ-~L^_h0FZ%C-p9~gx(;DeO3C}RemTfd!ys^$Bx&yc5mf?3t$zI{Wx z&zav-6riFx=6xJyCifG z$LX#0hG28X{&*Q>^_TJeLK}iun@HxC$qW=D9=eIVHp4uMTXAnMF~OwAyt;1qsQb;) zO4dS`Jv}>wwxK_Pq=GIyclH7_5VU+Q8^;D==hX80ARBZaJdoi1$)RpO3SVQ5zNuk8 za^J$5BOpW;Gex9nsv_uo$>>xG6x7K0gQ^4)-)#x*HS&-7{#dm#jHRK~Ef6+keWuTv)^ZN)nh0{jdh-ulVCg1Y=Q&#`!EoZd!%BgEfa@LT9HgHveYu~);vss_ zn3ZGwFx2@WYojNl!J@<`fP>p$Cq6w2nW;BhvAN1X6`+fExDtxuRNe7a0fZF~EO(|R zd~}-K%>5gQ#?U^r9`y$4Bp=R1iXgKcbljGwr2ehBZXtG2h$Toa^WhLFV~UQz^s8;_ ze!Wd52mIeiLPK4*`sBTUN7f(BOXe}gR?D!Pf*naV8Ur5G16*-K?N1^K>9`1Nu25`V zt-OOUrEHZ@BX-w0!wzVC6s*51_YAI4a^*W?h1Q66olB{-$AYZmf7rnDfM((zIl>uT zGRkqB5Gk~{e`+Ly)umK`=s{eUcBX^|g1X`TN%vb|cBeG9iRG=^^s&wx@ z&QEdZ4I<`-?6wyr|9?YP{84a%3kc`EvJ=8!1npN5nxlnjM5(55gFPJx1A{o2cpM>| zo#M}Xw%be%xHo$S1olMTi2g0(tm`#?UB!_lkQP+q(wZn{wGU1azoIiSK|K_;a*#38pn~{ly z<^RiZyBRteUoTi+#Z2RE{>N^w+q+n8wk+0H$5=N8-eBQzotN3>zIvT{9q!nVelS&9 ztazAAm-(`N#LHw5u7tt>`9M3;NVGG>s!sHMtf!-PP z0l3K@1IRfK)h`*oZ)9K~;vY1UtJ8x^eSL!q=v><3Pa>GvdZxx2`&t`N)1PZR9;>Np zU=VzKd}92X8!6fw0V&`Aej5MzWwIdYnHwU4h5fBOo1hX0H7iPH2447wG&j72pLbwm zVrz&XSH}Pupyl5LBq@sN_uUKX*A5sPIML0}O8-FydI0KZ`$ji8KR5%DOIkuoR!~_0 z5{qE63@6__YWv1q&-}qm|Hk}oy*PNb9SZ83fT^ov za0N{RuD1FIHTC--jbU^SwfEt=F|d8kSKJ$*^?Lz2_w^iyp$FXbHR;mYs>n`AHD+pE^yKK!{((H{0;tbz($$Vg%MK z-{A0N)k0G7vlrt#aTVg{QwPl-gY^dC_XhIk`S3PcgFWD?`}cJ0Kakszu(6`1CZmP+ z+ZS^$w}E7A>%VG@5xAV|=VftuiD zsz=?|H1%J0xG z^?xKcIJ4-Qnj`ZmV&k+`Y#B@(wR%}diEbLxe37mpxNh!s=Za_}c6|#yZ`V-oVjtau z5OD?~E9zGFT70)9fJqvR7*BR~C|(4+X1_NnUR4u(>DNv9`=gU`;tWOtcD7#&`hxRg zg~rnnAQWs90%+Z<(wS)&K$6a2nJH?pM8bJCU3fi)jAO1QV)2OCAxE*x?Llzv=j?i$ zka{z=1to5vaKb##K$%_ZXro#?r&p+T+AM+c(;hXtrS|_l2+|R3ba({&ZboI$ZjXHp z*1O5W?V9Wplhm#K;&JTi<{^w)Y*q44>D-WRTW{Q?Nv}8B9kajzh1tmDaE=j&nZ}Q$ z`E9y{sQ?(`Xplo$I3b+y*L5`)2Bm!1T#=S@-yzh8Pa=g#fAf-?(CsDeb)5eV84E2KKiZo&HHtG*7@YVrBVgHz&B?@Uvp}`Xew>-JhyV97`W41kAGPu#5RhVo7$ebbsOg6!Rkhfz}la44Eonx z&D?}kC*q?~lH~+ios6kFNWWEh2T+)%go4G=@wZHC5j&ID66*3M?=MLlj_K=&B8vyq z9xt}6EZ?uzf2{+S`s{f41u`!du>Mk(ks)JUL9YKorB12iF^NSsR5XG2((^S4T4SH`z)1}LmO-369m@Wf{tB>?1R-iF1Fs2iev#=eRXy!}WLh}wap1oQ z*nH9eQHAB}3ql&aOT%UiZ+L70L*h8;yJQ`HWWZ^e;}X}jXWlgK+jzO`9m{#D4aG1_ zGPmk#s-AoY!ftrCSg@xC%$j9Nyb>F2duJHUj^}2$%z%5Jb8NNs{-yio7^_I)2c8^r z-Y68l9_i{a(vh!krY@&2A{}K%y)3``q;?kxpGi8xeiS%~Bd`>*hf_ubo5PrnHu*vNq z8X{?+y!kR1RoH&PrB8oCnccZ88-KYS2G$-~lh{m0p!U(_s++?G(#=V|Dd*?lVMTE% z8q@0NwP?OgQO%@MHR{CbndqPzy!Yfg!SK~k+eokCZg$Y>714tM?VgrHr#S^g0tIO? z=8RGlsxDGFv;_iX6XsY7P63p(!1#+TxlaU56x(7hA%HcgSh6ipoQEI9FhJN|6xF`y zF#5OX1qN|)u7<-n`H5KR8e^8oPUj-Zm^ zxa=)6DjcPlK@EEsSL1=o;+h}lw87}zSM1K>{Jw#Ndfgt*f8P}A4M;4A$sEyh%P#Su z`}S8jfx{glW6)l20zX_#W$u*a16W$h!dmCF!(>hs%T5vmJM%vL`^b)>i3ew;qrWHHi$CTRQ zN&FNRuSd(C*_ppuxvnQdoy~F*Z?b8N1tE760n8GvJ^yvKv@xaO?4+zSB5P_ARB7f< zn~9D+MfnnN7DDMzrR|PK#-U;bOil#m?F{Ehy|tMNL=?i5jpea$v_86u`7+~*p;}rbP!EyWr4A`r@#oL2+JCsMr;jqy9 zZKTetHx0S^@dd&S3Z9GLnCL7z^U$1-=doOc6(LbO9XTl``rur&v9&lX@&*$$(w+|N zbh1?qLx0}y8{YM0W_yIUN@8H@2cXepoVfmcD-YqV5GcUE2FX*|8xIbSK5dVe1c_10 zJ6%pb4MFp@qbuQ*Rzb}3Ht!OzxWDuNuFngyl*jt~5x>o*4F~7mjz0A8+)B}1*myb` zfsJf;$Ip4h<#>GR_p@*4&le6WzTP=OnACvyRYdh2Tr16aM6E)cPB)P>;1$$0lV6v# z^`qCG(igK zZQJtKTxgG%E?4fFiqh*6WGK^+lW+U`;$Bf}lB#eNB1x-e$XNJ0%m~k{i-LpW{5$4A z#oK#DJ#BX0p+%SQ?F5z}uo0B8V*826a7}AFmZBb6x4~Hjp$NjHiL+4-5KH!2D8OQMB3;7X*jd*tN%$ zu1p6l>})Wcg|r7)768(Mv8kQHyWzM?X1>DJgm@_ipSu0Xz@hV;LD_0M?@x$TaO27l z_WUe$C&E75n09{#$pFpv`_XWrtGo~AWq#|%A#ECgB*Qibt>4&hkVfo3AamsXGDyRy z>bh~UZqGX~;g_ zLkrxL^)aMMTLv?!i@AfP@~p$2@_!_g^fJkEZnC_&f;3NxT{|~NkZsqh6b1_s`uKeN z`b-6B%p}uQ&J0TG`Nw_MO)ar$lv>jlH9bZyG>DlydTm&SillVKPp#<66L1Vs6+>eo z5J;?WVh1yssAXAMMSCk^97}*no zP4;wygNVM)^ar0zcgU2yuw}w>Bx#FapGU>Ivp~%3LTU@kbH-9sY0D%b?k6BovDq6P zCpy1_Xx`A}P9;eL7Kik=_Y=a{@S=o^g&pt&wQ@l0&q7<)TUPLQ0b;APGog^u@HbqN zgaxhBe`We70rhv$I*+G4n*X8WQA|iH5aSx6w;HF@SSZg;^l+zxz`HV1RNqB;Ao<~? z&LQ*^AQt^VR~`3oSeTm?!2Mw!o9ZNXb-PEdImVyP56L|aLxeOO!P3|C8c}nTR#vfL zs&F-a%=^G8FT`~}vKSYS4PcS64Wy^b^E${5wdjhNHE!h5P8+w^TCRTgV_U-oG)9!- z{Ujv9?Z$hcp3tPCC+zYk*7x`&*5f3+Y$21c86>^lUF3!J_6=VZ7;*I)N1r#?5}l1~MH8(}F7BS-)@92^Dn z_7*XZR=v95kU#&8RlhgeeW1tpRC>mJl-hcIKFRxB(@Q2|h4prGc64z&_4eDp*c7mK zX}5t|)eaUM+zCyAyWZthkRtPPnp?_uc1-HnB}_!Z6$#xDwax(U5!M+xp(b{i_8)Q) zUVqP|dc5t(vD-d_F*IZ_t!oe&H=_#-5C1?9#B|%YV{PUWk;^1MV60>5+P?}*b{B;& z-yi?Td`$bh7Fu>gfwS!RQ@uz}cC8#3S#@Z%BQ?_^TsJlju-->ls0Yudbb(GPcuB9&|LE#S zk49_ZE`IC&yEh6Dc3f6VUd~FM*w!CJuOT1FV#+`F`Ejff$s0 z$~tkdS2RRMMaxenq8VlD-mQeHEW?jR%`VIm-q$gHaw&R3sA$>j6W~I07k}RUq0BMW z)wqz5S%OYUS(f4zf2fW2a7E)2@D9`!dB%A4# zRt^_%&@$|lZNNsC#+HBxxO0xR>iZC4Uy;mq6Ns*yMn*^EPSVpBzuWobcKMjD@pYsp z&j%pvB)#N{FFnn*KrO1&#S3rCYtaG{In#B4TNFyDReRt?`;(zEeI3{FM1oU4j_6R1 zeQCuTyK;I2WURm_MhWJ7y3uv*@2ebx9Od%lxieh2dT*af3v=i;WMo$slk5jm=NE#z z63N=X*2-IPIOCiMC+FDM*+P3t@ZE%@+|sCm^+q>{vLol`QA%I`1;L#?>Z3ZWU`|#+ zIP&k8cCnZsJy@PnVN9`s4Pr0cBFc|AT;bcYQrIdaHa4ui6nnxtGIO$kfqYH8^a3;@Ai=gOe= zK7YzBFygx2tC+?8LCslbwTw@P`Y5*TyEN$TpZEN9UxSbj=`|z9FPh9(9|le4SoTZ# znkx!X>H3Z!O06kvR=;AEG-MAU<-?(7Eb#()i1ma9*Gu@)4V4h>tH^|6<@t8J*$~q( zAg~IG(pH%Mw9fiwFHm1`dGIT@;yh4b5m zsTgFNKewOC5Z=a9M3I&>BRBJIii&KnJAbbWeQW(@q%~9;Q(;w}$vOS;OEXH-KLpj{ zftqFau891Wxb1_IhkT#%d18{oT#F{Mb;(3NSkQWVd@7H(2B*Q9vwjt$Gnpn`L{COO zHiCb)fR9kE{pd6YfP-ICAX>*Fi1M^+DIVkTH8Ws`6v~KNf4s%A;AsJ`HzwC*G z)}c>bE|ZV3=mJfnwux1icgLCcvgp(Als058Q3LucmWnnK*AW^S4mlC=-TXJt4ltdA zdCRM=>55?o8pOMIBW{XzlN!Fv)G;jxq325mCpl{St7GYq1jgD*do>M5Ug}w~=?RJ1 ze!*!c2|^My68|AK|L_q#(Vo4BbV5e7{xvy%ZARyEcP(_^(tEy0u02Rn#hxs2IY5_C z#as%?zde2miqs5DUf}VH2`3*XO z6FLFiW)JbeGsdZFVI;=3aX0i1#>xiebkRx}e8Nv`U5?)|g<0NbYy)md^Js0nK*0{+ z)=4MSwAU4e>wGrGVXo_I7!j<;Y2gPx-x!MuBZ~28JPF@&djCvk#3hw-A6tav@bqkw z>XWz*UbyiGh1ijSmFD7Sn!waLw`-o-+x*ot$uee4=(ltvnF$b64qg%9VKMepw=-`nk@X}?GfuWEajxf$V?8mE$(vP(e6kSKy~+(kMyblH75 zR?iS&V@Wf)$xg*@S%}A`6sMT9ZC9emWF=w>bb^@uAFFQ!!YP1Du3R8oR)BCXRvC;QM#|JT1V9$uWH*=7<-q^-<%G}TJ?Ww^Gp1hIU#O=3xS}V=12dUzv z{j{m(nqtD^PmPwf479mT0tp7`x3#QVb?C$x4g$jRW%*%q%bLaAzmjyKO+viJuzhvYzBF}@mCA{0BJ8UOOadg%SPIG^jT@^zyhwK~KCg3%n}u0^64Vq>e$ z0Yy{?y*MvsZGJ3Z#*!5A?-pvs;Q5G+x8@=4N@I+%91N>ǜGY3T7fs&D;0TW2U zG9E71&ol*FY)0xbNAfMtw5`?`PqbZ3z7*kt)PhJjJ=jug!5KRJj;|n+Ox1z;&MQow zF{OcAE{U`04xMdv6&^z_?~Oj#b}xi$LAUuSu_e{y=QD#r;b$Vz`)I;1X9z&CL8ZbJ zKQ9*aRBNivk;evGEI5~qO5($C7y~+6s_QK6Zbz6v+M@D>KD&LN3ZEqhN=aQZSU~iz zoHfBGt#Su;C<$<+c*DLoCu|gRil*0@rD0RiaY}In=<6eVk7}|wh9INR-I^9t#C$am zexX6|!VmwTJ}pemaczl4&dG29k}W%LOTSvp6usfFao)4j_t|p2A=W?C0v-P*f3HAn z@g%B+uc-fe*B=t@<)_8lXALvfaq?ZHa?H1tTNSOT*B$Ie@tHVH4&V740r1zJY`Cs# zd3r$?7g7?QnQ!2mxFU0OK~?DtQBFt*Qb+dQYeYq2^Z?6e%MO(oRPz}`Cy zF~2SCkVT(|Sn?K$EioaenRUW}R1St^ZH1jVSfbi%-FnYlLWLj>JQ5QRI}5*)gjXwr z7BrH$DBKV`*7hqlf_6roGeY1UC*u;3k7Se$>J*Ls}?%JP1Kj$Q03YLjk`UPKxeJkOgS*a;FOa| z660nFcPJq}`=U_%pevN7!HOGF6gREik;!efs-C{ZLIyx3Zxy<|3pbj`Ko~*7-C-@n zJq}$Dl2+BzB$9&-O0->0ZodpNudFz}F&MJoLr7LGsj>|h?670_pXi7m3aY|y>RMIm zL<@REzYV?BEtIUXBOB)gKO(bp#xpk19;;xK!i6}Bo-g3Wk+ij_A)cVGevP>tY{eo% zsatc&Oqw|ld1sNA2(Ex8Pul|{MCeRzJ27WJLk5NKL8U*P8V6x$I;j-8ZQ(Mi~3s02bVzXlrPVxY-G0>E={N0qpV5#PM^-c1Z|Kpx>?|G8N}wqyoZaHa+^&5~k;*Rv9ioVQ~iyb-u&G;JYz$o{%Vn0D=@cY{GUHFr;+IC?TP@breRvV#%X`>maMOXu;dQHllbF8{_M7cLTUosaL+@k4gf-p~sQIq{U_fbH zl0I1-QjDM;JA)go8swI1C2@gg0%%Q6s@%^(Jkvg9>$#-5+Bmw%P)?g_WL5h;VX$lC z*^fN=2hAWO_I;Gg1!@)fqb?;6Qm;yby$#fJ1nQMWFmEl7RpLX@=)4vp&S6|46=!gW zdt}c~Svu;C<9G>gUH7$u!cN`%9ooqnSN=~|fVzyJQeoX=db?%6(hsuu;`^lOE`v8+ z!kQ|;UN!||rtVa>-Bbq{#0*wFp+phKv`l`W;21yhP?1p#1Ld>fnk#pxNbe@HA_br3 zYKk9;i{E^j!Xy!aX}v=;?hhgr`t`_j>DPBgc5-_vs=o~C!$ywjX$n#twf0kMuJcRz zv6&xuG~M^UOFe$hFoK2#R_$=-Q$AG#%ImEB|Z-=PNQq_j_yMpaOSukZwbv z8?wo62wmEhkkvYYStr?-82VKfQ@1a%!xRwT*!zN&SCF3}iDKgZVR0UXv)MaL^mS?fOPQg~46^h0kq{#(Dzv;79aF-Gb*r zdBQY$)-KkK=vo7yjA&N^g8L`Qe{!>m#%e5c*A!d>_>L87?fHNaq}PEe-o!U$83#_o zQ1f(?gR8FmpLiKCGTE*A`}TCt3hCLqtjwIqPg!Bm7}IZf3R6e;?}>^vc5$n5fgse4 z?7~hej($l$5wq3%WAl{S3!c((vIwn+WobgMuZt}EwqM8>P-=6}tmg!DxQ`ULU>k+9 z8+k;ow{BdsPyj!%&d8bXf3J2=JpBHsfsBk=gR!)*P4=-g<0_-9q%J=yC`nXz?xiEw z7xS3C0zqwD=MdDw_Hmst_bfU>#(@%cB*m)XaPHehk+sK6aW$4uOL7ntZSa9=xIGg6 z0#ItIGFa05t5`RTyn8o(4kCP%^TGTH5xth@?`z7>)6uR~Ra4>puA=rnH?VUKt$D2& z&Q4c2`MYCB>*n!}KN+85U1m&9QmP8dGv5pY4UF|nQ9clYDU);s`IiAZjLz5Z>o?BB z)SUyhA6kyBuG}&p5R@6GzC#Xn6O(n#u7!^SP(eqio*s8Ah**+M<01TbZUHPAU)N8f z#Jg|0N(3WgcL85L{l#Vrkbh`7L&?m>k5doI`$gm0jKnkLHe@knnIZI->>~|MG1MZadowK)YnW@TW%8o)8j?4cN0w_@r<8kj258vy@EV<*# z7#>I7)?=kfy39kN+IA$>HL1o8g8-fii4}vCXtCM=EOq0u<_>Nf};N6ZzZCZ#`xqbw4c@KwBnI!S#tE;xGU5 zV#R%~^$;M}jpxKt3=~E#;v8`bP>ubRb1kR1^aTc6)7j)N-uh7VH!-+vvVzsP9Xj)L zU^N**2tV(qS~rF(Z(80kq&98WP@3*oJiPH+RLw_DDq`#!3$i%Eh+|M8W&{y75RSr@ z{|?`0f?@AGTpEg|*Sc_7OxB{>`rQy9t4<$XiP|IK8j2-OA-&Z$ymXea^(JcTp@nhP zmr8rDF#@GSzbq{AEZ@+6m8Ys%>-4i#QJGQ45voBq;MQHZ1~kE>P$g zYZXbTSvVY)x3{wn34pZ8neGpXgZ1m`tHun|og3G>8} zl?;r$r|6!x^-_;ttsxi~87ej#3)?dOm&_H!sao4=En2G*ja#vD%n20ck?Py$ zrtF+7W+B81TGRB#MeKOsCm}*vo43<{ZQfl(C=CIoDs(JXx7^fcF18=~on0dFXTuYe zvM~}nrT)2n)O-VqHH0480rd}pL5md4hRb;kL0NJOz+g^`x_2+^9PjrPMRP*GAz2xkkx1Bw@PG{| zXt;d`i~=D}uuyx!d}KFk9Q2LPN%9N0Xcc(40@%k*tb+2^R+7kk6z*FXecT@__w`uC zcSQn7dqNz(4$*E2WtyOgc4G3FCelwgGt0r0GB6jsrvpTO6p(TeujqkIBj=}I#$vV4CBT7`UO25R zB|4nFwV?QXdAS8;8pmrA+0OeMUAqUg0MfNzEdm>`im2Uib)g-mNeat$xi!iX%=6aq z>I<8&y99HjE$0nd0HRMf-5#}~x>LUft4^hCTBAB`=!-qmzMj~2kS`{Y(rx3C1xrUV zc4jY7Z551;GBXr95Eo^;`a7!SCfN$7FcnNf%>yEF!`YXKb7zP*#&yZ2?8(QtgsSar zu6y7-M{}P@gcVigZ&E6>ZV6Egfj*1}z<%up4$IDG5{2ByhFo*hpLjEE?E#lyS0z@l z=QUp*I^j`Sh~dTfjQXspS1Q?!_0CWp9!b>@5ix7Hch-<5Cga18BibPW0~)0+=5S(< z?1blu2uAJ{IL_(GPUbf!05!>whX@ub2WK-+dX`wXgE@khU z;@M%*{=?9?AaFmIwX@JJ5QY^;o}v$-bMmOnLWpEd8JxnFc{dq%bcj54^A)?oZSmr! z1TwILav<4vu;O0>(sM7yc4cAzz&Kmui$lSYi>{5r>WC zo+z6O@eB;`Tnvh|1AV>+xYo8;QwK%(^sSkQ>K^r57>N ztM3lwLs}*fKIT&^?aoeFNCN-a-U<5~KYMvbl_<26jGWBs$g?3R&j^ST1Ac9t91kCl zhxIS05X7xx%8-xA#IxOfmKrQhy0O~Xp!^S;cM-vps=}PMG)W`#PkRDOTv54J`X!%n z*}{0Efb*(nZ&YE9^x^~)Rl`*y%u+Nep3zgob?9Dp8xv2Cykd+9UacWG^6b9msDe((#;4H*81D{ zAK`>iy?5sluGm+STeM=+5^mC8jn2P~+P>(IFiJOVpK2M?gYzl|2!1_Ez9C*<>wb&S z^@kB^t;&6P89b!l2POcCnpK-+k_y#@gvqs|q70v5#rW}A^VqVlemq&pIaL;KvO(i5 zb{)EziI|Jn|6%MLqC^YY#oD%Q+xBhSwr$(CZQHhO+qQAr-MN2~mt^n;nVmW{snJ>M ztgrUonDpl&rIy)>i5+`MuOF@XVmDq++(etZ+WwWJf#0pWr8Ry`So!zEmC(@~R=aJD zwyGz?Ek8Ljy+M=U3&{m($Q90>UKVA!AapC>H^#r+P$|rMevz zuEv!7pUsdWCedNa9kSg!P6L!Mx~PaLIg3U{dSZh+Y5}Fo&%iQ_R6CFmW0!(yYft?Z z?9o&>Xe^jOAvqHOBp>PUIy~~z_o?RZhaJk9qAeN#;;j@@PTWg1`QA*l?S%?wBg~P< z4zCJJ_e8;R4ECAo0;jcnu)H$`1Hv|%0L!L#a|YRxECQwBb?_L3aQlS zD5^meArUTr%4UYvz1&Qvcl}c7vd)#57&z14E#&pgq5N)F46}At>(eWlZ*pR@%*`de z2Phn$^Pm41(H!incJH#N5|iK$xeq6uhG9q^4KF%BX6A%?etG_g9Dret%1M zGb0jR(mVukC_wAq#fqoo{tjMHpts$vHUh83LmiUMb(DsCj51+KA~L63ABPPn1^8Wi zLN({RcrAUjXaDTvNFAHLs`gnK6?II~foJ1QqUxn4)gH)`r|!?9ooYkafYldinD{b6 zxixGZm0=iS+u_cVC~w(3qqt*5_!zHk+(JTD6Vb*x2}Di}*j%?jyb+{z>B@u{PrlPe zymeRauS!bNI}yLEmQNTsqUrinHZoxN%#$NkRHS1b+Wrt}EzM4XO_|{fOxhEHZ28KFDh6e!EVWlF?^z<}iA^=_%Ry>GkCK@#Ngw-2ZgY8v=r)Yit7i9|yhV|8mg7of{hi%R95S zHn0GWYi0u6WCySSFnf{v&-fwvNA%=Wob<79GXH4#=U~rIoZuUn%KmKy;AB)GbO7~G z@lS_Hs)XntpG6^{exGyXMmNj#TjxhcpYn4NgSUUTGd6nO8-MFt@T-!=`;EXjP*(>i zO(mlPFv{;J!NpnX^G<4HZUVRe0%vn^dCObm3(Wpq0MGv!6T13_-phPMrUmH6Xya$!-tXK_XXbO zjMnxHkV&Q4`DN6ekubw2`i;E?@N?#R>|dH%+xoi!@)k$^yIob$lM{3H%l(>X`r|{D z6xiOFSk1NLH@3fL!pM#6r6k4ehSUyq}l1c z?drGrk?*~)3=-ns8T)H!x3cbk8YC^?=>E5gJ}ZY!xk$?t@INa0Re=_qW(HP{_Tet2 zktr83f^0~J)2)v6)J`iR)<{4i92sfR#NbQXqaKuml&sHxDtgM3p4E^`J%RG0&CGEj z?XaEB;+nc|)#9A5gajW|+8g!3FscD03-!%i@Q6m#uFiXXa)BbTkks1m5PB%sXky;@U^C{B zehypR6Un2gC9`r>#}WGN(JzZOW=Z9M;2cW9`;#J7&!McLAx15%%UT5mHE>M7=|!HQfFr)xAQJ zQ~U2@FgZzu_&3(BW3VUDo<>(R>5K|@!e3@go2PS=4) zAG_+<`^IcVa+_u$VSR9^!Z|Cnk+mPZMX42yb-#3+xdf&gs>-wBwuZIeUy#%4ZYZCQ zsfTume`IYbtgQu#YhO}CLp$eU3>?}t#~IZ2BEMG_!0~TII!yB_&CK)X;`PzLW&|}6 zo)U$NqCUhfm@}-+c}9W^@+l|g^k5=_+|H%|H;iUqrYpYl_cd{nHJq9Py&o`+RG&ic z{z*FEFWlmVZ-N_(3S3C#6D|z8JzYYwzhcQKA&Z=uF`Psu?YplawE}s6!q*elgQZ_Cw4Xx%X`BvdQE9((mDKwdS3I?b$4+=f%Ct zFVHrp-k>k3atv|CeDeL<4Q`y_ybzeO=nRsS{Qhnr2w6*CYfQRo8gkcQnT#JCAT0LF z@@TPaceFU9c_@yuRYc%GjPm#)!({QK8OuMPE8{P{UKbR23Fw_rYb<-_UYjLDu6~HH zey>;9A#Sm+vzjL_k73sP!~ve+d^;E*i`Dfvu73AOz=8^m!>|rXO60w;Y3k$Jn!#Cy z-qRw~8fbBTYRKKnTJH5$G}MB+QXI-*-_mBLYbnhRA%YEVy(EPa6OesPIcW?|C<+n| z4rOs_D7Et*p(GB+f3sOjZm#V`VG+5x4i0!F)k9qKyr`)aVjqZzyqm-r*9sOLA!l}CY^}A95!py zLf-D1%24Mq<4l+Oh~s=^QY@y#y^H4SelImCCHWM2Cqg2Fc^=s-UAvn(&p2tU5L^f7wbtU?Du(0Sntiw`Lo4tE!>T5i!Em0Ya4< zDcyOvJX_GW{NMs{PWz&jO+r!m)XO0UTCB%Lm6AcbtMN$yS1L{=l+y$qt>DhqFZ1S( zx=Fl=KfkYsiFnv)j4uUbD{%yY1HB8Rg9Vrot4mrxGY2<+;Hf12l+&z}q=u-BEdUwP zbkHw_=I=>4?TX(9AK<^tu5lfp1Q7Ky4P2IfoYJ#&lVw-)SX?LGt(EtHJ1Xpx!3b*9 zMT;lm)s2er|A|hQ@Zb(#C$gx9|E>TnpqPY5B8TSMdL+Ge^^i?xSAY}!#v%Em^zqbf zS%Oo2?Kv`g5pr##hAD<;b!;3D3LiJ~wEWH1`U-Lnbp^JcNGp}$s5%+U?cnAEFhl{7 z!MmnhOA3lNm`e)tCfuBG(7Bo}$wIeILyz@mgQDoUr_%lgE?)MTKa#q1fp9CDmy*q= zUzUrMS>Pz<46;%Psl)mJl^U6+>OA5Zv|_|_+<3WIzaxXLkguRvEvi3hi*SABNj==D zA9!8#I8`O#Z(C)?D@iQ4PYl!_Z*eEv{I~#vefRleSH5jqr5*9H_76a%P8xCPe-`8X zXpRLCD!|h+3iLA2^>M^LIhzIg4#Sfq@#Mzi8uc*(9dQ)brA~fxI}5stR$Nacxyf2q zQRBf218Ntdwei)k>Q`Ps4n>5OKSu*iJYc1&hVpeyg;z}=gY}O}zs5}0TJnHq2nL`j zH<}++voe>~LIk^z(39iHK*^U@X|u!N zI7h6$DS;iHNaoWuS&IA!K5KUg{hn?{z`xvd4!puukD5+Qe;RVP2Z8di0u8I=ouo zcL8dprMro`%9Oj5 z#uUpY<&BqhM@Vd>b0yFUH+w3g`2e6*FQ_OPTY$FZ(ewuX4b|7hc>0`|W$=zVc`hDD zlwB=ua=05RRVj`qDbAfM=rUypVxp=dtPW;oO~SpUc&XK;^co(Ai4b zWz+ppt*&bvx~D<-;@pMXok2^ip-YCwtVH@iPLD`i5-2!~~0B~jF#H&UJ9l`Br+w+aKkm**^ zYNenXDR1W0j|@n~nz^O2v0i^U;eLy#<>N-{g@N|FD9aGv{JB79N-1x!c0M{+WeWVD zBC2e;+kgD$Z)%4UArZxR4N5|q(t1l6rDy@NT*BAQU^j1TB=98Svr>!3b(OFPoN;N0WII1va%cjiL6r!k zvI6N)=NMXRZSd-)cOJuSKP0F&4Gjf#Laa+6>68*K1#Hsx%!#2=DRYgWM`BSplQeyZ z6nOO;hCa^m`gD0V4U2!Lo^*J?D78Az!ItpP?WH6x?d+-8vw%@ z$}Ye&>at^p90wAHyp*c0CWX`WY1-t3bP|Yi!j(!gknKWiDNu0|{VcnDk<(x;oc4E9 zhe4;c_mHQr7@_SL^8_dWJj3RQ&u7^_-bL(21`SHhSEnds*+sHq-~GnhCVBEZw;7O= zh(JEZMJ(-e{HB#<`Hehwek9WqZY)t|=e{xk+_hsZtcSiJI$uQo;V-i`q$Wb>Ipxis zdFFMU)_i?jhv%>@O?%BWIX)8(JgLUX_a%%zu-LADtNg(>t>Ok(bGb7)PXOMZ<+?e< zHJqe^YH%-IlMpw-LTODwjXSEzp#sh7=HAkI&oP%phcq3@6sht0Q9ilO#lATK3_= z2t~SjuHM~rh7+r4nNJ`cmIquT(os8Zc(SN-n-cDYd&5$^O4e^y<5^>L9_bsqmKM-M z%CbKWKO7`m+t-99rX_4kPTtJEDffFFWSZJhjDi8yj@4JKR%gV?KKBzLy`W zQ{lP1Vv+^Ck`O->0%@L(UMFDGmC4dKyUF(}`nWh+#?M{P=IW9o zq^-mYHt%d!Iv&q9IX1wn>kQaq?DnD=#?AY7n`{CcO;)gMSzs}YoA`{z`-U8L9xNzfU8T;>|?g_&|uvp~I>X0?Eq>af%csoWkVNwfFb12{y%4bq^Pr;wtmx8k}KK z<){(=m^P+jSe}i^UZWR*g*9h|R5^_5`5gu8<)`Qa!SH|LG@{Cd4RYC%>lX6gnP7Db!Z#K$rw@X|Xoj6*ecQ*t z0khx;&5lWl{f)ding%hROu?DAaF=Pj?iKdAfc@P?8cFEdS|BoZB1|$zhN_=y;8DSA zuZuyFj42=-Lsay|tfCa$>euaoMWz)j?Vi-4c>N)D!3n-R9w}yx!U0PNBG~1GV*OL+ zC3MY7uYDtIlCPH6o6O`K!%DA4(Kb|QD#O|SjrkQ>B{$AXqaY%mVC#+^luT2B`S?7m zG`9c(_}c*qdxyzmS})5-q1j_^n<C{$++hq`|ju>O`xgnf4u&~ z%@Rvxk!^~Pt3cMF_b1pu)CE9`#Cy24isb3T;=41vBUy(?N`E;04^1Cib1}g8cIN&H zVEZU{DN&wR5GQaPNF**bth@XOdcif*2h4~8<@))Cy)7+s+jmW%yoYi}^1`XO4529! z*YN0M?!y^{!y{rMEg+#o8jA)0nEX+TV2VKRs5!;6_kz)_kVqs#3et&K!6zd0BOETLz2SjUZ<}J~Ro9-Z; zTpzg;n^81kt1xiX5yAe;5NV!9ioDVdI5#~rR5e|Mk$HkHZdf5!2#lnS4{pBwd@cvf ztk<^#TMzmg&&z!}>AyCzR0E*YOIRwB05v$9HaTR?W>e1D44X?@Ql2)x{KY*G>c$6<4GOcglNy!V ztfWF#p0qm#eoS0fEgmj5>w^kdc&+@*m|Pj@qlVX*1ny+X-vdmx23cPHQWC}^8 zOcP0t2le45b;7BEsPUGUYwaA(l77LMJnvHwR4^lSIIky3?=>4^*VCKPLfWMvwm1!Q zBxo*%r(&f#uN>#pm_ZwXxQ=v^3uV;dh|i0em@QF`E(!ND%jhAd1Rw_NFeY#+^Mggt z(jP4nf2-+*)mXf8q=Q2i{_dk^-;ZatwqeFgg+fCXSBgKDQOjSgWgE&8Wet|jSCP_c zK7+!`MzmR-)>`j+_xm+pb)!w;-M9}eZY;*I-+cfYp3pvi^9xijJm)5({WcrfKUZY% zdf;E)$TO<0Mo1Q7ur)$Rc0ckGVnye!1*#}_*YhZE&?PTHKB$M=80{kE_f{GT(-B8G9D5Xg+!&b3&N7)>~+r9Bw)PH z=FQVS-k@LF=+eUV1PNeSpaV^7NX83#oOvfovWzM9bUZ_M;!t`R-yFE2~IiXbjL<2 z+z@3ypj!p;@J9ev$(GOQ`~0&jN>K2g(XBrFU^t`kPU7b!KR!r2||A&f{D9~2T~E!(_Z z(H@b~!0XnJ>$yR`h>gC9&nb;QDgpR!3`mT@AHYswP2{TD9vbihtSte_avat_M=vqlF+sq|3xF9}+Zq8Dh@0ZDTXZU*5Yi@$ii?jwd+D5+0%u

z-hAPjun%VB^_&eB=3}4@heCBoeObBiV@9^V<*z5Bdtw$1+QJg~ zxDn=!f9@YNXh5a=3A4D!hnI)zmse~YH7{_-yjW>CV;kX#39M@(zCxVEX7ke{fxc_F z30>797}*y5-IHnh4NB^sj!+amwrtNfRDlP_dwR1gw^1QXlo!qk`C z#s%HBI_-e;-0OkrBuJ!=*zOk3mTQn-xT9Pl^T|frsb^-Vl{sNh6W zBUbXgSIPu*ikkk zo7=xQNXD(qVbP;0#mo;TNdEo?9qeAEq;(;z?3!Hkjie6wCch}z$E(z`^XTQ^y5=v- z=M&42XV|==Ib6C$i-eAgpz;j)x`S$ZE!y#wSzbZUqJN#!yz;PBbz*$r}q-y7#&c+VxAql-ePGF~J}cl<^evpbK*$^!lru3$ps6 z0j2rwXQ`gHmSbJN)Gp|GYeljXQ}4^r+yleVK5NL=8XNs0cQmk8(Klf7YC8OTybHCp zlO;2Bz`h0d=wjHF>K=zpu-k4{yW>bbM0CAn3zj1N0%`DSW739mt+UMAevM9gsmWBl zb&~@vS4`=&cK*r0>=((THZ~Z#NLN+lI$Nou1`w_#a z-CPKd9(TLfjs$k;&MM z^jk(~;nnk%2A!47+G(97WQ43=hS|0PDJ%HG~vhw6QB?1GD2<*aSv5zdrC7Zqi&o=!Y zeOXpG<*UH0&?g1US^fm+%#FP=w*ro2UinQ1Ji@JpAjRfql)|bXia%8AKSnF1_h#2F zyk>xEBI}#tRY*@lpZ8gVqL=7Jckts5c*YQ30tQ~!B;^S*$FTkCn;=N13pqziki8wk zqRtWFLyrY->|^Bk0ip%o-dXH^6c^PYT&y|52@u??+$YRimFfxT=%z{86SR7dCiIB6BG85 zA7-|w{#*kz%lPqxLM8Iv1cATig z$qGcBghqj>L>aUB!5429;pHlPcI-E{e-d+j`bN|rM?^cO=jh^vdB$zpwg-EU^pw%+ z?B+=jeX2kPf`7D??c8XLkF`B<6;>+>&Sn|TVY9^FNoaJztX8Da5x8QVYeNT@Z$nn| zBcTNvpL|t1fHx_oaAg*IwKj!V#3V9;EBUN|OQP502gOA^xf5=t0sx$H=DJ5aGSla( z<`EG>ig-FmY3TGo6i{KUwa1vj`%ii+vg8WtU7y>ALzdQ;d~z`Lf-nD>8z`a>(go15(0%S zk^iBvQmR zOnCs6HLf7mlK64z3`w`EwK*kOpz*Q)R!A7Zz3lW7obMH3j6$Iorwl>nATwIvC?cvY zw2*okT5|6}S)o4?lsjJZ zy>ZX>1Mxv`w|2;P!RBpGG5v2<_K4lKoA5Al2Ly9-`EEhht z&}8=~3n9hyvI1iVIL3fos9S~cGIj4P(yJsUUzie}vOt?*q@&tp5=|lo&rltcvkR3y zoi^B6MbK_$g0yw46m@vS1^y%cl@mpE_kuC{%pRI)5lG=;kvC01LOOB0w!pfd%8D!6 zL>|CV`Ih#01Db(k9CkJkyFUG-6m;SovP2sPAl3m?u)$>47kwvp2QS*FXPP6B>?9H+ zKch9iRiNG&fH^8-be0sm4@IC$xik@=Z16oFHHUV<52NwgqEF+X4(iy{_=_TYG&;z5 zVP4c0U5Q)%XgT<}y+?=JnM)Vwqic%J=Q^LfG!+kq#>A$)Hv2a*tBxA?3aik0R7ip& z)XYOMK5oC*w_>5Nut?q`#PJ5_8*T=;mIZj@K18iUax(dSvAbw^FII!I=CA|qIIW3{ z7`u~_vEo^3VVbxCGiEu9DT@JI3^i!U{Ti77@DMBF=lXVhvRFA)56mAqrEcv*6Hkou zHjyrkExpME8kNw+%)E~LtAX1x2yIJYq@dK`>*IFCH&m(pnm5fm`BW)Dj9d#_3DF4W zX{7_hBb1VEzh*Ol#dioA5rd}NSQ@lbzEV482_F;>8DP^d1l3A&EPGX>bW(xLqPYs% z>!Gye_!-?xV@8_cO{-cjIMem!Lcd7^+X-Auj1mhx?|}&Dky1*B0?1BxNvF8OrqQwl>XlQ<~@qVBcpG}+br zZlJgzg%45Pc-&AikbmBaGhrfnp6Or?-bgr6BcAwXWNBy83XKfSAnXVs0_&d-pQ;(G zTbeA#_R(2I0~;?CxNWON2r5B=Z?b(irKi!nL(hU&!sdd(uwaV45X|iI>hrzye{BEVA(l|I9Yw@_9@UZ zaA3*Hzu-?+*o4}<`m%P7n8xOE^I=!($)!O{4{o0x5_0nX)q4p+3vW{DKkBYs12ZBW z`25LZZ_#x)#w^p>^i3>SIn$%7*PGllz0t_V2%Rn1+2Lf@{(YWZn&*zLbYQ`2Q}^wJS2c&m6?@nzQ~jgY~{d9Py3_g(>=Pa`FEmhFKoA$`k(_ z19s|yd+25A_j1(~d4#IeLL3CD!3nykvx6*Urh+ECIkHfLNP)~3@{pqz!YW{b>0%=4 z4+T0FSOO#iRQWWxXGN==w7;zUdI))|Khr@2=#l*y1kIT{3DMYbdXTv;=5^81#YxS5 z#Na(HOuk1=3hDPn5c?Kxt(3tt=&TzV8K!dil*-H0E>*Rq<+z~f>jBEKmABaAF@V6m z*-6y%fjfjRQWC#a5=HEHHN&O8`4`x>xy07BXB{ww!o6D~+|N)4ozZ~9A+y#X;C2uF zs;rv??>kk1l=JH;5iWjI7Tea zyX}ok{6O>7y557#&8F>g%?y(1mV8?gHuNFIf4?x0*CE?%h*G($lcKV@<8;fn zuVgHo1)*U8|4~raA#=5<31QsqLPW*|D0 z#2Ea0YR)u6^;)*5pb8!oLMYd&)Ea2c=am?~Cyeyy<^bnzmu{Ekuy@_{&4YuX{I9W5 z%$O;x!;W2YUedS7_G8y>uhvi=*PDq}tGI6Nf;tYBO&WQ#lnQqT=_s89rqQoa97iO_ zXeKvl@UYi&2Bn}(|CYPC_~hK?6J`-G?^C=+Go1&nH!milqn#xZyk|@_Nim6sDNFFDS11#4X+yd?w z%7)xtE&TQCi0yBSYa=8T96{rR1ThLu)!(Jj{Na_Th7VGb{puTLJ?;wzz!nO3W%0qa zG>7$U;?`Y;Tch|x?+9&_=cydOHQEcau1(O83Q~!3%*SRUr{~<-z#hd*vll~s?72zz zv@qWtWOK{0Kdmi%Z{5;z6T6uLyO(nkBN*jGIBv$Gk$sYG{!tSC)OaPD-xR|akrs4+ z{r8UWQOb5`??gelD&>;}+icB&=KD}{p-2kLPam!vbpbskN*CK{(~0949u(03MVhvB z?mZhosZfMB!B6pGjX%kR80Iy2rt3by2t(NV23rcrFR`zOfdxgLde8)!$@$5(50o1%&>STE#G1bB~VJrf?KhVZ| z4;GK6Lv+V=CO8qQ*)^zxv!haQO_Q8y?eF8w_iGPW-VI^L3y*3kAH7Lc69#C$2P_?z zvFeg2p7fg{h_YsyNrqVr2`a+kn{6nG9lbPV6rIB3>Q0w%mDFA>CC$qZ`z;E~C6?Cq ze4&WR3YySR%SGo)3RXu`_Xrd}S@ltzC`}e9!sxld3xbV>!MBoC{16MiuCq!vD3RhF3R-b`QwCe79f_gfzPJh(1x(^3v@>sl`d)G41lKt4kor!m4 zkz1%R#1-P zzWO$(-?OZl5&RfY^Bh(r8-3Gvd&01)r?}l9;p$R^?B7vt6L*K;JOJ)td4~14cEkM< z)F|I{%X}H*z%&w?LMYxlqIo@8OYF=-xJ`FgKg7Oh%)Y8u`z}$KWOve_= zbz)h37TFQz3asDnzvCujYb>aBtyeBk)GIa}r^&XppW5X4dAF?Bbi$%yxj-MoMp;xr zz+fC;QLgnQ9|YmqY@9M#*!k4hm&j7Dai&@VFY>lR!z^c?`d(uQ*xs@*e-l94Em?wp z)=M%w)jV*R$uc{+`NkRKA1Lt_>TE#`)G_1qZqFvsh$RSS%05?yL4h6(I5rMrEe#SD zuo|Q^j0Q-#@NPX*FjVSR?xg;)NMs!+d--e#1;tIu4X54;)mU%1`|yWq7u8Z7bgJ9L zI#Q@L_en|gVd+K9tZJdQ)2B8WqWNMjlfd=_`U@ON4crWIZ6fsdh_IO4q@z=OLPncz zdGNuBVAFJ76|vz3zlHEcT%Mb5+-k+X_T&VBU76Ro?=WxMT<+zb}$6I8?BD5>_q|F0jYD zV8pA$a2(yd!XlynNT`3iv50y%N9+DN$1BC6QE#0{v~S(-T-4~KKaz!FQip`Z+R(aN zHP>{vDq#ObCZ@=y#7wVA%Ir*LO`CW|<+1boHYvKSb<3XXgSvPl=}XU(P5&FvL09KkK%_2dy+xR7_R`j^=v8Su9WxM+?Dt0F8UGYwCdxO;n@!FUG=u-cDxrmwL~eU zYepzaxW5>{!tk?d!X^Ka(}T*nFEFv3415m1fRU8Gc_`FthH=mj4sOaA6QV0IamxBJ=zdB7>ASONp-GTnI<6K?*%y{HSCrWK#Csl%>GBn6w=diM-XCX& zA)%hQm_J1+5l)~RCm0SZI^LSL@FR)ba|c9JWDHVn{goj*#)jvXfDYd&V25*F*?%L; zDhAJ??{2C~RgSLfzVE<$ebrc)NkakNTAS!BJ%F$er)L&^wx6-klDQFKAXP)EI?Y5o zSz-&^!*wzZsL7P1#pw7_=T){PYfbP%`e12?bt9QNoLydvhKDzrsWVrOR4x`z3SjL` zf%L1Xkd2lZH?146G3VGL6-PBBqu&KwU0OsN$N{Yx@2NVkAN5$h;njt~WiR7Dw;22uj6o2`HA>G($J;@j@;t65=0O$M!Tqjba`&JN^7;7W!*tgy$*+BT zp=CEfEo*nRY}hI8>|96i!dkS{Km5u5Oz(R+af%2RP&il2ig}JZgDh#3vD_`4+A7vO zuUtnoGD&z#mZ?e9A`G&xr&M>vaoQdJJ{8DT4jznJAjht069=w3zcpdYBRtj zKLKyLewkWf;jT$0)L0qD*EX3e%q#xJZs7ynQ_KMF-zD^5ox{rqJgx)uMd)iD7;AIo z(jKn|wSFRgb99X|$TuIvQ@u;7kb0ASo+F73XLsjYEN`g`I4(6y1-^^fK-o?35kOCY z$ph#dkLW|E*B87UNP97|!1XG>7hx0PYVx+w4P@KC@%BRzRdGRiw9NRL;7iRYL>eim zCr2zz`KcGD?uXDJud9(4C1A=GEeFsGLoyccv#Gm=_UY06_j_syJQ9&|+^)DeRn-o^ zt5BYx=Sr1p%e0&$g_CQUc0=;Z?mCxQcw10tC4cbj*O--AkAnSC;U5ZM)|CzzSw-cI@~&e@ z89yTlJyQ)VVCdXnMTnp8fB!d@zTna{7NG- zIGbF9-RDjpSc^GgvOVL||M+P_W9|!#zENY`OyvBg;nia;UbtA*4RYgrhAU7%`FZpU zN_U~G8$Rx2Dr+KrH1YA36+_4{eU zqr|&@5>kRGac`np05krln)&#VYhseJd#MvVg*PxqYIkay$BMaWXVs6#Bf2c9GUBLo z^$H+8BCa}f31WEuiWSB!embAMO>t>)|IUNJ#Zi7#hjn4Zj+2u3A}uqZcdjq6Kk37@ zD&g8UppoiOvG5}__u1{$>fP+u5-2JanR58KN%8W4wAH*zp`eCq*M3yg|HzB692wJ4 zc-H#D`12E|?vwMM;hLDLLjsjzZ?2ai7NB03l+gO=pr$aTT;QD1RcW)XpR<^;dfr?p zB1sOV9JBSs#dPcvp}Q1_vFA~u(t~FP;o>G#DUl5f#O)!)#dtyS5M2=M03^v)&)LCU zM98kIV8sJUwp)3 zWvBm+?)rb=E@cmU69RfULrW!R8z_2N0!D^^D3_>(qmwfM2mAk}x>z|`82@LFhTuQD z*3Kr51oWcT2F@nJCPsF~CQ!V*P)^Q{CI&W8?wcdpT1q%#jlO4U&qtgM1};1Fh_Ny8 z!3psLsq;R#zWfY=PH2Fk1F5fTcBg48%qvSv{R|YbL&wT%wA6jw%BnBs(nVN1#zY;A zglt@_t4a&3yQQP+Wa=yF>%%DJJrW6<6-|w`j2#P`!L(M`Hasg?qFQxW*jP7>MIKl; z7U@edu>-8Jqoi_kEXZ+gy^Jiq4#TsSA0)oACA4-}M?p5-WU;&K&wUc3EV&w%ni%wi z$D?DRp%-N7qnek}B3C#y>&RAzQZzQ<7S!^;!cim_)@;2InW>2~$f&fm9b_4!oQW(7 zJ!`!Zy$%WK3Q1DU>&aMkj@C#G%L6uu>bhb}#xr>p1r^@^ywbyhh!iBA^DGpfWFVQ@ zp`upjoUDwGPNj09+LVVjPpPV%5(7xmk(x1wfhRzK)i^WA?W0csffCeTn6**WfJ1W; zk`wpEEaMz=bI-=Cb9Jm%p_t~22}=Q*EEX}H4RC+1qFTx=c;#A@3q9v1m#4?bOF<9^ za64i>LD0kLHA3MCk>FcH<2`Jq$t_z+bD6nHt)Uqc4J@Qy7{P0c%8EVETH}x1X)5H( z`mc^uNIv2uS%|8x+sspx8-rnM5+!rhjxXrP&dY^e3sH z*%?-pZk}G0JxoQyR#77pcTqDfaZ}dZ5?-}~5M z@?O0m-W$etDEX8X%7hKx_`yA4`Bc-{y^`%ExZ>c22xkSubY~76kGEKqqaiv}aTg#; zYfY-MZ{zN-X!57Utxni~5t&{1wbvZRdg%QwX4GbIl}&!)kD>C5sb)YI|3&Wjn*h-M zqUd;aEP~O2Z;RY>w*{Pf$n>cpyd!@dJ9D^JP5$buI)}FVAW%_?As>JDvjISW7e!us z5Mp)8zB0zNL3iD{2Z3vM(z?Ko+7tZEFX}uzCe&a*dEn3Nc=X$_jc@&fF9KLA{cvIJTX{Gh~Y$ zbnmh_*Ek0)ik!E_k3yYsf9~HK;h>8Co8sMYGM9d;|EpkzK zQF%#HvHTd56@;GN$DC|AXEMhr9vqrWUs_VpDJIDn1Ew&SXp*5*=>%Ko)Ou-BjR`_0 zb*5m1?pkNfd)f$wq!l&NHuF;eB-uL^Aa9^=3L58-flAEJF^!Y`S;Vk0M?OQ`m_a2y zGBzy;gp8qXlH!xEDPMT51R|?5z)1BXc(8(7z?Munt$N0Fu>o%Ohr4CbTP-YW<~BK> zQ>rMp+*PcGJy~pP#Hi6HNI}y-PQ468T#tQg}w?w6drN)PxC2Gc!>9)G6 zg!NGGg~p9+8{G#yIT@K|CL|N4Kjj}FR#MHL5X{h6#F1`h3~law99kqPnAb-ZwUfN! ze20x)rjr~X*Q5#Kh%6vu_?U2%ku}DP7&el5C-WLQ5+bRZuuqR>}-7K2#fBG3;V zZ_>zRUhItr){-E@WTgq+t5Ik#h5_g`bGOk%w#2NP!cf(O)Ce-+)iq&Tj{K|e#I0%CfdES{wChOw?@-gX>eg7wy9Mw`@{ z^U5O(?jAF!oSJ%w6lDU;9X_Xy0|1>l6je5#)b-OGCLa^%LAEEws zXDayF&S?y=%ZYV>Q#Z_+o@IhtuUZbz38Mt6Yi~BE=?uoY+GIk(_EU{f#s3~Zg_!Bj z>Y*C}9i1G-lNQ43V;W|!Zq^LgDwIX7QLyqq8oTajIKQnOLL?KJAPAxiBDyidFc@ug zqC~XlMDM+mXfa51L3E--iQapU7A1P`LlC{s@cDhWth>JZt#$8O?;mIHcb{{fb>4l> zAJ4PieZ;f~-`!<9y0175i6L7rO>6iP<!;v`V^WSyVIKD0NHQXwLVN4F2>_!Q{uDY{d!yR{BZPl zL+cN@@IUe|kebyWKhFdJeh03kzOpJuXQ)eSU~?j~Z9j6f2iC*)Sc?Oa;>0~)D*|TL zd`9U%65}l}ei3xL7Z%)!N-`T%o6YDENkQjx#(k0!y;F=H3*!s1`@JBsc7`b!(^(LO z=N586Qmd%S_U`?hff;g7Jzz*qm?-D;jO2vU)9>#~1ffWUrI|Z@P03Vg0S`5xe2FO@ zMWMzov;%_JcXwooaXiJZrsVYERIJ{VFBwXcCyTGqM1BejBs^j$2BGNVDufC^-hHVz zCPBj};qu(MY=qE5o{&6?+Ar=?R31+rEP!_2Ja?V@CI6n^CI!-pAxt*z8@EY(W5%NU zF-T`;v|Y+8z)6J23x=b!fV5(jD;}t|SY7)3P!FMSl~vs>Vf9JItI(fMW5P(&tnjlb1{wMvO_-Kez z%rVg&>2o~*oFEVeZL*_5N*M20aom18nAO7a=ErZIZ?~spNlc?Teh{h}I7DCC5br#l zVS8J6JsQFp#BUXs*;22r5({MsF;wC>C$fKH4BS(oGN&O=W<-uQS8^l-e5C^-$t5P+`4Bb*cFtaMlupEAs1Bko(4Orv&*!gKW;iL@6I)P{3x$d;n5 zauqF_xH3CK4^Et_-wUuBWYIB819VI_XYQE_bWEb3B`Itg_isqHKE8(QIsCY6urP35 zqOF{F5RsUeXOgfJDO|A!lT3!c&SQ$BmUW4tXaHHR7lq=07Z^K&bwEW|))6 zOaCcu7W(HlvJSXk;$D;AP53z)mXeqvvj2@h$=EXx82SnBrU_7M=M1)~W0hzt_~=SL zO*^JT@*$pX!U<0D+fkrWpcpNg$a3PE1SY!Z=6c!)e=XgO3Ur7GngGQsszyrWw{P{t zXqVQ@Wy;_t1O%R;sXsf%~_x+xD zs5b)=u*;Q^bm&_b67n#fmWZr|F<2v<)DE&bA^9EiaW0g>jv+jPswbInyQ54Kc>CiN zJ+m45IS&kA8T<;4WjyGkonf}LyDVS-<~xn!f_h14jx0^C~VVp{0HO}?Fzy=^{xjvft|n~$#=&+`GWJKPkP4% zMt{5?3|sFM&M?eRy&QinP8t?c6_?Hl8W_hr+m3Z*;L%1=?gxB2jb zf;f^CmH|8FWp?oo3$#7x65i^Rz0>xw6!~;&Mt3D%Q0YsC47)qOc7k6fM1Y=Nu9kMK zL8udMYNY8@k>|)5*bz)k%;*xDMqI;ZgG0+75H3+(R5ENK@3QkcTHiv?-f^D;$XQRK zO{25jQCDl7Ii3O|qXA#D^g6;7R~e04o@z(lO5~q|Y-OtwwJ&7%hmefG{hEstQ04qf zg&XKuiVPVIN$Hq2GPsrNDWPf()04&nIU_Oh?KV>AHpMtl?;*g~jo)XDEZcAoI$xSw zPAO9R-u=Oz>=xebMN$iQ?yYAXSl#`W6Mdo;y2x%!IMjlwJ=wveL~|vq$~UEhale$l ziTkZzb#!GVA*oZK^0r?aj33Dm#EqCb*i@=)GYRVNL(B zoIhTIu0M64&I6+EN<8L!4R}WMn@-;X?!=PWs;$d==kIQf-JSuiYe{FHX~{?0`i!JW zRjbGq3K&M(U;H+?FLQ71q)3jFYasZAE^IO`lA^k>jJhvdSAKOxKwuMaCh5}N#`Hld zhU*)9dO5vcYcG@~rBrW{sdo|wvGSnLhccL-*MwvWk_xtA4ec)EM%;fivNS_?<`~bR z3by{P zp_J}>F_NLtop!~&pS5N_8Lo~5_gQR#*X#BB4r6i$LN9{l)AhIKel<+cQNP4r`=uUTOMeN_2af1GRK%bk5d8P~JMsiG@V_*yXY zDc!eaq0X^S#g__n$@{hxy2lvZ1*4MLp*~d2?^*3vQ8eB!oz%6&4W^Naf|lZcndm3;9jfj{C6${xGtP0EZ-C zeCuv9m-8w*+-iKWE#)6lSwD>(j@MsLlGsOCqE}l^^~G}$4645+`>y>Z!?GD31wGil zf3%D}y#}&x=DotFlo>U-;2)vhA4F2;Sy`$vJ*1J8F>$P7(U{EgsYf6#&rI9|FA&~P z;Wu6>q6UY<1x?-}mf-W`jQP#WOs`AcUC}Y+3Mo%F`gMVdh1b|~%lhLn?-cdN2=w~J z!O6&uhnK6P*SWj5EB0i2*~ZI{FF#SSdGOLoaXbHHebxZDaE)6PF~wqf@>TuX{W9WH zWuAIPvqpA9wuZMAwh~#44O6z>JTZ9`pL*O1v!Zc0b9?7ib(GdRzesaLX)TYZ!ZlBV zv!h77L=a($Z^RR}AAXu}n&CT7Tb(|W?OdL5O5tcX>Sw1s1KzE~wwzXCXVPlW2F%PM zoHpKk!U*9szw0^umt1-1p53klOK(>%kCU9#stWKEs%!Hr&8y)XSwJP4cxjg7eMVHX4X|a-;mNCRRUit^g`>Eyk?8ct5 z?&5fJzps10YiiJWavFr4$0jfs>)I})q69?}QI|l5u=p1L)QbEYvt)gvk%Uy7GjT2U z06(9joxxwW@43mvozbf!qH&Q8&wMazRgEiAXou8O`!`#=KpUqaa&-Vu!EM8+G zqTm$aZc47Q`JXTz&B;NCus{=s5Shsexu)1-zE7w5!e8`h_1SB@{kmXp(Hm1m|6(7QFKqOtu)B4O6}9h%CE!i)3fq*#=) zD@fZ_hqmYso-q}HBTK(FWFPyd?esNphrp;4Hip2der!xMXDdlQYHSc!Wjx>C)Rdks z&dHeh)5V+A-tRHJeB)qsm$qoSfk9YsIqT16U8PQbAzbxyW3oEjQ#06eNduA>BF>v^Za)qECcNaJAZ;`Q+-}%~a-*f6EhH z`qnMo-78ODydtW!!s^-d`=RD8&0gZnMZSV>vD!*+>}StfH*z_i@u`2OhL1@5${9}m z6nU3ceSR|(YQihrapf+4X(KPTm=YQO>U!kbQMhj93c{8$^rF%r%lr(K`o>5zRy4G0 z{8(oQRkE&>jcvdVaYr9ocO9VjYR=r!Lq!H_MTECwOO!%Q%$xH>(myM_KN}Yw{#w2< zQ+5?lLbhh$i}BdM&c08pNJWegbTd_gQsa9jw3IA0bj2?M-|9JT;fgzMG&6=&FMbgq=3CdUeDs}n_F2-|q8{f_M1Nzp-XJ39#1q_NrEQj$kW?5}qtP6Lp`A-uKyg6$ zz21A}*UsV}*-W6DFztp(bu`@WRh!c4Sv@Dy;Q0=)GaW@rmGDvr^0ZOpDCg?XbmPEm zgHW;uL%Y%J65BN3W9TS&l9&f@ZxK1mVP9kVqp|pA`+{~L!Ok`zX*M~F@TTArdFaj3 z^lrLtz}wK_`-gc>l_6)*8}J#7@wSMwoyp(%^V^oau@wNq$Nw)Zy^52)iR;^2(w)V@ z#7xapixa}d%gqJhVFiFCZdrF1``b6S?thq;_I8rD+&qXyQV`00Td7R|0)cWvAy5b> zH!m|cH}h?rqP@v~3Q==1a&Ry;xh49IY@AI2U==kfEiP$S8yjOIJG;NIs99J#gKnR{ zVd4O3m^wM%P7UJWg789M0#H6qC>QTPp#CpF&`V1=Th+g%ToMb!2e;&>b>5?=?KzMrU?Z~t5mghhMC$F*>kvt4i{l@cF8UEP1P|kB6A?Jj@*G_ab(BF{ z@8E+Ti?J>taT)MN-;aV`-lqtV#Am}}qPUNveXo@`3i2rIqr`Hwaw|nt8R#8=oC=t7 zw?OO{UB(11?p=%f^pp;{M7$#^F^{ou^coYBp2h0?f|uXT;x;M9qHfB=Z*O;~d%=z_ z3$0mx;&OElW0W#c(5qOLDnCRunY)c1$GBGLMn9MOmUHaWtZiQao(?-az&!7tCq%~% z_ES}seRg*@&k&LuEvTunP!HfsA4z0Xn2V0aM`wprrAL06Ah!*(@Xs6mu^wT&?{n;1 zp=S-eKmUx8-Jc+Rnd7lJTS6@&eIdW|@u%-O3CB7?c}q6w{0$ki+44=%T268e!I!j@ zl%jMrli7Lsb|a>{e0jr&Idk8(4E4)w@jTyO;cSdEf0(eqhaE50+A4RM=Nl(CjSd=9 z2A=Y8KP419lX0bxQ6d79sZof1kGPNgps8{kHy7C*sT56Q8rB|bK;Jo+Cgz4O^(xO` zn@{f5jL2wZd*zDJFAt>=nAI4?L`>};(s=h`?oK52nCu4Wf%U+MM+&eva9M<1G>w2+mTg9JCh_8N9yOvM8>|TtoKRf8Hi!IJ|sS=JTcD5FI z(*f486|CJwhE(e9+!1e`GY-Z!Kld;+^%p89_*$5(!Gu#V{o<-2#gl6^LXPhSr#HQj@c-N8@PA8fEmc!9 z09ek>#MA?%!wrJ)3Fra9uPwby|7rrjnjjqrhzA6@b*kFiyWBeYZii6)tB0BWt@YQj z@s}kD(m{xe!+E8lP`IQNk0cz)!;h4JN%Bg=1mHZ9{19#=w+QGzhuqHd($vn}#RA03 z$NOLJDW(xQ8^u@DJqL?>bH6<6ePPwzR@OGwY-!)Lwbd^N5S5ixhEm4koq#eBec7m_ z%~y7t&eEzX`nK-!hi|jU8Ds}q(g&FrZv^-$X@q)PH32j~&Yv;E` z+PrYf&L7V2kOgH*VMd+27R(PL zi1OGI_u0k?7An*g+V|1BSFwp;a#XN!v=+x_lv(ss&Mb8fvi?q|GGq~{t#P~-=LD)q zi+v*W#5izD7IFQju#m8a>c&jh*Rr0f z Date: Sun, 19 Sep 2021 20:59:11 -0400 Subject: [PATCH 08/36] update ImuFactor reference --- gtsam/navigation/CombinedImuFactor.h | 3 +-- gtsam/navigation/ImuFactor.h | 3 +-- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index a563d9d438..ce169c1d0b 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -42,8 +42,6 @@ typedef ManifoldPreintegration PreintegrationType; * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating * conditionally independent sets in factor graphs: a unifying perspective based * on smart factors, Int. Conf. on Robotics and Automation (ICRA), 2014. - * - * [3] is available in this repo as "PreintegratedIMUJacobians.pdf". * * REFERENCES: * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups", @@ -53,6 +51,7 @@ typedef ManifoldPreintegration PreintegrationType; * TRO, 28(1):61-76, 2012. * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor: * Computation of the Jacobian Matrices", Tech. Report, 2013. + * Available in this repo as "PreintegratedIMUJacobians.pdf". * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, IMU Preintegration on * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation, * Robotics: Science and Systems (RSS), 2015. diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 0df606643e..266f2a5471 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -44,8 +44,6 @@ typedef ManifoldPreintegration PreintegrationType; * C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, "IMU Preintegration on * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation", * Robotics: Science and Systems (RSS), 2015. - * - * [3] is available in this repo as "PreintegratedIMUJacobians.pdf". * * REFERENCES: * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups", @@ -55,6 +53,7 @@ typedef ManifoldPreintegration PreintegrationType; * TRO, 28(1):61-76, 2012. * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor: * Computation of the Jacobian Matrices", Tech. Report, 2013. + * Available in this repo as "PreintegratedIMUJacobians.pdf". * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, "IMU Preintegration on * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation", * Robotics: Science and Systems (RSS), 2015. From 28d0393abd7cd94dd690b4a9b95805add462917a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:51:24 -0400 Subject: [PATCH 09/36] add test for checking covariances between ImuFactor and CombinedImuFactor --- .../tests/testCombinedImuFactor.cpp | 443 ++++++++++-------- 1 file changed, 254 insertions(+), 189 deletions(-) diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index dc9ae288ae..f7acfa79e5 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -18,16 +18,16 @@ * @author Stephen Williams */ -#include +#include +#include +#include +#include +#include #include #include -#include +#include +#include #include -#include -#include -#include - -#include #include @@ -44,207 +44,272 @@ static boost::shared_ptr Params() { } } -/* ************************************************************************* */ -TEST( CombinedImuFactor, PreintegratedMeasurements ) { - // Linearization point - Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases - - // Measurements - Vector3 measuredAcc(0.1, 0.0, 0.0); - Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0); - double deltaT = 0.5; - double tol = 1e-6; - - auto p = testing::Params(); - - // Actual preintegrated values - PreintegratedImuMeasurements expected1(p, bias); - expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - - PreintegratedCombinedMeasurements actual1(p, bias); - - actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - - EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol)); - EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol)); - EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol)); - DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol); -} - -/* ************************************************************************* */ -TEST( CombinedImuFactor, ErrorWithBiases ) { - Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) - Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) - Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); - Vector3 v1(0.5, 0.0, 0.0); - Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), - Point3(5.5, 1.0, -50.0)); - Vector3 v2(0.5, 0.0, 0.0); - - auto p = testing::Params(); - p->omegaCoriolis = Vector3(0,0.1,0.1); - PreintegratedImuMeasurements pim( - p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); - - // Measurements - Vector3 measuredOmega; - measuredOmega << 0, 0, M_PI / 10.0 + 0.3; - Vector3 measuredAcc = - x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0); - double deltaT = 1.0; - double tol = 1e-6; - - pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - - PreintegratedCombinedMeasurements combined_pim(p, - Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); - - combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - - // Create factor - ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim); - - noiseModel::Gaussian::shared_ptr Combinedmodel = - noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov()); - CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), - combined_pim); - - Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias); - Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias, - bias2); - EXPECT(assert_equal(errorExpected, errorActual.head(9), tol)); - - // Expected Jacobians - Matrix H1e, H2e, H3e, H4e, H5e; - (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); - - // Actual Jacobians - Matrix H1a, H2a, H3a, H4a, H5a, H6a; - (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, - H3a, H4a, H5a, H6a); - - EXPECT(assert_equal(H1e, H1a.topRows(9))); - EXPECT(assert_equal(H2e, H2a.topRows(9))); - EXPECT(assert_equal(H3e, H3a.topRows(9))); - EXPECT(assert_equal(H4e, H4a.topRows(9))); - EXPECT(assert_equal(H5e, H5a.topRows(9))); -} - -/* ************************************************************************* */ -#ifdef GTSAM_TANGENT_PREINTEGRATION -TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { - auto p = testing::Params(); - testing::SomeMeasurements measurements; - - auto preintegrated = [=](const Vector3& a, const Vector3& w) { - PreintegratedImuMeasurements pim(p, Bias(a, w)); - testing::integrateMeasurements(measurements, &pim); - return pim.preintegrated(); - }; - - // Actual pre-integrated values - PreintegratedCombinedMeasurements pim(p); - testing::integrateMeasurements(measurements, &pim); - - EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), - pim.preintegrated_H_biasAcc())); - EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), - pim.preintegrated_H_biasOmega(), 1e-3)); -} -#endif - -/* ************************************************************************* */ -TEST(CombinedImuFactor, PredictPositionAndVelocity) { - const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) - - auto p = testing::Params(); +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, PreintegratedMeasurements ) { +// // Linearization point +// Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases + +// // Measurements +// Vector3 measuredAcc(0.1, 0.0, 0.0); +// Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0); +// double deltaT = 0.5; +// double tol = 1e-6; + +// auto p = testing::Params(); + +// // Actual preintegrated values +// PreintegratedImuMeasurements expected1(p, bias); +// expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + +// PreintegratedCombinedMeasurements actual1(p, bias); + +// actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + +// EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol)); +// EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol)); +// EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol)); +// DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol); +// } + +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, Accelerating) { +// const double a = 0.2, v = 50; + +// // Set up body pointing towards y axis, and start at 10,20,0 with velocity going in X +// // The body itself has Z axis pointing down +// const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); +// const Point3 initial_position(10, 20, 0); +// const Vector3 initial_velocity(v, 0, 0); + +// const AcceleratingScenario scenario(nRb, initial_position, initial_velocity, +// Vector3(a, 0, 0)); + +// const double T = 3.0; // seconds +// CombinedScenarioRunner runner(scenario, testing::Params(), T / 10); + +// PreintegratedCombinedMeasurements pim = runner.integrate(T); +// EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + +// auto estimatedCov = runner.estimateCovariance(T, 100); +// Eigen::Matrix expected = pim.preintMeasCov(); +// // EXPECT(assert_equal(estimatedCov, expected, 0.1)); +// } + +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, ErrorWithBiases ) { +// Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) +// Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) +// Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); +// Vector3 v1(0.5, 0.0, 0.0); +// Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), +// Point3(5.5, 1.0, -50.0)); +// Vector3 v2(0.5, 0.0, 0.0); + +// auto p = testing::Params(); +// p->omegaCoriolis = Vector3(0,0.1,0.1); +// PreintegratedImuMeasurements pim( +// p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); + +// // Measurements +// Vector3 measuredOmega; +// measuredOmega << 0, 0, M_PI / 10.0 + 0.3; +// Vector3 measuredAcc = +// x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0); +// double deltaT = 1.0; +// double tol = 1e-6; + +// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + +// PreintegratedCombinedMeasurements combined_pim(p, +// Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); + +// combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + +// // Create factor +// ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim); + +// noiseModel::Gaussian::shared_ptr Combinedmodel = +// noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov()); +// CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), +// combined_pim); + +// Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias); +// Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias, +// bias2); +// EXPECT(assert_equal(errorExpected, errorActual.head(9), tol)); + +// // Expected Jacobians +// Matrix H1e, H2e, H3e, H4e, H5e; +// (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); + +// // Actual Jacobians +// Matrix H1a, H2a, H3a, H4a, H5a, H6a; +// (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, +// H3a, H4a, H5a, H6a); + +// EXPECT(assert_equal(H1e, H1a.topRows(9))); +// EXPECT(assert_equal(H2e, H2a.topRows(9))); +// EXPECT(assert_equal(H3e, H3a.topRows(9))); +// EXPECT(assert_equal(H4e, H4a.topRows(9))); +// EXPECT(assert_equal(H5e, H5a.topRows(9))); +// } + +// /* ************************************************************************* */ +// #ifdef GTSAM_TANGENT_PREINTEGRATION +// TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { +// auto p = testing::Params(); +// testing::SomeMeasurements measurements; + +// auto preintegrated = [=](const Vector3& a, const Vector3& w) { +// PreintegratedImuMeasurements pim(p, Bias(a, w)); +// testing::integrateMeasurements(measurements, &pim); +// return pim.preintegrated(); +// }; + +// // Actual pre-integrated values +// PreintegratedCombinedMeasurements pim(p); +// testing::integrateMeasurements(measurements, &pim); + +// EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), +// pim.preintegrated_H_biasAcc())); +// EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), +// pim.preintegrated_H_biasOmega(), 1e-3)); +// } +// #endif + +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, PredictPositionAndVelocity) { +// const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) + +// auto p = testing::Params(); + +// // Measurements +// const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3; +// const Vector3 measuredAcc(0, 1.1, -kGravity); +// const double deltaT = 0.01; + +// PreintegratedCombinedMeasurements pim(p, bias); + +// for (int i = 0; i < 100; ++i) +// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + +// // Create factor +// const noiseModel::Gaussian::shared_ptr combinedmodel = +// noiseModel::Gaussian::Covariance(pim.preintMeasCov()); +// const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); + +// // Predict +// const NavState actual = pim.predict(NavState(), bias); +// const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); +// const Vector3 expectedVelocity(0, 1, 0); +// EXPECT(assert_equal(expectedPose, actual.pose())); +// EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); +// } + +// /* ************************************************************************* */ +// TEST(CombinedImuFactor, PredictRotation) { +// const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) +// auto p = testing::Params(); +// PreintegratedCombinedMeasurements pim(p, bias); +// const Vector3 measuredAcc = - kGravityAlongNavZDown; +// const Vector3 measuredOmega(0, 0, M_PI / 10.0); +// const double deltaT = 0.01; +// const double tol = 1e-4; +// for (int i = 0; i < 100; ++i) +// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); +// const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); + +// // Predict +// const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; +// const Vector3 v(0, 0, 0), v2; +// const NavState actual = pim.predict(NavState(x, v), bias); +// const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); +// EXPECT(assert_equal(expectedPose, actual.pose(), tol)); +// } + +// /* ************************************************************************* */ +// // Testing covariance to check if all the jacobians are accounted for. +// TEST(CombinedImuFactor, CheckCovariance) { +// auto params = PreintegrationCombinedParams::MakeSharedU(9.81); + +// params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); +// params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); +// params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); +// params->setOmegaCoriolis(Vector3::Zero()); + +// imuBias::ConstantBias currentBias; + +// PreintegratedCombinedMeasurements actual(params, currentBias); + +// // Measurements +// Vector3 measuredAcc(0.1577, -0.8251, 9.6111); +// Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); +// double deltaT = 0.01; + +// actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + +// Eigen::Matrix expected; +// expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // +// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; + +// // regression +// EXPECT(assert_equal(expected, actual.preintMeasCov())); +// } + +TEST(CombinedImuFactor, SameCovarianceCombined) { + auto params = PreintegrationCombinedParams::MakeSharedU(); - // Measurements - const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3; - const Vector3 measuredAcc(0, 1.1, -kGravity); - const double deltaT = 0.01; - - PreintegratedCombinedMeasurements pim(p, bias); + params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); + params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); + params->setIntegrationCovariance(pow(0, 2) * I_3x3); + params->setOmegaCoriolis(Vector3::Zero()); - for (int i = 0; i < 100; ++i) - pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + imuBias::ConstantBias currentBias; - // Create factor - const noiseModel::Gaussian::shared_ptr combinedmodel = - noiseModel::Gaussian::Covariance(pim.preintMeasCov()); - const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); + PreintegratedCombinedMeasurements pim(params, currentBias); - // Predict - const NavState actual = pim.predict(NavState(), bias); - const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); - const Vector3 expectedVelocity(0, 1, 0); - EXPECT(assert_equal(expectedPose, actual.pose())); - EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); -} + Vector3 accMeas(0.1577, -0.8251, 9.6111); + Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); + double deltaT = 0.01; + pim.integrateMeasurement(accMeas, omegaMeas, deltaT); -/* ************************************************************************* */ -TEST(CombinedImuFactor, PredictRotation) { - const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) - auto p = testing::Params(); - PreintegratedCombinedMeasurements pim(p, bias); - const Vector3 measuredAcc = - kGravityAlongNavZDown; - const Vector3 measuredOmega(0, 0, M_PI / 10.0); - const double deltaT = 0.01; - const double tol = 1e-4; - for (int i = 0; i < 100; ++i) - pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); - - // Predict - const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; - const Vector3 v(0, 0, 0), v2; - const NavState actual = pim.predict(NavState(x, v), bias); - const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); - EXPECT(assert_equal(expectedPose, actual.pose(), tol)); + std::cout << pim.preintMeasCov() << std::endl << std::endl; } -/* ************************************************************************* */ -// Testing covariance to check if all the jacobians are accounted for. -TEST(CombinedImuFactor, CheckCovariance) { - auto params = PreintegrationCombinedParams::MakeSharedU(9.81); +TEST(CombinedImuFactor, SameCovariance) { + auto params = PreintegrationParams::MakeSharedU(); params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); - params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); + params->setIntegrationCovariance(pow(0, 2) * I_3x3); params->setOmegaCoriolis(Vector3::Zero()); imuBias::ConstantBias currentBias; - PreintegratedCombinedMeasurements actual(params, currentBias); + PreintegratedImuMeasurements pim(params, currentBias); - // Measurements - Vector3 measuredAcc(0.1577, -0.8251, 9.6111); - Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); + Vector3 accMeas(0.1577, -0.8251, 9.6111); + Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); double deltaT = 0.01; + pim.integrateMeasurement(accMeas, omegaMeas, deltaT); - actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - - Eigen::Matrix expected; - expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; - - // regression - EXPECT(assert_equal(expected, actual.preintMeasCov())); + std::cout << pim.preintMeasCov() << std::endl << std::endl; } + /* ************************************************************************* */ int main() { TestResult tr; From a10c776fdae8a6df2ddb5a448648a3a7e50ad69b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:53:25 -0400 Subject: [PATCH 10/36] print statements in ImuFactor --- gtsam/navigation/ImuFactor.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index 9b6affaaf8..c0797d0e15 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -75,12 +75,16 @@ void PreintegratedImuMeasurements::integrateMeasurement( // (1/dt) allows to pass from continuous time noise to discrete time noise // Update the uncertainty on the state (matrix A in [4]). preintMeasCov_ = A * preintMeasCov_ * A.transpose(); + // std::cout << "A * p * A\n" << preintMeasCov_ << std::endl; // These 2 updates account for uncertainty on the IMU measurement (matrix B in [4]). preintMeasCov_.noalias() += B * (aCov / dt) * B.transpose(); + // std::cout << "p + B\n" << preintMeasCov_ << std::endl; preintMeasCov_.noalias() += C * (wCov / dt) * C.transpose(); + // std::cout << "ApA' + B + C\n" << preintMeasCov_ << std::endl; // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3 (9x3 matrix) preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov * dt; + // std::cout << "p + iCov\n" << preintMeasCov_ << std::endl; } //------------------------------------------------------------------------------ From 65bbe6b577c0d28a91652a6247e087d63757fbf5 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:53:41 -0400 Subject: [PATCH 11/36] typedef for Vector15 --- gtsam/base/Vector.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/base/Vector.h b/gtsam/base/Vector.h index ed90a71269..9567d9980d 100644 --- a/gtsam/base/Vector.h +++ b/gtsam/base/Vector.h @@ -60,6 +60,7 @@ GTSAM_MAKE_VECTOR_DEFS(9); GTSAM_MAKE_VECTOR_DEFS(10); GTSAM_MAKE_VECTOR_DEFS(11); GTSAM_MAKE_VECTOR_DEFS(12); +GTSAM_MAKE_VECTOR_DEFS(15); typedef Eigen::VectorBlock SubVector; typedef Eigen::VectorBlock ConstSubVector; From 3a3640c5e0d94c1108eac9ef863de6bc9e0e849a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:59:05 -0400 Subject: [PATCH 12/36] updated CombinedImuFactor covariance with additional off-diagonal elements --- gtsam/navigation/CombinedImuFactor.cpp | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 24e2e3016e..cd579d716c 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -134,18 +134,19 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); - Matrix3 aCov_updated = (aCov + p().biasAccOmegaInt.block<3, 3>(0, 0)); + Matrix3 aCov_updated = aCov + p().biasAccOmegaInt.block<3, 3>(0, 0); + Matrix3 wCov_updated = wCov + p().biasAccOmegaInt.block<3, 3>(3, 3); // BLOCK DIAGONAL TERMS - D_t_t(&G_measCov_Gt) = ((1 / dt) * pos_H_biasAcc - * aCov_updated - * (pos_H_biasAcc.transpose())) + (dt * iCov); + D_t_t(&G_measCov_Gt) = (pos_H_biasAcc + * (aCov / dt) // aCov_updated / dt + * pos_H_biasAcc.transpose()) + (dt * iCov); D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc - * aCov_updated + * (aCov / dt) // aCov_updated / dt * (vel_H_biasAcc.transpose()); D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega - * (wCov + p().biasAccOmegaInt.block<3, 3>(3, 3)) + * (wCov / dt) // wCov_updated / dt * (theta_H_biasOmega.transpose()); D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; @@ -155,7 +156,9 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInt.block<3, 3>(3, 0) * theta_H_biasOmega.transpose(); D_v_R(&G_measCov_Gt) = temp; + D_v_t(&G_measCov_Gt) = vel_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose(); D_R_v(&G_measCov_Gt) = temp.transpose(); + D_t_v(&G_measCov_Gt) = pos_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose(); preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt; } From 3132cfbc868f0e382e2be34b0eabb9ffe6761f92 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 10:59:32 -0400 Subject: [PATCH 13/36] CombinedScenarioRunner --- gtsam/navigation/ScenarioRunner.cpp | 59 ++++++++++++++++++++++++++++- gtsam/navigation/ScenarioRunner.h | 44 +++++++++++++++++++-- 2 files changed, 98 insertions(+), 5 deletions(-) diff --git a/gtsam/navigation/ScenarioRunner.cpp b/gtsam/navigation/ScenarioRunner.cpp index 3938ce86c4..3a447dcab6 100644 --- a/gtsam/navigation/ScenarioRunner.cpp +++ b/gtsam/navigation/ScenarioRunner.cpp @@ -15,8 +15,8 @@ * @author Frank Dellaert */ -#include #include +#include #include #include @@ -105,4 +105,61 @@ Matrix6 ScenarioRunner::estimateNoiseCovariance(size_t N) const { return Q / (N - 1); } +PreintegratedCombinedMeasurements CombinedScenarioRunner::integrate( + double T, const Bias& estimatedBias, bool corrupted) const { + gttic_(integrate); + PreintegratedCombinedMeasurements pim(p_, estimatedBias); + + const double dt = imuSampleTime(); + const size_t nrSteps = T / dt; + double t = 0; + for (size_t k = 0; k < nrSteps; k++, t += dt) { + Vector3 measuredOmega = + corrupted ? measuredAngularVelocity(t) : actualAngularVelocity(t); + Vector3 measuredAcc = + corrupted ? measuredSpecificForce(t) : actualSpecificForce(t); + pim.integrateMeasurement(measuredAcc, measuredOmega, dt); + } + + return pim; +} + +NavState CombinedScenarioRunner::predict( + const PreintegratedCombinedMeasurements& pim, + const Bias& estimatedBias) const { + const NavState state_i(scenario().pose(0), scenario().velocity_n(0)); + return pim.predict(state_i, estimatedBias); +} + +Eigen::Matrix CombinedScenarioRunner::estimateCovariance( + double T, size_t N, const Bias& estimatedBias) const { + gttic_(estimateCovariance); + + // Get predict prediction from ground truth measurements + NavState prediction = predict(integrate(T)); + + // Sample ! + Matrix samples(15, N); + Vector15 sum = Vector15::Zero(); + for (size_t i = 0; i < N; i++) { + auto pim = integrate(T, estimatedBias, true); + NavState sampled = predict(pim); + Vector15 xi = Vector15::Zero(); + xi << sampled.localCoordinates(prediction), estimatedBias_.vector(); + samples.col(i) = xi; + sum += xi; + } + + // Compute MC covariance + Vector15 sampleMean = sum / N; + Eigen::Matrix Q; + Q.setZero(); + for (size_t i = 0; i < N; i++) { + Vector15 xi = samples.col(i) - sampleMean; + Q += xi * xi.transpose(); + } + + return Q / (N - 1); +} + } // namespace gtsam diff --git a/gtsam/navigation/ScenarioRunner.h b/gtsam/navigation/ScenarioRunner.h index 1577e36fe1..cee5a54ab6 100644 --- a/gtsam/navigation/ScenarioRunner.h +++ b/gtsam/navigation/ScenarioRunner.h @@ -16,9 +16,10 @@ */ #pragma once +#include +#include #include #include -#include namespace gtsam { @@ -66,10 +67,10 @@ class GTSAM_EXPORT ScenarioRunner { // also, uses g=10 for easy debugging const Vector3& gravity_n() const { return p_->n_gravity; } + const Scenario& scenario() const { return scenario_; } + // A gyro simply measures angular velocity in body frame - Vector3 actualAngularVelocity(double t) const { - return scenario_.omega_b(t); - } + Vector3 actualAngularVelocity(double t) const { return scenario_.omega_b(t); } // An accelerometer measures acceleration in body, but not gravity Vector3 actualSpecificForce(double t) const { @@ -106,4 +107,39 @@ class GTSAM_EXPORT ScenarioRunner { Matrix6 estimateNoiseCovariance(size_t N = 1000) const; }; +/* + * Simple class to test navigation scenarios with CombinedImuMeasurements. + * Takes a trajectory scenario as input, and can generate IMU measurements + */ +class GTSAM_EXPORT CombinedScenarioRunner : public ScenarioRunner { + public: + typedef boost::shared_ptr SharedParams; + + private: + const SharedParams p_; + const Bias estimatedBias_; + + public: + CombinedScenarioRunner(const Scenario& scenario, const SharedParams& p, + double imuSampleTime = 1.0 / 100.0, + const Bias& bias = Bias()) + : ScenarioRunner(scenario, static_cast(p), + imuSampleTime, bias), + p_(p), + estimatedBias_(bias) {} + + /// Integrate measurements for T seconds into a PIM + PreintegratedCombinedMeasurements integrate( + double T, const Bias& estimatedBias = Bias(), + bool corrupted = false) const; + + /// Predict predict given a PIM + NavState predict(const PreintegratedCombinedMeasurements& pim, + const Bias& estimatedBias = Bias()) const; + + /// Compute a Monte Carlo estimate of the predict covariance using N samples + Eigen::Matrix estimateCovariance( + double T, size_t N = 1000, const Bias& estimatedBias = Bias()) const; +}; + } // namespace gtsam From 53712149f98b8325ce91fdab22f8fc2b0f395e10 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 19 Sep 2021 21:15:51 -0400 Subject: [PATCH 14/36] actually test the covariances and fix bug --- gtsam/navigation/CombinedImuFactor.cpp | 4 +- .../tests/testCombinedImuFactor.cpp | 40 ++++++++----------- 2 files changed, 19 insertions(+), 25 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index cd579d716c..c8d1b10fef 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -141,11 +141,11 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( D_t_t(&G_measCov_Gt) = (pos_H_biasAcc * (aCov / dt) // aCov_updated / dt * pos_H_biasAcc.transpose()) + (dt * iCov); - D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc + D_v_v(&G_measCov_Gt) = vel_H_biasAcc * (aCov / dt) // aCov_updated / dt * (vel_H_biasAcc.transpose()); - D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega + D_R_R(&G_measCov_Gt) = theta_H_biasOmega * (wCov / dt) // wCov_updated / dt * (theta_H_biasOmega.transpose()); diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index f7acfa79e5..0dbf961fc6 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -269,27 +269,14 @@ static boost::shared_ptr Params() { // EXPECT(assert_equal(expected, actual.preintMeasCov())); // } -TEST(CombinedImuFactor, SameCovarianceCombined) { - auto params = PreintegrationCombinedParams::MakeSharedU(); - - params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); - params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); - params->setIntegrationCovariance(pow(0, 2) * I_3x3); - params->setOmegaCoriolis(Vector3::Zero()); - - imuBias::ConstantBias currentBias; - - PreintegratedCombinedMeasurements pim(params, currentBias); +TEST(CombinedImuFactor, SameCovariance) { Vector3 accMeas(0.1577, -0.8251, 9.6111); Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); double deltaT = 0.01; - pim.integrateMeasurement(accMeas, omegaMeas, deltaT); - - std::cout << pim.preintMeasCov() << std::endl << std::endl; -} -TEST(CombinedImuFactor, SameCovariance) { + imuBias::ConstantBias currentBias; + auto params = PreintegrationParams::MakeSharedU(); params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); @@ -297,16 +284,23 @@ TEST(CombinedImuFactor, SameCovariance) { params->setIntegrationCovariance(pow(0, 2) * I_3x3); params->setOmegaCoriolis(Vector3::Zero()); - imuBias::ConstantBias currentBias; - PreintegratedImuMeasurements pim(params, currentBias); - - Vector3 accMeas(0.1577, -0.8251, 9.6111); - Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); - double deltaT = 0.01; pim.integrateMeasurement(accMeas, omegaMeas, deltaT); - std::cout << pim.preintMeasCov() << std::endl << std::endl; + // std::cout << pim.preintMeasCov() << std::endl << std::endl; + + auto combined_params = PreintegrationCombinedParams::MakeSharedU(); + + combined_params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); + combined_params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); + combined_params->setIntegrationCovariance(pow(0, 2) * I_3x3); + combined_params->setOmegaCoriolis(Vector3::Zero()); + + PreintegratedCombinedMeasurements cpim(combined_params, currentBias); + cpim.integrateMeasurement(accMeas, omegaMeas, deltaT); + + // std::cout << cpim.preintMeasCov() << std::endl << std::endl; + EXPECT(assert_equal(pim.preintMeasCov(), cpim.preintMeasCov().block(0, 0, 9, 9))); } From 10a73338da8a785788bb954e26dfb7a625a3f3ff Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Sep 2021 12:28:59 -0400 Subject: [PATCH 15/36] update test with comments --- .../tests/testCombinedImuFactor.cpp | 26 +++++++++++-------- 1 file changed, 15 insertions(+), 11 deletions(-) diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index 0dbf961fc6..a8c0391449 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -75,16 +75,16 @@ static boost::shared_ptr Params() { // TEST(CombinedImuFactor, Accelerating) { // const double a = 0.2, v = 50; -// // Set up body pointing towards y axis, and start at 10,20,0 with velocity going in X -// // The body itself has Z axis pointing down +// // Set up body pointing towards y axis, and start at 10,20,0 with velocity +// // going in X The body itself has Z axis pointing down // const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); // const Point3 initial_position(10, 20, 0); // const Vector3 initial_velocity(v, 0, 0); // const AcceleratingScenario scenario(nRb, initial_position, initial_velocity, -// Vector3(a, 0, 0)); +// Vector3(a, 0, 0)); -// const double T = 3.0; // seconds +// const double T = 3.0; // seconds // CombinedScenarioRunner runner(scenario, testing::Params(), T / 10); // PreintegratedCombinedMeasurements pim = runner.integrate(T); @@ -92,7 +92,7 @@ static boost::shared_ptr Params() { // auto estimatedCov = runner.estimateCovariance(T, 100); // Eigen::Matrix expected = pim.preintMeasCov(); -// // EXPECT(assert_equal(estimatedCov, expected, 0.1)); +// EXPECT(assert_equal(estimatedCov, expected, 0.1)); // } // /* ************************************************************************* */ @@ -268,38 +268,42 @@ static boost::shared_ptr Params() { // // regression // EXPECT(assert_equal(expected, actual.preintMeasCov())); // } - +// Test that the covariance values for the ImuFactor and the CombinedImuFactor (top-left 9x9) are the same TEST(CombinedImuFactor, SameCovariance) { + // IMU measurements and time delta Vector3 accMeas(0.1577, -0.8251, 9.6111); Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); double deltaT = 0.01; + // Assume zero bias imuBias::ConstantBias currentBias; + // Define params for ImuFactor auto params = PreintegrationParams::MakeSharedU(); - params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); params->setIntegrationCovariance(pow(0, 2) * I_3x3); params->setOmegaCoriolis(Vector3::Zero()); + // The IMU preintegration object for ImuFactor PreintegratedImuMeasurements pim(params, currentBias); pim.integrateMeasurement(accMeas, omegaMeas, deltaT); - // std::cout << pim.preintMeasCov() << std::endl << std::endl; - + // Define params for CombinedImuFactor auto combined_params = PreintegrationCombinedParams::MakeSharedU(); - combined_params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); combined_params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); combined_params->setIntegrationCovariance(pow(0, 2) * I_3x3); combined_params->setOmegaCoriolis(Vector3::Zero()); + // Set bias integration covariance explicitly to zero + combined_params->setBiasAccOmegaInt(Z_6x6); + // The IMU preintegration object for CombinedImuFactor PreintegratedCombinedMeasurements cpim(combined_params, currentBias); cpim.integrateMeasurement(accMeas, omegaMeas, deltaT); - // std::cout << cpim.preintMeasCov() << std::endl << std::endl; + // Assert if the noise covariance EXPECT(assert_equal(pim.preintMeasCov(), cpim.preintMeasCov().block(0, 0, 9, 9))); } From 755c75278215739d39b36fed689d3ae0b6ca79c5 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Sep 2021 12:29:36 -0400 Subject: [PATCH 16/36] update ImuFactor doc --- doc/ImuFactor.lyx | 41 ++++++++++++++++++++++++++++++++++------- doc/ImuFactor.pdf | Bin 225325 -> 225898 bytes 2 files changed, 34 insertions(+), 7 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index bba8f212a7..c79a5f37a7 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -1427,15 +1427,34 @@ pose/velocity/bias \begin_layout Standard We expand the state vector as -\begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k},a_{k}^{b}, \omega_{k}^{b}]$ +\begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k},b_{k}^{a},b_{k}^{\omega}]$ \end_inset -. - For the jacobian + to include the bias terms. + This gives the noise propagation equation as +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{equation} +\Sigma_{k+1}=F_{k}\Sigma_{k}F_{k}^{T}+G_{k}\Sigma_{k}G_{k}\label{eq:prop-combined} +\end{equation} + +\end_inset + + +\end_layout + +\begin_layout Standard +where \begin_inset Formula $F_{k}$ \end_inset - of + is the +\begin_inset Formula $15\times15$ +\end_inset + + derivative of \begin_inset Formula $f$ \end_inset @@ -1443,13 +1462,21 @@ We expand the state vector as \begin_inset Formula $\zeta$ \end_inset -, we get a +, and +\begin_inset Formula $G_{k}$ +\end_inset + + is the \begin_inset Formula $15\times15$ \end_inset - matrix. + matrix for first order uncertainty propagation. The top-left \begin_inset Formula $9\times9$ +\end_inset + + of +\begin_inset Formula $F_{k}$ \end_inset is the same as @@ -1481,7 +1508,7 @@ derivation as matrices \begin_layout Standard \begin_inset Formula \[ -F_{k}=\left[\begin{array}{ccccc} +F_{k}\approx\left[\begin{array}{ccccc} I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & & & & H(\theta_{k})^{-1}\Delta_{t}\\ R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t} & R_{k}\frac{\Delta_{t}}{2}^{2}\\ R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & & I_{3\times3} & R_{k}\Delta_{t}\\ diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index 37badae9cc979302341b1dbac23e03b5be7445d9..933c71a749610b513627409ff903042378fbd989 100644 GIT binary patch delta 48287 zcmV(nK=Qw>;0@~J4UqaI!pjjxityai0V)|)#NN|*sas=V4M|64(Egp%ZJPc71)N0( zvmOEKO9L}DH))s60T4qCMat4{F5+;|=j)lC&erHW=t`>QpL|@v)MHDAgr@CYEjku=kT^|msPnATVL98W!>rAaR@_#n{XU3 zLWkxH&P;K6<9`KE8U#`1&#~FAtM10z44&LpWmxn#HW*8=sj-Nn2rCLw2BSNJ&jl$~ zA2z%9b0v=(nqZ7L<-@yoH`US^<|gPe=vIcWa&hM#md zr_&lqEQi<2+8LCQV|HW)DJ4z`J4=!S834Zr&2DU1*Y;~4#RJf~-fmH}2^^BbjY%Lf zBA(*He%%JuiSerY&8{zd8}HdDwb91IR7V4wmm{0X{lk1gqyk?(l)FC!tUHFK_gRfF5M(q;<&Br;^!ZGV+mWlNk1M7Dc3=sC zd4Hg}4DJjEIt4vg3eIN~M965ytawNiy zh#bLp*KYga_`why(*9kRw?TYgYwVM8%3gSUL?Tz1GU=T6K%Iuy7wsNNZpiloWn6K1^aoOd`cns()je$I+ry|is#R)4W^ zh=naY*k_X3WhdpblMS!;&33W2&`9L0!62y1@en3w4RDD(3*SZ`@JVf9pllo^?M#VcJ~_u0Rpz!Ch3# z_bE{y-?ar~D2_BBY}$R?l>0_--+vwW!r?#VvblmtQI&NUc7_W+A#x3Y?ZT!9#aQ?^ zVVU-&umL~~l|PYyca`GwT~qJ%sVnQt7+Cjk2IvUfVX=q>Li$b|jSNx=TCHxaZpu4#kb#(ljHH1U`~6uC@}=~%Rpb-8YBxr#5ju77pc+f_{Q znX~y;8S|s<7eDi_>`+7H7wSaxCQx^ovUmNwrWVF>|rY>(b%0ZNrP zCxCJ$rvda>#D?>lF+07>UQT7sh}aLh4TlnfT{G_ra64N4KCGhucu}ov0GFd1gC9KD z42JUG1~~9ZAI}f^)e#@m-+zrw=a9ROMf_Oahb#IjOcU;gI|p4r80x^gw(KfDWP$Z| zz5BB8pxJj1E^j+8uXi>!5Z7(98Rfu4v*0X+yrDwo22)VUG=3#5O|UOn<-xuz!s)k&efK91*tU zum!yu7nwbI7M;8JP*RUY z56dT80+q)^6mY^BPLL@HWK+oAllni}8`Ka$=-LqPJz%(S={a)rV7U0x<;5=-E`ES> zpbUUA9LfN$7z8ykTYqjYK7Pit6+8q(`T%j~NjFYcDBfYYp8b6BkBhf%vYKc{nHz%5 zxP*R5(20W|4rM$Jkdl!qJC0!xHpejcT^621C$oa9aOW{%z~NNa=F{`Tc|qb?r$XZX zy>|~sM}Tdtr|$bcC)9wllVV!n95cYvKD|6LhN7p(Uk@Vg(0_q#J1T`wV+ZUD2{+KTr*GlQ$Fcw_VniYW9}|`zvDwoq?$qY)T1lQ ztc#SC-llpAPkcTy={d+$k0TSJfEKd};Za=jb8yMdACEq5gfYSrC)^+%KP}X$64;YjwRIC7vogA^tq-^u4A)3q{V$DdmR~ zN1!QALlbH-18GD15gi>O)d^EQDG42ox#R_duKC8G`+pMUz&_~8-#F;1bAs-q7C3UF z+#HOt)9G129c}pZq`!U{{dg3k3~^zm8a)rW2NpXOe;%!6pvjTki6zi>u(M+9uWl~} zF^q}xbdoO?_YYg4v{9r2X~||#`C&ySbZMigG7X^0G>Rwa#zrxYaiLoCzjwLbT$O&_P-vKuWrX#sUXF&cmIPSMDgQp zW7}%!{vjdm&@reVjE6zANq#&ah50>ozZy}&q<9tP8SeEkj}(x74Y-6FXkKGWpog^j zKOWg%WV2vZgeDO*HVQ9HWo~D5Xfhx%GdVXjmm#zP6a+CfF*uhI{{kp~jrj#ooLkm_ z3*+t(g44m>U4pxN2->(e(zv_32X_nZ4#C|?AZTzWxN|w@%uHs!|F62YsA}G4`PzG} z7pj`_gR&Z%D9Es~09aVqnOIoZkSHnDEx|UX|CS?BYMMGa zS%U2N{>wtl(G&=NlZgX=!Ec5NAUlApvkici9l*-P$I8ve!UAApVd4F^A;^&rAP#h~ zGyy0u0c1gTrcOwdVjz2WM@w@H@LQgLKLTisX#uRfyxa_by8}dQO&u+bfp!1|AlSmx z_AR3^&<3CeGPX1YyZ=uJ8UYJ1*q)D>+11sR325uY1adV0NXr0!aJ2+m08~w#OdVZJ zO#pwj3{V8xn*OUbCL~ILx`n0FKMFOF8Q2x*XbN}}*jO5y+BvX z0ZR6!cK;a5|6{-a_}Ae8SeaP=6YgK$e+9C%``a04Yz(rs2imz?+L;5)ENx5yN|N$S zU^g%W0BC3Omm$!9#tHQ14|D-q+5nB-4E`=12#^#}0RZ1R{8xWY#*UWuU?(OgOPjxX zWd1A6+c8VnnTUaGZB6aKPDp>%CvNFzYW#NY?#%zXTx&a!tDWb+$;{Hu#O$v&Oq}hR zHS8=MoK0oK|7G(gLi!^!Hw6PYS$MeFc{l;44gga(V+-bgzY?gs+nfHaWc^G0)`PdF zJ;)wl_SS}}x22is+b<+fC!mWd0PN^&>h1a8ivJ}fR#t$Cr7;*_WNL0{hx8}x5B`uWe3-rIzkfb4AC|Cs-M#mriYTH5L&^#5x4KT1(ikQ>00 zk(~{|$i~Tk0$^p~-~n*IJ$V0b9A%*8zv}oeUl}_y5a6$1f7SbTQ2(yktx|KFJZ73KeR(*JKolFl|Zf9q-fG5G({ z18psB-2Y|qHoDH>w>3}zy)A>?|25Sz{bzR-Oie6*oo)ZGRt5}wTL%$4^S6;^WaVID z;rK^x=_G0CW@@5r2{yL)XKenFYy7ovHkNj#${;7pzg{tKUMwvCNB6d6#@27I5vRA= z{6__JdRsa0-xv88o4zg8|JEU4XACm=Yx~$Zxd1>%N1!{>+vUFzC%}{SZB0!~-Tt0# z05g++9SHp90(k4$8(;=mUI4Sie~6m}z%2QP zSOLsZe~1mhEd7Vr0n9Rg=q;wgA9{dsF-lC}fp|>b%e~1IXtp11Is@D8N zJOJiT{~_MDe84~SrZf5valU1Ldwtpd(f@USBg`g$@GXsrsSWtQ4c@9U`!9Se%lr@i zMZo_J_?F-L55Dafv)zB;+qr@MgY0kaAX`)O|8i%2OK1P*3f}6m2Rec+fi@H5576PZQ_47_Ls=zKgjl$$<6YQ_RZVl-{$`_f5y&# zj*f2w`uB_DZ8-nUfBz{kHFYyJMp{|~8S@8O)dh9j)rb(fGVV+Yz@DYuePUyrEYwE; z4@k@!Y$m8>WiHE=OD^@ZO6ps6D~dYYWv_j|^xUo|ZE)wfVI-B@HzzfUTYSBNoKN(; zB_dlyZ-L0uN)aXDD{&lvP$rJV=s^^JGBF=eqeSdHhQi+-fwezQcKiN1gM_Ha2i8N;f=J@e7%pK-WD|f@?L##?a{S3T8iXZ=}Dh zOTf-KMF<#Ef`6DuoCCgEb0r_`DW}Bc=nIyokrcM@k;y>CI&I2bo#KVX_QjEZ-Uphb z9&QW6B(o^iV~=}cO#2la(KN^0g53y{pV^_L(9J_16K|a~`_e6?zpYjNBDR(d4VH6X zp6{F4cyg9YmC>0R45DFBNDzGax_#{3NZA?fVip3`MqQJFxh+ADn@M}k~j?-M3FJF1IiT9pPGbK~9+e3ABzrw7MN{$*E}DAlq< zb);Q1R+Ps^{fgI@!n}twR_2ig$#A}AVFi9t{Y1Ur&{OR0aKdZ7gEw<9(410Fb z=i|0*WAS2c23tDsOerL7D+!}pcr#-Eq=`Wdz)=|vJV=O*>JZtuYR!qHovS6BKSAjz z74%17;w{_DJi1~xCnUIk%oIc;)#)-IeKmRo8N53eCDJThe;5oHgKxUfA|pM)huUt+ z%J{Ycyf^@TmUL2zrwvLfq&zcWyJ&TdQf#lBlm2)u?tOiZ@G~oZKsy<&7WtDqLMp2j$_F5}&MP$<)j{ zP8&0no*^2d7PIceJ{22loy(vfWt8yc++(a20f;;n%wZr3w{?gOi?#ANIQhVOMnAKR zIR}Y;tkqb@Hfj%l$`pUhtO$qha{D-H_FcOEL5EaNUE-$K>Wk`dgby?QBl7k(?jhhy z8pf&(&$h>>l?3~`tDKB1=?|K>EB+=;ADaC5O*rxk)QixUIQba19$aw9jpbtLRu=i` zJ*M8le~PNc@<6o)yf0LlTX!A!2y_@U;@V-2mU(EMl*6EZ3KlY*Ubu}H3_CPyZ4x-Q zl6#7oqp)tVxmlw$xU!|t!${}dV(bsh-Fa^flppgYSh-JApHgP^oc6~iz_H5>k6Fl; zT=q0l?;P(igA4g}l3VE+E|dVbH0n z>zBDrKBQ28k_^+!Z?flUfy?nR0xJSu-&MT$T-a29<;n!DANmkzX`(%&zaiY+D1=~- zV#&@=ROc@`&?-V~`uIpPbajmaJwsM0XMC`0fP{4Q@oD5q9W*0YNJoU-GBWnyUg)<( zZjTK|k*+aG1T6Ne^ULB?Vf)O^hnLk%I4qzoHRH*8_iC&ugI@#9MPuNoKz0`n4mR=g z3tTOKS3C+~(=)aNZr*TQz6zcZPdKKxySV?Xw$P{Rm6lto_0qlip&jmu-AJHtRKU(a z*VrH7!s*RaUc_7cz9xr^3)sTP~30)IhTacd|VS{^vMz30IHL zSUAgtwP-@v;ET=aN7sb4Plp1(q_v}K24UQPT(CN^z5TW&87VTzGK_FO&@_5ji>s&_ zf%)r)&kw&*_xQ*BYgAA* zNQ1=ejrJ#m`S1F~Ab3p=s3di0B9Zc+g74$*i-jifq8%Y3PSQHs46dqz;W1~;ln}Ik z)~2DhN^?q`?^#xFPhW=roI7k(i6*D|ilYioWkH#+9{l&v$);yiAJ z`%z-vy3Vie!>55B`M9p8yS$-zjntZ(j4gmdsLg}AG|{l#?2CIwzp2LH;Omo9un5db zW&|jhopjPmj}%a?m%hDA=+WxGs#ryTl}wN%wV=T&+!(^d%nQXoG$R9fI3?+kL{Z%3 zr}2YX4hq`lyBU|8!$vMKqB~NZt9NaHv@~-)9p%GMqh#yE>L=}5caYn3lU3Des#`&w zT4x%xu6rY`-Fu<7Y|Z@u*(Q9FdpLU1VM1$QaIOxn$I7@_TCE>e>UT34x>X&2GkifP z1uR_lIamH4>|E-W2$%;~B|& zGk=`qw8lEdyA@P%%~yKi#^rnpBPZlb{?3rEVSp>IEEL~3H2PjqtZG+H;by_|Yyoxo zV=@}%;M8r{4$97NcDnCYlI0`;inEb6ywOADSg2)e&FHSsyggr-xkQ~;3fE&En-0PGNe>+)&F{L!1_=y=i>@MZa*p` zQe%J>VvQ9FL_oe=6qz4bcekMl*pi2AodUP#l0u(p#9^Ht?<4l$SJ(=F&(h&O#;N1* z#{HCNg(}igGG|;)S?rBMuaQ2m-^D`%O2d(mA?SJ(K7Yeto}D8JlCaW*^~_=ozhoT` zRIg3elz*P(bk~ye^6;Cz+)6$7T5bZv7g~v$90Y3$R(UM3FZZY~%KCKd>eO{LzAUgC zKD*?;*xNY}+YL#by+%WB7YcqoP)6))WD(l!hvKD^F2NgktA_=H*fms`E`d1Cx zjlS$gK;*PR$Q+~mb4x<%3= zntY!J6pM+cRS^L4ktdmEgKoQQ;xs7%<94}q%Zr&mEmxw;r)J83qMT6smO7#Xe?2fc zt|8PwlUz#ZlrchoeQrL!M%xc8_4nvZ*@<6@9LcROF=X2X!4;BIgg{mo{?Yy`SbY*l;w7t*RdDVG1GTf(?M3HA6 zTM>_?>%B}ElP*Pmvh8#qJh+*J(k}b;j+@kXE%;(m#b|zsiqknYG5zaa`~W%lQ!b1i zk@eg8Aw$FME-OA}WT^KLpX+1&USBkdDd`@#2z7s4Hi_lyvB?0(sShU58W8Uf-BJQ;lmvZSGiN3c_egaF>0>5Yp&RCx}{z zmOi(<*i!(1sD5JrOVArAB+3&crK4>jXxHDb6|%#A1+S~_SZ3Hzuu!^Le|Q#4=kwz| z*fW@9Z1=YIk)ILXJNfzzbxcaIU%$fQ$04nCbw;ZtB9GBr{GG6q{`)&OsaK}>5Crri zJf+)^FP|e%t*W;qanx5jrcoIvfM34k*LdSR4 zVf=a}4nvL3A{oT094`B)LY_ZiAITJC49=&)ICkp(Z2A^3^7`vh)f8mtlCat4X!71( z=y+B(EEvf5c#j%{51AAZ5#)tv9gt#)}Aa2@g zM(aCe7)!yp;I2fxaCKV}(;1uohGTsZUk(ki^vAEJ`^(DXtM&8z)we%}zUKvb+iGPV zF#c{-*c6%ca58i<@{Y@nT6*qtY7xdUNObC8hDy!ek__t(LRU(V_*Ri>a~ip3p(|y7 zXaso!B;hIi(o8|Kb}_84!H!++@TFn?`fTe`43@0o)ulVK<=W~66CzqDE$3lnOoVu@ zd6$!^)QPW4Z-|gznyo6hvrfpSyP?h)2W$HULb>Sn>Vqjl!OufRFl)>YW&-A+cq4(3 zqq7t&vm$inIurgWG;44?8G2{^wx0^j}#?lxcy|u$kAZ4!f(F0&2Ls~fT`5P=T_>4MIvo;5)q!Xc-ev=KiUKtAs!J)vCup+$#Jx73gLXS6U+o?>z<4FeF zDt;9?YEdXm`pe;f4q{Cz(n5l<^Rs)ahN{2y26Wupe-7-K+)r`L`XBp@5`gRSS+7&EdCIfyBLOG=txB}?zm z((zI5R!`~(AfZK+a%ieToJP!QDQQ+7?I*>5N|Uis!KN|VMZ_2%{jMBgMg~y-B8ATPC}y`sd-g7f zqhHz@d0!m@VH@e7409a;Ww#>8m5CZWgF^$LI68YL6ry`niJ}{S8|xAyVLKK2%W;0y z_$a&Vgm5iprs~nlJVf1HJOrCj*~#`2d|j@iS=lqV62@4_i8*~= z`vhgK55h}ihYZh0l0MO@x}B{h9K=EQyCHJUFfCh@k|VTh zmiyo(i%k1^C9MlX2#4d%kTmO}AtWw9>o=BirdOEpTzHy)+A2>`5N$Q4-7ieK-N5`{c}= zR!F3+9K0}k5`IC{3>c}OzP=tj7~E=(_EaHt6yes_+Y`cD2#v*Qkw68%ux}~vamYvO zOuZh{u8gXGf03jkqk!c@d1h)^Qb)tQrsfX2lt^gT9j13MB$L62DM~p|1%hsMMQsDH zk;|w*iVb!L1YZ*|p6OGoXO(z&LPWgB@$z($H{JEo83f%7qIxSdVB2GR*7LZO5JIg) zm$!I?f`x+icEn-ZqaosnbYiaD#gmr0;cc~w4agIJj3R-rDPFF$m@PbGu7mi(?g1MOl_cvwU#~ij)S}EtiTY-rW>;06=SAL z7|fG@)D(_)jdts)hjIG+RrM4jttHfNTg}CFny>O-Qns|rBg-IP947^tYtg%@SS8iH zCG>uGu;;Cps8JG8DYUpp7ifzWCLtQ#Z?zOh(<6$wzLP6Jy6prIRmNu`7D#Yy6WeGx zh6=!Oyxb{_8W8BIho$>ar@2%UKMJY1BUx>K1W#udZYKHmBByyV))>oUzyw`2sKa39 zoO<{SV`4&Oz7onm5QK2g7gb8pf9@H}5sj){kLW%WY(b!-8uwS{uHfSTY}pj=I@xhPc8VlU&qXO_9TA z=F)sDqMLj`oGm>bX5$RA=-5AN^O9lWbnZ1&Q7*V$44^gqU6!h%GSqZH^8|m(k;sXc zT(4gexE2(Eqp)5L3L{3~l%g|#6q-<#R47H==<|D77&qUFIkfLFTV980~(?roHOpPBl%60HT>u3XMGVVd*UDKdU>lxP_!=sFP zFGXnd%cOh8Qs`+Sq;!hCW$W&%rm;n~9-a-=&-FaXzE!@~Zx~922NdLg!x0D{#Q91g zA~7L?DQThLae#PR847NR&%;Ax2J)#7LPXz8u;?E6LKj)i*z~yFXpY-B?2)UKc{=Eb zm|$EuiL;%?j0CP@>hw&Ih!>?Vn}@6;ytw<{ALi}@iHNzK>IP|Xjn7ZtS+k(ykgq_oB(&<`SF8!#-w+e^qRH3gQ0&EDPELhvMZPyityh$7x#-tGN=TewrGLTbJ{__dgP zcdlXTYC>pC8m?WpayRO=#BcqWa3&#B8TvJ8irS((#vd7Jft=C6`L0U*90k!jKQ%EW z@7ZHi@l_C0$^39a%qI8{t5D1+5B+`e#&vP%tHpcwcw4CFlu7QZAnWPn@2_m?$gqbu zIJSkQ&fUo!VOCCm%brrHZVM#SR&3GGAiNzkHqxeN^CtC)`n?~C$5YqY^>*X$f@*SU zlvqx(!{l^Uy7>_XZF#b7cPf+*FRPi4yTo~*Sff;%zsbwQF=h%{@ih^&0+bkuAp*@e zKE{{rW?SQxeMU}x4Nc97KdScoVt$yo0K=(pWn*axRuoNtGa|t{qq61FRFdM?5EBhy zC4^Od(c7Ta6Z?%$n3zrea4d+a4uZx+15U*PX(QYCGdgdqjkcQad^clKdaw!149#p% z`o^G|Qbhu|H4yPc;c~Nx8{;MC)#hnB``B+KgzN%v7W|VW8H~pK;Jw2)jJT0w35~K@ zrZ|NVBfP$UJkQsl&6#-`7>(B<-X#p!1VDUpR9Q} z%E=aR3A{hM0JkT>H=P$bqxL~r902&#U3Cbzh_qqOIOqRUoIPq&w-l29F^}0JjP*YX90n#G*rh+plAPoHLE^MI2bN{fh4eYa|Ad);Xy~Q>sH} zNQ=GQxxVna;j$#-A5cwy&JcU3KELi0X*2&QRK~GDSNT0buEZ+CF@H`935_BLo@)`2 zUbhl+q#7?=Fzx3MsPanL7cU>MJ$!yH9mzVuzso8jeh=pyV+Pwa>W>Og1xH>{16t(=nYJhu z_bM_PlRRJcpirh?`~};dE!TsJ<14^_-kogrdScxGdMDixg|oXQDuoms;Zcvo!BfkY zvq`uknMckGvMK^MB>miX7ssJOg+h9l=^+mI>kH*0`p})uo>HXNmRnIvcsk)XKIqq3 z_A}Hnwrse`Fv+zii~y8%9l|=JD@VsvyacdggMOVnhdhkH)yC2Bu^emOa| zvm)6UWzQOzqNOPt`6@(2r4xCR`i)e|_{aZ#M^@G|Y0fO|iZWJs<<(?9PHekjYBC|i z7GcxClcUqaYRi0D((HyGKglk^$8}ySiNrZFBUE5QgbH!AmGHXNb9H$%! ztyP6$z6{9ye9W7%r`E}P4SAA(3(9IX*;pn}N^TiK;Zgd@@f+TFTvA1OWABo(?M`H} z)eTwrcgj}To!y-fs@$kCpG`{ z>C;v)Q;n4Z$S|kS{NYv(2d`;;Cl!)DnI(#prT$VyA}U77M>p6qVt6}$#amLaEcQT0 zh9=beegQXqG2a7qe%UJg zHMAST8MbhqTc<6uWzvk(0n-=vNF6X*tPW5F^-@3hVgD9oY8K0Y|bQF+aJR&vcv6RFBEY9XG*Q}^LEhXDu5Cj4N|=$FhBGj_r) zemHl4NzV|beY!~|#W7y7eQ24EMq{M~FaCR$+~5!NoGDvO?h2THg?CeC%T!T}39#wY z%mYk%-V6-7l|RRgV9Wf7OJj!lm30CO6ixBMhssx z2GmbnvvNurc>%G1qT3?t)kJoYLJRS=<0eV39J5Ut^CyQqP_m96+e)hx7qhbZ3|FnI zyIiK3=W3VE$o5+zeRk|o0WQ7z{($o|uh@B)w4chjv-Mf|;m?ul^i)pg1_Jb;k0z@s9~bV z6KeA|9v(^U!&TH^R)u{sT0>t46D92e(2!UWCBxa;SOW7*+4G~O`bEij;Ttq9T!nyS zu3if-X;u$tVQn}48ztUZ284|H0f(A(nFwc(GIK~L@a}1_u05NsCba}GkV-lGELjWs zAb!;!X%EeRs>3+)y&{`2eX@HN3DWR zt;ob>zBwiS{CE>j-%$>>sdhqqWbzLz6)m9^&jg@*&|@d~Jq#3LX#g-2<17~CbS`F} z;5SdnL52BU)tB5A&plYCSrX;;VRXjsL}(=%8qS4(ckLUp-n~sFz307JMDaBf3S~sy zCEreeA`-RG?3ZtSq3Zh1vtVzAiLlKQWAto!NWt8aGDHfJgEaYN<3bS4j79}n^L4_{ z99{WqJQaS5fX3Ia=g32I*G+RwOcO^H(Y~ToFS+?v*Ve>IjMjFIuAt!w$d9HJ0pQ?u zl##@LrFnx5nw+^0_2A@tWlX^`irIW(3+tGth?&wpE5&ngJXErIV|;E~&$n~`Vq|H= zRWpLnpE?4`bN!!(=BWcji3djoamH``u7wXVo$?3@55@(7Au zw#(W1+kU)I`nYFeQ-FG2AKx7?T+_@IsR=26$Gx~6qCPycqP{P~kH_?D7eA^#6z8>o zQCAQGQDjT_sf+p-JIcmD(KsO%pVupmr@{FhyfP7>cZ=pbYemhL>ZLaW4#5p=U8rIC ziiU?Fd0p*Trbbso1AY;b(T;$~I!$_}2O8giE;zQjB-q}<9DX~W6>fN4-*s(I;+`;n zm*VGwXs1{VL&E!TTxX7Uy%^z-L7+}ftgAbR05L?fOwS|T97!@f!INKwMdMAc-jsyj zq$9SJ`G}>;bM3y(doM@_BG z%lklL$_kGUVmzmh-e;UFGocHZQ>Z~NSaxTWZL~&>F=@6DF{{CTO;_nOIPGqeCNmt6 zeezb7_dXV*)LdTMSt7Zh;t1@z$MDMDHx<`|$2I(JYk*ow~PY z-DqQ6={sM!$y?hLEg!BHYWCp8$&64NdQl~cGs{Y7wF>meMNfT_Mu{1JXg<+|1hqieN|%|rq>XcR+;NCQHE%x3?A^+XJ}0z=OK9@V z0YZ8kP7drxiz#Obki|bz^#;-##38C&vrC^54Zv0+>*1bEPey;Q^GsAJio=70@~=xP zQTiQ6oB4Sf*X#W$w%&+qnbMP}BC$x9a+?ATJwjd9`!9INI!!x&nqh%oW?@7$H$z-5 zR$?znAHqiT7Wpe%6@B*H?!1BnnDoJvsT`yF9E*uz(GqPQD>e`mw_a|<=_dR0p)R-M z8A&#Q_wD%Ja+o*mkEw|PZ@GUcHl-v+X)8fVQk5tF<2^*}nZY zirgeAl_qPfcbzJKV7)bY5q0{u+KvbK87&PZQi%#p6;uZiB=$BAH%e|%E%)nVmM>7n}3CW{^*PY5uVm8m{Z^|dK;=? zX{4X~>99Z3U;VTUbMO;2UnC^ofp!`J^)))f;;<$a1oWHJ($7>>xOyM_u&+d3HS}Bz zBx+JVFb&tmyPG|1V|`f}Q6hEPlZj`Yk^VX%kqiYhq_1`ch5K1TA9;9P=#j!(-51Q& zx#=);WJ=dd>)E%h%6w zJvt&A?`g~E$|JaKdqO+KeLuZkt_n*HtVD$Aocuh;H8jvRm+`OU{WNvushGr?xl$?U z-JEb*YwouOZ`oDS1nh?J-n(+EWcd(?RI9=qckOrL^(F%UDDxR}QNB z{#Iy~SntkggB`3rY&!u=K{5+|YiKT(zn8nLDy|oUsdmmEq1{RQNHOX3%?Bq9^=b60 z$|o92oDqFItVX!WN_?1PS+Iq8lu)mf2TYiM+sO=D$vrJ!!$aUNvmF#eqRW>bDP2!Q zsz8zvzR@o?klq8xg#~7eTX9T?aCN9f7&4vTFT&FxLli{E?t}7cA>$TX$aRhg$!#?xv-Q(VW z-tnL;JVl9gjB}v^YXl_a_D9qmoYB=8gb{PGM%mav_^8t;?*JMT555vSWMauSY}A7iTyF6$?n=Ws#RXSIe3wZT2x@ zA@1;g(UM=UB^S<8QtkNTkIAUl&qU9c=bMcx!F!i+xwSUyM;O3rPd4=Yij_0mZVXJR zWXSpB!C*1Eg&RiCCD(uzBu6#4?`=5xGptK3))!dL98TU<9mx#i5cH9-=`}8Y#fVNY zpE6?SYuJ!a*K~cxX3lb28j@o^6Ui#DPcSIhHuLR&@iefm>u9Lp;boWbW;y~pQu%M6 z=l#YHnDZuQ(R|PZn3F@hXi|&vjSx-dsKp+<=doyj&a9&z^Q@b_F61+53UjkIZs8Ff z;hvHynwfXROU1(<2%%_Z)6=VeiL~9HKIKK7mY51aB(fUOzJOKyghh<-G9r`y2^c{L z<2-=+ zvWXRK58vTaA*(t0|}75@U4Cd)&weUuq6vXTvSn4DGKe& z`g0Ok8$)mGWD932DB28RjZ)vgrTaP2Ul@&~FO-jsIyzPZ9;-i3!*{#CCf!PjAk*f> zL_qi$J52px>X$tAL%Q>S5IP1!oby(i4tlSf2_RTDdptw|UP!Xx8#168ZG#o3Y3it4 zDW$ZhoZMdqPQq8A5#w`{uFTDc5FZ--<_*btUA#THT)S9o!^0H)-EE`c_?3+omp|EY#&GFG$tD4_LS0p>1pVEf?Ct~R@+%u z#iH3O^xv?}Z!93ggSZ z^uI3Y!AaK`1^uvpOjWNE{MH!!ZaWec% zXP-v3?tFF0*s0SXTEhmAWb$+L!!Ck4+&jerhGXxxg7{!yau=UQcCDmQLEBqbv~qQ; z>1jUJUj%2l=A6OSxf^Y|(xY zv`#FTcU=sK|sSX=s!7MU9$B5>JXdLBd*-C+f`CrLvV-XbTlzyyxw>?8;lL zxVV!v+Y@PKVaDHY@1hW~?~Zi&`UzuEAYZ2kfO%Lg^|qG2ZcBrhU4kTvj#;`(?eh7y*k?z7$93mCTDp(Zd{vZD8(dx0Ce70G zY9L9AwKXA-{qAievdtlSR};xZA0YeAuf}oG__v4g!_fm^`c!^3OOd)md^5&o-qUHcH~c=qAq?UgqqX}Yy=0ef z{THHtjyqYVM_~iuWayayGA(Z6mMWyH=eu<1oS$Rs?j)FG)18UU2J)ky(DFZ>pdz{o zt@dw=XL1R*^^9>=&mfG1_Hsu-(c0JWip!+lZ0)|ZqUrfX#TAW7Z4rA4o3kNgc8tNW z?Hm1Glij7^dnLDfl{Wb$2-G};Ij_?epLSh;M+(Ae4^S7DbCN#Z{q;`9D|SENJ9RDa zfz2IEsC(@SGmCqaF=0_MB>&X#ONa%WS z%hEWhR6HBpYo{O8P`BZHe>tLE$o}L9MwL?;5tHys_2_F}-3s={!Nuf=D zYOC6$|8hkkoY#6sCFn##w>F^+o#@rF;~3PoH>%gCq)>9P>wRwoud72D<=GMKo6{iE zYBA}+hK7CA3jHwNKV-NO?d5Brgl;NSKmRG5L+T7aRXZI2m4L4VaIuR z1<@_?+?)J969r{fsTq4o7Sdtf@QCz(r!)gA?cfw;8C0+DC3)ImI=-$L`$D2azuOl- z({({?ZYkQFR8L!tl13Y@EfW`ee~G@KkQ5BVp%ec^_Zex-JeVnh-Z;FJ$~gmNZ7gs3 zS#igrw+q3%wkk)uwPN{lO2&pNl1ho&>cU%o9_h~DopPb|9#QiqY48|Nih3Y_Pg-he z!*SpNQJLrHZPp72NtGnvK>w0(STYMCh-{M*H@|*&lKH$W#_JO=^x2IDo-wLMGCg7c z%rD4}iB#(BPv1tq9)sqYIRnF&!?e;T^i!~6`kfl5ue!mQW^nH%xnJA0eZ%1Azlu6r zk@1$V{pe7o{?(RE7p#6bdKLSBT?G)_o5I+_Hq1y>j;^x!oK6NBfpKM33Vuv9#Q>9E zOqGiMxOTwt&ob*gO6sM$>3%->(vX`=_oIdCjA$5*=I>7j;BIMN|vHcWE20^d^J@8(?w*U84^<#j}nFZN~9+wY(X4s zS-&T_T(V@@lAffgQLDB`wS7b-vY8Vs6~?Bh;)rz5Mv(&`kmO zMadrPTf2z|FeAD(w&wc%nYm}5v8Jcj#|(;9Nzi*;9bm72SfIe=Z>7;<+sAC$F6N{vGD1P_ajc> zNdr|&eG>)p7kF_Po?|!QI=t~0B%LS)07gK$zf+^Lg@N3QZH3flw})=6#91NQyn|}q zNKx%9UUb3CD>G-|f9TMm0gR=@+}uTW)8odeV2Q%-_VWmgxTBumE)^oPjEhJRSn%{8nC;V>mL8f8&p`PD*G%Ic5hbdf% z&25hOVhMNf=tY))Ocz1q7?`LruoKG1EUq}!dI@wiKD+aO-s%(6bO^q``EfjWmHZvz z@TZ->s`=M-f0!1pD&t?`i?cV%CJfogdpI1baL!3xaCR0YMRYx=q|pV1G11LPh}GtL z=btw!0@eLqZtX%z_ZG7(ivlhh=vB%-<<5EmJl=N(e|g0BCAs3(Ki7<*f-`-H0r+a- z7b{hk8?l95`F+Y4sUw)K~Zi)gnJBD#e6 z9=?-t9-h-P*}7SDN&uTNsg-n`Rr363yk*R?t!2vbABkM0J94Y2zjurOf?-WAlm<=D zvR6W*e;}{=`okf8Ta%#wB7(s)I;jV*`>MHN($O(f?K2>jzt1c>rIMw;AR8z`+mq2Ath~P4Mg@QImftRyQ=hFG6>$U?o0btonvMZoC2A| z+>}~7nrc{_M3W8vqd7q~Q@W_D+PxYFy@R9QCn?vLQWfDdEgh~zi)A&#$2|-af4W#& zYk`zs^yVP2?cZnJn>7T%+5~GreVN}{%%Zk-ds1uBR-dSRbVSRZ?1miD3g{>SZby

~OfkOd`-4xEMWU~8bWDfb04Jn!M~#U~ zLz{eeLB+euQG2e!aTj@bi9L=W@^&Ur%qcEd(%UPfQ|jra_ol9dN`KUVMSu z`hNh=ve5stYqnw@5HvOlFHB`_XLM*XAUQWOF_$5<0Tcx>FgH0lmp^L(D1WpCR9xv2 zEliN$PJ%;2Bik%gG+$m1Pc;0!686!w-6wBfCLEc;gOlSGjs3% zul3&QwN9U1wX43W`gR>gI!zr;DJz5pR2~6$;{(2 z5D_lI09l9!%nG2!1yDx7p{`hrG6*Mc7nqH$+ru&cc?GaovI4+DLeDt<2nR?xLS0~% z5I8^$;${nVd^ph(;sDS=Si+!g-v5+tbsN3*zX?g@16d5ohH9c*5Ll z0oqVksEY^G3h=vOfI7qx`e$ccSd0K&TbS#gb{&MZnMNml)nzybJcHUKae`0sRoMgL9&gZ~i>v9v@uIziyxFt`oC8s-26 zXvnK_xp}#903dLy-+x4igDc`89^wIkIY2BP2!B)#0mw^f0U!?z{?(qVr3=i-&6Ud) z=J2~k?%!!1rYr}yl0i5+Lg8+%SikF&g}Fd2AI9#@{pZcv!x5fv-@kx03~pupy9q0I zCvH7B%-J2PB>NZT!G!gX%?9cQ;0Fml;}zruK%D_lFH2kQ-+$?Ky`7+cIKjWo4;}dX zIw70@)(=fU{bAP7hd(S|SBM7`;O62E_4oa^S}tE9$9hD;l!@+40{#X=#KPz?YMU z55UR84+4O}V1E$c*~5$ff2Yxe!2T)&^iQl3+!_IR;QvwX!<_z8vd3QvVEJo1SONc? zOdatcTPT3#AC((}_(7Hr5Agr9*8d3k|C9LdEdMu^|8GI^?hX!rxLN-2|9{*NN0@{6 zUxWwMy1PAWfEwaq58(exeGdI|Yt^7uFn7oQ^(whR9)C7L3U2eDW==347l`jqJIqxc z<^{FVgt=MT{;8Qi?Rvj=%>f37Y9d@=zdtSyQ6SL&_#PI_(*EHC;`$)WKV1;lhi!BF z;~IZs=)*q!cO7zYON7<$#pB@@06<(^Al_IHSO0+c0lwge4Yh)L{UL1tHy0e?_7DPi z=-D4&jel^#`hCrUJOFO(-=;qiAAno;A0!CiHuxI}Jp*t<{y`5ui@(wDPPnc9fe&e{ zpbl>T(7_ME(0^kPFM!+TUyvWb4f_`q0C3y=3qC~K{{tUn$_@V;@;+ojI6`gyl^pyK z?)DFSDD^>f|33Y<$>Sf$^N`T%5BOiRwRCrJd4CxGA1m=N`2XNPzHm^e7t|8#^Blrb zB+RZZtnIQ^iqeyFYfKdFF!R!YhjXmh6vM4gZpv&eS?6`mqDqDQ=U%Y9sa>bKwDV=| z%KVA%W<70#H{UrYt^AG+twrM8{rRJr6yFOf`Z@gfNCnT+rD=pqUHXtTsbdMcFeR*P z`hRp7@%@>ZldaX_H|M$P}i2I3zQ^1%IL&*yTjqreJ+1!*4Il`c`6#2+FwP7mx#^N5`=y6K>?g0>XqA9e4N=4F05w@xDXW6x)D&#IQBND@uVtyoPU7N zN$IX+zfCCRk=GsX9#rK=D!h9#6jr=Ut z!)*E2fhMz?nQd*3FDMOf&kJ_0W*baCrd|L}&ST7uZS~FPmB9PT=bLwrl7@0rFWx}g3wIPa0jzUinR`Cq zj?nsSlXO5vMe2@htda%Bud~Ny*a93c#YC235gZfhXG&^0c8O-U9{LEREye*t+k(;o zE!ZQ#hirZW(Uty+w+<4mBVC`bu>{(@`oEu;p~PR3&~t$M<5dO zCF#b=lJ$5)Y!y9p^NgR4^%zD*oKB%Eob!{{lYwA``nm+qH8O2`d+!?_qhE2*Y3^j> ztJw<1d)#ad0{WUCp8B43AmvxTUK?YWE!N7ltx+}|SRaS=<7*OP?tcP@wA`G#n%%`M zLF^1emU+VavwXl2UTt>UfJfesc=_K|->viUsDza_g*Kc!ZtX2U_u--}wArGwieU-p6mf^r zTFSC?p1KN~Zd$lU+Nmk8P3PT+gJeso2N}K`i>&p= zad6y)SM4=P8*1_MW-s(&|Q2Zfr@*t9)Bb9;*+w#R(?sdacM{< z+acPFuU>LnLUt$-=co6}$O?rKmEdkw%4mMQE_u-I%~Y89o|-l(&ZBw!2{5abbM6I% zLv%ibRy#dysz*K8&R?E}WnM0u~t$%Lo2Ca?3JMTr8p5iTBwR}&r-zM-qA9Uq3Le492baoDR=~W_fT%K`8 za^n_)5fIGcNulSj)*mKti$N?+`wE1-Sh)YaZ>5&05HYM) zD-DuE@!tY8jEs?6qIvFPtR+9{px3eTHOl0u(uD4vNIT0iFH9lyoC90Xuw*7eQaX-V;!* z$`jn*C{#@nsNeGJQRu}4CkurrCC*5H3!>&1IDZCi+`L@@8m;g%(KAP!FV^@IhIiY% zeevyE0ABD~ee1d+3akIV&UEP9{{9T5H(O!9DnPVbXK-SG%8%7NsLw%R&0yhbaI^0G zxFL_rznj~a!lXEH&Vj7D36pfPl#u=@gO-Qf)Ugydo@eUkL$gyVeMekyBeH%!WpYdDnl|q=FpU@&`QzUQ$xbMr*Z@u#iCN2 z45)R9%!A8u-2@uOPs^@4q?Ke)H$wtz{XF9Y*Xs4Mr@Qh`inS%*NpeZ&`In)V#0eCJ z28Zwr73qd)l=c0h3?Xkm!Zq1W)>r=|wSUQ^G&91Z4L-S9z>Z&BmMrT+AC}G|r=R~J zlWZ1}Lu!-1>@E}f>3On&tzuuyTUD<8bw*uFmjEi)ffq7aO4=i2%`pu_%yR|{R$~Iy z%;~1b;<3m{=SkYDUGDnxUcloVac{@imbq-E)yHREEsygKV^h%*b7)R6yz?XMuYa04 z?q}@16sMl?n#F!!h@NdU1r->DBn(a-zrycGL@vzP1@M0QydK@B0b*r1v zFaX&|ZTPMmAdFj*+mQHv1gEwCTNe@_eEjD{dqEsY?oJz>CSAw4Lp&JdD}UeZw#RI+ zSDc&F`b`D7S56IOUT|t{%k6A#IEv*KDNl=+*50TL8#6O%C3~-cuP$!_W+wD>oQBD} zD9UxnL270wgO@F89a+-Lo_U1ss5~f9I9}5 zgoBA)51)g!J<&D3SFm$pZhx`y?j3;x`+TSdW!trce5zp=GUWN_fudvR>%D?HV~5;1 z%xB`3yP`MHsKTPY}+Wbcf9(V%8#%N)Y6L{Tvg5T-edtXn`ID*dtAv>Tu+b_@r zsb*`LfmwFsoWsII{?#ADpZL-95xXDNJJLOgMonYwbJ~Q7zbfF~h=1zn02Mt8JOn;r z4SzzfYiR(0BQb)p;||;66|j$>%fQi)?;HRn+8(o!q+c@@H3HpeWPLPu&*zbGb2}`; zRX#q+*|e{`J`FtuMus;MVck4(yILDL++H=WU%0!Vxh8gf*;H!H6@T-B>K*7hbK;?gNMB4q#iqCULz zt|C-eFL(vU#1tm&42JQ)p|Olk^(ETZXYVq zR9@PimkXB9LVtFAW5mOf(RmSl^tlpFF8dwxIQE9;*#Z;KTY4W|AwRo!s>4m+oSvFo zYcIYVCo51;U3te9D>&h3l=9Q;E>f!5pVMdQ7&l?j>QF?)>tW?zIc0o076AmzWr|LX z|6uG~k8ttgT7T#edc(e~8(eu`_T$Z>uT(!0ANhq(JZqk18l)sJLKR@gDBOa=5osk+ zhJ@gp&qPy#57K%I(i=L%=jiV-zD`_THdD$@%%xqns%g#I;k8BH_mkOiy-dH(IhV{y zOY+zH`RfzAW1c*%(5&oi!EpJ{>P<}Ccn7q?&Zl(ci+@{&I`wxEaCMZD&5*e5^>iTE zlYvX1LCGtd5M{)IHfTh6Saxt>GOS#zZIAh0>*@ZF2uqAPHeECOK%TE|d$o(uT1LM> zJH@bKdhaCYXAnmc|K#&h+zYPZlPkTE*VhR-k)rX&cyCnrcKQaDj!7Qr8z<`(p#=m~ z8pM#^AAbqbb)WOb_ZD|uR29Vv$+$E21gHmn9B5+E+M)NMyS83CUoZJU=o%>7rPM(_ z^%?+dFG)M%Cam~8G;LJqIxB-^_2dlr;mT_|k77k_VxuF4D^#R8g*^b%9*4lY#%D{T zcMN~*i^n_A2H5(_XqHoc!c22jr6hV#RRtg!!hfLG^H|}7GTm~n8cNqi{5DQ8UMcBn z>6tro%a~)u&7&WpJXKsUp=05ky>1r7@qz zA%6!5+orzCx&n_9H}k0s7ct3xa}WA5L%oikhD@##W4KDNif`*XpBp~T*m>-gWD@F; z#3q^w)su0S?2BXC-H_qBVTM014y8EO7dIxo0YQLBl)1Q3oiXGG{w7|xAs*V+&8%)k z1Vyf@V>`t+%QCL7fQ*paF^8i_#Z zqe5@rq{}}4C0|D$5h-&&DhXTKele4QDT%TlAQ+rVaqi{jk(gV-6+>*TSI>ZpZGY<3 z>+86SRBs;fGUl2VxD#yjWs76<=uYeAmv&u#)%ao)YCmptP!xVO;5B0~O_C$<_xH{w<`W|m0x7ThAy1>ZJv&N;##{}h{)lHWZ#YKy zw-DRsX0l{$BSGSCiCw9lmVtdP>sI3GSUT=)3hNeC)B0<4AOjf}DRknNL=e7yS&5 zageQEO`UoL;^WlzTw(yF3EvSd?DagE`UM>K`Pm)AL8hQOs)~W(iGDj(kbk9OI;TGI z^1j02D2;WsGhs(76OlH=Uw68p7x?;F$o9rP!EhAYxRgQ}Uk}(N(edT(J?{Q!j+ptx zmry0q69P8QT=tyvyKJH9{T2JJ9bAO$t>|~n?NlM6DX4feyMUOTwOu6lkZHuO?X)R76s8b2k zCpkaMSQ)M}>ieikca1y>a!xT{o#py3VIfo~^I;kao?N2v#46e}s78;3^YO_sa54aViL7qoLKh zd(MSpZqo{hW-b1BWQqP=*!M%{_Dl9m*INl}cySp~dqCX4m25I$rfOWxF{V$l%x6GV zPVCKk^2<2yG8wtyUq{Mc3l}E5DyM3)lwB{f=}M1xZdoR%(`GWo*B5PEO)ka+sm(>Q zi5|~XJ=I4Ndw;*2U~69&{yHT=7hU=C+(3khy#C1qe0H&%INVCZj`jH%5dq{o-#-H0IDgnWx%S?S8HY6R<}`W<7rr%53#U zJ!|9hN0zu!hp&C$ifZY>MOiXaleMBYABt10;ljddBARVb%Gw!jO%5nxaM(@ z3)zfUu7zIUH{nr3{P$L8Wo41c~LBmJmxU>jB zvY+tf09#}B9b?1B^&=YL1Et4?dhEs3nO&_+!;GT9)V6XTlL z>+(Io@rN`Kyzm)dy7D_M^Plij%1{Q2|i>Zv!CYswXD zA9U9XflKr!Q?_3y!{?7+&&~LWhhC*okU>;Nb;~L!P8jBakw}prxX|_v0KxqkKd}u_ zAZU)?fy4K>S3*Y4L z=bjt{Rzw_vQ~B=)$a0LupS+nqw|}h#Zi6S~N8*ih&84dB(Ld=(*u7U=PhSvb*TIo( z7B*p5EYa=bCnf2LwSJOhte+rkJY-XK1{yf5E?)60O1 zB_X!6>tY~{pIz9m>7Iqn)4NJxbxqq>p1-wT-CIkjw(n_ zr6b)$V|#7Yh^-hcci=C?7k^M;51di(tMyFmNS@jMXgwKAfjZ$mvmIHcp8zhvnxNif zR}mY1duH*Hpn%YGYv`Mr^cxa)QCF0!nn}yRU-`n&p0Spt7 z9+jn%emyA*J;YgIzshY>9~<>7b6>2 zCfmuXVl|)Mwb}%~%1efhDEa2l^vUd9>4u$<) zfhD3d_2xjil-{5XOV%fBJjMA7zeo<^BszkAG=n+eVE8@rGeUB>t>G~n!6#v8eyjn~ z$_Ab_!k!kxgG(h$BILl1BnXFQzu6HAKY>MvEElVDqvcw_8h^heIpG0Ed5pbuV)eX@ zR^$Ln5dbSAa|XRGfSxHyAeNT~j*)taG$p(}dc=({!MWSJXFys?ODR=~d3z6`woW-RLp_*N%Ux1bz3cuj{zrxs|h z;I|EYbZEZ?Gk@`AoW5rZFbo)LWKZQTJjLxYOkAF2KbO2G^muGv z0t96;rvk37aRj@RxVRuO+ow^BItebLZB`A^bRCO07(@3^R=YT)4)VIfC=_%t&1At{ zro(MS>+|IVHRYfU;U)DM7=SH2vWbmlwWTR9i|XjCV1GkVK!rz)Oq+S;Y^We$p~yvN z;qmZis|`}0;C;(^*e^WM9|oPZjNVORd_c9=O1;T0Q!Ss&;*WM`chpz2^t#kk-RZ%+ zIOkmD>CToR1h4s+^!Hct`G(>)c?qh)iSDe0L#;`JVywpUoMVo(__j8e;S1aw5L2!e zTBNoQRex^B{1udiy!eTYYI)6_6RtNZuFd+Zz^=KJyMhkOGzz1cL ziYM|rEz^9u#XBu2r|iZkKAFd{82ae9rW2=0(w8!t=Nq-@o^P}BJU(1e1xCkiENh` zJVL>vZtnS+)~!c;&oY0}f5b2_if7@L@IaE@tX+Vnl27f)jZRy_B(ud$sniy`qjXs2RB9`2~ZVJOe zN{bqLK6#CFC^FA^Ht-8`FpBs3h8xa^}19*!w&Z)rn zHmg1p87zcxtY-H)zhV=rQKrN-3Y4gjCy4|{Rf(m~4_oCEjkAY}gHsN!lTGzZJ(bcq zK`S_~r;2sk(Pi%w6^17|@o2vg6Mqm3yeg6H4E(zC#T)OJC1iN8zSDQZ#k;XD8Wi-^ z26ZU=Tw0=Gd(knRWkyfMzM=Aty{K8eyIhQ4-kG5eAW7M%GFN#az!b_$988^?@hISD z_w8xQq|Mw=EVI)99m5XY+uNbXhCJ$8<9#XQdDf-Vh-_uV7!?&+LI}fHW`Dph;ddw_ zuEAe-O#o|TCG*~oi)B71`oo?n+8BtxY2S^umpaa1isY2bfo`J)FI;U&reIq|>iQYNzrf_(;DPx%&mEa}3L_*grd4KijoBC6n(?F4l5m7$# z~PPjYGzqBGRLG za{byO!UE6c=-R@tg73(}fFDZe;G`IAu8~73E&*8`p+dV9=V_AgYDHnoBt0c2Bd#C$ z-tCe134Fd@2~i~#RDb198bg;jdY6wg1T7M!iq-<5isX^3L)7AV-_u@;#h;vxb@Bd^Y|%q>VdwKpVPq`iYSVb zZdP+52i8m!TYKy7QY26>w*0Ja_ukiog>QzVgZJxC4%E%Z#eX~$-JX_kpN?b_k_bY> zos&0Oas5gbYs#(B*^jrDA^GFcsMB!@->uB;)Gshep^BzkVY2#MwYd66&}ln&jrgIo zpVtIoDR>9m3H0R)!%5_vZsl-|pH*<>&AZ@xQ(nf)-604_F8= z*{swkU(s*Vcs1jcX}uwM1{-Q20(aDClyU67`ci@llGFR5t-4)v+!ykA21m9_T;mQ2 zPxFFKlg4boFda#;hEhD)R7pu}e(Cc&lgW&VQqv^R_2+;lR(fsd}>0{TfsB#${(O zN8Co-q<=>M9+q3H^7Sqc327@PMdVUPc+#^rGy_Vo+_+@f(MSYTJ`8T!ufg^5vl_o4 z%Mo=1w>_WaY>!x#f8RaBLyI$7nXAV1!{sRJb~&8bes@sS8kWZJyu4$JWcctclS|6w zd9Qj$sKwDXHlYYFX4HnJ&7O6U?POwzR(shiX@8oaIjOHRD$1jCygU&!dOb#WuStd9j&#Yt$pqBTGsjZU_*asf_qSr@P1KoI4Lf?stP~;K%e-m%FljE_L6O zT;?&COFmo)U)$banZTM#wDiTaQL327{f48**AJ%B6&!(-23(dV!A~+mxxL52>X*kCo>DPaU!^jE`_o-S3QI zs-5H7lol{rx?{@2AyL8ab0zXdZ@v??Tz@1nbC6n*#W|yBabtSZzyItyK57*7D5hD8 zlxQpW1t!k^r-%^}Ki317M|bSC6S{!rWS0|yCrs7SE;Ujc$?E+c#6^)-JM2w*?d1@Z zFI`)%H<>q(% z2&wPHF}N1aQ$hfhKHaX4`o3ah#-$IFTKl`30c!8{uFJ8K`}lxJ?ZUx)l!A!qh8zoH zjEXrVD#Vx=rIotox5_hQqgLI@8Gl)CKmU93a+U%`eiyZpF>U1`URmZkY5%I9r@r5j zG!!#zlv@*!4$}6g!?(H|H&@!jOvf4}qw$XBN!pH8?-7H^w^BDNGcyr4_R|Q&p-rO_ zg`mx{tQLQ3H3hrGMGUdZ!7u!j7JT~Pvu?Ngk5e^tMVs>{p86I0Bbj{{Hh)hg1r_J& z2dDA6P_kL#I|fy*Sg#b**~??sly#fJSJ+Nai4^rwjVqBGcbrL|&ZZ*c<;P^5<$99U zk_<67JLA$)FxpD4$lu)rUCOV3)p4xU#bc8Y4g#+uP%kLUx0~?YDfT+vN>ge$MymzU z93erKcR(w14v(iR9FN;&iGO6ti^tN742I|z5(f7b3-IOomEwnd+jOL1iP+4sF=0u& zn#kMzBX?IyW%qk3&)7XeOQ_sRlvcM*OXSPM0sCKjT!ZY$oc%og;j@g+LIi@zKSyrg zjePse7BnlVtA8P?TJdfE$y(g0Kc}RYt@}FxkU+qxSSL~JH5m?b6o1R`C2W36p^>V~ zrD?Z)``L>DT3Ihe5w6BPWy(G2kD7N3;pVZrOhT|v2{h#Vwcow3MYmEdQp&jfTeOF* zw3XtZ_v+KfA;03({pFFKF9WmE38fmk1@keRc9mYT;U_nz(2)r&*&tiTRYrtIqm-MF zx}Yk72Kv0*AtD}h_p~}Q0p`9gqEj1j0!#d6|X@b_^b4? z%VH1Ho#|U6-zfv6LT>0{lF+ithWBWK5qA#$ilqV-jy-9wgMW?ko*(7CnaEvW8`~gy zlS}BMB@S^kuNQhl6|0k>(_FmRRJRIMJL%zp<&j_V zPW#J84Co5BV?B5z1 zyokeK!qit=T$*+wSWkI_%SM$bohq1Q5!@G)gX43C&wsN0LU;s0JUW~qXQWVOB(lSC z0vi+8fWfafooK!5?)l3H{YtHa`}`*XrjI}WG;WOj(P#IGRtm*Wswc>2YlZWL>u7LF zNp%FF$8*tzgnbJEgJb839-~ynFh7S^vw&%(Sq2yRx}npX0Fm1_{;xl@G|ty0SCx(X z{U0DE2LYFZi2k>T{s9lP12s7|mm#zP6a_IfF*!7se!9cnv|*n8#^m2fR*_h0u`0GGtk5pjV+6SV z&$2c7pJn<#>wj5i&;MA=2yAQsbC8)Uz!Yc+vPWR~mu|B577hTe|Afum9RHj8hmgxZ z`~bB7Xh;Vz2U`4tcC)orG_eB$XvH1u9Nk=j&Hx1mbD*<5K-Iy{#Qwi16FZQt*Z(i> z{~}~vP5#kA)ZX$Rm<+>@5LmuK#Fh;%xrEz`xVV zCZPXJ&wt7McbWif|Ib%2adifH0`yp!|1}=0|9bvw8T>z#n3#j7e-9HI4<~@>8#^n2 zjpLseF9*Bd|A(%bo3k^}-u2&t|I^EV{eKS<5aj znKIU3SYiWTp6t5PLkA65nHwEk5ZtO0QW2!pJB*0`$zN?vc#BFVq#c0if9#=nM{H5gU2W{dWZdx@ zto42HIm$-LozuF5X`)RwPRv;vMB$mLGZw*h`%$65Lql3P7VWVNp9XErawZCAWZ~Le zi98rF`fH*y0o#~#@@>*PR^UCF#3@$GRQ=)F=oi%nl|ZA(ITw^`qIk`sdt~fr);g~7 z?=iQj8sVd_e;Y?s^M}x`M9Zp9BWxo!au=G!T}Sd;ep0E=H<;AJzUG)6={)!*6#!@J zKm-(nX}YT1evO@NgM1=pC$SOHvm%H6Daq+dTvayX@!cuJIcJ74u5P$n5;>Gs==#P_ zJ~#doXIt23Eg7TtMc&X|4=?`{KG^5Sn5B9lv4nPge^%3TmVmh_i3_pz(T2_Hl!rAu z)*Q?~zAiQ2Q!_sYqu{pBtjgp4F+%A;ao-*2c+HRnZRmnQNt$HViN3iEj$IjdgE?D@ zy%g6rt1v}s`~1{=kk}s{lVEg&ACspbe)Yh%D)C?V*Q7!x5CZ(-*anNs>1=i5t)YpW zji8=!e~QO>1|yQXI)EpYO~lOv8%BUJj~-$__vLM zY;O9rZ(Ip3roPk!Sj6H~lwVmd1kPcY?rJ`TA#wJ^=N6pFy}LU)Wj@umc^14OW<(_y zfs@YGNycMX(h`RVYjuhF;EI9Wd3k3veJg6HHwFVlVEoV*kkJ-HQ#=)ZwaZs7G)=nr ze<#{Sc9vdVZJE-JnFUu~^?-_gD-3-qi`2`z_JY z5qRAvKQC6hD(sOnQw9BN@9LKvuufc&f8o{<#0|Kn2QSr5k@dETpSG~}c_!5uk(^2V zb4>djuOfU+l9?LIW45C1sl(|e2O3i`tyB=GZVb|a>Y85kZRI(7ydK=;|mJJCc~lV}a={NHYCNWv*(MJp-SAL_ zrsr-L7cIIvi(Z|G3+NvqT0OQAbcL<|%Au%BqEPp`UJ>_AiaiaGZr+01LCx1C?fpx@ zWjcr}S^5k4wr$_s$^EcYF-|w?e4)S9wJU-p=f~Sxi%Tzj#>W}!^H|VmH z=dNo&dhta$6CyRWcxjqw^iIi0gYm8J!jte1C;ySYY2V}v+U*E2@+mC`eYXmb*p`0mXg zGEa$fV6|GV$?Noiei0}g3Pg!wac+LH_j#)8(1A%8v1Lw{=*588Wk z(178UtIl_~rj8;bX!sGJf2PeKHmUV_euSxKg~k=JO)87$h&_fSWgROBKp}9i9;Se0 z6Q{cKhCx5HU<81yw6l|8*!9Eejk$tOL20+YD6T8R?C2b7I%80gFFzP4Z)Z_eSD9)f zqj0eyOn8rTMKkrhk-&Yw*!V9}WgWIF;8gaXBnaj7F~(b{0)v^he_!}Z!=^=kMq{1@ z$q0{pS#1DlL%(cfc`a7Aw=88bS-mT$VO`XlclUZt!98{a5|LcFh}ZpZp3f zn7Z&u1_Fk%deAz5f3qVc?XyvM7q0euLK^T8X^YM@0>8Oz zi}-%fKn9olOqFq;Iht|$b-2>w*S;zH`e6h%xLSF5klxmFN-onScxK4Ql$9b$*c)$e zj-SsLoV@z}xN17A_jLpglP5Rg|44=d>FpM{2Hj4K4J=r%ou@- zbpo20IWTNezSR4qrNji~LgjI*F4uqTM8K4;9_C2=A7PVy{3qV`M3{xF7s|5$F#ZL# zh})+)A_qYhcqS_I^X;LVp$c0}%+&ou*L31A-dB4?e?9ZP^zJS8D0N-XB2yLhTifYL zc?DJL^s(l;6C4U1wCmEN8PNT`Qp6cw*{Y}*;sQk@6D<1o6ON0{>I zpr({~e_NDjlfYqFd=mzpNq+-pQ|1*~JF_%QTNi__!)PcXi8L9zG7n^lRn(6wuj}fI zXF0exT(y)5#1l^5jCOJ~bf>u<%r%kH~2%y0F~}oH;*N%ECzn`sajCN?mBd zdXenD5chEmp8udL>r1QlhqtckxL}64l|yi|e>u~b4tlz=#S$nl_Q8Kd^u) ze^NV79o?J8Y~cVd&pS8Bsk}-e>yG7k!?jIV*_Y3YHM&6v#7J|>#ma-0WI6)7f z(Bt@mAA&gFES=v)eKXsv36`3)FYBg>-$xg_7o0NV+sAvq-xjVP@jnb)I^=)hWs;Ct zsFo-7(PTWR%KwF54tf;ZjEb<6S|X?#e@wYwDne?==m;{Mo}ZC@4j7-(cwM_8TdaOJ zaa}?VWRZ6nU}@+SnWWPkBB#@ts_gbixzt_yX*ONnyQzXybBksOHIqyAb&mhkOedFD z`<6@wIi=}&8|)nHIbk|;K#Z%q+wPW66>&&T4~v6LJHSJh)VY;Ek@?v&2?^zCe{%I) z6r1YpyNkLvsEw-IjYW<1-vn78Y#Kj#!j#bkaK%SgU(Az`EdWr3U3uGA&;=uNG}M zhma9c>Z+ghgM@bNDgAVBfI&q zNK4J3>l!1m7!5;eoM2j#--ddtj3o-mc^U-|n1Ss(dXq~|5>*3x7$v1Dbi0W$NISW@ zCMtT%@b;!Ib9L)NT!eXA<#WvIm>g%D36h2IgGP$aO;jPr;1;8Mr%zLqe>;#gV@C$9 z1y~R1SkF>u|5A5-tmbTx?7(64pBE9qZZ0glEEAep>boCb!|dRsE=$Eqtp>Q}XfFVa zBKnw5yo-?^j4N&zwq47g;Kt375yY}}apGEy@bV0Y%#lqS27sY%u*Lgv2z}zjm!rdL zlkV0w7cgwk_t$~xUv{iKe<^xVdyfGh$7CuqA&Qzf-dJ$iSQR79eP)SDS!2om%XTfp z`7WmHs7*(btXl=^w17r_7L)h_^Q%a)#?sZ^iF(+S;K6gpACgWKCBF@mf1Ru|c}HHq zR;dSBd_$iC+81HCyCwT!R4g0nj(rkRg7Z7Yi5?SKQ|mIQV5@z1e-eX+{ec@Exb#ih z@z?mW=2kH~Y>(M^a#s)J>Ju9~o{*wi$+`19zC*@4ulg)FI`Vnwlj3t8LCvddo4FIp zi6YEZNCtQaQPv6*v~R#1IIa0=P11@SezKu66$Bf;idSPX5rUxUR0fKvg@bt#^1WIz zz^td#L2f5!=gdmsf4kz28H<8Cn$l+Fom-b?t@JC8TxkqU{x6GST?PVVHyix`#iD1c z7WH})0Q&FpQEPl!9;WloGbjKjhS5S3tq%`8k+BD}vt5$;3be~cWW<3`*$=-2#&q_8 zSUEALR9>%A21AYyu1E=Kzh>dc$T@(Eo9$#xEyV)oCxst3e>g=VG_Al1syTUV?;9SmZ0-#04Ev6gQz-t32hDITcK0Ih;3VvzojUbnF_IASngc49*txha$!fC-YJ2XvbC2(~BsM?>@#C-6 zv|W;M-R-Ugwu@{x1LR@G3|{uTfZQuCn|`BEf>8D5tJ}G4N)s0m(-F1q!FKyWTUm^R z9DgIHCN5BNpj!hoi9QfDa)FDD-=dKtVra>XlCZf$M!JZVj9+ML@4W`$!%vewAOlLl zcjMTd_8p?~DWW^`Asw%C8~4e9?BpZf$TLsOcv1El(q_tsSE$&p`Wsi3eo5iY8yY)ib zjP5~D&y#r>Z%Gs>5zmfd#LpvqZ5AAFNXU>#WPI2UKB7c%OJ?U5;;|=PVTBP~e>?f& zo@fg8USx!$Mv3#i=-4gLdu1&vAVm$_*zqtsT#X$i<`2KwNQHyI@m|Bemyz)oHJD@hX4kVzPCf#p;u z5AfDUr7II0z=!;(34-;zxQztfbQtR=(wmslmNx5g`-#(^{+G`5rhDh~m8Z6CV!nbi z1@vSn8W1m0`TWdUG~m|5?8eqc^1ux$aJyuHyfvr5W_(Yhe_C|A5CsX?1d`cmq*~84 zfv@xteQz@fqF$l{#vj&71=In$VJk*nLG85L0(UpXTW`1Zd za*w^JSrMf39F``!z439l)xiJI?Tl$#>@3e_UT@MIMl(_f6@bpc4olWdda$DY0Rhy2 zzUs&D!MiKFdTKUGCV{raPl1-6kIP&`CQt( zGy1%+Acf$0y96{$b39#!~?GWq!|iargvYk$;Y5*WA@sUzA_mPD+-+aFRIPIPeReK@wm zenW2P5d#L(7Z@Z(6a?RP+?nD{?{mOLdv_^IGZ099W!#XXj@vFrjBgMEN=nc+^p;L8 zQL0~UjHM61r>J@$oi-=bQ^(%QlRG*x(or5=Tzh%X3>j?yYc00-VLuLL2wxEm@n(#O zPRhZ^ZR6+6IO5doB)i0Ad0s{#OP2%kGX^Du3qb9}jPuLSAGIfYFLw`lh9}yzf?spp zm42t~Nd{=!`}W8t?P<9#d%>TIYL>eR1zQ$V$$G~mSNRm>i{)xaq`iGS&nE_CGW-AD zvn&NDtzyZY9qtc!py4$P{^I+wkQ%{^w;3sltsYGB2+cbxX#gOT3RYWE*az|_{(*0> z02qII3cU3Fcz_z4=9~4O&P|r2iYEeSFA1=g6x&Q0ArV_I>Bm0D%k`hw)=g`z=tmiu z;Zw|7YG=N?E;@N92BBA}Ud~NUSGH*Vg$hn=aaHv3{gG?epC(YUD%dDgIfJ^DuQUIM zPZ{g$ov#L8WF`*QREDnH*DQ__Qw1kQ0vrY? zeZuS(80ZGHR|6MBH$q`=bBV+n#jz0-;NQ-+c?cJxHqaV$uDG+k19) zxRmy79G#I)U>c)%W7*4TSX=^CaBqypRF}vkC7}0{$_JM%?`k z6yCmAf`?z31>BHCLKT}zHUU?j+14Y*pi4+T+rO5QxP|^n$%<`Z?w_A1*(|OP#szG2 zO!|Q)EB=jhR=o-7qh&1uYS?WxE`)kN8oJ^lPmRr;0Al*wQZ!5hO_57mc!gHEiJ6{8 zR7~vD+W~ufWU$H3>uVkj0c;~_W!;>fQ?fbMwFp|mh2xL5qizG?-pZjxRhKkG_rkl( zyMAsTptm`d`l<&YeV3Mgk6zX^im#+UR=(DJKBqe4izIS=H|oj^JcwNMO09h!KSd!G z+6YiHpdIWKP6ta(TkDEf;p$t5)O(+b*v)?e%;|mP;MAwBUn(zC0qKe^sPt}~HpnT> zRJMt$M_BL+ime|%m|x4x;7Qb%lt0vvfcI}yjue4jlpDK$@0Oh(ntf}Cmp>DBZ1WAd zhfuQMIaSG$b9u#;P!;*+7S`~%1k_We1w79B@=A#iRu>+L8fbsCCk3HnkMWfJra@V%&(CT^LgS1xhdP!i%#V@WovZUuDQ>t|X^84&r zFEg+hiidC+0GK7&)N;>G5>PD%{R@dkx>MQZb+xL!=-hnwa;0fogc+&s<|rh~k`{8l zmvJk!PKooyG`|nLO9KnYfGW86iQ2YU89^wsC4ddw&%cvcU$3E!c`j2`YgT(&hD78~ zW>J+lmB!%aa3~bdNpwmUNa4E%5Y&b;|1uNHb`g_g1HjT<$}emfqV25>a=S}&CzCcR zsPA)Q?S5>J{+6c&bOPyaeE z`(Pqj1Ylo`QnW045r-YwLCW|RZrEN12bUXmOLe<00PTRqzI%iIi+9kp@hdnabe{aqqzSxyhAU>*cihSNWr1=FR>wHM)JSMo zmrnjZkheu@Fw;kJ=@N5|A3ri?60l4zxHFh103Zq}&s*gz!*Kj7{Uk{uMfWFG>S4aP zaIaexnU$3v2>Dccv@ebCZNCs&bTokKM6>=CK6C6xIc?Bm3J82;*vXC!G4$Ku?~@UJ za@PPPj&^Ihah?X0YJtPybYJI;%umH3+;BWx4#zD&o1%2V?&Im#!eHIZyt{w8HWha_ zDL|wXX0P$#I;-&MSX;F22tFpWq23LiHUce$h~sgk@$+IIgc#Q8Xj?W2O!WKdJ?@kM zPsVk^LyRz2!M$^icyjVZ06`ulE&t#hzQnuUIr_J|m}ibDB0=IcEW9LV3nx2hLmstN07q-)@&LF{S8nxtBJ(8wq zKxciMq$?#t9g}oGt3lFtH3SoGeEhU-|K<=ep%Mw5*D)s~Fb-#rx2J*E@M$T3;~jNt z!R6u2-~1QlrsTgm&32lGk;3GyhU7(My^$F|Tic~Xd5OcCt5DeuXB(m(KiW~kdH~A} z)tdjW@o z<9eH9CMF45batjZPTVMt?$Z1r*L`)nhsJv4SBpo;@j%9v+J$K@^N~nj{0=awbj4ml zgiuIQiZd%a0(GMGb&!m^a6qZMP$uwvAXVHw`^ThZXxWCTmsg8iR^`fQ0Wj!6 zT-`V+#zcGE9{dc5o|d$Ic*|D&iR5*ow0wrnavmvZTzMu%rpq{b+ycQ1{v9zV>I6ER z8gW|Ov+Nqbe-laM&4?mY}0CFU8sDK(2w=Iicp4e>xq6_bX`p$VM&F} z^Y);X>mGmy?)Da9*s5>iM!=%!lk5&Jbs`%gnET7*3bQlEmDMY2KITZjqMkvI$dTG% z6I?fvzi-FM<7QQlkozIsUOZ~eFe@^TS%FSE9dAR%l!KwgU;jFJh%k6H_zLl+_q2%E z?IqoJ>@(SsSdq}oxG714gDFJU`GAh3ozr`q+|d)1*(%xV3+9vSQ2>4DfQA8P{ z;y;gg%T>cMpG!uj zdw}3+6YrgSO(Hb{0P1@gXGI!M^TW4$`T~T`$D5D%VK9V(UEy!3N4Mt^ou4s?(`mbZQ@uz~VjMM4X zeWW9~Gq3dBaY6pdt_(AFl@KSE5*%H6SQDU9SeE-ysNOrglC#0=lRtG= z?7oV3qxy;>UK~adr3n%Wf6gG8O&WEXa0uGq`t(;AJ`yCeU;)=?2RP|JG})Q4HB_k%Jco)>&C-itw zi;hM-Z;TmLw`U$q`r}Hrq{H2n&<$yODUAJ}xvicyrG06c_W!|%Ecyo}(iG%9=77|B z{mVUUHfDQyC;+_s<=F=(IQy`ciV_*zV+r~hBoBE^KL@XApR6PvgFm(*ZjwR^+HeH5 zOM|m#P05tOF!2Hly)uEpH_2X(@zVqJeFbf7#E-r>DFRp*si<0}Z>g5y=`FXlZ>so8 z&-;ThdN00T_Z8(sAt-Q3cq}4O-4Ae|S8Bs=^=ldX*Z|`0)m2I9SuhHXYACcOA~l2h zRppx*MF+}s9=CV}O|CR*ksp=ac-Ub0+z>y7G5H3|j=1k*UoedH__)5lgh+1ws3`^&A&G(kwaQaGAsJ-7p4M=-oOGm8OZu*Am>_nw`Rf}3XAU6c^nU7B{*wENFA}ghyK2N|Z zMyF%or5hDl-`dzH#0=W)nkq4=%@kH~TmpGVHh_0ij2w~G zn3&uqVi1eK<9tSBv$JwIGFW3=(>m@CY+K5lvsLO2SHUZ42RTlc1}wV_c_ zf2o2jZDRu_=2mTIq$ir@Hx&6T#@^Zs9wVtx_Vmp3w1a6GO6mgzUzD(uL*dSV^KH_& zHHjRbihA~`SSyAFaE-yMLp{C}mfdo%4YJxjB zmL8UHsWxV>!wdRdg~Z>=9~62~TXaLkd&E@2=?>gj%ip5d9uy7If)GPD`R2+{34pF^ z0_nmva3}_C{&=MvlZfn$NaJgQqB7v#M+a&WPlPOuoeI>~uWU);PEuMn$rd-QVSe1g ztW8o7@cD{d{o0>3<%;@wlwsWPZ1_D=*oL*(WP&#Rc-7n(mYI*U%ie70k9o(fH_gq& ze?+}(wzAE+RYKUn%e^lxZk=B?F91fjUW4r06lCG;B{?m5;umt2Y1Op0*oTDT*_+>A zGWxP#e_x*$S#&O%r4i;|2_=Xqc>%+7MH=ZOy{yb8LO5I9 z7q)aJsJNDX)SGKcO&!ORcqe$%S<#G`SplyU3D-Ty6+q=)Gk`3m9SV)icT|(0LbU=kftU+=d*>!d@CC!$w^Bj*5oqnWbQ9!AK2KPv zFEdTr@I;(@k~}!;m(V14V3Lb?8!)XT)@Lx~dqLY~b=hXDFr|r<>43{rAkbCUPKO-h zX6`7u(?1Fw$0SN>U;qt@!T!C=uO<7mt1>2+xHewSW3czA(dgOG5MRspVWTb(A@L;V z3tJ(K3mNJo+-|c6kaI?Z3m**6FB_``y?Gmxz`H8-ouzdUmZJ8nV1yQ!l4D zns)4Jn4mn(bpohvC?nNbl+$hTxcYtSLCuhJZ%&k>SZl=}aac^&CV-TqpquIvGW0t1 z=RsM134DulpUZpLu{ipgXrS?cMon=YaZ z+$0(1%K-5X@eJ;Jvc=FOC<*t;KV*QqFFMVlLnc*gT2Q2n%VpydZF}UcQZaJeR?F0q zXy!bB2SEF~U66a9=>@&kUNUn!IBk$J4Np6RROT*=#hZ%`7I!312H%gdttw!OMWD2w zN{NHMx2|%Vsl(}mT`h}R(Gd-eFroA{v5u*g(Cz+C8F0p7p=BunOf_wL`IDZT6}^a@ z`*t-loIhq2fu$MM(S>IELeY>{pVIiu+5~US1i-DR_SJZ))>$GBQaVMkFw(2Ik?2?! z;w@B!TH#}U*{m%c68J4nWI`UTbo-2R^mzB$Y{ftWuMZGSUwLPJ%pR-)6E~>N+?klWBJYlBqYOIr=pFf?^ zUEo|;;3Ya@J7axQygSz0C{?vPHz{9>rH!K;8&gi_Fl~>yZD_!}2Vdi9=5tuVwOVs} z%6TgLhy3+ru8BE>XneYV{%eH)R!uui9DuGq{Hi|1x)As0sd&C*ic#~h&hu5V7^Q_P z9u1mWnlzvosQ_>-W3 zhyBQ-X@c95@^eIN31fOap!5*`QV=Hh-McIc9Qcsv5Y6z>6bV9mD?j`7a*}W`D$Uy!1%|S<$m`TLb*h|0v1uCj= z?8W*)E`z^TH8-VaP>eI1dk=K6KcJWTUt1f95!SkHZ>T># zERrJxrvDVu2I%wbxD_%3d7B0)mf0M{L<+E{Utt~~%4ksG-zzd`2qgcIbxk#zEj5lf&FISo>2d5y z0~_+}`WrDV34SxCzgz6VjsYvC7qFcb+|^<0YM56=Qvdj4M^iJul^DudQJGgfs+?r8 z>(tF{o35&z2YE1V>zvthjSNY9ns4AwPFzqF5@_hFfaxD|lgCUa=R^dBRHFM*!F;`Y z&orRTfjM7K5x-%g`!4K~e&^(#d^j89F}B|0lzd9tWF0u`;3SqTF96;?w@0rwT0NTC zlIdt{2O_Vx5s*PUx#lpca`)=%QC26-POE>DN6)WY8LsNUfXkTX)(xiuLn%fQ~(QRrm>~C2{{$`EDV~ zqJx*K0UdpB$E6K?Z2;C^mAf=RFBewxu8NNYVi5I+wRQAuHCV{&w$Zwjgz-Ob+5~Y8 z>+L?Q)#B9r#>sBn2or2$w{K+(!oaYIQZ1X`$3H*I_DsSa`VUVrDRzJe2^W}q+hI&! zf2omj;;HhO_Xl;p!l<>Lp#Z%t!UcSzicdbitx{@fVqq!X!UG`vG^e=KdkQ|-AKrlM zVLMo?j*VO$C(klDmaM^I<+9YF4Z~qwxG|efQ=3|o(=*bg{@?`di;aE7;40j4wxuLM zN0tXCWX{H0B9(X}=^#Q~TGH00l`wZRdTT!ahm%ub~$g`T8v3JQI_VwHkGD+6~M{)ty0L=r`A zO3(wBPa)@OX2fwuNmlOmzSdRw9(J^LAb&n8QUj6%Xp9fbSCoB0K3}@Rp%omg!;ESv zG9p#Z70!ersj-9*#S}q}vLQSwbUX=vKV#Kg?bWVm2>|2>u>~cO_D$=*Wc`BGcd1Oc zPRFDySNVSxwlU`nZBw4uM=Sb!+hH{#=7$&J*x@P?_f&mmu*+6chGs~aH!n`oK@uqf zS>9!m4C;eHhZ9b?A!q{S*4MF@7(l5vOy-~>mGw0BZY2jnUZ7!b*g1LL)hEj_9$p}I zZE&zeMBy>iSuEnPCC3sk=9p>cQQa z{;nD2OQAH8=cymCvc?sz){3qL3D!U;QR@BH9tBK51r<^UM#yR0TSAGTBd)8~a^(_E z*pF3%#~Pe}hFCTutB6@bSCh%;ybb_cER5=alWEmQ+c-ud20k7GUy{BV*c!C{OX3_Wip#7^%0OobA@T@6ZJ{!nKz z%mCCjaA-W|B)YFy{0nEtmelc(b{*=ovqGG6?lx_jMA8FrKePtorJDQIh?86eu0q%U zLPL?2g47W9vX-$C-S&)RS(O{=v!l=RTo&#rpY2@ldDuYXB2iJZxjO^x`wbrW9URG} zjtNR`O^r*>AEL~kf1@~3NtM{z*SLgZN&*Idb(<>{t1>Ad*jST`!Wk`-wOP%XR~fY- z1r8E=sJ*UAYjoCPcK@~hMHg?{BW%yfm8LZElRbqV%S`)WXOFFs!qC5+AyiuvU9jjW z)&&8(l-3*Vo@j@TO)0lbHb&#vo^mY{{sX=Ybl4FoVGXmA;sm3wa$DLCSt5`KCIO%} z;N?df!4jQfI`N>G-C^F$r_ylYqJ$?>sz~9;WCeVu=Du*fC`}D1q9|9C&N(ghXD~fFfJrPCDYNq&I zA9Ivry0NqSQ$90||HIH>$3o&hf|62}^A!>Xo>28|hE{T0*Ajcp0i=0{m(5~3437^Is-S=9(T6RGUp#1~!m7vb7y7cNZ?Fd%(Ew+iYQD*k-`P5=Ozxb4*gKZQW%k!~ilXxXv%K#@2%m=Y( zWpq|msBU~I%~~@mvn;v%70nGON8KVE+()mC-w3nL2--bCl8ac%Y-D8WYjvNy&pVil zc5987d6F3fvqotTqg#J9v5BxdHD1yUgxX?TqmsBUN1=P}h+-QkfiU?$<26pm=<&+l zD^o{Jdq|BMy_FE$?hn$7Yys%l9)Qo@W&~&i^dfpmXrMi-@574y)yvk~jf(K$C5%JF z_DJZ1;>7wx&svlmQN)L`#6fbys1Hq0Y6sni?A>Af5h-LD5^2G3%0)tW_^so3ms+h3yMTZ0Wgm2*!*RB{ zE}6&=pKKf$A}==hC*Hib+UcPrEC)84cJT*Y-C=H)6P#+EooV9ldJliFA(-TX-HHrr zWzFoqxKQa6Hyhe@pCKe4Byy#zpNQtz5w^uQj8>gx6a93(?%?LspVbX5)Pkd+s_2Q> zkj+a($6a;#9a-FSCjj@X0Vau$q-5SbB-BJ0aPN<-&guCeu&a8_K-Bji4GNa_V7eg- z&++M<98R+zAL-C^krbT&bZsbb$*RI}ehn0Y>PJx~ni5hD|9ba$kTwk?)%=^iUV7qd z0_6e{S4WFg({E_nZ`~mMb`FE!^d`rEjWvfmn@i^TDxm z4Pm=pm!EC2bg7G(sIf&N36UMNevhi#he9tKN-;wQAGx>Jls9stm8(hIGN?Gf;rY2? z%KV-U9*+V0BQ=GYX`h^)6T7sqB#&02DlBe7F&3@?=LXQ+Cw7n>-dOCE&816VC5q#J zj`i%aJ@%=p7%2Mj@{bt!MJM%}iRIYMs7l?Gb~pN0H$Pj}sX>MH{mB`9Af&|4bPe7X zOEhh}FoczZF2KFZ>44LJ+xjaM6ic3&m}_&9+#wB=)1~|qZC3f%L8w{boWE)g4;efC zE(M1Ca1lTP0yB2AyZZ@&1s>sJmL)SthiSK=e%lY0M1Q9h;7swj+PKEv#256F_YT%G z*y0Xa2BnF2FTh9M>O?SbSS}^0=;4YZ$WcQQXg=hq)&~HENOyRaa*$Z)hsU>9UgUA$ zD6j7PAg^p_>2UJ=9{UOV!0McvYmi(uz46;D&;oq*cygCXgM5pzlVvJkY=MKXlkzX+ zy)j4VtEHLE>?1iJ+kJ$>zdXl9Mm#9tYJOWrO(m%^+UqPym?Pe6ckKkHJ+0|yXN9mwO?6rKNiNl z1(!pC05{6rBl+>3|A3U*@VTTKGyo&Df?oo2+5Ki@U|?kAU`!R)1i}8lft4o67%)3i zV!aAEU|LH{2}`2E_f+lakb}XX<0dsMJo*kMmWTBasH-O!&lo*5nVF7m$8L@i+PA?R&Ir5r()!YBx5aYnIId@ zB3x;0#NuPxYT#2C{Tl5O-9pRE%Cd2}wI&V?Xtu?kA2r7mdkQCp4_BaNi($va!b}y< zBI}sS^%zX-L-!F9QcX0s3q!eoC1wQIM5w3F$l<9UE5G*-IU~Wt$`!AXld%_I%Tbka zWDT$+tRUdPz2Yfv~Q1zi}7Q}su!;ijQNM5avO)@&x#(Ls`6v#}6~4{Lq} z*b*Vu%WklSheb=)NC;a~GZgUx3AT|Cvc@Zm3tOWYq=v6y3Q{B0M>kbWl^v&LN)HvK zZrBHvI>pZs7^Y$)$&)QUj6rNvPQ@-UWFVBp{KKBPY416_pK358i4Bu0k!f`2w3#400)+yd9m#8a#p z<>Gs=dcQm7Z+y7$*sd?<=iLi^xOp<8XH8S1Nz69a&D};)7b_#b?nyjw!F8kINDIXl zYp2CTK>SxQ8sC}(YW3#4h!e`c@8Rfo2u-JJds(kh^Y`6DI*-70*y2>TNZwxn&%@3D zH*PE51;rd|mg}9rmsM{|^&PI!nsjuGyC(5Rvcm06%$TOJPI{O%FU^lug~(OgMXSL5oBsePNQ2kgJ_8^Ub9!3)PG{~72l?IHN`+hJT2qm15Zh z6_iVw(&ru}6&n65XU!Q>m%nvt{JuDh<|v-xLNl+Q*_eK^I5c9VW_jnYj8c7sv_3#c zWK;Mom!VBbE@3M)$Qc(cDDH@ATdHOqnsCO`B|AGhbD?B>gUJoIvkze@gybd{DHOQZ zW{yg5$}#q=E{E|4;~EC|RCLlH1y9kLo64^Vo9+`)oh5D_A#(83D7q;vnhhk#yi}pT z=Oi_)KG`i=qTr*}R)75CH>bufGc{j*OW!VktJ_=STiCge$EBt-3a@zp=R!_vHHBo! zq^kC(vu9D?@85+ZI-#$HNg>%t;)79VYY9ck z1<&CwPjm;=ft4Pp9tuDSs;F^#3uYjA2MzL|@mg6qc*aU6G2|kIB1x>ImRRfAQ`5@_ z+gN~VW^%;M5H7GdN79CDDVLt4ZJ_-f7_j9LTLxB1TmdCTjRYQc#zBcDIp#V?b@3~j zQC>kH)r>ASG1vf2^FouR;%D&21y$}#R?p=RB6DnPFgymU82YAXEoW)NC2$+Xt`>tz z7*tK(1X02Gl$o|qv6Un8o_d)-jJETr?*m@6Ac(~>eTr7x5M9957z?_*ww{Xa1RxX! z1lnrN&Us)h0fKs4FnDhntx1YFo%`a~OgwmH8<1)bZDW9OjC!1PyPG-9uLY8?0uE?=pO&s*UcLahLNN2Ei$d9~_=&Tk0)DtleXs{zwj1bz@ z&4@(E7fgH9Cp6$DpIp|mBslDA%yQ0BC~kNPn_t{xVqmc4G>Qt=B%-W{qt0X;a}HzW zvve(bSe*c{fmvq-)0@^1eF=96eQ04*yjm^xm3lt6znit_MV!9O$?O;u5$JL*)q7Hw zg!RbPjNy-5$BWH_fh!7>DQud><58I;(RYuX9&*d})ANYE5K^bWWF6NU=fL-o{su%> zmqj1Y5Mr?F!$N=&OGgKD?u-H_kTK;QW5klwS)Bri3#`|n-(qHb*nC#vl7$(}q29F# z2~1Fi8xvttg=Q;xnFD>-$tle*iOFLuL>eb{ocM^oBb%4D-Z-d0*zlK~l)O696T{L( zYD*gGx|(_%QKnQTJ8carzo+z32AXFEz;Huk!`taG)g$?vfzwxs%t+MmTl}YwsCdSK zUNMqDTQSbnRtC*yOHBKTmcb^oG|8zW zAfaX{!OKk}$sBTh5Q6iR3#&{o^rvtIP|z9!edjPp5F^B!g0VC?fYpWNbcEov;#F8x zFv^X`#b2;LHSaA7%V*ISQVRc7`M)w2@@D`^ExeLR!HOu>o?AByD^`{N`yk&ppq z{+4X?%<3v5w8-r-r^3ciZT+U`kz#3_=DwMWDI)?gh5U!wAv{tS-mywrqPEaorJYgi zaf-a@9KRi6;->dL7ksCxbSeFS=xzi?<6$#0;LZ6UMJ{on|?wuztWIRqtzRp%jK3O#X2Z1C93Bogse z{>)7H2fK$RN}epnuR@-qcM@OCtWyl|{rwf27%$3WvJVHlU!>rn5n31Dp)4yGl_7(w zl`vZDx8%t_=EyUaTo%Lr-l_OCm%j@T?ZT-WnX(vcEW!O&pCN(7G*K(_QJ%`?U8m(9 z$&jGDOHlGa$uVosFrHzbHG%OWIobB`)>8LdI~&P7)EJbz#-(GC;e}OPorq+b07s@o`KL z1R>ntZTPLvZ7LM&#$d0_XitBw6ovlpB>0AWcUBtM|}7>Y$&j$7!QnLCaD(apAJ z5$3KFdkEJ$T!{Eep)yBfUzq5@Fpw%a(#q}QMcNBrFrBr~)_j3U!P=L?JoGG|MJWu8 zmC84kqGEooN>1c^XY~4~rYQ`dQoLB%>_Y#8ohq?t2`$@+tpJ-Yp`<&p7K1Q7ljkVo z&6UFF=nUD0EMe_QAej@1uqCTVM=*rJDeG)cshtoeUu~4bCr(w`feH5SCW%fR9WJRm zagw`uUz4ettSiZhqzlu}D(oKAyi(q&J_`WNu?Q8ASN4I9eSB--~oCb#mI!c&eNras<7um z!%{xiScVG(4-C)%;}S5s08QMA&8<#V5jZQXc1M8cpBv2mj$=DwL$e)@2%b{M2ei6k zSGnd9)DQ6YKkDcS?hKSk(zOZ&>lNfgsWX-(#kN>vxP& zfx&QUf3CARQ{~|2uvqp-@L(mRT)HB9D108AHm~=XDx&4-*3m z-qfaFHub>`+Sf2P^Iv5jpcy?CJ`BAZJ?R;$BlpX*XPI6$lT2SeZUkoy61bS?AR;A`|r;JdaJ&3Uml0e0p5(fSv(oo&$tz( zv)fBxPVP;g%6zUxKbW(YC6S{$kEh3{8eh!cntanUouxaJ6{p{Qr~Q3ZuWfrVVupa3 zpTj&Y7Tl8r+FDsTvBvSID}6@~U&i;9Zvf9XCsredOC678tSI+G?Mqd53t(~a ze!dJWqjCJ~NZ-+YEho`Q8g66Kb!8@I^l4%DdR5}X?&3M`@sj`b;X3qso6V0_J2Gnp zjQyJ~`xQj{fy#f=g6z7gR7P7Yb9cx3_VWdIqXlLIHDTmBb`{Nvqy;YK!Qth^F> zX%g-F`^?aD!l&x)9_t|A6-XVx;Jd&aU#D0S`(A~xQ#tK z3xT{;jjVC}ZM+p1+p2hK8-P~3%i{~puG$Xj;r5aP$mr9XIr-o>YF3h-fh99bTyM=p z)}~_ke!Gh`qs#ezc$!|ROn#BQdP4Z8`zOoL;p(})7>9?3S>laV8r!o{JE_|gttb1B zXSX_0+^o2mEBCU)>-#cUxh+POOq7hvJ|RECxoNB<(gY=ikc~D`4XEGJ$IIHv2=iY-f-^$kvzw#HTec91;63t7{(z2GubZJm(mQ5|Xb1$%At34pxu z_(-^Dz4rKe387?PvfEY_A?2|y=jO_qoAH(Q`jGI7z`W`Ds_f=(cNOvaNNqVCvZyY4 zK5Z=Z>YN3|KUHn72griu?Y&9P{Yd+{Li|$wj8eIxXi?=p2zO-wR4k)xtd=)~~~lG>T5QZx{A6HH~ctw{3^9mKrF? zyWwUlE}h0UX66G0to^`L@y*51oilG zEd8x;=S@7jFEtVX8OCK?agMt2hz0#*;PH%Z>b0Y`pmztldYD)7qwJA3WybB&{L}d9 zTHe{au|VZ`9!#B>`^=R7V*Oc#x7GH)^;0WH2aY4S3-b6q*vY&qA6VC$;GUT|SM;gZ2k#B3wmR<(g_vj8mg}N4 zPv1c6QmeR94b%KDl=Hqm^Iul}B;z1*PR*6=!S&m*=$&p6dI{LJ3mnR{xGQK~-mbcc zJoZc~gVk4pEn0dn3j)n_oaLFqon3xhwR9ft08R}=UcarOoLrT>R6RP^P0>T&zWb0+ z|KewFx~(tZ7<;%&jFr2u=OY71h-FV{6c~Z+LC+AE(*;j(i~g5a|KLtgAG{aLC10sa z4C2T#)#}l$e|eFOfBEk#)%V73IPVl&^OPWoW zyki9}cF5_lXqf ze3+05GFCy~UD=+FL=Yi<+Ow_9R3unEHR^E08uBI~S<6sG8LEmf^@Uc7u&%H$%)HBS zAg6+q@eB_uAk32xaLqu88GevBii3d0VE8lI>B2ykAuPxoi8@cYA>4TepIsp39Em$m z^)9UV6bW>&w_pd2XogoqaB#oEBHh)~E-J3urg(G}NhOn#SflW8G?`3b7o%fzwEfc? zl?azx^XK7hn`In7+d+nbyi|J;`i80o1ALc6ErkGyvqqzy>IEJ5r0=dNfG>@KxChe2 q*4W9}(Zs;!zmc7xC8U$Hfupm#qlqabBO?nF8v`T>iHMviW6AUY delta 47753 zcmV((K;XaXy8Oue*nDZ?0Znb2TFv8EnYx=6QEoMI#l3w-{a zYnEB}p~x1+HY}QQQ?848{Tv>P#iH78bE>m8Y}^BDzql)lCajiqc^}_aj`A_5DzlNS zEjKnN*(-Q5ChI;aY19_nIgopsI}!jRx5m;+8| zP(J6(WH&1>fYN^;h%#@-X16YzmG>FEc`S>tXje8kOR%A{h@uE93Q{_!JBR0jWXt!P z{dKP7X-5-`5vRQS_GwivoMTo&mrl1LJj(f#ds#TIJ%=~_`~3Q@1iu$e$~vu) z#IpOm*gA(Ya>|d)Af?1PVHZhqNd}4Ef@Uil)?53jjp8BEn%3@6^a&VA;lzwmq|bOR zGW%&4REKrDiknSav~l_99ByMA;JMR~>rte+MhuQ@RPh6*IFKAYt&R~dvq0cWczr-^$wlDgM*Q?zyY z$%lVmLUFS}%eLCh*A_}|N(NLQeZY8=(iWnx)kVtc37@g922s`r+ZQ*d+$uV?DFCiF z@gWVO3M0k(TzHd6PmPGC=hJhFV=>0<$_07f1RV|$ms#vRV0Y!pohz@8gM?_^ZY;8l zftFCyN9oudx+c`1n8u7o^I^-CHXC32V1<9zRoLm;E0x762JKZSU_>J0F>xU6U9~;* zSKHF{RpDDO0wBRzi**!@87Kz?2mN3NPAmM<1IZ4W3+3u@*bfB}_Jb3kLc87rO0;`? z4m8n5Ac|b*!A8fTj;xDyZHs06$TeU47FsXw%AswsUGWVc<|ms7@crRno$bE_2h@M; zQ+sLa@-Y`s!rQX)KJ%h{FN#Ix8ccV-7B*esu|yj82mfs{JE^(|JUJVccjxXDn1QjT zKTz+IXswL8=s1k)rOOb4T|b(;Z0ueB96eIUt#WBYVmZ3DYfRzArgM~k>QaFZT2Ve} zx%%9ozC+wJE^F5zg+sfp0nx(wd=-Bh;?U)~HI8!$d~1uQ^k)^;yY>EI?lXqsn1!$# zLcHDwX*j#DVNUAg#t*xu*b_9+-IZ13?@uKBK9oHGz*Fd-r;|p1xIbXVw|+2zGhN$e zziv|jm9Qkxo^yk=AzxF3Cv757jk?5eV(qxE>)BpYwNWYI7dspN=?GI3nAMw~!N-A@fHUHXWCIr|_A zIN<~*Xk-ZHAe1TH6Ou^C;eZ*XWDFfJgvQU9$kAuQ)ekpU|GRSF0l}G3fH5rLGsdBn z;IqZ%>h>d^E#W0N(xbzZC*6NIT{(7ku4lhp{qyRryBQd11|`>}fuOKO#UQ}P*&=)& ztYq|ka++{$W{+{-C3BN#;#*z)l2(_FTHR4(eWyDg$AqRQAINR2hvEA%B@~)oF-R4G zQ_LWrh8^3ky526gf@)IrUY;0r+jf54CzL7fEjQostP zZNZ1NO#2$=7%(z|z@vYw66s2dL{gfI3XuGK0pb@FAT=#ODU}AY{&ML051oK#dT_p^&aaM#TDl;+) zFHB`_XLM*XATcvGIXMb1Ol59obZ9dmFbXeBWo~D5Xdp2(IWRPrp^gD4fA$4Xo!QcW z3*#OvxNh7Xf(LiE;LgTjV6?h@QJNYDU*;Dq4r?t010oRc}<|5x2xRKfeS_gdYn zpde9HVGuF_83DyXwoVKzjLbX$5ji<27G?l5GaDl_Gb;iGg{p;z#IPH!?%L#H=Ge>spXK-$?Fz`_P#`M|@%$-~SHU}a|J{*NKZfd?RJ=we|4 zkYfZ$gKUA02oxe9J9h^QGjpf6JpcIwP#e<#Sh%@4>Hl&E2-yG~EQ}3p0dj^;=0Kab zjK+r602Pq21<=X;e?n06nL9bz@h~yDy1FtN+Bh}#n8gq(CE$JuhICe&F!NShTk0=F?U>YT zE$p3vQlkIZyonJ0$jpFF01jp@PBtzM0MH%)bTc+*`kg@4f87rFmy+eT_^k(TPdktu z!1S#Rptpr7@a+$Rr=y_@5a8tC4D|N=x8i>ZfrSNNVqxqAFanxc*dqLi{w4;R{>^Xq z?_l8u&}M!cKNbM<@1OsE>Ap>v3CPyk{g3%ySInfODx)T^N%v37|5XYLgWLd~3~a0b z238Jc01Goae;0uB?Zf+j<0u+h{8Puje5GtnL4e=Ee%JeUQ2(jf<)0y-{%1pI0RJ0I z9`rW4KmhfhN!MZKU^agH#q$4o-v4s>|2O8pqx`>4`v0v++}YatFFp0&2LC^LLmLZg z_kS$jM%UTtZ4Kl=Z_8l&e@)eafA6jw(8R*o=KpG?f1C{8)}{kOSlAhv+5eVX zIEq`i0ZkMwoQ%!?9-F`AYQGoG+QJs72y(Re{lvU^F*E-k-P@KKTfIFaj&HO1x607* zZRMQ)y2#%Qd|RsjtwYS#7-aH$`&c#hsXz1g9M6qP^34q#IKLvM9{`a@g*CXN3R_gg;0 zKlG+E`Y&<3Wq*6HZ2stf-vN`!AACz=0)w`X!b96mbY|ve-8bv9y>z^CksPs6ARNnWpKQ;W%ssJpnsLl z@^+Pu|H8L3a{7aB4sW~n@5X+MT>gu!Z<*XI{%GI4J^o|K*qd5mi0lMceO(Jt_<7be9)(9cN(k=<3)OKP6J|7`s)cQ*;$J+ zpT&Rnvxw_icFPOf-{q{#UwUpe5I4HB-!Kr1@0k%B#m&9mfX^g)-V%_`p|pbKtEUJP z@sv6YfGHA2qV~WGn3xTyP@s5G)%PtVf4Wj)l!&Pwc4{*k zR^8^f!lBCDu!#-ajM52DmCqoR;p@6bNN}w|T^kx1UP9|9?2Yu7b_v)%BM)&x6XP8w z5M_t0`LtAk{FGbja+rbcX(aJp@X%zSVwEQ4u3rAaeCy&+mxMa0htu33$ux@Pf5_vW z5Y280LpaSLuW%>ASO2os}X8p#i#%*0!cE|=)>|N#2X~S{6Hjfq)1>yk^=ae6GM+8OV zFt&%2R{h%S54$F+gorZ%E0fQwc)0S%`aTHi1Y<*RDf5qdIP`cvgvbEMe^4HoW6#QL&2w$E7{i`jbOl)LTj<%kVz z+Y@q0TMB|G=H3kNe^JN03&2ns4%|apf9YeM2@`xOT74J{7=>-VP$wlm#)a5w&d&V0W_Ym=(h_%6 zh^GlkDxx?wVZCT`jgs%EnwI={E$V%J2KOsFen2xBx%0TOj>S@|I?${P8K#@XsH-hY z`m>>zL6>=SsgW;Dud8O@sj)UCvt`m*y#^Sk`<)rW`!sW0m6qTFe@bXyZ*;pChN%P7 zIX!^knk_ZUsgPL-+S;{=cOp{x+THmZt z=wI28>!PM}Z!+`;=51qJ8Oo0O;w{~$sZJ=ec>eHzkB4EK7alX4BfjWqr21v7(-bCT z<2bL%GhBA+kTR^N2Vq1bn|pJlWbNVhq-ph|fdBi&twzR8e~_RT2h08OxE0wuC@<7$XHladu$`3C@50_GXwCG&y9a$|GKr=(gbPYV zd0Hdc9UGl5%dwHwGFd^db3L#fm7)hJRxP_dc+K@!({);1Ba@N=$mP+`SrqlESTp{6MYmAV+!^?i6g|=NGvAS^hADRoB?U zaQ%k;fAW?8l<>PldWVbquNreb+FnVSpLJe3R|}fquJ4=hKG)U5QulG*st$%ln=(~^Q(yT3v00W|=6uh* ze|#GsZN-#OO2USUeVcV$}_so8v+Th^plVh+D)KXRiD430S+)I}j zP@|i^wS(``=D#doO__|BBr&VTBG?qdf5^lQ!8R))cO+E^Y-W2R|!e(0(5rc$)a+NQYt5OU~PY|}Ipf1T&$ z)u@T~pR1b{sG+-c7_>;DaEWpbrTY*hX$TyYZsM8FEk)kkp34;k1t{0I}n+oIr&hT7V^1AP^4m za!zPwVAb84I$%>4yluj%BaayJR4oquDZab`^)F}aDwt4l7b6LMEmZCpTOqNGEzU%wh86CLsf57Ol0#^%3bSb7? z&H!2Y+;Vh{ycbyJ@9`yNJJz8Z8s%VZio96(Goma6Q$*Y@PpdH2HDGRKp3+YOKWA#3 z#rXrXuA_lJLc&$DS4MjxbsZLa?rJIZ{+V$7GXt7cXGdGkV2V}o`qg8H3{kaB&U}wn`*aUFe;hrzG7#QoMpPTJD!M1y&S&(j`Yap~Mq?>a=$Xq#$m8erZWfeD zmpm`&R=N)k%w$4Ym)&aTO)6$9u82elvR|V7kKEdr{#7qtfDG)(2h<*+)!UgN1B0zD zOCBaf2y8H|hFHJX7qt=!+J_JLIt!Q0!aM7Ui}8FT2iuBKf8=(MmQ{W|gZr+1PQi2* zWh)ldMbe*Va$25d0AJLK2S(2v_cYtHErY!a5OlseNs1i6o{roTr86Oju5SZ6M&Lay zfc=|D>5!Ft`8D`m2NTa;Ul~19jcY@#@0eo>!>CKK7JWtF(&$dU6SNZi)M|aPBL`5P zqZ*c?G?I&be@+mWjJ5%zS;bx{VuP-9T2uflxcfX1pOv&{mY%V;|OPS8;g`_4_`l`%d94&@L>;Wi{gEAqs$ zW>XwPb*b~mJ9=`%(?C4sU$qa8rb&&3MGHDMe#TZTf1oYzh1F}P@~gG zdXZ}T%Rb7GXN~uVQiYj=Gigu`Uvz#oe+~Hdy78zC1R1y_thYOuVA}~CP0Uo+WSP#2 zjAO#omCv=QL*Lki%v@T*6ap}h!Flv0f!aQoF5@8qnMd%E|ywt%FG5AZE0krh@#22f`&bBcL zG4mP9Jps(XU_jyfwQ78WT4uCf#25sF854HX`3@2whd2!q%p z-ga;zs6*9gW4W7StEQ#<=?iO8*T;$@88>^jf4<_iZ~9K9gjJdQaX-8!)#oX~mq8)kTGZWo5;^Mkx?)U);(&YR@cg~mM` z4IGWU<8q>YKKD7c3S#IdI(9Naq~>gjhjj;`C?tq|tw^;#iCi()kuWd-@BL^$2D!@*eQ$kU}e zgwHFwv+DC1!yMk7+30h%Y2Lap~FWk!jm= z6=r`j36wdW_dY20`yk}zQ8AYU1zNb>e|YD&!@(B0bDrts2ixbbbM+2t`OQSm3gR36mj&+k4(B~!d874p z6FVJzfTjS+#F}s>rzga|%e@aG<(v{`F>Pu0-|%@*?uGfe$**D0hYoSbGih5sf5cxu z44XTkT$2RC69X%G_ePQZrql-*%S?Q3C0>}t($>e}!HQM{S+<&squnfOBR+k$M~WY7 zt*J<=LY=eQH7k+_cXiiYozux$a%8o)Ie8JtVO%JdX@0oj^}N1TZDS8W4e81K8e1w~ za5{s!2GeDAxYlp7=GH4^F2+9;e^?q;tec?g08mZn@qX8SA{Fp>oXNV3TTS+^I20=V zZ4GjS%^g9cX^ee2;)K4nWy%72Xw}e6o&%u#RtT{wQH^VGXaE#PYv+hWaQ{xM_{Q3*)JV`)iSBZYe^)s^$~Gq!SJR}nsQMS5apxs8%;UYEy{c@I!W$0OQ_sf*_Ze+e}vYX2o2Vfp-R3dC3my# z9toDgg~iS!N9a}C(oL4jZ}0(c5E=qH-s#=@aW1P7B8!4O7(S!>fVoG>~f zUjBEPP!hjz8jz6)-`HI<}A8p`>FeNDl}ARDO%dOfCH8P#kM zr6VFa$%b-Gf7UUlj)ZwlOdoV95YepK|JX(qPj-S&QOJcT!hQp`n-IpyL+?M(J!- zJ5sh`AwkL=cfl{mSR2y;OfWFP5Ird%rkhx&NjyY1#N^9sx-l$T&gN6e3H>`IzAGFS z7e@uZwm?u!krR}5J$VNg#J6BypL znr$Z@f5z!ES2Yt1G!_u&HlOBJsVikOQa07iBFn*F9LD*X>QK5VS;SSn#dOa*+45IQ zRVWB3EMN2F=Yx7ZodEss^YWY3&lQc5n8J|gz~|#zud`< z=;P_ChNb&ZrMc7)J_;zgBUr8l|Hvs?Px9?We@ydYs5O>Fg$lZARE0vzJ@N1vMni+h zdc~K0zzgA=DXx;B)9M+`6^^P~jp#n$Z-t|!9P?M@tl;wT4UHp9n_3&}wod-aMU2@@ zTtD!o)m-|qrKC5Hpn%#k`qgNg7K`7@DGHz7cq)+@eSq1z<+Qf(yCdJHc2}^EVjt8i)pD>Pd(%0?8EkBgwF7QeK;j}afm z9bNabN-v`Z;*vArtVmaMNg%eaB@zu?_vR2V%Uy%W%w!s;c^Qb=-(~dvD zPn8`FvvP!)ckZ3Gdr2{JIQJSTDHh(&1<)9rm!~Qz4K?pmKf&IzCvxBF{vzSi$9j> zKSbA-MR0Gmhi??_X(sOzq{0mw`LIu-ez=A(9`_)I**qxKcKYFt{!vP`mpnB3W!ydU zXXr^HxMYf*McdBnCu8#*T^wu5U#t1zeak#;Ur`l`_Q}bHBj89xdCI^df6>5#DQF;I zF${4wGv(Y8pNEG?^<`5Z1PH#Gpwm9^gw8Ravg&fWQ6IIl+aXpfa&^)YFhaR-5au|J z8u4AnH0a7Ig)pDe-Zje{C(qNh2z~@IGAx2VPsi@Ph~QS^qClnO5Bgb;pq>s+>iFO) z(_xak^np@Di_;g)LRR5kf871=5Aya52?#kI>j!DDjL%Lmtyqxh3X2$fpU;Vgzm#X* zMU!C-31S%+%2ps*;9K_a%GU<&t%(SGQ5W=ltJ!FgYMqv4uc~7ndKm1aT*8kne8Di< zxfJc~Y(PVg^gUJ0Ve4*c#d{LjF9hS`M-pu`>-Ihu{31{xG1DFVe_BGeGu=3G^<7|8 z5~f3^YA5Qo)Nl0&e=;FU5%M)@g37!*#vc)3mW)B)`L0^@3<=(1|Jh?i{*@n1 z!R+9>h;{G*dXb1xJ_>g7+I30jt2wrNybZ*2$~fm$kkyaH`Bzp|MCgMX44a}d=kDar zFiXcpPl;5wS)w17f2`4vAe?PvR^sMovu4%r4Z918M-$gM4Yp&LLA7~Q{vg%#NeZE~ z$R3uRpDdU2*o`tmeg<1uYB2|A_ci4`p;zrEjcCI>oZuN>dybN?7Pgf18*;sqUfB*< z{Z&xhdc5PfwIMAfI4LLAdSrN0BL&UzlLiB?DY;7vHy48oPXOX7%meiQs-36=tHZ*a6>$YP-k_{%#0cLnwysUunYC z7lL;htw<~Sz8ul?UhYQW<)FEVV5{mxN{p~LO7Qx{_`8G_4Vk`zQ6maZZ!PZA$z~ke zM(lp&Fh4GtjP9}*EN4pU)?*jn4t0_jyYfyu%r#kUe^PrvIRR--{4iU_@x+37eg^iP zls*iX5?)}Kld#fU)OhCjH=&u1mjzDwNn%8)L8J}j2wr;~g@x`P7GRCzpK5Z*wZ@_8 z_nh*G@gV9=sBe8Lr-k9mJ9-oS{g-_#^Av7lK~JQTBzGe#OYB7m2W^!o0U+pxsv{vw z#t$pze|B&ONT-+hcp@K*ni$Y1E+N8A;ls=s^QhL?DN{LnAtiHO)Q zE~FfQRknkUcRN*X{O+t)YoVNX#dnFauR2}mf8!!|41hv?r*nU)&RcY3B6aYv{&ZJLm;EyVjJ7s(4!_tRK0f7S zf8ykrU|yWTZbT=A`3dyfa0nAx?+SCu4k)M{KM9c1SL>Z)@OkqnTK@cHX{Iv87FUCE zI;{n1SP*>Gt&I|24`w`$GuiDCS8hJ6?D9A_WQI!hS+Vp}^H%_95{_$Pk?QkvewMkw z8Ak7UlVtc*t9XdIK^(&83|vIjSRsa5f7%qm5pQLnpwavQlDy!#{fQ96!Poj#@UexJ zbVE*_>F`S<`o?av_L>zQG-)=J`{xqMNv)}Xg@CQx*J7(!A79=I^J|(M4$^t10w9sU zc{#-oa2G6J?Yl)htnCd=AKNJO5(YGDttAr@Ge^b)YFDFq$kh_H4(u#M;u`Qof0bzL zgB*^Y9Qq%M?cZlo7@BTHt?W})qUL|7LU%NMAjpBA6J?gM?nWqY?-X_FXjqKfB__pT zB(6#(&a*!`rNfSR8Ib?tq6;(@6RU`zG*tJGcio*ecH%N+!8aU`i8_EE+`w8-@8$|; zpoy-kZyHN}OqJMbmLM~%Ajl&Jf1!KHh#jN>GAE*KmZ~ZD;|q`yOd%FZpFU~$Gr`j_ z-iDhv)igpFU0ifcA;j5?%Jx-IZB!_HNpx`}`58+rPN+~E@U6wOCAwj)2UP|=A^)!Y zgP0L)L%TSLBt=4|yR@N!-@_V;r3E^j$!Pb=Rvqb;fbD%-&y*)P>rzS>f79y2SAjyw zwe_x7Wp??E5{aMiBchH7{lKC34Rfu*^r00M@GcUg4pikjcvPlkpOJd8?W^3pw$GuI zrnjVI_4T&oZa-|~HuCx|($+_o#yV2$#+MT)yvApRCF40ZobTz7nBT8+7>!=%)9aO# zVSLHvqaw3|d@`hGh)9u4e+g=BNmx>TyuQ2|pEvCBcV&|?i9zcFW{x8s1`m&m)xS3E zF!JFeK>5h{+9kKKFx1f}%;X-S9K_&ioqNr?7lKfqsJOrO-*j&IAZB$-!<-hRi8eV+ zTJF0LF?MFtC+JGcM=20XuI8m2)rTiGxz-1mY5kmBTVQ{EWrZ*DfBP}@8F%Phd%nlG zwFiNhWr$PBxAl9fH4S;!hT@Ka1jNm^Gs%c*RHHU@J%ZakX>*6bKpqvrgEDkYlC`DR zib?^&h`QsTdcCg=@mfc6+rV3a#u#J&R)a z#&zc$(jdyf6M5h7ud-zW1eOv<-IpZ{0_V-NT6ya0X_C#+f8D;5Pnept{nQNfun>uyyW(UW>krTNSEPMplKIGvj9rDSz?xMA3u=2a~3OT$xDkN5GA7GuaHLp{<=rgCD|B|hI!!FDpJce-&A8|EoVYF`;vpHU4 zF?W0-*S_FV63wCh^+Ql5>7l7*9_8|l6(Pj+)b+dKY zFzJPwf8+9xNskHvX=j0e`gxO!ch!RuX|^x{yNk29C`wV{#FUeR;ugGDS*)|Wko4*E zyu+Ibq@gJRWk05*Jbzs6yyP<`lUSAQHd^uSes)-cu^)^OP>=V0KJVB=U|Ms|;p!$d z?qT)p8EO)AW+H%_00xYKjH#_5a)-AtLEF!@f92B$2Wer`IfekCeZFZ}hBMGxJBX|0_9ZEP1sq_^WS9U@HKs>)Y_{C*~gA=uG;LpYmLJ+Ru(6YO03At zJhYPb^_zk=_QmH)>Z4Y{uu3@yYcM>mFTtlMSk?|?Xj*0BU)@l_;!hz`QJ$)%v5M{M ze@WzPehN>1m6xj(I=(zB0V0zKDYFYQ*p*~_de$Z7t5G3Op?E~Gw#q6NWUN&i?9{b8 zjgZ3YGe?oFBi&OG=*XD!ygD@#f2Xo}fE$VKp)9^2qH2;7;S!VT4VG5CO6fo!a=i@$ z696>fQPOr@le_$2;wW@)6?ftz29h>S3!=vmQ-w`6b@@@r@ zA7-XmDIpes(b5DUv~~}B57OZ!fsT~P+?#OPgEMme94MEeF$V!Bs!%PImg zx^7UXkhFqnj)Xj(5Y^72BtWS$u}&8hUd$KZyzIFfZX9{_)`Gkq?OieOil$d3e`RDV zGbll3uBv$*zDo(n{d{D=RZF><&k4Sc)zjgw&HAn4Kp*R?ow+xHxI-q%S$4RjJS5|n zTE)g?^cPBai#3d)n6G9eqcvo?{m$$NxZL`kUtMUm=}^}6cV!`;FkKnB4;N{@6;r3t z^9Lw;;g&(75U-_v=R$A?yspbkGSp!>6n(5>T;vH zXKyDdSP0fTQ%yS)T?k=J&kzO;$7(nXZT6oK@9s@-Hsd_<559~|HDgKVe@ETEZj_iR zc3HA}t*M%YH$iW#i}H>PFK~OAh;0h>yrym_q$9XNd<)rbSemUFXDr1MTHesr%yp0A zk6^&Mz><~A$9h>1taMNQHk#u6J@XMulplfW=n2so6Ncwr^1F#(()NK{?|eoz!h&_o zkqe*S9#YU?PY*?D3<+s}e{5Xnu+|-#k%ngu@S^C!9eKec-hkL zajADHC8-g)xDnS0&Cup4B~dl^&_mXeg;zc0xf#c^zaYCM%w4A_afcN7>n@>Gu%Si- zlXk4~qwvInFTVgIj6Ampps^va{kcChJoX*`5QOegf_sv5`laYTe-Pg?DR6%pYNGkk z;-)a9C6%2HjB&lf#REx$9FxRUVZOrT5NOR=qz>Fr~^9 ze_}JKC0Pbp&0O<4vdkW|4hsR-HYKbxU;g&ufZe6wGDchOmp%_ofnlpJ*^gA#;^mUK zXy1hqVW!1Z+Q(Hee8JGg3>hf(3#9DS4 zZy{fhXgy$~9k-4z`2-7DeUeLy^10KvS1JtvbeDOe>wYoxREj~MPFQ@X&d>D z$qXh*OJpM8f>!i+sPK+L4_lf{1SDNjsmCV+Z4Pt)v|-16*?d1n*jp0UjOv;i8N7mK%uJ}Cvtd#Xe>o6qdH5>8j* zjhMPW3NR2lf6e&3)}ff&^Fm$Oq|K^@=c7=k;J-kNa9NO+pT80Yx?;!H?~;3oNhH~@ zyIMibn_!9t!ExYVYC6pC3H0_;TAfqUu+KeXJ(ykFD@f3OH+`o+5b)5pNia%%ADYy1 z);j*m38xx?KuY*^PB|FUjk}Vebw%VycCNOI$hguVf1w>~nl?n$n$b`bO{2EJ@Vbef6lnR@C^G6CZ?uE#}jH;H^0 zq1B0_0l&;AJUI0OK_527G0RC5so#+ZUxB(HBttdhv9>fKM62wWuv) zDt9pFH}3S+*2`)nswbwt=(`CU=RtZY|B$HdfAKzy5&K@gOUMdp4eHlf)j)OsNkJb5 zMt@W8?!Mq`my)56?pJ6Dbmtu?6edCU1~^9*l=#~i4BlpfGz)eKkpjs}IZj&`6JL7Xn2~u#wSUR7;#=5E7gP9zAKBt~|26pg4cJ2A*xAuyZ$wF~O^ zH~j>cC%z*ZPB}5_AubmKGNQK7^yv?S#1J*gUfWOvqn2qXf5|Q>-;*3Lc3D`OKsdC4 zKd0We^=B$LTd{)Nj(A)_Q6e@RuN;?6>HqW%%-aab-fMa5Qm#O3nWmRsPA~d}e_Ko% zd>=x z+a7P)ScWFc=%?`*WXX%$Al+W`e}nNWPE-huHNg>3j22wjKQ3b71jr&IJ!{;L^C5=} z!|zCj>M|7a4T!|DMlpqHJagb7|71Vh9SEuf_1m;gHKKE2?abv7Yf=1qS6`s2d5^3Z z`BQ*xJA{LADsIbqmu)@Jb_quBC9WLH7r}A+Q-RW&#s08zfi6AAsC_Jue`L?aZ+op4 zMo!&Z94={aqkvHqO_E1z5QGg}G^RA>za6oSTqR;9>FQR8K(2Ua430zLYnni47OI-+ z{wv0s;t=dL{xES%S9erf5^dOtjqckZCQ^%?K~!{uObq-gI3Ah4aDiI=@Z1^Fbq8E7 zuAwk)z`c?i%q-SIaj#a?^&{wpE_RW zjxl2#Rh+ocL1M8P#3j*@b{Y{-B9M{nt4yme+%t1Hxy;k}az=#|vvL?X3~(u09jUmO zx3@Q6Wb%Vuh(VN2#`Ix&r!0ixh)AxI3NBtuJzjmtUiYAeW2Iu1e`NH?p+;s|qZNtC zz0r1(1W+o+sxPK~DCPyV)WVEzE|+Kb4!O}*&k>yiN^h^& zv6w!-Q2~8+W_`?IN{P&$ z=jXy;r|W7vgbWLu-?!{`E}>F^Gw4G+v8Hbf8Y$TQJkKq7KWpFQooEv&4cMm84A1;3 zzd1NgxpMY+5%d#oxCHfzp>KZKglViKk(`$hiATqRs(4!cy1o{Py-ktWWA(i} z%JWCd!Rd_Nf65VEhTJ(V@J;R(F|>jp!UXE?=vbg2XEat4!TO~R!y#QujjB@~kc02W@uYEXtWD!29!(M@gWYXMtF3|_3!$!@Ve>84mcX&Q=M+exU=L;*68ld%# z`eRd{1W`#t{sMR_Nj3Ba?aF8zLa2U})xxHrQ&&c21M@;3trtynKBwXP;!yBC73>$x zLFLe9OWb_`rjY(t8EK%5btD#MP*)&f0K@8-yrCU|m)3B9gEZLgiD$mRlzp>|p9myb zs{0v7f5MDgq%^|Jo#t(ld4tieSOJb|&W%nKiE^W@yq5OdguU$h*42~-**J%1ZGqCo z({uNRZrH`kLRb4ki)?Yh4)|k<3>@@OdgU}R1NN@I!PS)O(wU}Nq ze<+M=OW}oRIRsSNBg-htuJ@YFtUY?hB;fGSgJ4da(E~<@T1ulH4hbzY+4CG|i%)x+kUa_K#kl4+^(TI2A0i)fv zssXgnFn#q=)ePJi5gd>JF$4#c%5Iadf7edn*F_JzXl+sxtiY9%p-nXu=_N8Djgtj` zBXp(tT0gpO)zgH9K}zXw;p*0LH1l3afad8$Wn7c{)35^`&vbqZ=5p*N_*SI07+N_9 zG4|GN5F)8_^2BdUO)%D3CnCHOp=GxVIXUodLH^@8-Fof5m#YfxiAvqZOL8r>e`f~0 z!@wAyg$CTs@AdCw-JgoR=Nr}0jdGn8tSRVmc05L50nJHh&~W*`>&Rs-BR zG-K&3qw`%1JaGs0@G1Z43j>v6xbMTqZ*BV8NW$t;c~GmP<~E{;z~S`32pr1?V*0Oe=ZF4L-}lN zG3%eb`U5G|n*Z{35o}5t7hlDX!OdifF|T-T$81{K{Rif$| z+raGXE5G{7^Arma?rQEae@dRcPfa;H3gPlX>r}1)t==0$nX=m%wM;)|)YY0#AklC-;xuXO;3M)i3r?!d_bHkG zSb^d7v;`JtI95X2YpRdL-9*Ugm?!_>FN&qV;kVETV#pIUX|j@ve`u272``4KQ15ef z*dUU#cLzae7yiJCn!2O9pi+4Bl*%o$XozUCn|9AZ-mXO1_C5^hpdF9ZnqxmFYvN{W#3h=JB&%; zY-*s&5(D-8c7}AANI6v^sTUkNsJtIX>jg8^@l$Y($+Y}Cf8t~pB$w&as8E{2CSGzQ zTN&Ug5PsdRuNT?|bkBvo?oULY<-JL%QGn!d9 zoR$Fl3B$B$e+_%k`g_|5OTjU-OyYA(hrRkQQ zo;NH5=wlo`k2Wy!K%0H0(9zuD;EUrQzoWm4it_8He@{SZn(k2FS@R~HG?LN@4%@-$ zqL)TM*~G@1*my==Lr#cpveuJ1z)cy5@{n=CkBXM8ELB5r=7nHnou;gJZknrQc>RdC zKl)i;eYBdlh^(^F4%K=%e}2vdrSzQ+L7^)GzfsL9>74Y<_u}LeE&91YcLp(vbN(BlvkHZv z>zY!sxI|4Z(gQz+(VQzv*r0cMOK}OdT$AzEu-x0mH_Ejt&hjBrky3}G@2F28$*M>6 z-pM(Zed;w8VGq@9XxOhQJdPVdTk<~t@lX+kZwN>!LVrAwQH)uTIiC|;i>iBXXQ(p^UW;jSpJDg;B6=;P^uaiFHm_e&zf*}@B0HdW?WN)8$gU1sOVjGurC?eDvX(VR-(HudV1UeBWIri#9EnbuS zx(7Z_Rew!tK9kHoj!#bWtvzh^V_^I1=@&b7JQ}jPXz!L{MQKL8x{-Z}J1|Ft;=+mL zj6;YQlQYVNjBnQc)eSC|R)e;I8=4X>V@6YUSE1M=;Ww-yIfqtrs(r4NyV9&cDN8f3 z`IoQWedwFq)XFD<``pd~>m6R>mHJS{kK0WtFn@Nzuq&ZI-Ax_3QCXgFOvx~t6L*5p zi0i1Ou@SPIpv3#8(QccFg0~j+p&Ver(JHb?Yc@POu7({#-~;SY#wwNME@+}ue$gQW zE{0LgKGTAMCvBc;nS3#T>V|??;3N#ts+y74$yO+GMzbyb0Bf0kJY+-7vT&~(!hXK5 zG=C$gNeZ?uPi%>|EavG-TP#(TdSuR!yUX0NKy?_s-kR4|=A@~bhFLg*2goPbu{)Mn z8pttQ<&ocbf05lPU_1Feb`dB=_KN5CdFvRX1L(WZL?>bO4IV8 zRXl9|PO`{&cgM5LaETLdm^yXPIkQ$E*E$Dg^my$1GGlE(?_QR$>mZn^Hv1Gi>w2Z|f6XbDl@oxP_~3Ili*oh_Whwu~BwcV%BIUcI2GoMn(x<6nD(u`T65c3kvyr%B9uG1&3NK7$ zZfA68G9WoMGnaw20u}@?HZV1pp^gD4f42otoaquSOpriu3l16FVUWRtySoJ&V1U5} z7~I`0L4!L45+GP05Zv7@K=2?58r&|~-E(&L{D0NGHC4>_bU)p1cfU`6HPBP5Yq3jM z!ptGEFh^H*E)Jj&KuSeLK>z>*@^Aow-01Z5+E7<}$X{l3dR>SM913$3`UgSEe+2?| zeY8n~T_1TWFh_u*n>~Pw2f)QA#KkWJ1Om8$K*9eIVJ<=dX|Oxg5}?8XP=q-`;OO*H zFefh;sI`sj<1znv1Ta}J1GoeQ`Pu#m2S_+TT%Z;UJ0f4NwTGP40ZpsqFmO$Z#~;tsI{{B9Va3U+|}*%=2q zJwV$A3jfot1+#MX0J}f{j|O|F1;i2l7~$q<32^~D9uCk_PzIf7AUH{W}rV@sD7zg$2yP3GCV|q4~IR* zgWbVUd$9Q<;g8C}09gqQ0Qj-NzuJRaxImp;;T&+N{qGhzf2VnzvW%mp6wJW^;^+!T z|6QLn)CFSkICd}2KX2B~5$56O^B1s!I$B!&Zo<;diBrcB>g)zlkp7GEXhQ$nW({!# zfPe!0JOVrbh%*4=UlmlNa9ya0A?5D>t{f5im^@IOBI{X301 z82VQkz`tV^9Iar0NB$q>KF;YsCA{^9z6 z*7_eI|9=wyo#p?g^8YPJ*3I7j4>!{v{{N2~>;Sd*`it1^ABkQI5`|)u8$#r$DaKFe^xLT^xxMkzzyKk{B8OZ z@d7xt|3(4;PW}HPL4E)y_;2*+GygC8-3h1V-|#VwCB)wKZ#vgwFyx;Y$OGWC{s#mB zIHCW5d;m_{f569RyT9S1OgSC@0Uyb(f5XSZ9wqkAvwoZ0|AyR;;hulMe@)WD&Bf($ z)PF3%Dn8u?5stla@mD$E?E=XHdRUI%bb1({f$Qz?rPs){}Ns|Wk*bqqI>Yx z5nZ?|o{Vrmg)}c}mF`jj_HAyd`+f$#kGULy6p@xnKD8zZdcRaba?>G+(Jd{izHL^N zO%nP(e+kZ)f{gFQHn707D;`j1h(KEIG);tcw2!68vaDucYtvlB;3V}diHJGq;J-8P#9CWhkq zM#Qgje5$C~4N@TnnK{N;38vBrfyFYPD%I%M{ymt}sAnIj2nAojv0uvPSW-Isn6Hb! z*uXak%taWcb%CrV$)F`%zMy0AcAQ~<-_<pNi+3cOwhsB`hM{PPsnre_|JyMik9*ZE41rySrJU(tu~At|J&aCA9a4 z0wcsBY?X^QkS_&0a_j)+SuUvuUfLbO^_d1q|FrVt9qAYabF}-jr=}QuZ1FFJmttUS zxVJS4RH+0Z%Of9I9M zH-zgbBH%YoH|j!}bvNeXIfxFl2#lA+8>dTFV|6hfXds(sAZq3lC<#F-nW9kE5swEQ z?h55~F*ZCRWqW(?J2t&&`cMrWm?wA z8xE{aLVI!4@t*C{4r;hMw|{aIf3*Oz(hXYV3jLhnr5)zcWVP{s;`M|F^s(}8otIlF z^j$+p-MPco-m;!I2YG?@7PW1h1TtB^@6?!kykHsx583&AXt~!*_LXzz0#0vd8lt^z z82aw{Rw+VK);2`~v+d;D5;&5meQ7m$St@r;x%KynbQCA;?KW{V6;7X5f6e9xN?fXX zId@+u$*)c3TnPfDODPBFzMcrLb;q)?-GzPFYmhY10P&y}$TE>8$Sh$5Q3(KUN}mq(Ua{FFyQ{&w zxO!YAw{9JJ#Kq@j0nH$Bf73BZa5~E&%CwKpo0f#k5PbH&#$`mgg76Bi4rTHvkWRZS zaQ9|1RCG^8lNj^K9L_iwv!!#+1(;1_F8GCJYRY7%WT`>Gf@ywDYTl=&=}Ru*0^N55 zde5&}jP>7%-C&7bpwS>G88$|Sgd^CBYX~rgKvtSv*Y%t0gLWE4f0l@_=dV8Rr`T=d z`kW8I*$okM^BtU>!(6%*@Ew+?oe^9)1;M%Ds)R95tt|`>iKb;EtSTv`eeKKkloJiE zIwWl`tUp|bRcDs^nN=MHZ)8>5&=F^B(`6)R%lEM3Gm3Oso672Y3ps3F3}4)|(I&jg zCKdYRkN(oAOy+#^e{8D4ybl!x2X%j;e9eP&xh~%8H2;o%{4KSQRk?oJ7NE1VFo;->(@-rRGxY-*=aFFKDla)RxF(0GSRW!e>C5Lgz#|(Q?gbGi8Y>L zRrT{QJZ!Qb$$Zg2;e6F{SLoi6>HSGu>9{r4igvI0E&%n{5-VIbQFz!7Sf-?rTV+Jj zwp3tu=?f?j2S zNQc(Ict3?Nvsqw|z1*7q{MEo_&G|`PE{9(Srw^HNQR1vUNoB(`;)zl`8X`IkcbUm4 z-7gfYy#~4BLq9tazxz?J(hFWq-Ra-~Pe^;etvsk$e?042?`{tL!ew$-g*k^eZCOEK zK;p|7l5`bPA#(f6056wF23M^}M1q|Txh9cuU^%t}SIvm1?5b5#K?->@IH20sBUWIo zRwr|+J@2$gQ~aYihh(l_8FFzfUqMJvF!x}gcBooe&pmlC>8E2Xd|Oaf{31W$ma#lDVWbb3dfsmh|%<*%bUfaUO zp90?hN-9G^bC~2)blo81tp2>^C|@OGs>z9H4C3qa*P5&CZn|@xv?p1jUJfyzXEPaA zpPqSsewuq2lZ=v>MfD5KD=*ycs-g8^+Rjscf0CcaG-iK3YNp-CrDqu6;QWA^_O`trS!CyK)amYe7n0nVY>_`ZZ?Y|IZ7h`Uq=`VfyNl-Vr?Jxjtl4`+u^#$sJ~Z~fAhNeyAoozj0)16z~tJN>)Gs3B-1TIt_IHw zJHs-JXX%kEnS1%XHM!$ZQ$eCJDh98@Ncf<=#Pnbq4@=}aqPV9Wn>eDcXZz+7XI|*S z#MEHw9JAW2h(uT?DW3i>-5K3jWTCKddt=*9UVBYD{A(P~Am_xKBBR|qTzl5Je-JhD zmTNKDWP^4@u-?dlyhBL#UVe>{ea`GNeo>2eEH}~+nPMv6XI8h>c~9irvH1v$P(mZd zu{(4G_G!L!XOB}kaGeE!cYt>`Um*z+pRA<%XIK%l4hs@Nt3QVNK&W}J-7eMER1f?S zlNh_K79oOfa#%MaT3WR79{KKke|_jfeW*2`>i}F4Xh9gUhb?h(7{`!h+L7RWHh{v5 zPSfGn_tWN8d>tqxJydskbBI_ut>$4$UC*;N?JBN+h5Vw82&>0Ozj@+%wKjaXy=qoF ze|JH3O#qK?D7E5u>&L^`Uh?Tff49nLONoE@ zNg<;3^tnZLy2egf-R>)nwL~Ef8q)Wn&9%jz=oHa*hONIouFlibBM_L%Iw_W_zbr>; z>bI}JiC79+-Dh0vCAEBw$NKG6ZCL4Dd5DnkDMHVXnA&G=&^F-(uG%;=T%M#CQ)AqT zXzS^{$wl`k$5G{4YJ}o^e@l`MZwirQo)?|*^A`LeN3GxKvC*ZpUPT=*R5+4K?>{?< zx#8xYXW)KMR(Pd^zQnj~p=q;|_*NN2YfX5}*9oy_Zg~ z5*95Fg@rvISN^S2THlE&xE@yp9k$@P#7a9uNv6Z z-@v4?L*q?-ZMAm3UfhHS50GwGXeFJ@2GD*fPC4epD_5&o3K>i^6R6W6QCdrPf*6le6S`$ymgm(`Ww47=>Osrsr?anyja57 z2&P3K&%ugpizYqrGxodw z^-C94f0JDqd{6_;p_2v8%?6IT9nQ#&!NYm0)cPT$39n#3N019WZcPsWG!^2jn-c`a z6F7N_ym=9OlP+2^A4f1*5h~g0@qwu$g6~UGrSxi*4liPUGfYvnKDu z*kS{6FIH4wBu*tDn?8stRIA_OCvdGV{vL*`0LAygXFzxfpfUmep>_Msi85h zglFxbhvDp=ExBBMj+#PmIDd2r+c0PgwtfEYTieG@kx4u85_-6Tk(rrXI?WBRWeO>rhpnPa`(ZozQlOwL+z;)MjaHYwEI z+EZTEn5VIXT84qnM^0uFm86A7LDBZom8;2 zNFV+CSRe0VXwEOeOH0)Oah^;gK|R-;gp8_LZRHERfFpXLpPNLJnI!XtG4H1;cPPZAa`T=*s(5Rw{CkIw;q!pqs*!T!qo#L3h$t#)0jZPi9lp6V6&Fa3auy0*!mNyfr;DyHTEmSmMg=I%gfsD9_|8;4&r5hlZ2u9R4Sb;0VK;7%77We+yCxN3R!eW)LFLt%?yjJ8}5%)XvYnl3!0mg=lXK3#R+V-59IQ zqV$<1+kV(xsO7?Cjf}|9dmh4QS)!V;vCzd7TWbHUhpW6&a$r%K#Kd^5u*DnggtbGN zx0)+0yZ~S0tq#63dMs7>8KGQ8k|YUL%LCR@lCA_}{(;t6f9b9B6kZCZt^3wxM+kE~ zQ7u02LG>~A6!v&b3n>P~cZLGm(?)J@=7tx-8MB>?0&8{?HJz{3Mr1b8LYZKv3Ul=E zyJN$MG*oSrc|I=n!Jch*GoTZ)x8RGx<-_zU=KF8+(m) zmekd&Z&cbp>$R#e+5p=9QEqzY#Gnc4jM7q^H34Lde{N2Ha`}~_-?r^GM;cuazk-$Z zW+S_RIS0Qtnd?29WGVjvj$G(RwHfI?92vmYs9o#mkWuZhT3CPSi2-S>_@#|wdWsOs zap`tlw77;?MoLJ%x(tbQpw_8TRm}CfJ;3sO-ezubb!e4TEy?w1*r|$*hDK8Eq^HVQ z+FNP&e|h8G*yg;s^XtmVl8QCOa+W6T^#a-@n$t;}ujFBK$51^}5W(Qv6fzR9(uj6h zIoT=Q9Bl+bL=y+f-T@$}H|+?+011rZ@IA2WC1T>3)rsCZZ8s4?!mewtErYjxn8K>Q zIH_x9P|vr<)rRB%vY={~>%)UDh>W6UE}fkEe^itixb?bBKat?Da-=Z1&`!-_gs|gw zv>6CvUFZ6BUJ+YPx-(xqLQ@se+QcpE;)o0p;O`T*;t^ev&LB(dQ*o=Qh=}+guZ}!*NDA ze`XRN>`?o(#B3Yo*Hh<(ShX;vKM5JL$`@<*fQSh@W2~OPHquQHG8(l0a0cu@tbDf) zNLHAvarHy*s)I>)+2NePA4FNF2Z*S;rRVPimaakH{8H@KVt)o}v56lR7;$u*>*uX3 z_wNbqjtS#OW;BdotoYGB^G*}C6nnX|f9s+ziIZ8-tL~P8!QH(|W_kUh=Uv{`dS!QE zfp$GwrxD7UMODpd*(h~sQ5qed3&AIK_DXN&LjTc-m#)h)FhH$Iaj+^snP!{c%?d{0?H_6n*nD6drfagl<6jL<)e>NZn7%99C?3c9*>)k=dm^TT}85l&`ku6bX7HB5pbUe z04j4HlmhQ(`lmd|h=B#brbvgV<0>&i9J{;L=wA7XiT!V%m1BzYP-Io!#w1|`yVV7W zYPd;O>}pOJBpNG3u{!C;`O}R@f4Enaiu-mZ&36)HJY%PEiew4H+;GOgi|#LUA`|xg zXzkPRet|*ed+9Jmw!%q0$u3$ZmQ<#bW%+6z4ZO(vfp{@kJSq~e{HSKK?PjoGh0(W{ zKLIgZh|ggBHi{fr&O?U*sgbwBFI`?UToZE{5nx^)vY1X@6h3S%J8dJnf1STo8c`cN zfPSkU4Ck=fh5C2hz0v%#iAiR6mu~@UOTIZ!ETz$JL6`Op9ZPcl3KGtOokoSzjHEFp z91Jxw^5c;@+8CU$;PweY@?!K6RyMG$V0JIi+&Pp&#X?$mOsss~E2t=f7?CM$3)D(g zy5)|{jf|5Pc=~7Ko~D{pf8G{!_2}Y2MRd>JKd;OKej7>j*IeAO49$Zv%e|k-v8T#h3(iIgk6;fz;Z;kQu%f2>bw!TDA|fh^il8UHp~dQ%TG zuE7HS1V=1jT0oGsQrb}X>Fe2NJF=~rR z0!)5P!V21(`>5&2sS+0iMwu6`i@%0+;* zcfj^q?U=rB)LlRECS_9&*Qg>4w-9wcw#pMbv$T8&N$H8&7?N}T{1lrGd+*Y8NFqd+ znUS1AcYPz4f2N9X0iWiy4^OKt&pbpLlb+9_lVSH57;GwZ?{3C3`y?%RhfwNvp4X!M z1wwpoH`*rNix(u*>N{eh*BQ2fS{(y|5Zcs5vE;xJJ79Orm31p0ON=+y$@WDf7h+Df64*Wu!w|92 zq`ruQSa?|;Pp`ZkG?mA6T*Yuu&PqZ9=8&43YJ{#}9cOLbYcc&m6lGd|%3@B5P4vbm z?H5O!M6SpZso-UG=(jvNHH@>Zdi~}A3u6@9f3{6@xHpcWTIO(54YLM<2GYu#v2C2V_c>lwn&1Lv~K%hQLmc;-mB|LSQn z8-6NJ-9p>)bJ}JQz>c`UzaUc(m ze=*5%F7QnOBbQDUZgx_1vzkfZv_$mmXntwnd+TI;hm zY{vJ&i2U@zHC_}9<*I7fkOGzCTk{=0ERk#%;Hqie3EcA3u+z<)a&ast~`txDXf7)l!qK~I}@yL7#X~n%D>&?cumKGw7>X`&_O>+zL7p-m& z_WXU4ZK*%OK2JoWprg+aA~i7b$KUgH$>j)EJLc&Ckoz#W%G%)HJ*`kBQ4|xN(r6uR z)Kuo2D1qX>^C%wnmC$1F+B61M5hSG3jP0WOwXR^Nw3`Km`%hRS=)$;7!&Qim?c7m=r4}J$6hwAS+bK0c^|UQ0UIYPiQ~KTW>JvP zPD#n+ak5b?RRpy4|X?us2D-jd|49bLL)~Mqv5$t}p2Oe`mE-S``GD09Hb6LKz75 z+dtH3i$R5On1GC=YHI{-biD=4U4K~tb+x0!t z#4UP5S#Ivw#I@v_b=~-2HgWy zk|kwOyf97Uf7>a(iqNKfhkBrA=Xv%Uh9dBSzP;nPn(?uGLlQT%QaCm+`d~HF6o<4L zKwnWAG}g-Dtwfl$f*S7E(w2k>7>I2+F1{xBqOwr#d)8$A!8a(7+Fj7_mt{v7Ma;|k zYkhF4@oM%<3jXKVM@fhHi#GUF9C5%Sa_qXGOp+$>e>Br8G=UHX{IX7W$X)k3+EBR}8pxS%IYFp`t4jLZ7N6coZTVi(yYq&a4} zFEv}Pf67^wcw)%9a7EK^;q&q``y1ad1{k#Ka_dmS4#W|{h-){q$a#h>6mB~+^kaB5 z=05v+I7c4b9SgkYJ>etVaOz8AO5Py#shR#OS1b^Vy~mrOa1!qNzlDJeRVe@k)2^jmS99N!fu>&s5%224p#>!BV^ zPc1#*E`v?YbCPN?Mq|pLQ>)lQg9{rze zx4EBxSLFB6h-ALT`PgA5w@Utu*e80T#9P$UF{4?`#q6M$RirOO7VT$yr1kqwP zG)yPGpgKLacrO9krw7gz6c<}9>lWn`e+1>9t+O3Xlk}BJ`Px_Rg`~tU26z-2V&^X2 z?FY`~<1&7sES8N-pR3p>m;go$3+Eu8`h3MT&R(+3{8s2+->i_x z@Qrt7jl%bc>(CY!n_zI~xI>GRZ3XwAwYT7%j4M)hFm0TryOY(g5|p0af3k*;f0c)Q zQuFJh$B#BS!3XdMSC9~SrRGWO(C zg^4DWwb;+p!pRKibY6X$0Vc448Jb-iRH<8HYLzqw>MFgH=lfd3Hdac}J1!N~)j807 z51y}kTtGIfiPtFM^T8M+33$SGe;=7|j)zi_KVBL`h%d)25ii&*_#ZN0IbZ>4ei{3L zoexjEY|S+(t$>7l(5{r2z>M|saJ7pGT-9}IoXDOVQw<}ZaMjqvfsT{hd< z3b)R`G*zj8j6{_dM`3<9A@`A=oU`5IIRvHmBYG#0|0d^2mL9QzIJ&%8gZPfOjd8+P z4QzYV&!uMlXa47}69nqvf45WH!nbZibvERKGDIi#q#taJ90r6VD#*|eg#y!uhs;7_ zHGY*JhzkzodsRB|Xu zB^~Tt)x8{ntcqS*bz~H!05npH8UQJvJO>VDAoecKwH#g|mYlKtV!XL{fiAQ5_&5#;h&|FtIlW z$V>lIZtv>C`wtpu=4|(`?ic{B|FdjO{%4u~&-!21+4DaZ69OwMz#L@e3NQs)g6t8P z|D~IZy@dnd`+vgbZjS#={X@v*AASIue>9{8m;){TLA%-7Dw@~<0W@L`c8+eYKxcr0 zgE`RI9-!)AXJUWZAu_n&&;KYILgqUH|vwqE~t%YWMV_lC@3+8Ux#BJ}?ofPbeY z?9Cj^LH3paHP?T%G;ucnU*O+qWfRbUrsuz8{yR+o*8hL!E10-CgFFFxEKL6z50-ze z|5^tB4<#z<;OWE2%FPL2WM^XmuyXwK;o)HO`~T22b8~hE+PnT+@PB&wumA5s0s=jO zW(aG`4rY9z)@jY*<^B?dvlYC1<<5ee;Svy_d%m>$FDBj+e^_JP@`w+ej)<*>8nv^t-=bfOog8J z)*yc5h3q0;Q{ov}6_f`#9{$j|WoKxzx^mz z;HD-i7?1W?flq@rW$GC3XZMsJ2`0KADiuprWccNugml2i`E13&*;+`Yf zEgy;G=NnAwQGZL!u2e33vkHK-Z7>3g-ZWiR_Mpbjwoxt-ql?Ih@L7?={*3r+HLfa) z;pFZN;({|n8AtbrTM`+RR@lboPhK~^Q)ho$*k>(iqxU7Ausshi|5IMr=f{}k20_t; z4t*BW3+90NY4JXe6dT$XH%-@Yz2@~N4hLs4)$=T>F${^((}pg4I4S{^eb z0UO#7P?9F8b)s($y<>OA-B9+nVjua9%^FOh+5sOGFC^B7#}pVX!N=4Yh)+GRy-I(q z67PmY@DzfdPYlaoX(gStexfZbk+TWZJ3;=qKyO4`Uk~u4w2AmT$%-D}86~-ys+1cb z=mx=;6xB29T;9}x(>L-dW<5kGiIu@zUfmYt?b`FnE&D0U9Z-^DU90xyfpnU(bk4Yb zjPiuo6}fl68-T0p`HjvHh2FZ5FgAZu>YJ}t(au;ao=H&~k7fNg#3>n4;9f7L+or$S zIGpLxP;ltD_2#EFryR`V(+~E|{46fIH1_WaE~dUz_?SduloVgTUhtj6G2GRB3PR)T zi7qTSll%5|bxM7zZF4PnLd^(^F9WBXt&@z$F{Q+h5Z3Dx^S~7YdvbHnsr!Fd)lmK# z3=)FzL0>{fTMSQgm;2SOT)R*=>*67!dD?pu$+S?i9_m=_^E-4VAuc-KQvGSignHVW zn!9LJnmt!%lfiP5<|+-1TkFdpDbF6-vpOTrEMPv%t@S8{{Rqe`aGzmCX7Kxl#MoO` zLi-mvf|c3&?xxq8ziv+_biRL1yt6a#reAJBw02F%BYU#T>;3rfr+R86u!6ju%UI`LTH<{5Yg-XejHxH=o@b%k+OSO}>AgadA0& z@|HoiNb_kzeYI{f&}t6fquG%WRhel5BdYLep_IPKXpiFCdHlwNVROk?V^9=>5}yQ!T)YLgdiFDh3VD998RH7KC8}*XKC*vgkP7C?5 z{Ubiz@shiM4AWF9m-4sRIy-df>2voDAie0ajPV;4l~_rdNc3*;XruA1@8XkCkdyyt z|BP?)CCyHRDA}}@gT7li$ZV;TFS_CJfw$jkXW~V^tU}`Yg+YJHoGhI_3GzfvOyY6f zjL3iNyO&fmx=*!6&BE2Fi*|Q;E==#W8#0*XwPvWr7$nNQLUJwL+Le}%;r zvQ8sID>AMn>UaL74EIXt?q-V&R{bONp4_byl)@PstrCe#+0Z342p>zQpLazUsIx7dm7wb3#Zeq(2BG@7 z6xy+36q|g|$iqRkc-m6`#*PXzZSM&FQ5{veFEunr8@vz4wT8U=B z13c8505c*k0CQ_Rl`di$iqsh4JIf?A5mR9Jlw67TX=||w@}Jp^*M8eM!xn!&47R{EQCV2%2-^x%*k)v+8W_Hz6@&4< z-Y@K3=%aIQwMVY+h8CVKZ`j^RPs+`=`Y=8H41kv&hq{KlaLp~>$eN#wNPpDybccCd z8PkkNmpl}H+gm=mWU!-mI{G8Nz?0Y#u+t^EM*4y*%0GvU%ACGMPiI&d`%UTXX^?-I zYD8L5@tWJVgI+Dwc@R7fz598TF^?8%T8XDsi6#jgmf1I9$eE-LIG3`Z(AM=!!?bNF z_$Hj1Jd#k8p*!}sneo*s2Ni>Y$qptlF)ywpwp3=gq4JsVs zzyO$?IR&u8EiXYBq`yGR||pTTJ2(k|@AYa^Spw$zd~fCsxpIanDO zp1|`985lv@n${MC&(fB(4tF?33n16y_<|pXxY#OL*h6_U+o}nXoU$+Np^iU56TKIh zHsd|OeZSukY8drD3S2(od*Od!6qjDCmLu`eWH_wKtHdha~WiA>=K@$)f^_H)tRp7@kqJSUH)k{ zQ`Wbof>?8lY6vx(L-}=q_tZiwn_K&qObR)z>3JLC9O5}?I(tZjqq~3C;g&}kaYRN3 zi;YAx$W5BmwVgMa`Pn)J3FT>W{ahHE>g~ISvQLc#C4P%{S-;u8YE}?A+%A?id8O38 z@E{N{Hz7uu%tBY*{B88nTsOBN;wP|%jA7_Zg(t`D_6@5&=Wy0%B&IYx#GvC_VY<<2 z-*8~9?)4zcqPvwElt+K@j9lr0TD0LjLPpfJf*@$ce`m<#!4OiTg4HJ=5d-#2V$s9v zUHXZ>myPx9)FCFi(GLypFk@QxmMS!7>nj z(1`Ili7I61T%xq^bZLsRhZ1INNTBrq>tP-1Idbhvb=Svg&PIt&YzF@YVPUM6g3_x} z!P({h`-ydoPEM-QRLsQQg@z5n`4PCxF6CG`v7)(M#0J}IHj&)j3%T~h%7!bbs8)R8ynyGB z@y??@2abkx5%#3`oQq%cD${Q6gnX(9a~+xi9!mIYl@Z!EU>=;te61#FRTeMV(3ui~ z6;H*hsfd3NLBMo61KHHV!8{4+UM(45)?4BryPLgxZlxfvxNF9&ppL4vRdMImtywGe z$}L+G1Cv*2QKULnXf{-Y(_>L3YG@>B`~D31;omVI;HY>mC%11a(sM`6qoXA5sHkQ2e`P|PSwx94_S6hS0wZsJLz8s}g* z=0WveAfp@GFr1tvxse5A2_WpAe zZ^XeW`+#JJEU3?LoXAv1k6Nu1xXT0~9#Jxk*`{I1ge?y}9 zh6kE1G0w{R^^-?d(O2Jif!A_m{xt1@eu&WaE3Udq54^ATuzpIneNnImA2*COk=X_N;g|wi1F7=3II`UBG0gE@C=DE7azy*`$b)(NxBrE;fB*@A({>w zN;|quBO+hA@P%EP6lLbhgycXI^ESFD%Yj=ZC}?qC5||7$8bYkwc_+UuKffq8=cwh3 zv*U4-c+L-E>Ec?i9+CWDhZfj2rC5JF-95TGR`C;Nki4QqUW;gBq20lMx|(H&820p- zx;0@1qy$IfTzTH+7h?SBJ2z}{6e4&=3mZoOLPOx7EjUQCjIvar?3$KVyDXo z{_~i$#nK$7pqv(?(ryiWi6lQoPNAKwLqp$78AewQEpriQ6u2Q-hSmV@BM_R<^Gq78 zq~(69qpMM>`nk$>v6<&yw{m~qVW~dtc`en##0o|$g{@eRmN8F-ol|fiZPaeRiEZ1q zor!JRww<2XwkLKnv6G3DiEZ1q{`_^$xjxlbUHiT1uIlQ3``LS~#{%|cs}zY6gaZat z#VywyFfpiJJFFv+fi%6?D!O*>BG!{>lWyz9)=}-l;O<+?DuMiP3Uclh^~kReq}psq zf!N6B90-2oDGJVjKwM zy@5Q@6dl*4(%HPH2q5|okegWZEZsOa7j}>8mNMnWn+t>dAwXI_I=LM4CNorRpq?mLddKz4Pdj~tYy-j|te7T{3PQ@= zpfD9(uH78h?@GeLCp2ApeY7$QL4idb93FmWe>&Qsa7X?I^)f{6c}Ozf{Sw@`BWf(9vfIZXT&= zX@4UeAgR0mnB_TG0FEUPxjB3}j)YO^{;XhFj z|MdD4f*|Bd?1zQBf^BRF?m`_G`Mb0UoLvrEP1Z8$(-&MJN|2{!H>w_|AZ88?PoHvz z@**V1^?-_C7$EN@i?fl_>)Xv@w4t|K*~8$DUx@J}DlI1?7)_2;qKQTszZ=SlVT*bi z7cBRwOt%+GugX3dC!BI$iWyy}{7-I*&b_mYo{dVIa9J{I=tE!87k#%rrI{i1L50@I zjh&Tt_u|ycZ+g&lxgZ%)YWu@+^hW_|Sq#jp=`Jn>H!v$`7wF1D;oR7uu)u3$RX#Gs zkOvBkK?@O}x8WcKUqWGxmdl!!``T|7I>V znVe)S8c-sX31hxP5E_*`*yhqrmtIKxVgzxc_&Hq?v2zAK3VLLYRJNDH<&tB?CRzFk(qm$i13DvIIS?7RU8mCIn`8{^-_jQG@9OSp+p46Os;Qa!fDI(Q4C=YpI*! z1x)2@?@~#-Dcy(EmvU3YI*S&mQ|~3F21*UL8e-P%X|XYcv$|o@G8%`ZjrD`w+@(Iv z_h0w^)p)ELfQRdr{5f(Lvpz^|^kCKbNZNOHvOAwOUpF`@pD;5<^TNKHU8l4JmgLhA zi>)a|Vv)qD@5_IkX&3eV!b}Nh>TQc41$HpLKA5?h?#F*wkO%!oxVEtHY}c1#<@8(G z(W}f!$IMVZb$`@7g<+qL+9Ntrzk#x6z&`$`T1%Ng21x^&b}=!w`hp9EYfoa8R#hrn z3Z%1N;QD}$<8mV&gu0?PI0RH^lG(#*j(xHu;*{_fOOIkDr_3@Q7eg^zB1f!|GC;xT zK~-9y!m$%8PsgqH8)BMe>A}4~0uJ6f`Fg-Jz)1P^gE?gIj!nn~RVYZgv4r3A+&{;< z*YH0!B>xZaGHS2TPfHgyk!4y#QmsT<{=4<*qrtj96lgf2`9qj?~(#P)3yE_cy)sCM5XK^t;rOnIy zQ><$CriK^bssy{ev3J$&LF=1&499B|#aRH+Y2n4Q_rSE%;nX`5IK{`*{;*6{Wtp}`Q9H&?QdE2i_s;xUXaz^5Kcn`k z^}HwbN$<=TWd9b{6R?H4`kznV3)4Aj@|J$V!GFV;*=&4PTFVE?Y^{}jNN)wOl@Ukx zcD8qmc7iMSI5?23;X=|2dVmdsiS_*xUs|dVC=V!8$5%8$pdkD-%6q@ttD?*B{qZo4 z{gNcbMUVostnAkb&3cwR10GH=(h6Fa)K^mVnnzno0hrj9TI%yX@#*YzXzyZ4z_L`} zEFD55>9?f`|E6_u^Y_SWCoDazlJ0KUR4fawrQ5Pvbl6`oQKj}FZD3)eVcJ{dj4Kg6 z>j##d-Z+(-+&bb*Z>p@Jk&E&iQH@lr$o=L8Y@1}8>&hJlrTz6Q_N#~lQJ9yiWP+o{ zX+>c`{UtlcKK=3QkwAHc>_Ce|;CpQkcq3{3Np=RzFvy$zKk^!l?5t8cijex)j~Y-F z7TK`1&2}xOkHtFaQ($E{(P2tZ61~e(6L;X`4*tl0!_iNMy7>zOeoiQ}^0loBT<6p9 zWVDXxbW(HLpwa*=H|@DYM%5j9L58j>GSIoHh_lvC(p21nKTNe0NN-$XkdHmsRBXQ6krY611TW%4I3R_X9seyjDU!J!l5dBhF<2X){b_yq$*nBR zxA74ws5g+T3n*g0NR`UrQKcBga?I`OYQ+Z&>kfB}YEUN_M>j~98?6?u9KR`)y(W#i zFJ&FCAKWrrt%g8@;V(fxwq6!VvUyCgx(fz{JLi4s+OWi14ck$fHl)#NL&s^ghrKb3!l?3`JIo63=*s$Z zJ94-+0SI+na(f8|(nWiYrrr+1kaPATd|6jGJbC195pe%n46cDojE;pg{=7lP!xU55 zLefP;q?2$ythQKr=!cYqJ6!GvLPCu`KY1Wt5@E=^kG_l5WGLKruhR+*dkEtDO~WKI z_&}`t;`{=Ec^&)A*H0x&Glxo)?rQAj35Lcj2EduS^+TM<@Izts{?`Wjj>-G^WWOiO*!QDdzUG4K1R1z0-ukYX5mC{%qO^y;GlIHvE#$8-LaX2gg(+7#2Crp~K3F#nYcVNP7gTcf&S(DANM8b&=&%;|mB=%yc zd2`pqtmbm*5IGst%vQHF%R^ZK4Z_a_7D!+#_6{L|L6uaVUfLA@Bi`5mS;e)|-_ndA zcNfeKSrC#;y5o$HyojLEJoWH!na!hN7cBvPJxpwzAU~7lClM^t3gv6Z-b=jhE|JYx z_hlBizFPso&K)7TAUsnbBORBHP=^>myV<7s&#{qaGQ7y+A55a#6&C~REj`y-Fkthg z?+D*4uum_0tP;UVZ~AL?lK2-tKjuwfQx91>)vv3hiNVpkQXHj0Enk^&P9Ho2Bo`Kc zF%FL!hkCb~EK>}7P_~l*dykGtC<|lQiRUE2@+TwNw=AM0RO`v5t#$8*_;}|^R!|mK zFEPhCKDR*Jy1Nla!Z*7nL+=wmCtxHfkk%$#QVRzcUgA&Y#?!Zb3RkA!@2P@1uN}nI zeomn>H!1S3qhGReCN2E|?gp%pMtF1!>_a-D`t0t**Sy5Xr8WfLs2AQ~&P@^qsa|he zlb!FG@1~bo(x_2B%92n*C{*mc>opo-^g4AxlbMLDRhb^pi<5zf5lPkpEdW|JTdR-2 z+OcK!4J3E(?m2L`Z6QOiYbfx8Yv>vgRpkkr=XbPe17gH#43+X%=)G-*EJ+5VIwG}+ z()<;;W6iN{xyLFm%o*%JoCr%P$pnk_t<_?LR=9Mx!tr@Cr2Q29t{KT={J-35jP^gP zPg(dFgr4O|Z$>*rxI^)x`9R(w{HapPe-Yv(&8!tTJ$ZE_bD}?;qNvalE8&Xzd|hwL zvmUrJSCN=@sr-FN;I7BUKvV97VB90_`?52Ss#_9NiWH80PTEa{eyiC}ux8VIgy8Hk zAYz5F^r)0(F7Fj@IrR`n-b0AiPM@>f&)AQVX{zH9LO+{8MHF;ZF#|6uH_72#uG|&% zT6r0HB_8oT!^%tR3%C5%P{KuSOS2|gHd;*Ng z@cI8KB3F3d0RFil&LCsMHN4<__t39W#yiwBKJ=0!(GTlV#ns-~2ht)$a&1_sPNg$q zdZ#01zu?!;TzRAY8GwfGo;?0JVev$!g5S>hpiF)sDlThHd1rj1f;;8eyBK&o2sX+Q zS^SbohS~!z`K({t51I2BC_Ou)Sv$E(s4Z+iN2nienYrvrrHzG5kr2-nO$xjYvh~fG z=MY(FFA-&Wwt_9DgI|gVQ?)PHJ|D2_{O#_bg<}}?_gYX9uVgx3& zc)@886|GDJI;@E?Wlyi#0XuC})P-&*f!^mdWUrb37Su?@sk^Qi_{2>h?__3x36Dk< z;`vf$LpYXbN@)8JQJ|dFE@rc5Et~QJvV2ODT2{uKYek#bkyMW$?B`>CE6<8MBw}ZT zh;d@Y4U})+UjY0!jm6X1?0E^@4JC=JW2Ac*;x4}6QF^)STL2TPWQ-xsBu-(-N77vB z7s5Kvk%R1ywwAfDRPBQxtRCA>$a}BMI>$M#es7ASrk6kU_T`Ggj9s8kTDqN^n~B?# zGFKjtYvjFtZ-hUdkf`X}UU?885T5#Q=lle`11jq7iU5(h3pM#3#<;tr<66CH8Vc#P z6!wv9qIj1UUjRE-Vkzy{KU8wb5SN{NgnW03rI z+WY93KNy)g@(dB}E-G`%3KOcu&$t6p`xucNohiN{4QLMaB%Gr8)1xjnr~ zBh2QCPRFydbM=D#CnxG;rI;`mZR;NV+6K0}CWU{=;}sYIqnVaQ{m1Pm#+J8(q%D@N z+7o^gsSuuwtc>*CNd;=U9cABxsC^@ej=+-*3IJ(MDjTTiTewRlk&=KiJN^$v)ejH} zQ!DlZpwQvm;@kW%Q0QDS`EI$ohnVKjA$+=lfxVYVtyF$oKXYY=r^ZS~hU1-ZSEpxf z>Cr(+wTu9j{)|Y;P>)A_gjpJ3>G9wr%d_iWj2!qaPO(tHv8x+I3HJq-JZy1Z0pKx?m=BGZm z|IwbN@G}WhN4*~Xp-!4KRRaSBuXsD4Bc^~+m_5e;4>41cXIT5StXojGfuM-<9Xq;c3( za(D7Cm)&gOoKKw_pI~TPEm@4&RFe+w#PTO-; z@ANx_zm(bvh~TfgSS{-%k8aVz6Lnv?VjW4Vj`cn}=c1J8=rg;g-KC^X6C!kND#Qhk zMRTiwN1YTZ=@v|QzdyW8Pb<&{P!?d|Hvdsv`O6jYb#~2RD(!~jhp5s4u9VJhS>%9S zukd2n$EH!CK~UsQ#uG{aa1Bm56{*bld##6GAK+K~8NGf>HggB&NsOAYShk<_?wNzz zvg7Z!xv7Mf%#)kCe^u=Argej~dYpnyZFf_yk$=88i+@hUcxlb;r+EU(D?h1rHyKH? zIQ`$S1d0mem%0;DKvcY$iA}du99~5aQD0R?R%27A(*Y2hzPJhso;sZR4=S{$;mh*GWj3(Z$2)4mPM4`6$4Tz1ONkdf2nk{yR1Fm%rE5?J7)D(sgPSgm;h)@t?Zx+r>LM z^nE~@nD=KxufZ*-J-m0gvkP1*AFfn)h7+IO!5Hdyc4W8RoZv81bLY9F9b3Z&2X*i$ zuZ_8rt)O16A{86GUkC4I<+uE*{(?#zbVr%k6)RX8Sf&8beewysto{R65IfB@a6x54 z!{h(!kri1wCkb!=z7rFJIvOwhYagM|PBh^UZU>l*wpaeqxpI3Tgr}6Z+^l~Ovxx2w z3pld=>=Cu~Z%g*n4e`LyDIfHw%QJ0%Wlkr@oYeG`?sb@&hr7FYQYs-6Eqa}cojU(- zh|ZaG7Gwh;{09PCS@b@p;D=SrwHO>0(jlVT=-GT)QGOPg1eW{3ag3$UC=*7cfGBgour;(Ie zg(rMcu3tx|=6d$qvN6kt0qBo_tN>d96YIONw?G5HG`uSySJKA`iz#*z7R+MO($Q@K zbq!SQ$+O=vF8IIu%G_}Xk^s!#B*0fv?B7QdJ8K_z(}%jDfvy_%x>>F%sIIW3sWqsA z>=Z0F$qtmv+2T%2sBTpFEVsb|sGDXSq$!yOIg+4x4};tFmd-V)J?U~vo+T$CL|m3| zi=I3H@ls3}e3YHfbSdJKRR9tdY>H)TzZ(u2Q%3@kF6bu&Vb;6|p$EDULg5tA@aH{J zt110kLsHXz6?2tz13WjCPrL91iZ>W4UhUNsDLgkp3kqh#rwpn~Eq!QQ&wAwzHX?X9 z<3v0c_5S_g^RnNRy{Xa>)=MvNSz}zA9`pg+%$|asUNah+)A+6m*UzkZX)Z0MQ~%be zz49EKF3jRF+;G{I-rNY)e(EZRt&!_FwoUKIb5=JCrk1}(iYmeVtz4mQTdp%VSb=~i zKdCY;z+{+dJ6(jXmc9)h=P%R3)|m4h;HhMX-{cZbvKHRF&*)}8Mz3nVdOQksJMRK% zM?dv``_GhJ%UW4x_NJ)Rr?-3S>ue7mOQp@s?_v%?$rkc!qaSKcGBoQ1re8SR5oY={ zxeAi=kY9+Ghj^%`;6A425u^6_%2@1t;q+=R(c@2hNByL2f)puPAgt4~V9|L0_(WT; zxaMX*?JgP}f2QCpxck&Ux`fF>#q0u-4#1{Mdgc=7kwSe>B?QG&W>5Iab>oyjiV2DS zD|Vv#*R0tMJDfjd6IAVL9(u552tE^O|LR^TVc)I4-5+D9alfkCQfRJknoj5ph0XIG z*+%7Xz6&4LQjUJ%Fmuq^Po+pjGt!)?C0D9Ys9)acI_|cu3Rn2&K4AsJ$x;jW7?$M7 zd443Np0hAOPSUK|s>d@b`SQDD>w!?IBxdf5UzOr!@?IEPZ#(!Uoq0z@pG;m6IdZq7 z2(uyWI7XX~ar}!+qs4+wzs{3=&WZapMAoW`@}7%vvWd*^SH!bjN5jMVqElQmkHKn9 z+fwIexcgKl=r6neMpF^f$Xy%YVBGwA44$$Ui5h%(rj5@)Z9tLkaDVB_zSiFh2Ozy} zWy8PJ7cTGHbjA}psJTiS5m`=#lL}U79R8QS4ZMuav8wF-E4z@P)^NzE12_gZB=TQv%rsoqMwJl{y74hKW8R4Daa*123x-KAa-yk($F6VN~ zI2vXXNRl&y7#Q<&@4_%>C_Jhxg%Kv%N-ZmG)#UEd8drd&4(Y#&;X_K%luo}gQ#e&_ zJfUI6LzxI%5HYMXTb0let{wNK{bqxZ+u=o+B9e+?RQsXpja5+xkNk31?U5yI+8bJ` zBTO~4{JD+)BsjykC<_>dao_K}$Bzb!Jr{5dlVzlaD9i|A+Zz5QF!%$wp?s*xuOx{@ zkjijL(v03556MgrPnn@XXZ&Nx4@2|KpATY!<5^XYsJT9-E!jnfoEZc;XCo)-Q5!rl zGT?W{PqAk5@;qLCG);Y+u7{?|BN4k(qL!G53RF1&=R@sc_w1m6&LO3^QVj=x{1Vg)=3!D_1ZE4lfw&5bXa%#HdMoc-Jl zea+NIr{Y{BXdx774Br_XHQ~iP@l~B_j-iNWs?|ZT-+^hqp$ncc? z&E?ul*rmI3%)2$KBsCltvTOkvSz(Uz% zWZD{$FvHD6VGR+S*3$RoEuT&k_C2kDa7{2NHgg5lEP(UZX!3y~6{p=b$P@L+NJz_J zVFv5q94lS*RYlcv#jB@DHZ@f)A&oid5(Y@VB~yuiQXr`F8(y4h(^%EsZDwn_*mH9- zWUxj5h~vdI#^3lL%J5|BbUHhvOq5Y6oHuO&9F?Epg%Ekd~mU!LBvzt|gjv!HKaF`*czjDj`0TH-I7flguHL z(Rn&m(?e^ntdM?K_klkSRaBW3+#f7SNnb7|RRXvwMqiSo8#WVBWnJDVLDMC>Hmzpr z`Q)A8BRM~raWP@qn^t)Q#|mVU@Al}wFXCOfY*p`LJwvLa*n=uky=id8yebwp`e7lv zwy8A1BVM9S*~sYVr`s{NVD_f{yldj>pDVVeP21wo@cq%%lpj33wiKnbh?VmN{Zx7; z9u2G-4U+%J)O*sGDiofmo$c81NJEAf#o_T5U}YsMVXw0Gj!aV;ljD8=g~XO% zXm(PPS@hi7WGWWaYo8N|hfxY0kq*-1-b5A&2-8`jU;0{SMH-l#@7)5*78}9nkOu&b zJ7J8O8RJn%OLkhu%GNz}h_0ohGL51gFAW+OI-0{(DT-E^k4xtYV_kOdhlCT?V~dI$ zk#RG6hNwg1a!O=>9CW3oA1Gx$I~|ZcP&fTaT7n_YSbzi=#%2(+Rn9`N4rU}KJ6C|_ zywgRLb=1gSnPD($pQ_=vpcl;Vy#TdXG^DMvvsiWujt}SOD)W~&oBuJRIe279%6U!J z^u$QC{=P#CduU20)+*1$4ehq%{5l_x@wL{an*BH5w!0s{cLrTbcdN=@?|;F*)z?0C zOU?U3U5_=Nw0%Vm1vA7AkHK*ms0rbgu+pR{u=@gI>7T?NJ zE~|73MlSst025c)&$n22fik&*BGrhvI{K$0uJ2MX3qwvriTb)k*i)*7<_h&P&xLwE|f!=B}B3$g1-lvY5*y(}b;Gr50-9C+Y{#ew)=KfzXo zcjx@AFo0tVdFRdKssGB5@DNb1ImxkS0q&+m4L- z&6o&LpVNF!gvUS$>p84LO~v3G(d{}MYEK<+9$EQH>Y|SgDCSSjw=Akn4ycqyqiNyp+GpjE%yd;-2yL zHI3Z|R+&8rd0=lKuDqMi0AYJPq&T1r18Ta<@sz$Pp>0{_Tm>5IyhhUiiK z4@pI(b-0!7!sm8s3osrC)!DXEYjwu&@lCc!6yGJX@lYwl`$l7i{&`pGN`f9mu^DHnMe zE1M^MS-0QjviNIk6sNjXa#BrQ=9M~+*5HERxxJ}lDzfuX25_1cRat1ZB_)hR3>ohm zGujWz<*mDrO8QZC7x- zE^Cx1;l7N26ezK(9pC?(AsY6i$RckI=Cvd&G%xvReWBYHqK8zZ<)Cx9KY||DoSl=a z7N52cYFPW>a!kauB+qOtRdI^CSeaAwPy7+HV3X=-5^bx5dj!92hX^e?Yy5_U#-|I4GSlfQhrv0Iz zvsIFxf@3(xN1Md$eA^&q8U*J>wxRr4LIPt%sUSm+GWjPHXYY)=p;T(xJ<}xU=I|KT z{z#B67m$I3vn+Huq@G1*JF6(&*6Z#OxTY#9e! zAq@dz5!yFTtd3Hi>^Y<#nW5$ncFqEyUmL$P1K-zmVug6zAyD%l6qr{aC-XF_l@l5? z0bF(%#Xj#T#CVH!m=+JPRxO-^=Kl~XGPi}q8mbGrEla6SQ@kz6$^`(<8iQ^%%AbS$qs(y zRemw%!n zcphs5p5ZWZL-41nu1(g@%{Yo`kD58^m9GcN8er>?n_toOFr~-IsYH=7^51nN46=~% z>DPZE@x|zA#JZrUEn*iSybd(XoXl)2Osp*QOl*`)OqA3xjB*a9qDHP}L{y?YEKDrS zOx*u>Nm_+2=m-cWcN%fa4=P|nM@I#BG|~S^<9^RxHofNUoBkwt`JZ+kWF}z1x7Siu!^VFz8wXT{1fP92ycs!$};E7g_}4>L^xZi3?A16Gvw~ znIA!h3vCgB0^bRXn*hYSDR)Z++oDZS3UjCM@!?n{&#^#{THcTrb<92NcN~GX0=i_vPdsC<+oK@i!BWSS7Hoh*AXj| za}g>|t}KOvC4s3rdo@Ig6y&{?B`0eAClt z?>ucv&eQx_T4`O1O$kAD`1_>Kypz(@mPIv%@4|%z;KmZ}R{0g@I-B%_@Y?3lxy%&5 zu|YdSzkhKM%)1}2Ca^U(y8e}BY+ZAkw;)1rOuQ+DD96PxMKyJ9+~7UG z&Nzm!&}6Cj8>GyJi&iVvukAdEs!+?`ij*Ubc}6k~+q5dIWWeR>`-A2q!!dMbj_QEoWL+KUBpHt6_MY8gf^ZTSN`$y?-h za|A~|)e5A2#E5iSd)y}&G>65FNdkc$_-m=P22vjOL*Z|vIeei;m!NV?P~kSI`2;eA z=2ZblL=(rad6;@RNJU({Mqjd+V3PQ6VF{^?Gujr63P>F9-#`P)DX(9Jf5G&uV<5jl zuFbMmjD#)x)V3qj$?-@Pl|<}~)76&wQ0beoaF-+|M*nm2F&ACcE9vofzRsiO)Xr z6eQk2(&P}~9b>v%h%wz(CLsHEh(GB!bgK4Bbo!h69>J^|zmySMzvW@4oCCYv3_ zIVbziqG^6rMy-l3vUWdbPK&ubK)iiRmo61WzeBl8&vLkH=;ewDm3Mn^b-8x=6K(r& zC3efWL|C71sm_ht0^=m~ImOpw7KC?!Ke_**7FMw6hYZ=#34%}g#RfO@lTC>qJo z2b13-4Q+(+e^HNZqQd`Z0xc*p8NzZk{1)Jb4hqUtbtr|LWN8!C9&_KYXAH87OD3nZ zuv>pbqlHp5E$^GBIC%_maqkmIa@6wm5b2@M9#C&qoBfkO3)l0SfzkyR5@u8Fl zrnQE0t!YWOUY21DxTu1@zJ^GliiKS%K63+6VyXqIs0&(bj~87hl@j^J&qyIRxtOMH zM-Jq3=O@RV4hWfBbpa}=;e#4X>5e05Fp;qs*l1UQu``)-g$J8=ifh^o&( z!54ZHkpHRWw2(?9QiJwB_$%8fQkvMtd#g>1zn2=k!Obi749R(Y9L;u04GTCzQO5im z;|Y$LFP`PETePijP2|&uk*p3APdyW=5p@$iyOMqok?VY6Us1p# z>S>n+XiDVsY%z09M#<1UN6UR-rYd#iSj_HSwEFd-xw#4~$ZbWpl$(AqNoEUr0qd%@ zUSlDFWDYfa1w$QV&&rL^2u5uTQa|v+hitN=$I>n`ipGZJ5|Edqv{d(%E$*T?*GULG z6TMIv-c1j43IR6aDrCf3cun{&T(xasT7;Gq3E0VQ;ZF-8WU)BdRz;M&`9aNdOC@^l zYFGk22JYTURDF14`1OQ!C!5YjB>YETZa^O3eumq zSW&zcp}_m$DEjer3AsgyNQyR0_}1(LF%KP+Nx-P-I^prcAB{g|`5C|#hQIsnPwNFx53xPf6Tg{|JZw|OVgv)8vszb2b+Z!?~UO)^o|5Axg z*=fgGs-z2#24h*u=N-v#gW`wI4>nVa>XTe3n8kT~+$C!=-uqijtHxN~vFHf@f*Y}% z;ZZY~tHS*P+p64As%@NgQyuC?ZnzF_qz?IW#umPEfgmI#bc`^>tkitBUG_UjrWB{^2tm$wgz1huBxe1vRy>;Zq!E36>w`^Iw`^=ZBa=b_-o>S zgT_W>l?;+?4c<=1__tE6lP#^TY7_E%Khjqmih!w{vE$Hkj1riLzG24jFN(0U`%oT* zku<=}>BvhLwh>p)#ngc6OgP~QW3_C(s~^bBH2IO}_VF%6wA5Bo3i7}Ag-#2-Z?d4H ze28LCz1%U9hv`ZwU{qFELh(`kIdBe}?)RRsgK~A^&*#VSRL<&=565&cYX~WD2T#`4n|y43FYl(f!|1ZAD&mEdnDYX2VIbuUi) zRUWXs@n-gRFz2B?(|2{W?>DPP}$K8FJq@))`AAH z2*ag&j1ASJPFMNfuj}-BEFskgrLT1&A5Wg@sCs;lxq^&>Q>UdjEw5JYGyD(oO8ifh z0*DmmUBlpRd?+ulpM;PbEj%dHl^Mc$i5GA8-l05LC;5Qs?i}V+3XB45!J-XH(TQp zW~tuZzvo`LVV~E`dm*@H@$Hg%dQ|J!B515#1DdW@mEPL;vlD4n3m+|gd2pKyR`(t~ z2Ux%Cr`D`^`Ed#3w2z$u4(uEPxo%%8#u4@si3>Ge8w*O4)q9OMyV=h$asI&99lRyrZ?=eP!C z(xaiX?4_<*u70j1qD0!<-J_$km#5$3L2~`b&V4dPY)Qim@two)#q-qJj1}*vyC)Bi zO^@s+PRmi!ofB_y56ze=bx9XjSIIS38(!Sn%97PvOu?SBb|uHDn`%c#Q`cAQhm~NJ zW2t-t&l=GtxMKc*a!ARtYOo>07ig~?PYGB~cG5$HXVy|}F zOK1IhvEkUZMQ8nE!V>-uQ`1?ul2|c|i_-N=7&3Bjc zcw1^d8nCJ^dKkW(TY~H;AUaZStCJTK>bwPcb}ir1gES3Djz`^=f`&uzozca2Wj5?eKU6WFFQbJ$q04 zN?Ii}wpH*+U*6s=UEP%VLUkd&%1T~Xy1IkEvVD8Fu=CP(6?Mx^;kpS+HNM$$YCEJ| zy?MYz-qPI4^YI-uQafa?QCug^mlz$_7gU>;TSsKAzfDie7xsFiRrPqs$K}MLeO#Jp>JmVT z5pCG*UYK#hx&vA~64(;IF5=T`^QsX} z&v`m%KSOyxtCH2UZi33pwVtFeQ>*;e#}>n*83?4wdme$YoTOkSOLKf88a zBKl|*EknNLhvQAK^8R`U7sn^%wz7C^9c|DErw{#zmjYx(<^4OCWvDejCx!>#jZ(r^ zndq76&cU0IuX)z!rC4cq6cme#yXoWm=$0Tt^5vUuAEXmO9R$RhIz-mI$8y; zidz``HkIJ_-Ps)qF`U1^u8PwLWjZH*J<%-s`z?N?fy!h<<{nyWxWJlp-;69Q%H1G#x> z(u_TN=QS}yAHjR@I)TM^?^Np_!uUHsCRwZY-;PH6(U2sd41QT8o%rBE7kWFZ%D6N-U(#Qzkb1z%%bgvpIJj9D8xp~QhFUES`-^aVfTpw zvkDL+MA#%sD5U+S!O@A#Eb2J3iGKm+^aTdp1ahKW$->==W%fWl2O id@X+lQH#?g*qKMQmnP&4N&w5o$;|>oPA;Y(4)Z@CnVJ{? From bbde7b980c732a3e70db397e1d3f43a33eaa7e61 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Sep 2021 12:29:45 -0400 Subject: [PATCH 17/36] remove print statements --- gtsam/navigation/ImuFactor.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index c0797d0e15..9b6affaaf8 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -75,16 +75,12 @@ void PreintegratedImuMeasurements::integrateMeasurement( // (1/dt) allows to pass from continuous time noise to discrete time noise // Update the uncertainty on the state (matrix A in [4]). preintMeasCov_ = A * preintMeasCov_ * A.transpose(); - // std::cout << "A * p * A\n" << preintMeasCov_ << std::endl; // These 2 updates account for uncertainty on the IMU measurement (matrix B in [4]). preintMeasCov_.noalias() += B * (aCov / dt) * B.transpose(); - // std::cout << "p + B\n" << preintMeasCov_ << std::endl; preintMeasCov_.noalias() += C * (wCov / dt) * C.transpose(); - // std::cout << "ApA' + B + C\n" << preintMeasCov_ << std::endl; // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt), with Gi << Z_3x3, I_3x3, Z_3x3 (9x3 matrix) preintMeasCov_.block<3, 3>(3, 3).noalias() += iCov * dt; - // std::cout << "p + iCov\n" << preintMeasCov_ << std::endl; } //------------------------------------------------------------------------------ From a2bf0c4da4e3ac52a99da716f4067e0fc70b5b53 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 21 Sep 2021 12:30:04 -0400 Subject: [PATCH 18/36] minor refactoring --- gtsam/navigation/CombinedImuFactor.cpp | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index c8d1b10fef..de4d3f66db 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -123,6 +123,9 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( F.block<3, 3>(6, 9) = vel_H_biasAcc; F.block<6, 6>(9, 9) = I_6x6; + // Update the uncertainty on the state (matrix F in [4]). + preintMeasCov_ = F * preintMeasCov_ * F.transpose(); + // propagate uncertainty // TODO(frank): use noiseModel routine so we can have arbitrary noise models. const Matrix3& aCov = p().accelerometerCovariance; @@ -138,15 +141,15 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Matrix3 wCov_updated = wCov + p().biasAccOmegaInt.block<3, 3>(3, 3); // BLOCK DIAGONAL TERMS - D_t_t(&G_measCov_Gt) = (pos_H_biasAcc - * (aCov / dt) // aCov_updated / dt + D_t_t(&G_measCov_Gt) = (pos_H_biasAcc // + * (aCov_updated / dt) // * pos_H_biasAcc.transpose()) + (dt * iCov); - D_v_v(&G_measCov_Gt) = vel_H_biasAcc - * (aCov / dt) // aCov_updated / dt + D_v_v(&G_measCov_Gt) = vel_H_biasAcc // + * (aCov_updated / dt) // * (vel_H_biasAcc.transpose()); - D_R_R(&G_measCov_Gt) = theta_H_biasOmega - * (wCov / dt) // wCov_updated / dt + D_R_R(&G_measCov_Gt) = theta_H_biasOmega // + * (wCov_updated / dt) // * (theta_H_biasOmega.transpose()); D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; @@ -160,7 +163,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( D_R_v(&G_measCov_Gt) = temp.transpose(); D_t_v(&G_measCov_Gt) = pos_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose(); - preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt; + preintMeasCov_.noalias() += G_measCov_Gt; } //------------------------------------------------------------------------------ From aa4a163480424688835c68384c6ae7aad239ca15 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Sep 2021 11:45:31 -0400 Subject: [PATCH 19/36] updated ImuFactor doc with details about CombinedImuFactor --- doc/ImuFactor.lyx | 542 ++++++++++++++++++++++++++++++++++++++++++---- doc/ImuFactor.pdf | Bin 225898 -> 243257 bytes doc/refs.bib | 68 ++++-- 3 files changed, 547 insertions(+), 63 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index c79a5f37a7..4b71a29ed7 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -108,6 +108,222 @@ filename "macros.lyx" \end_layout +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rnine}{\mathfrak{\mathbb{R}^{9}}} +{\mathfrak{\mathbb{R}^{9}}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rninethree}{\mathfrak{\mathbb{R}^{9\times3}}} +{\mathfrak{\mathbb{R}^{9\times3}}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rninesix}{\mathfrak{\mathbb{R}^{9\times6}}} +{\mathfrak{\mathbb{R}^{9\times6}}} +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset FormulaMacro +\newcommand{\Rninenine}{\mathfrak{\mathbb{R}^{9\times9}}} +{\mathfrak{\mathbb{R}^{9\times9}}} +\end_inset + + +\end_layout + +\begin_layout Subsubsection* +IMU Factor +\end_layout + +\begin_layout Standard +The IMU factor has 2 variants: +\end_layout + +\begin_layout Enumerate +ImuFactor is a 5-way factor between the previous pose and velocity, the + current pose and velocity, and the current IMU bias. +\end_layout + +\begin_layout Enumerate +ImuFactor2 is a 3-way factor between the previous NavState, the current + NavState and the current IMU bias. +\end_layout + +\begin_layout Standard +Both variants take a PreintegratedMeasurements object which encodes all + the IMU measurements between the previous timestep and the current timestep. +\end_layout + +\begin_layout Standard +There are also 2 variants of this class: +\end_layout + +\begin_layout Enumerate +Manifold Preintegration: This version keeps track of the incremental NavState + +\begin_inset Formula $\Delta X_{ij}$ +\end_inset + + with respect to the previous NavState, on the NavState manifold itself. + It also keeps track of the +\begin_inset Formula $\Rninesix$ +\end_inset + + Jacobian of +\begin_inset Formula $\Delta X_{ij}$ +\end_inset + + w.r.t. + the bias. + This corresponds to Forster et. + al. +\begin_inset CommandInset citation +LatexCommand cite +key "Forster15rss" +literal "false" + +\end_inset + + +\end_layout + +\begin_layout Enumerate +Tangent Preintegration: This version keeps track of the incremental NavState + in the NavState tangent space instead. + This is a +\begin_inset Formula $\Rnine$ +\end_inset + + vector +\emph on +preintegrated_ +\emph default +. + It also keeps track of the +\begin_inset Formula $\Rninesix$ +\end_inset + + jacobian of the +\emph on +preintegrated_ +\emph default + w.r.t. + the bias. + +\end_layout + +\begin_layout Standard +The main function of a factor is to calculate an error. + The easiest case to look at is the NavState variant in ImuFactor2, which + is given as: +\begin_inset Formula +\begin{equation} +\Delta X_{ij}=X_{j}-\hat{X_{ij}}\label{eq:imu-factor-error} +\end{equation} + +\end_inset + + +\end_layout + +\begin_layout Subsubsection* +Combined IMU Factor +\end_layout + +\begin_layout Standard +The IMU factor above requires that bias drift over time be modeled as a + separate stochastic process (using a BetweenFactor for example), a crucial + aspect given that the preintegrated measurements depend on these bias values + and are thus correlated. + For this reason, we provide another type of IMU factor which we term the + Combined IMU Factor. + This factor similarly has 2 variants: +\end_layout + +\begin_layout Enumerate +CombinedImuFactor is a 6-way factor between the previous pose, velocity + and IMU bias and the current pose, velocity and IMU bias. +\end_layout + +\begin_layout Enumerate +CombinedImuFactor2 is a 4-way factor between the previous NavState and IMU + bias and the current NavState and IMU bias. +\end_layout + +\begin_layout Subsubsection* +Covariance Matrices +\end_layout + +\begin_layout Standard +For IMU preintegration, it is important to propagate the uncertainty accurately + as well. + As such, we detail the various covariance matrices used in the preintegration + step. +\end_layout + +\begin_layout Itemize +Gyroscope Covariance +\begin_inset Formula $Q_{\omega}$ +\end_inset + +: Measurement uncertainty of the gyroscope. +\end_layout + +\begin_layout Itemize +Accelerometer Covariance +\begin_inset Formula $Q_{acc}$ +\end_inset + + : Measurement uncertainty of the accelerometer. +\end_layout + +\begin_layout Itemize +Accelerometer Bias Covariance +\begin_inset Formula $Q_{\Delta b^{acc}}$ +\end_inset + + : The covariance associated with the accelerometer bias random walk. +\end_layout + +\begin_layout Itemize +Gyroscope Bias Covariance +\begin_inset Formula $Q_{\Delta b^{\omega}}$ +\end_inset + + : The covariance associated with the gyroscope bias random walk. +\end_layout + +\begin_layout Itemize +Integration Covariance +\begin_inset Formula $Q_{int}$ +\end_inset + + : This is the uncertainty due to modeling errors in the integration from + acceleration to velocity and position. +\end_layout + +\begin_layout Itemize +Initial Bias Estimate Covariance +\begin_inset Formula $Q_{init}$ +\end_inset + + : This is the uncertainty associated with the estimation of the bias (since + we jointly estimate the bias as well). +\end_layout + \begin_layout Subsubsection* Navigation States \end_layout @@ -725,15 +941,6 @@ In other words, the vector field Retractions \end_layout -\begin_layout Standard -\begin_inset FormulaMacro -\newcommand{\Rnine}{\mathfrak{\mathbb{R}^{9}}} -{\mathfrak{\mathbb{R}^{9}}} -\end_inset - - -\end_layout - \begin_layout Standard Note that the use of the exponential map in local coordinate mappings is not obligatory, even in the context of Lie groups. @@ -1018,7 +1225,15 @@ In the IMU factor, we need to predict the NavState needs to be known in order to compensate properly for the initial velocity and rotated gravity vector. - Hence, the idea of Lupton was to split up + Hence, the idea of Lupton +\begin_inset CommandInset citation +LatexCommand cite +key "Lupton12tro" +literal "false" + +\end_inset + + was to split up \begin_inset Formula $v(t)$ \end_inset @@ -1075,8 +1290,11 @@ p_{g}(t) & = & R_{i}^{T}\frac{gt^{2}}{2} \end_inset -The recipe for the IMU factor is then, in summary. - Solve the ordinary differential equations +The recipe for the IMU factor is then, in summary: +\end_layout + +\begin_layout Enumerate +Solve the ordinary differential equations \begin_inset Formula \begin{eqnarray*} \dot{\theta}(t) & = & H(\theta(t))^{-1}\,\omega^{b}(t)\\ @@ -1095,7 +1313,10 @@ starting from zero, up to time \end_inset at all times. - Form the local coordinate vector as +\end_layout + +\begin_layout Enumerate +Form the local coordinate vector as \begin_inset Formula \[ \zeta(t_{ij})=\left[\theta(t_{ij}),p(t_{ij}),v(t_{ij})\right]=\left[\theta(t_{ij}),R_{i}^{T}V_{i}t_{ij}+R_{i}^{T}\frac{gt_{ij}^{2}}{2}+p_{v}(t_{ij}),R_{i}^{T}gt_{ij}+v_{a}(t_{ij})\right] @@ -1103,6 +1324,10 @@ starting from zero, up to time \end_inset + +\end_layout + +\begin_layout Enumerate Predict the NavState \begin_inset Formula $X_{j}$ \end_inset @@ -1197,7 +1422,50 @@ where we defined the rotation matrix \end_layout \begin_layout Subsubsection* -Noise Propagation +Noise Modeling +\end_layout + +\begin_layout Standard +Given the above solutions to the differential equations, we add noise modeling + to account for the various sources of error in the system +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{eqnarray} +\theta_{k+1} & = & \theta_{k}+H(\theta_{k})^{-1}\,(\omega_{k}^{b}+\epsilon_{k}^{\omega} -b_{k}^{\omega}-\epsilon_{init}^{\omega})\Delta_{t}\nonumber \\ +p_{k+1} & = & p_{k}+v_{k}\Delta_{t}+R_{k}(a_{k}^{b}+\epsilon_{k}^{a}-b_{k}^{a}-\epsilon_{init}^{a})\frac{\Delta_{t}^{2}}{2}+\epsilon_{k}^{int}\label{eq:preintegration}\\ +v_{k+1} & = & v_{k}+R_{k}(a_{k}^{b}+\epsilon_{k}^{a}-b_{k}^{a}-\epsilon_{init}^{a})\Delta_{t}\nonumber \\ +b_{k+1}^{a} & = & b_{k}^{a}+\epsilon_{k}^{b^{a}}\nonumber \\ +b_{k+1}^{\omega} & = & b_{k}^{\omega}+\epsilon_{k}^{b^{\omega}}\nonumber +\end{eqnarray} + +\end_inset + + +\end_layout + +\begin_layout Standard +which we can write compactly as, +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{eqnarray} +\theta_{k+1} & = & f_{\theta}(\theta_{k},b_{k}^{w},\epsilon_{k}^{\omega},\epsilon_{init}^{b^{\omega}})\label{eq:compact-preintegration}\\ +p_{k+1} & = & f_{p}(p_{k},v_{k},\theta_{k},b_{k}^{a},\epsilon_{k}^{a},\epsilon_{init}^{a},\epsilon_{k}^{int})\nonumber \\ +v_{k+1} & = & f_{v}(v_{k,}\theta_{k,}b_{k}^{a},\epsilon_{k}^{a},\epsilon_{init}^{a})\nonumber \\ +b_{k+1}^{a} & = & f_{b^{a}}(b_{k}^{a},\epsilon_{k}^{b^{a}})\nonumber \\ +b_{k+1}^{\omega} & = & f_{b^{\omega}}(b_{k}^{\omega},\epsilon_{k}^{b^{\omega}})\nonumber +\end{eqnarray} + +\end_inset + + +\end_layout + +\begin_layout Subsubsection* +Noise Propagation in IMU Factor \end_layout \begin_layout Standard @@ -1257,7 +1525,7 @@ Then the noise on propagates as \begin_inset Formula \begin{equation} -\Sigma_{k+1}=A_{k}\Sigma_{k}A_{k}^{T}+B_{k}\Sigma_{\eta}^{ad}B_{k}+C_{k}\Sigma_{\eta}^{gd}C_{k}\label{eq:prop} +\Sigma_{k+1}=A_{k}\Sigma_{k}A_{k}^{T}+B_{k}\Sigma_{\eta}^{ad}B_{k}^{T}+C_{k}\Sigma_{\eta}^{gd}C_{k}^{T}\label{eq:prop} \end{equation} \end_inset @@ -1313,7 +1581,7 @@ We start with the noise propagation on \begin_layout Standard \begin_inset Formula \[ -\deriv{\theta_{k+1}}{\theta_{k}}=I_{3x3}+\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\Delta_{t} +\deriv{\theta_{k+1}}{\theta_{k}}=I_{3\times3}+\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\Delta_{t} \] \end_inset @@ -1325,7 +1593,7 @@ It can be shown that for small we have \begin_inset Formula \[ -\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\approx-\frac{1}{2}\Skew{\omega_{k}^{b}}\mbox{ and hence }\deriv{\theta_{k+1}}{\theta_{k}}=I_{3x3}-\frac{\Delta t}{2}\Skew{\omega_{k}^{b}} +\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\approx-\frac{1}{2}\Skew{\omega_{k}^{b}}\mbox{ and hence }\deriv{\theta_{k+1}}{\theta_{k}}=I_{3\times3}-\frac{\Delta t}{2}\Skew{\omega_{k}^{b}} \] \end_inset @@ -1375,9 +1643,9 @@ Putting all this together, we finally obtain \begin_inset Formula \[ A_{k}\approx\left[\begin{array}{ccc} -I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}}\\ +I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & 0_{3\times3} & 0_{3\times3}\\ R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t}\\ -R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & & I_{3\times3} +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & 0_{3\times3} & I_{3\times3} \end{array}\right] \] @@ -1403,26 +1671,12 @@ H(\theta_{k})^{-1}\Delta_{t}\\ \end_layout \begin_layout Subsubsection* -Combined IMU Factor +Noise Propagation in Combined IMU Factor \end_layout \begin_layout Standard We can similarly account for bias drift over time, as is commonly seen in commercial grade IMUs. - This is accomplished via the -\emph on -CombinedImuFactor -\emph default - which is a 6-way factor between the previous -\emph on -pose/velocity/bias -\emph default - and the -\emph on -pose/velocity/bias -\emph default - at the next timestep. - \end_layout \begin_layout Standard @@ -1430,14 +1684,18 @@ We expand the state vector as \begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k},b_{k}^{a},b_{k}^{\omega}]$ \end_inset - to include the bias terms. + to include the bias terms and define the augmented noise vector +\begin_inset Formula $\epsilon=[\epsilon_{k}^{\omega},\epsilon_{k}^{a},\epsilon_{k}^{b^{a}},\epsilon_{k}^{b^{\omega}},\epsilon_{k}^{int},\epsilon_{init}^{b^{a}},\epsilon_{init}^{b^{\omega}}]$ +\end_inset + +. This gives the noise propagation equation as \end_layout \begin_layout Standard \begin_inset Formula \begin{equation} -\Sigma_{k+1}=F_{k}\Sigma_{k}F_{k}^{T}+G_{k}\Sigma_{k}G_{k}\label{eq:prop-combined} +\Sigma_{k+1}=F_{k}\Sigma_{k}F_{k}^{T}+G_{k}Q_{k}G_{k}^{T}\label{eq:prop-combined} \end{equation} \end_inset @@ -1467,10 +1725,19 @@ where \end_inset is the -\begin_inset Formula $15\times15$ +\begin_inset Formula $15\times21$ \end_inset matrix for first order uncertainty propagation. + +\begin_inset Formula $Q_{k}$ +\end_inset + + defines the uncertainty of +\begin_inset Formula $\eta$ +\end_inset + +. The top-left \begin_inset Formula $9\times9$ \end_inset @@ -1509,22 +1776,213 @@ derivation as matrices \begin_inset Formula \[ F_{k}\approx\left[\begin{array}{ccccc} -I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & & & & H(\theta_{k})^{-1}\Delta_{t}\\ -R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t} & R_{k}\frac{\Delta_{t}}{2}^{2}\\ -R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & & I_{3\times3} & R_{k}\Delta_{t}\\ - & & & I_{3\times3}\\ - & & & & I_{3\times3} +I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} & 0_{3\times3} & 0_{3\times3} & 0_{3\times3} & H(\theta_{k})^{-1}\Delta_{t}\\ +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t} & R_{k}\frac{\Delta_{t}}{2}^{2} & 0_{3\times3}\\ +R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & 0_{3\times3} & I_{3\times3} & R_{k}\Delta_{t} & 0_{3\times3}\\ +0_{3\times3} & 0_{3\times3} & 0_{3\times3} & I_{3\times3} & 0_{3\times3}\\ +0_{3\times3} & 0_{3\times3} & 0_{3\times3} & 0_{3\times3} & I_{3\times3} \end{array}\right] \] \end_inset +\end_layout + +\begin_layout Standard +Similarly for +\begin_inset Formula $Q_{k},$ +\end_inset + +we get +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +Q_{k}=\left[\begin{array}{ccccccc} +\Sigma^{\omega}\\ + & \Sigma^{a}\\ + & & \Sigma^{b^{a}}\\ + & & & \Sigma^{b^{\omega}}\\ + & & & & \Sigma^{int}\\ + & & & & & \Sigma^{init_{11}} & \Sigma^{init_{12}}\\ + & & & & & \Sigma^{init_{21}} & \Sigma^{init_{22}} +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +and for +\begin_inset Formula $G_{k}$ +\end_inset + + we get +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +G_{k}=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}} & \deriv{\theta}{\epsilon^{a}} & \deriv{\theta}{\epsilon^{b^{a}}} & \deriv{\theta}{\epsilon^{b^{\omega}}} & \deriv{\theta}{\epsilon^{int}} & \deriv{\theta}{\epsilon_{init}^{b^{a}}} & \deriv{\theta}{\epsilon_{init}^{b^{\omega}}}\\ +\deriv p{\epsilon^{\omega}} & \deriv p{\epsilon^{a}} & \deriv p{\epsilon^{b^{a}}} & \deriv p{\epsilon^{b^{\omega}}} & \deriv p{\epsilon^{int}} & \deriv p{\epsilon_{init}^{b^{a}}} & \deriv p{\epsilon_{init}^{b^{\omega}}}\\ +\deriv v{\epsilon^{\omega}} & \deriv v{\epsilon^{a}} & \deriv v{\epsilon^{b^{a}}} & \deriv v{\epsilon^{b^{\omega}}} & \deriv v{\epsilon^{int}} & \deriv v{\epsilon_{init}^{b^{a}}} & \deriv v{\epsilon_{init}^{b^{\omega}}}\\ +\deriv{b^{a}}{\epsilon^{\omega}} & \deriv{b^{a}}{\epsilon^{a}} & \deriv{b^{a}}{\epsilon^{b^{a}}} & \deriv{b^{a}}{\epsilon^{b^{\omega}}} & \deriv{b^{a}}{\epsilon^{int}} & \deriv{b^{a}}{\epsilon_{init}^{b^{a}}} & \deriv{b^{a}}{\epsilon_{init}^{b^{\omega}}}\\ +\deriv{b^{\omega}}{\epsilon^{\omega}} & \deriv{b^{\omega}}{\epsilon^{a}} & \deriv{b^{\omega}}{\epsilon^{b^{a}}} & \deriv{b^{\omega}}{\epsilon^{b^{\omega}}} & \deriv{b^{\omega}}{\epsilon^{int}} & \deriv{b^{\omega}}{\epsilon_{init}^{b^{a}}} & \deriv{b^{\omega}}{\epsilon_{init}^{b^{\omega}}} +\end{array}\right]=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0 & 0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\\ +0 & \deriv p{\epsilon^{a}} & 0 & 0 & \deriv p{\epsilon^{int}} & \deriv p{\eta_{init}^{b^{a}}} & 0\\ +0 & \deriv v{\epsilon^{a}} & 0 & 0 & 0 & \deriv v{\eta_{init}^{b^{a}}} & 0\\ +0 & 0 & I_{3\times3} & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & I_{3\times3} & 0 & 0 & 0 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +We can perform the block-wise computation of +\begin_inset Formula $G_{k}Q_{k}G_{k}^{T}$ +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0 & 0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\\ +0 & \deriv p{\epsilon^{a}} & 0 & 0 & \deriv p{\epsilon^{int}} & \deriv p{\eta_{init}^{b^{a}}} & 0\\ +0 & \deriv v{\epsilon^{a}} & 0 & 0 & 0 & \deriv v{\eta_{init}^{b^{a}}} & 0\\ +0 & 0 & I_{3\times3} & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & I_{3\times3} & 0 & 0 & 0 +\end{array}\right]\left[\begin{array}{ccccccc} +\Sigma^{\omega}\\ + & \Sigma^{a}\\ + & & \Sigma^{b^{a}}\\ + & & & \Sigma^{b^{\omega}}\\ + & & & & \Sigma^{int}\\ + & & & & & \Sigma^{init_{11}} & \Sigma^{init_{12}}\\ + & & & & & \Sigma^{init_{21}} & \Sigma^{init_{22}} +\end{array}\right]G_{k}^{T} +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega} & 0 & 0 & 0 & 0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\\ +0 & \deriv p{\epsilon^{a}}\Sigma^{a} & 0 & 0 & \deriv p{\epsilon^{int}}\Sigma^{int} & \deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}} & \deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\\ +0 & \deriv v{\epsilon^{a}}\Sigma^{a} & 0 & 0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}} & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\\ +0 & 0 & \Sigma^{b^{a}} & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & \Sigma^{b^{\omega}} & 0 & 0 & 0 +\end{array}\right]G_{k}^{T} +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{multline*} +G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega} & 0 & 0 & 0 & 0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\\ +0 & \deriv p{\epsilon^{a}}\Sigma^{a} & 0 & 0 & \deriv p{\epsilon^{int}}\Sigma^{int} & \deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}} & \deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\\ +0 & \deriv v{\epsilon^{a}}\Sigma^{a} & 0 & 0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}} & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\\ +0 & 0 & \Sigma^{b^{a}} & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & \Sigma^{b^{\omega}} & 0 & 0 & 0 +\end{array}\right]\\ +\left[\begin{array}{ccccc} +\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{a}} & \deriv v{\epsilon^{a}} & 0 & 0\\ +0 & 0 & 0 & I_{3\times3} & 0\\ +0 & 0 & 0 & 0 & I_{3\times3}\\ +0 & \deriv p{\epsilon^{int}} & 0 & 0 & 0\\ +0 & \deriv p{\eta_{init}^{b^{a}}} & \deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & 0 & 0 & 0 +\end{array}\right] +\end{multline*} + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{multline*} +=\\ +\left[\begin{array}{ccccc} +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}}+\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}\\ + & +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +0 & 0 & 0 & \Sigma^{b^{a}} & 0\\ +0 & 0 & 0 & 0 & \Sigma^{b^{\omega}} +\end{array}\right] +\end{multline*} + +\end_inset + + +\end_layout + +\begin_layout Standard +which we can break into 3 matrices for clarity, representing the main diagonal + and off-diagonal elements +\end_layout + +\begin_layout Standard +\begin_inset Formula +\begin{multline*} +=\\ +\left[\begin{array}{ccccc} +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}} & 0 & 0 & 0\\ +0 & 0 & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}} & 0 & 0\\ +0 & 0 & 0 & \Sigma^{b^{a}} & 0\\ +0 & 0 & 0 & 0 & \Sigma^{b^{\omega}} +\end{array}\right]+\\ +\left[\begin{array}{ccccc} +\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & 0 & 0 & 0\\ +0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +0 & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 & 0 +\end{array}\right]+\\ +\left[\begin{array}{ccccc} +0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & 0 & 0 & 0\\ +0 & 0 & 0 & 0 & 0\\ +0 & 0 & 0 & 0 & 0 +\end{array}\right] +\end{multline*} + +\end_inset + + \end_layout \begin_layout Standard \begin_inset CommandInset bibtex LatexCommand bibtex +btprint "btPrintCited" bibfiles "refs" options "plain" diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index 933c71a749610b513627409ff903042378fbd989..041d8bf1a2d3e93d115dcfee3a9b001f5a6ea52d 100644 GIT binary patch delta 150562 zcmZs?Q+F<06lNLQwr$(CZQJ%6+qP}nwoYe1B~dyMA??29$meAeYL zeAhKXA{huXQ3i1bFcpA4URV~487}PZk=7*{!_I!$qny9{d=MtT)&K)hy(YM&Bvt$6 zZVQKzk@5cF?pJ>@KX}TEQmb+zRPp~=b1Whbp zr@zKe!4p0_u(ITJ#hAth1|gL_?iVq~oJjfcV-<)kDyNyQYel8bv7~eV9~o%0o+53- z8X@~kI=|@V0~>r$X-y&7(okD@QTlXX!>6?XcxJ8HcLR+iB16q3TFC9!M%ol<+- z+FnxrWYbMUmrnT+#xEps@Du`I3Q!hSu9P7SYCxa1uH)7udcZ=1(jL{INjNJW0(K!{ zPBDWAFlL`u5V%LjSSHSf9GNnCRpBYP;zhYyK^^_FUnypEY5FZb?#&BlW=$U(xg|tjzedx z9l+Fk^+P?#kTU5}QiAVDewgBzRr&t;XLEQ-{v^RRPg4IAfx8w3H3u(V-sI?*MY?xa ztE~7AvGd-qXFg8PI)y@7tuCeVq-cT=ePfQb{>k>HctLIx9#`$Dad%Mc+$kF)-03(A zfiN&c6;(j}xhsuvJyFt~Hsz=DWQcOJ7tmncUCZ%B54dMF zpz8o3I{Ze&_xK^@M;=fCfr?}G2;3+v}NCF)MT;0y+v3WheD4nL}@A1WB*#FN`@a7-c$?7>8KbRtD5 z_xazBPf8gA!}=$7BI6dBL1`GeoauW+3f%>cBFNWdftM(W;86YG(WO>22_R7HD?bXg z&mtoyLEoWTF1HlnSO)Q3yec$f!>qS9(wQhG;1Hccx2w~s+AuJHBZ`&iPxa+Ua?D=o zbdaQkugoC{vf{5^5qBvKxVpneR?;O&SS$d5!M~I{Lp&Wr%QN#wTfB8+TOY^5rHWO?J1pm~zvy_!$e`?ny)c!ktak{lP z_R`53BlUm=j|YQq9^m5)^|`=Cf`GEi{5j1$_ME(@HRV|%pqp~VTz47SP$Ua+n6Du9`P}%;+Q!x?>3LyBS83|7ep0(G+3H*Xe zAFILu!o#9vJ7zk1#RQC~rjcSZFTs4m!-~8UWcBeZ@oFT~4zrw!YRL2A^~8HY1ERoS z9#&qJ)2TrZou8NJqdmB_Y;QgMLOJ<$jWEoc^EC6tYaXSst4~EG<@xI$rSPiNq&@|$KQ`VW-NumI4J4qG${XHC#6BglzLEvVrS>g`R zJA|AHm%mX^r3n)3!&_m)|KnZDvR@#&Lof2F>aV2=?Fy&M0N5HR3xM1?xk^!c$Hnc}pQeOr~zlJhv&LZCAve&=OZX*OlpRY@{Lx;|^?5qPLLD|i+CzO3XD z5hF&&26RJvw;l;2hy8wxSQ9F_WUiDi#{+T9b=6W0Ot_Nw9k^jzOd05p(nsnIj-)N~ zQ!xSZ)01Mt@K^mxJ`^k=oKP*aiiv^wDSn1G&gY%p0^Q>(;H$VwzPTrX`}d^8vG2$d z$gYruXEzp0RCIvX(%9+@4W^Xgw;Kg^3;jM!04bD8IF*X49CXk#ghfvj>{E?&V;C`f z(b8xG&HYnJaXt!61Q|<%)t0i7VW&hTl*C2&#z(~>+$qE6r!Kc+(55udW!cAy{IYbA z-m<#*)%?Yq*Mf}v(mcj3-7mB}#%@cw@INRdTJ-NY-IG)#`weFWcA`4hU9#e(1T=Vz zfL9Qwa90m3DdGutCghKCED3V+dbZIwlu~IXBEBeMo`^j=fV)5Dp}3~)dC|@j6~e4! zT(fn;wJoo)Ay77(VaYUa{CkvXh^I1-IF5A2&(R{*$j@*u_=Qi6X9`AX&I$ZzOiyC` zp4eFcY2oAcaZG0)l$_|A9ZKe3GAtJ&K;f=hgpgYIqrPfdk-xYcPA_z6hzoqhDMJ&< zgoz8fIzA)OOep@U@Ji{$*S*FBJ2|0R!569Ey7UCb8Swxd{Peo4F;(*@cY*=pVu=1{ z{>no@`bj{-rD@E0&)BZ0uSEe{sf+)SQpm`yUt0mxK99>Fphz;^ zBY%qsq&A-Q0yNlmn)TBIGcdA`FCRbK-O-VieIZ$>8@1snMqwpQK?uP;<=6@EzP)0v zT@Zfnuy~+As1iP=r*xtOg|Kn9hq+9z6)3$?d2t^x7L7FBY_gs0HBmOX!{+mFA_UF^ z7kD_U26T#4y;FPj?&VE1>59w`Py(f@VBvS?Xc)QUH8V_4gl2yxRzeIV5)&MK$0~{B z@r9SNFM?TV08?33HcXGn2q^)ReTAV@Zkr~js{p6+&HG2&u%AipTs?aiRFb2a@b1 zs46#)N%)iU52?~1DV_$qcqFrtuF_Ww@b6yQ2Zq6!tL4P~6ekgGT#CE>`2ZT|{y2WbE>oFIn|IGP_j7O4?UONZO|JuVe$1RPdJ!ln)HT(_T73U2vhTKc9oPjprKDcP zHL|={)A017Ox@+M!wu-u=AqfEuWTh#(O@W{v7qb0ll>~VhH7Q8ac1S1sLq|(jHrOh zqWWr&e~IzuSS`zC1ueG~7-_&zV8x+=DWTBjyNJ39@RORBuh^uNvAk~m8}lhCRj9v} zL9vG|)<%<$EAIMNe1)?PmtzO0DQ5I!d#k^^vvT}km%aTG*pYa-#d$^G0?}q~v{AN7 zqRB$Vv{$~%29-mn^N#SZL0nSq7+AZtm~3kLkC$e3r1`w_c8d z70FenNHLP7oL*rzx54sgsqRjAC{wMQv*AE)HNt|VSHu6u{`J~frIG_UhVpCkS588D zdlW+Sm{?Y{KmQf-*-ZPa?k_89w$Je>)cfNrm4!y~u;PSIQ>x>Tj>OkxZ5$#c&qv+9 zl8b;L)N` zgmoW+Nq%rZKJ20Jxx*yRLt_VFRyW;mZNx|4Zj056TUMRn{A2)-&fiP?cpS-B3D@z@ zi^{sTu&Dkzf#^Ss=UZp8n5lPti$=`DE&_6GbDtZ!JCj##YdzuH;PnlV1g&RQ+bL%N{blPh5TeD+@^^q_Q|WQjswDS;S(%J&=qi;suBgrE+RA#xB2!w?X` zL9{#E2MKGW=^TvM1J=?95zf3H?o5Rx;P!+34l@5B7=QsV;z8}bK`W!9hj~K zKZ6R$rn%PRi(#_)I+0-n`uz!o|0O29q|<5J0SaTFdo&{st_b*)U~eB_S?5G7BTCho zCy?Eo9_@4-i2FiS3;w@9e_dxsm@;WNB!+S_m1xpza{nbz8NoybFekCh!YYXABy;8t zZ5ctaT>)m;t^ShjNoau7#50Pk=;=(C%8jM_U>nNBtgG;)@pY>;HgL?jHLlphO*z?0 z+5%hdBjgTV&kQN#As&i*lATd+Ic#aX`pXFjfh=~k68ElHg47ZmUDem->~_^RiADl% z64!9dl@aV##$aomVX#7j2l!E$+Gg?1xw4|F9s{x--!mb#orv0{Vntn;LZXbvu^ot6 zTDBF;0=q2Wb9#KeKn9Syj3y#7fIZO$7h>8@qF})qCH37q_cR&Mhxg$Xd(}*l*u9%= zna#&(&6Y>Vw$-2OH`4`tPp5Oo|Jg1-(SbBFTLAwBg~O~v#JWlBw?~emMoANVURulv z69&AV@MubR-Q+1DIT@;*1f0PX&yuph{S*ZU5*uCk#9w zDZ2F^Q;Y0_u-g**@1XfR8ZOD=?`S+X&I9O5ebweUd5N?=2hqywM7EBVR#xR(_VVh) zXV3Na#PBg}WtcrlSi@Ym74t%N-uPDtxbBOsiDlNT@NbIN6*qYATftAB>tw~^YTkH$ zqa)yuEN`>%3Uyk<$+S9oN^gSBsG{;oCtcZ2Og~(R!th{0%H~7|-UPatnS$c<(f|sQ zb3b)8X^YGlm*Y=uI1lue-akINZ`J4eSIek(cDybkzqN&3JyWz_^IZ?4ClDgG>h_4+F&yGip-dL*rDqFoa5@b|!E{nSUlCr_dgfk(o@*h^FVNnCMQgGnqo$ zZB$JqnE=Qo7OLdykC_iaTr{M$l>mCg^_VQ+Yy0vL^LHl9_7qd0@=e$CRHR}FEmSxW zKEr6N`f*}p+zPe&H{zpo?2VD4?Khn#V0mVc360L~r9WOV=!=2lNYaZXbQRP6O$m+7(gqlEaeh$ z#ECNYzKWrc_+;U1C;Cbw&^7Jl*0ScB!Z!(|a-dxi8ld7|_er^(`RKE8RnNlJ3xRP9;Y$3+)&EU8k) zy<;Wd?lXJw)9p_xsUwER_;_&;jlgl-{_SABz3&D89gvD9t2mkTTr%R$lX#c1`eKgQfjNb8Y~b6TqmrH77{kPuke3o2T5)0?42mE>3Oh9R4>oo755&7OAN*mnL$?AuToI67AGbxOiSElg~YtG!wQf9&W=Tt9_Wh_1; z>3J}_%`Y3uuU~J#N&%9^$Q?6{SZxS;$qExk4N7i$`0P;CT759WuX0X(2?O zA2D0qWX2(`B19C?f{%%h9%9D6R@+~(x`rb)igwG^=jl5Tz~c#rTJ&BTbhL-9(D|)@ zV?92Q1)Wf5N&MM5aEP#2b|=G{BqvD($K7A=^W|0Hgat#&IpHH4!F-z@e-FOSI#&Ve zVT9X)XOVnmdIx#SC%q8#f~Rx`N`*x3?c%0b0$3e9bxKycH8JFZGeiN`M~}pD$nlS~ z!WgpfwcC1-YesXpuvQ5@kYfmb@YUE_kc%MUz*l-F@zG**qXFOO{aD3=jht*6>=kvY z|0b{e9Aj`Fup>HyybK5ubzGDWlBl3Tf>lw#IK341c-LmOqtxjdS#l~+2H<-1!~{r>{lF%BoPZoNdR_yJ z|9R(s(fr8c7i`*|Aw_m+w0B?Yy8M_QK|azO{toTu)|rb7uwP{uL=vW0ubG{RZXU|4 zDfah&91jTBKneYCN=gaF#s^{HN;&AH2JGnSrfjvN2kaRZ^((8wj^T^3cw23np(yfZ zaqwo%aydlQoao@m9%>ZdbPn{N0qujMQ8{xybl${>%V_QI@9XtH9=u&`FbU=n$MXXU{<)wDa)mIri2F(83qI^)Pp>{2MS>A9!Z? z{n#ylH+^*E0#17M?cWAKrKnPU0JzpiwNa04N{{siLX*!$fAgrmUq3hJXG1FsacFFz@eZ}D@F42%h!jaXfD^^gX15oov@i9gQi^0Q@Jte zN~P6W1_k_|@6=p{K-6=}DXvF42Ku=X&T-=M_il{%Ktbpjexs?Hh zYqeYjp2l_>dcqm*H)}yUfPGIaRXIvKuA>-o`Qb*rS?VJKUzQZyL3z%ZC$aRoa59qu zcrsP>S7FbJNitLXQW>thc$aF`Ow5f+hJdtw3H-7iJp^dOksT&zfnRY0chN3c7>MO^ zUdC4d$-iM!-s2AK)ih5HGCLV$&}Kh{oNO3q5_FWqV@2Yy(M*dsEm#t~p@XGkq0Oh)P_QKowRMsv?ytkkTQVkRZoK^Sj5Y+9$y} z&GP1~ew|TUgMVe~v*hETsk}AEXh8 zO$M?hSKWYw6z?N@B?npZ_o5xHIz~eQi%|rh14bKQ7))*_Xupk~C{55EMD2sYmbV~^ zAQ$S~9>+~XlCBLhOMuFRx@W)|tK@D`UW5!K7$oPgTd5LMhovgU7NiG19HydFac^Ia zS1MVg`_Q2WNY&3;0l34d(Az1OgINQyYK9uiUrvM%*n1gkIB{EFc@1yyIJ{se9xa{k zCOmfeWC)>FEVlRxbo;1RPnOx=s3Vtzrf^}h4wVK%imB6@i@uZ&|7f|JDAHP#CD7re z$On*{&ZdlWO*`S}Ss2B(ux!`*{I+hIMA=+v)5OC96pKmR)PFwCi{KniRzppVm7U-p zOhAC*Y15H`a#^$%F^)B{a5sjy(;;j=HN>_(O%x{AE5{>;1I=Kams~;p1~r%(_$JiA z9E0fYhku{SA8H482X+r;CQ2iMV`$Xk_CsNxHx$NZ`O#U88<%=>QKRbVK1}6IxFQpD zWWELgA4XD6Vg_*Bup&%q$)k--J6oZMfq(~wb$@Y65RzgnE=$r;p~f6X2ge`xkSc7a zKOph3N*2I;AW)%j&AU6jKJu8a_eZiw62VS{+lxEHD3>OC9{-N!_8j^pXq?5q!@9_T zsOY`PzSlXa6Kr|m$n=H~%o!LOW3IK^3n$tEf%#;n@Q4fOLiDLFsd-qkxiW0Q4su(Y zFQ+2vS5u&g@K-0b&)YU}2Ce_%Uw|4}&~@gR77Ur6-JKlu-4tTx@xS`@cuW)8(?js&@+bKXxO(H1a? zra0eVPJ`(9-X2%c2#h05aJ<$WtN*|S5CR=Vcxo8lp+!dL6_=;h|48PQ)Q8?quXBk? z(~+3g;zwGh-&|2-YP4i6lC=Tpx|Avc%Agdy3q0)YA8Lvou!W>hu}dDb!NhB;lrhL+ zADzbtAPhVIvrKGqeUYtfIbW7uR#e@ z=8K34K#G%jzT2|dKgi%p`b0C!RK(Dvk42DbKc57XF7F=(H%#l_xn09u&EQS}7@Sl)k+!B!iWxG^ZRXqkTj^a!Ap z`B}vCm}d6jOstHCmJ@{)*_wE7;1NwhF6fkQE78UgJgGQ>){0>OsOpH0XV^7{VXRC zo%0@>d+5HBkr4JfeYV3Ke3Hu!w_2YIH0hXAx<~b5j7xg-<09-{vFL+mMeAt-iilQh zZwCmgPt5YS#@56ImaCMVl5llAfs*A+46#_Ng2NDKbMdS7n;24~GCBBwp>%iS76gZuvC(Q z6}F3&RztWo8z@Y{LK$N7ol~7U_;B=0SuBKZRrnbndBnLv(3Y-YQcK)ZO($`A%DgLQ zJD*Zb1%PrYSBC-D(GwGZY2r_4lQ_{X+kENT9g6!>Fx@w|UY(Cw^n+9H-c9>qOJwAl zvmpXE9SEfSLvTI{x7QiLWX$_a-_U`G1;uvG;=WXh^f~iBE}>`dna8M;3ApY;7rS|j z&D;d@ZsRcRoX#D#l(CS^eKwUkT+@!pv^eTMf$EOq7v`N$vVBJY@)J%)fhEnoofOZX z{6e54&-;X#s9QSFArJ6X|Eq9TA|(_g)2+eB#)ZxwNIdKC{(AvzJ1)--2vM3)lisrG z=SD4Bka6aySrXLtKhZL;NK{aQHANsf(3&7)(AT5ETuv%Qob+cknxeO)O-2aj!Ddl| zY{f3p5ciGGR%;C*h{#NU;EfTkg1>*}sBm&rHvod% zZt?B;sE5`WW0Xz|5n^`r1}&8W=>RQ=_I3P?T|u~NNH5ytB21)WrV>6(N`2AUMsbEY zYom=FTVii&d*~aqpJuH!PxU0VbTByco~nLXOQ)LSlrZ>$)M!9AURAMv4 zP{uwaATMb4mJkT0aUQ|&NtNIeNdL}F$fN3@Pnvp}eRegvfP85KVz zqgD**lsHX_x7qhBW{nfrMZb?`i7gP^_7Yzv4AC^2{ysJQaN`}gnl3U+lzOioh7c-=Rf(or(ke}En#>pEWGqI74pYLB%GhlfEvSSj|2L1EJGcP3#0Sa44N&POADVly)@|?7X69ol8o)H)WsA7_08o}9rZ2u zzW~AX`-PH`{kwY|G4nQ>cI}k4N6rjEzel~&Z_nlpkw&eG<-Xgo_FZ)K{$R)yG9O+{ zijU*XIUdhA{q`Kj(71_f+K>hUhJUd`I$6cCKlRfs}F-(P8!Fnf^!bf=o zk8g8u`kcpcJ7t3+pRrY@So3fW^_+$01JF3%aeE4>mjc-08QIu<^C-+ksY_SuC;{_KwyxTZb^T+_C72D$Y$h%F?Yh1n{6Yg zbuyVBF&J{wm}c4%;!nLnon1$+4hy4n>oC9}Ihh@;GS0U$CbzTCog9rb5vEo)f;KX8 z#OvQ{Wt+o**&Rb!Hl|3$eE?1a0XzwpLf8%cWzVJo&0GJgS=qj>%=QCuX(f{#l2Mbt zsa3(@)}xB%<8|dTMP(GBR~wzH!AEtpd)5I1+Z#-VD4;U zloJ}w{+XOD4rsuBeGH~^D<(_kl7^c~#;;ed#>OHuMQNsJ62l!bou5@Yymm^0&Xi~* zs}fL|r|6r(gWYGY2AFZ)Hoc=B&KYG>N?GI3*Wft?orQmj@-{8m11ocQGUO%3aT|1#LVUZF~2^r=#0Dv9mQ{12m2VV$? zv=*afkY&dQQp=zoS1(5j?Nl8aBppn_p}eF6NbjT7#;W#zQ8o6hoenTG5Kw~>M@7~d zD-J4(rx&U!qzT`DnL9CT@wJI1GeBKL0GOpN>n?{_zGrb3*; zMmSz3;i5B%9f1FYW(w2>9!CZ;z*8je8;@7BWr~g0B4QzI<1mA~7n)EnACXi?_`S(4 zYE4{hy!^Kd@H}H&@EP?4iBOD?7b?usaio2acO>`b&@Is@nXF+)b^NN9fyzLt_9HL^7h z8Os`xEE#0C(>uo0ayb0K-*AbEq;ljq4CLrpZpuJQ^&T3UUD zEQ8W300;?K#5HqLe0B%4#yA5`7OLF;Y3u3=F7C zyb0*1FNNQlOYdVkSe z;$oB9I7Iw%K4f=#U1gS@Ol$c@X>V}4F?Twjt^?z(GB#em6{!(mRlFn++5Q6}%duQ( z_gBpjSiX7Kysf&R(-yNleB761A+@~7cGmtRM_p-+J=YEOIgRYlG3*FYHCYryrMh_v zfKx3pMCQg#(p#WC4y>u}k)mpl=?)BmrJ1PdVpnamC+$sa!kpfO)tSOR&s}5=sUAT( zM>Mj;BRyMi=aCbfzUrF2rq;gvF4pCg6nlcFI=_l~C%ZO=g4yhm;h-|j?Um3ihNx?N zSmYnXmXd4q9%&V#Hh1R%&iWa~x zno2(4<|M`V#B44i$w@5*H$xeW6_ozU=2VxEE>)eb4`5)1r_K83ExY!h|GCLIU9*(; zRYE&P)A8*B-|HG8uCq=w2=NP=7i3#K&J?lPIHJlM7|{k;`E`{2Px0N9cS_g;-b0o7 z(d-bo7NkEp)bzy}HD?*IaAub4Sbx_$5lEna^ntP2>YD;<$6XRf#Rl})y9$c$5f_WC z%5!%5i9@sOISTYDjv#9-)V;#rUNdg@oKbN2MXbHE2s72a8)fKfU^Q>ccl7QNVTD2( z9VZ{K(ED~&-?Kr0(e3GTATW#o^qT=$pA~EU${|w^`Wr9Zy7X>v*FM1qONIXxc4iUc zKUpemm(P`wmewJ#s6WUh6h}0&|BY+~T&_#9ndd*?yp;5RtaxCyvDPFvuat~3M~cAH zsJNxdnh3HjVmWYR2D{f5-h^%4wWr$sG(MMHCGxm{QWn&IRCntlwvk@~5I_1BRYH76 zgOjHF$bU0;t~nf1HdeSPPMTzrjidHog)=g9H3*;-np*A(cOB@DNndi(dR&&_;O`#s z8iGiK-vLa2gWdwx9AkRzS0NE#4z*Al-qF5ioz_{5jf9d^`u&P)#Y5 z&tQ!gv3o81Wd9+g zGr?XSNT;Lou>A#lg-ipVFXw{suOTQ1T#Gin2nye>XMM^~e}NJUi#kDVFbwNK*LNka z7-bx4emuFQ8HQf2xyc+|0R0&33%9e6?WRP8;pi{H=XBnPkLhd$g=x)?LqWN|c~JAw zD?in@VKeBMk(A9%{lb!2&3gS?+%+pfokHOHV{N%WM?8>o6kxhsX2z`{`pFR@YWFu* zk|4fbgb+Szbwlk15pUD4beKPq-u*0iQM#R@yarraJ1j&1JX#B-1ZP7=>9A$QMi9VsO>Efmg4NMFrM8D<%WowV*{l>9*ckd{8?{CRa$ zn1-lO7pc@vlwav^82PF*gP zA$rZrW3~6^jy5BU2UVpzBo^L){!K>F+g~Xq6(uTX4xp}qi*o_rH@@GbgUdohDVlV3TT6=1Y9u?&s9GJC)2t`X4-jnKcUBQdr| z3z4Dh^RJ9J*1fxey7H)%sG;KG2~7o}A|G{r>p>NsS0>PZbw-7Ph#y`Ea}va6q-8UG zy&ew$=hb2Px*58J%zd)JrHX(`B>b|Fot*k#Yz)|M?hOi*)nQ&8>;NB;Dy!ZHX9CO= zJrD}J3m&BXL-TbUvEU}sM^nT^lmk2nzkCSAGmP)6sES8ows*<AaEuZI}L^4jwD#{|{HOvHwr&bfb6mpLIh14FH5a#BsJE@kMI# zzAu_xO0!6B@@Q7DwpWPC_VQBjNE27Ne(!k(fs-eLknd{0N=+1q1<5)!txq@xfe-X^ zeLj$Pph`rQrOPugP)eZCT#IRoQ=O#5ydTRy*c+Ul-7)n4K9rf+>*S-*&xMk#>P}Ou zIRCi-BvEyfe_Z-aw@L4gcAHWsRoPGta23F$tpKG#x zTe>A%_4tb_1GB1-WqnGc^7iqcQA}ArSNj3WPg4*^f8bb8_v(zK4d@f?9GZIhdADhs z&5=sARY!Mg(TnP~=aO1`Ih|Nrh~NAKjCL#lG&s*{y?wG6cj~%H9FS6~&_^eyQlXI& z#ZMXQU6G=Uq~Y&8k9n$^4*u$&v7W<29A>|181Q?m%9rj&AMHtzj*6kyR8ck+!a*3w zr7lW|o0_nTO-jc=k>UClkig~VxIi?B4|^9L?MSQm)G#%GXjYG)L-IT8VQ-!Ahegx@ z!kK~7NHn;MkR{YJUhDrNfwP4-ljF%dAT)!7{zxCmigdh1|96&&xhOb#?y z4!Ol;z~1r<)IZyadQr{+I%(|zc*5iSm7@JCS*z80w7ir7zKCp&3pO{g*-T(N^P$jQ zE2*99u;t=kXp5jjJn_7ZY>F44U0lUuHES=Oa!;|@NZrXhgK;Y;-#_$Q<6=P9!qZ^lCj@ttDn;A)Yd9YVkQz*I8kC{t0=k@{sW~O}^2odC{nj<&x z`G*`+K1fWSDsEk_n_@??ciK4|NVBvsHxEz_gl=dIMZpt<)t`RK!SNZE9_Wk>m($o6 zoZMBuRh3~hCvWQC|pH4`KDQ>7N3c)(PP#seclw?wlJURo?)bP&b zQCv>~v1wbRC^M8{w76e9{u4K&$v4oVnr@#S;*)VVOeLf>oC0jHP&H9A^0!=Wkg;RzHo;86s)gM-K;PG zc9xLH!gx}BeL*u5ReXUQ^^YT<4=?hed6l#TxypoNBmJ_b zQZ0;QqO2Mq1q1yg)f7z$LM@s&c!0P$0rneNCIr+(CYXO01R6ZrC;nVf#FxJ5Tb3co zQvV#N6z9)#{K~_iIR69m&>J_SYW?X{n1<-#iawTr_n`LIVuCFXI5CtieR}-2V#iMP zt(IM^TszAY$}Q%Z_!v(yF0(Mydc%c_<(90oH%A*Fsz}4&TmRO-_>s6dS!X877xAyQ zr5dF5G(yWTqh?MWO-WbixE68b7Mt$fpUudTNq5wxiw3ftU8jdiv=|h(v9<#i!yM0u zaG%UFU(dUTdu}_L*>xto2^4o60g+o8p~#^J`yk+!n+F*i{|L!XG}2&vr(_1d!oE8q z>Rli3!gSh#hI72DV~4ma+d;Ntevc~py8}#h#^sD^Vf=-+7>ycU@us*9^cBC;D*k$| zm*APW(08pV3#UmB_L5H5Z5KCMzgC)(^Rn8 zzOzcxZJ6UC(dvdi9?mf6v?2FFHT0~&daXPm&`C`8vf1USO zT^=Y2Qz%Rgrt!#fHHcCn)?KJJJ%t7pK6ovH7{hS+Ej*@QOK+ijv@7=hYTAW zhYGqt7I8B7|FB+^A2lze+sZGD3=c?>Db^p(0;z)edCXazCle2J<}jvB=yK!Va^&=cLH_|%v@z~nsgq`a6O;(g z_cf6q@8kl)gBn6|!HRIUSo$A~ z4QO=l$(J$8ji0L^6HUoiFxk|gni?w2eNWFY!lMjV0?CGW1p1gt^z>xGDxIA<_NPYF z=A=p|PW2p!kx#&SvkClyiVTFCyEC``B3?FSNo>n<>VCmDvCCOOD-HCfQc4b7f zVkcJb0==WA0XIKZWiLpc@g?+#F#ul4>bKhi*t{)^o4v>3@6RFov0OJm+~nx0B~7~E zondK(1=&y+HJ9qWRHzqoS1E@lAYmCwK~*ffPSFxHC%XAaxIjK}Pf?;gHkhDG#$dl& z`}7M<%RXNv&V=0uD?}HiH&X60_2ZF3b&zYWnIi5^TIRBPDit2Ktf2&lq;dD|tvspw zsC=o!w|;6x$1sIQL^vP7bmG+yW3$90yBYdPNpH0e2B{^S66x7H$Cu68-J}CRixkzi3YI za`lBM)BbjkJD7pFO#x@$t9u3?do^*w|?Ky_w2@ZbbZLJixa*K+IaymI@ zg*9XWiT1P-I?%cD35t$z<7L+l&GnG71ZtoXYlkPZDAHtA=G+ zZ^7<|Ql)JlYqwE9=A42u)~i#FxkUfCeD;Cd^lJ(Usj8r}ffLLR7d5s^x+G|3>YQ-~ z)o<=^%7+0$&~`js8;$krcNrgWD=>6KLK)kuxVPy*6mRA3+`o*BruFl{1cUg#wPi2- zI7oq9M4JHg=j90;5DCg5w!8R+;p2P5#5d%-w8MARxxBJ8{|q0^K6`lHn_%(>XwtzMe7pV@CA-tyy~ zF*I_*PP)z#Qzx+jYkLk{DXiWK=;bUVdT83JP_$+5fRLB zCxwExvn@4V2 z&h;0weV$q;Y?;hLsoue82iGG^##~iv`9{RUtuy&QL5_{-{{%S}rvFtR{O^*=aZ3W} zze_5kEle2p4qrn050pY-oI+up9^oJ|Dy$f3t#c=;P3w;<-WhUphCVdvtn@s}s1++q zk9kLn*Qxg@M8&EoCYxuB0G=@34biMvXQphhZb0tX~)Kly% zol1sjI9oDGWaa;2>m9oTZGdjg*tTt(opfy5wyjQbCmq|i?R0G0w$riQN#>b3>&&b( z>-`7yaqp_VuUc3qzDEH^1d>smSUb7$q+oT(@+l)A@RwRQ6nCuwt=*BaI^kV!&D}pf zJ0YIpG*-H_yj`?h&9vdU&$Xec(m^9iDlMLi^qe@o;#>u+1TkrNXmpSZdLMUwU#wY_ zOX*%s26`!PKIVCD|NQmaR?Qzi@Ta^QXtzb5&*<#K5pkl1vV2l}z1v^WHXw%aRFZrz zrGw}QJxmG{7JSBlh!lO5zfKE%!8cNPXwq7FqzqEQ1MeA#M~QtsU%=$Ph@pS^^H0kx;}ecwG0FuU*va~n?;-2_fWl93;g;5) zzQ56yo{;P6p21em!B{D68oKcMk^c$@OBpt_n)?b)%6udGsX75{t9p{|@5H?aRT$tF z*N3>o`x((?AdiQl@yzf31>*DSn&*<4mW6H}h+RyP;`Q0CtgL@TA`NRe1WMDWJ;ATjHzn>WO{<)L{t=_@&Cc`XBPAh^m4dhnM93#)q9{z1#GXuAb#&$kBhHh=agP6V z74L}7XH&J_KOp1dfBQU==FENI9PWdqxr~+l`=Awdc2!Lxl~ads(70W*8P3=kwdL-h zZOHWsJhlGZ&U!f$Kl2ZPa%?Km$yup8w-|p8)0{Nd@qKGh;c1A4aZ#d>s*wh(DedDC z1V`bu^=j3sjq>jK4Y{@WBkbQGNnDMc4BZ0;4nvn-^Lc+B8fy4p@J2%#E{(R<26Bzu zp?~r-hhy@t>;u=ra$ZO(`<~B-wEOAjm8O#;5Q$~iNm!&8HHNQmOaQ~uN8q#hGr{Qu zV<7LhANm+9oC*;kr!u~P5`VsnC<9nqlj~E(TrzH0>5}N_nQ4E;r|vFI0!gBhY1!ZR z2J#_k<*6N0H#U!0|FL+JQMysQBE_Ip#HBYRnw?~8<&_}J@{wVmGrDa+yP+1|o;|-A z2wHLfT&0It?P+?}#oBJWs3)a6vP{8oMNX{z$Mk3C_OG=pwYdN$q+_*GM8 zCKrYeMq0VX)g3 zXJbLz^DS16-RvR>^(dOC>JX^6f%@ba5y`Clk~DBie4ya6UZYmBO#FaypM_ggCK0hNh)_4 zoVc1hYvc6NICk zUPWk~oK)SE*!o8ju|s|myr2-F zdK(3yoA5cFB?D{vG~wVa!h#TCmSu7|=-Fq3GBigIC0ggTud`A$z*~`GT$fjlA!(doL3oNd{2vS(JTehgP z703<38daj+&dNtIhsWf)YK@6YQBa!-&Zlvr*0QI0uMErm$#DW34639U9BQ7g+l6WC zHUkqfqK|RQ*%_nsR(5=>j>LgZ!ra;ufkPv^o)LU2xNU-k*^4UED)+M)r0@YLb~H+* zX>-?}N<4_WpX4$sOaFt$_#Z+zY&@*&|EsTkr6=pUIfmMEp{c}OuaTbfVye$;R@Jp$ zY}1-p?b4`E8y;-0CM5zTJU&yWIEx?zx)%WP8h?3dK!HLq_4sJ}e&KLCx>Ur_%$7z=5HFhZ`FR2# ztv5hnDKByE5C*w%dfvH5rFQaQ(CrwX;SafrSe5UFY_#-Y!`Y_R^oC|BO%I_AN_gOB z2x}gfbjC3~aM-}w&*020-K?$YiT3TSk3N$N(|R#`IhcA&{NwmH2Q76lS#3&@q3YEc z5JmeGl#xwihT&lfNtP^U@;h0@e-8jEm8)4J$)#zXh7ez4)h-um#Cc5!a9%m)^9Gtp zg~bGxwF)<6=_q&{YhQB+IY|+WwSJS;ME8E*pir`kL&$zO@?S?}KZ}4lPvlu)@o*4J zCO7#g;jUqdLOnk0)n1-tW&M5{(~Xukl31e!=j~5MyXMBe9t#Cstg&ku8~_^U!(IKP z*DtI8GF@N-Nb+X!sE1wv-ahHGW>ZG0xRSztU0)Ybm~)>C1)5O=ra6Tee>6%`8|$Kb zfLBPk1Ec4un!reSKSP7apNy9)*daw@RTo)1sXT;6pN4VT6jhXD|20le=Mal?1hFnsB|) zt8NC;gc$RpPP}|(?fS7fW?lqsA=a8l5HGq!s7A2O_C7_=uF{L>mU~WPkLhHha*j8Z zx=7RlrItrG^N;UdrLjpEB`A16Pu_2Ty3s*yQnYk2mCDKNn;Wn&egGog{tL9s+Dld| zDi-gN;9koCks4N|u6Rpe?=HS6C-=sR8^XBZ&`_$IF zJ=rK+?Xi!MhFx1XX!PY}^E4_A7OI1nhLBmr_O&4H{eiD(i@?2aN>RowG5c%NT9 z$B~*X`SX;k^`MCzS+%mT*@+E9`OM|VNWj8~(@#T7b*|AJy8DkK(VQLD4w#s&fjWvE+5s4|4*vqU&?_Xzmr%L0gZobq z$r0K!sXz}4_72)sGS`%9$KcK zzMT4F=0^BdQY^F7JNn%{-S2MZxPjESUCr>75qlWc026i7@p6`@7h4!}ppMg{%l+R_ zCPtIxB`BDvaYxPXw)c6gz>Q}15dBawmUj$?xqL{rTj&XgFx!=Sp_WlF%7qmWScZaJ z(v$;)cp`-oEpW9o=@J5tK5(7tXIp1mS3_0?s(g(#m0i%09}v;_!V%CTOk+N74aL2= zWsa{Miz-H`ocF+=05aYT@F=Aqe~MUuqIQWhMPP3=W;^j18nI(s$w;S|fT(r8`LcL5?K0hJJ43)WS+Oz^%c(@@1OgnG27dYo4s3e)<#x>`5aV z*Su{RR#y`Czf5k`{8Yro>?>bQ#3DS(O7ZJ?W$P?fIg;B-uZU|wy*3i~mS~XlT??5=qZ!yAtjB*Z`JEe0q9H7p#AX;H;5_ZS{ zeC<<~TC{HhL8soloKc|0kP!Y#FoAiXx0d38csvI|&O>93^%pfee0wwYZ)}dLjw?rpI=YprWPvNRY)EOKd+S)igGiaST&}>J;;qL@pr0(}vZ@ zceW`BirRnBAag_(I(C}ig__^9pyE9K}p^@((MsIP_Fm5$g71@{cwJt zP*n>S!C6!_?xN_-x3EdsuCIWA*cJAwf)z?le+RrUA0VuY%NzncgLR9zxdIRX`3TpY zOk2IUu@4p&k@Ykp6LS3ty0x#MdmXGgSD_31T6A=KP13VqafXOCd^4kmMbJy#wmYI19 zN9OV5hnWUbj~eCKll(3}(gqPAYAOGPP#0d&kJ<1d9Eszoy0q$V#u*VKC^5=r0+@WI zIL>y$53tP3Z2!2HhIgZDk!jUgFkBW05H{xur{m=Kp1bNoKU_)Rx6U&tDj19oy){)B zHX;>a8-ld8xC_6m)51OR@ts-o`o6>>s@}ABVM#I3Y{TAL)QvGs+B^?uPY=u zaB^4;Le(lK(`vMLDSsU5r$_gplV31bYSZ#uq8f43^(9Sa@=&;c!7xZMSc- zg}91#8;`KUP(>qve+&SK^ssc(xm3FQ7l$~`qLOBLit-%Us^(0fY@N3OM8gexqF{`Tde4ea}eIaaxO2mhY0zF442!PTZfeu>3Jy8FnMgT=0NQ`(ia z9^KUBy0q=XM#(n&dvi zr)^TP#XF=*Dd_C061%lIBmX0oJv+%jqGb}$)g9pfm+Km})h`^$LM@VVU{< ze0SiE2Oo_w=3dmAs}z{L_UiN|I#%60J7lV=^FH$F_%AZ{)g*6b$8hR<(F<06Ao3zn zHdQ9C^5-Hs<0b+ioi}aKQuBLb(OkF&CwpQRt-e>+!)lTLF0grO$Ux_>b?A`RXgW`D z*S51Lx#*H^twU>TMYE88ib5~GBgayh*Gr1CpVBUUV5o3qC-f05oej6edlkRj2j8)4O8YaJ_iu9E=ibvMn~4cY;QfI%2)onc9YdYfAfiAZVSDxEGX%ckUgjA$)!E#aEpZ_p8XaLvu~0taFZ=atQV0U z2vcW)hFmI8#q%2S&o8!K$R9-9J$^&EF$|qAzs9y;9Q&ogr^`1 zRtY%^gs(N0+cF**iXx8FCpo~_SWJd9X{djyCW5FnYxJPDd_q6Jac%f!Jy^yhJ$I^& z1Ys<$SS5#a8O2tQWI0==@+zLLIIEfJoniFnNVrL5?)eRFB!hA4DUHmkYVh5&4fsbB z(7vwH*wOTaP8CteHi3-vyJiYu-y=Xxl7@gjY~B6HD3$%I;biJm8>}q>`#9Rxu}rJ^ zSrorvpFy&QTm*J4$-^StXp)^EOS!NZx1S3Vfj`FH(2UzAU<`SrgWeBBD6I7Gxt?8`F$nMD8be*r=o$A4K|N6VP$`%b4Pzx+ z&X$%!F;6YsK`$+Qio*u+M-1evou!b{KuX|}0`K|M+@07ru}ykytqabvQhwB4J7xG9 zR;!*7dw+OVaTw3CDs{PW%Un?suo(~&{Vyy*B#vMwj#5U}aN~*}DvA*xRb%XT-v{F! zW6?D}0j{%V3NHgBDQNWixQbm_!-~K<&MWLL;?cnJL z*f+Wu*Cc*CGcBePiLjr#)~n+xdx@^EjKXeb=ruv>+c`0}=1;={g9TU|jsEapMtWIT zaJ9U;+MQ1+YWPGZ@%>HJO|9T)TLF19m{EU4!~)WheC&3p zz_nw*pj|SQ*nVb=M|$rJ+YnF8g|#u7(QmIZfk=377{_rryxVcN`RUS$8H^F~X%+9h zXmklo1Pv9<>ulNJs4lR<=3@)Fp)RE|j)nLG_bu=arxyR*-_! zDR4z?3lW$M0$H<;2~zr3{=MFJr8Lx2F||Z1s?z|&VZI-|aSp#nYqvk4oG-lf2Mv`& zkR7-;Z*5xXh=}g%0jTGhu_nrfL;7@_?NQ~~RnCMh@amivfz0H@j1&;p6~}Fxm$KaM z&|Fr;IVjW!FzFF-!(vMo)WCAP!ab{Mzl6+^T!z2QTKQs=5Ta=VEnb`RauR)6fq#PS zS=&stO2}dxl(V2aD;K&wSE^2JuC^U(IVd-nOCNP=qZxt8v_&Q7?xVRv-?Nhn}i%%cQ1&b`tw0Zxp} zq?^Pco5lPNs+IA7xiX~b7_>PbbCc|H{_O~QxJtPZhiim|(FTG_L@%ggrBrBYQmTI0 zA-Q8N$_bs}0QTmiODUhMOYT%4Z8eb6M=0Mbfs?w?={Bb%q1)BWUZ;zQUPP^Lc9b|* zej_KWw)!Ok+~k0lcm4>44GW9o-eVer{MLptN5ece9&VbYerlA01$m>EB-YED2;7W} zNOF|5eA=tX?rA*~&2$-km?Pu}wKQ8R7@@8Vc&zj-&_Jmqn4f1f{fE$vf`_g%2ZZ8R za|g-V?^&xKE3u&)HxCiw^a`_my_4@;jFY{R^D~r$wJCqKE~zq`sHVdPahob@vf=WlJT$g*|4j zGEKZ60QkajjL<)O5E(}n=OoZ?&Gb!BG1^W9bKwW_x`)0NH{-mE)Xw`K7a29k-+ip+ z_L|DaWHd4DMsrHFU2e!lJ(xC1qA?^Y@He@zbnG~Z6Ffe@f56uGYOR(1>L~i9KLfkn z#)_?8QM;A?$;a$^$-@J?!4JE%D_ho}b?Cf>1w2&xtE)j18Fo3|S9o*fj55D1`Tk11 zDur8x<^^N}%B4JrS_moP<#cO&u4yrbOy2Fpi40uYFYLO#)>4NLT5mmiv;_p!1#Hf5 zsPF`Ry|R6@7b<_jhiKDh>Iq4oho9-)`hBRW-xY?)vsU0hRvK@f)DGEZPhrBBm+1{^ z0{&5K&pmXvGE~2Y6wsntkp^CuKF*doEA9taQd|mz;Sw4a(*2I5&0r*u1G zOfVTOD)*HMAj}8!XhVTh-IRv-CC1k&h|FN#Yj^2-> zZ#4ws5OTA6+1K;-b@dEgw z_Wk#~5y+dPnPoqtpc-dX*^(yj-l4wOUZ)-m&C)&@W^(c1k9C^qm@C2wc%fEe?C*az zu7#8hdwApj+`gQII;^*8A4qhXV&UVi>1~V#PP3M6nrg8(Q_PD^fc70A_IQ8O`xb9+ zdAmg`8L>=vT){|$;fLj4^z>X6U+J>rx;WA&q*+o|1mw=j@&nVgfYZWnpkY$eROdEh z=+$G&cx=e08-m?(>(18zVKTm)2fHD35&`5ZgKPZ&h`x3yu)8Xh%R`rSmcC7hQhP1}fR|1(VL}XDc-_Pmogi0Y zH;o@sZ}o>N&3x%%9-2=Eh1b?vpKEI*Au$X+fkn7HEf2}-=`W+ROw-ltl#f8RB<8)e z$}_qThNa+V*tW!Xr;b>QeS3>t*80GrP}g{A1*Tm0SrH_lI_?aUmP?{kqAtnSTc*nr z^cn1zp}l>MD{QDX4kx&ZRm}6xV^z$JsQdQpzeVw_w7!dyq{PAnzpw@&S~Be_^U z#eb!~{ZB(!75$pp4KxHQNjWv*RZD&nBseNi-sck(h?-%YZ;W&NuCey@IlQ4l^}T-P z1%=3ms$9_mcGvb)I<=YhvQyT;vikJi9#pSnp1y2ARqF+6{LY}=uaWyA zS@<_9`)A!yU}s3&*B6*Rqy5q-`OyIXJ-OrmoW%X8??E?xe5UHh+cTL%(|V!q9fGPNd98(>9n29rMmF^^wc6I1 zM1F4oa(OEcF1l$Quh*9K!o4B0ziaw?1UaZE;Kixde()iX&}ETdHf}d~B-VSJdIp|o z-7P8kUb#XLMn1Sq@uXYM&v-R-)vtd#3gvril+K(D-e--ji+bxm{o4xMiK>`P>)*G_tJgK} zF*|78D|!@KJw@%#NdPyncwJvff1gu0rurfC>H;2WI45J~j^aEJu|4-}X4f5>sL z^KkvIK)$}L>;G#I)p;V z+BXr%frxHJcYfQ52#;6mnPdCnT%CvTUR%*6W|2nfSRQFF5 z%LZmNS1*=n^9&b1!X{_S6lT8NI^uz;X<~ofd3@gQSv15MM}KYRx|<6}2f>9ZF9(-j z9ep>B*P2f+lNV9%AJpfT?%qK^JKx^k0|otSH+?%g{mStqeE+NVI6NSS~a~oecN>NL}NNU zcXAL_c}I%6951*QrWmLqLa1udG(<}#bTnJv1vptWY5&<3VP^c8FAC@}7(wclb+el9 zJKxF7eJJ3X7W`sAoN`SEmo z`u=%!d{`H?$8M#}Pu5dI{dV7Q9W(uNXIt;jC)dv|U4a@$qAaMFD%UnZjQo4Q)c@06 zzZ3X8WA%ctC_JqF^JDzD*TH2%V)Q!eVTpDu48%Om5(qf5t2|=BCm*NcFVGREI zOtsCtJ9+blRj~4HY0f1NQyqtn3}VCdn0Qre9fWPD$w3+v-T9DbX?cz(qDn=vB79qL zy0oVE&f|xlDOkHP8008`M8(p0rp{I4Tb2?}R~wfHk^n1BwU+H3>~>{kEU6P~uNgmt zme^L#v-nqS#5_1OW;l=?4-s_b>7TV6yU%UR&>j*sz|a470}Be1<%~0+sd1i>(AcOq zHB+Y`_;1Pr`;{C47v(_J%17K({crj-ljYCce@^#|tm2ktB9U)2OZ?`QnKV@2`JZe4Rh#^PoAxHlm)zWY;%0ow& zCEv?A19G=(Im#JQHnO{ymd<3(&bG!Mw<@^FG;mK1J;XeG#X8tH2H#LC4jJ2-(tM)F z9Af_xR|NiQTa&N^GE2<Mf$N!YNTK? z>?VE}4AxU-0$vd=tW*{b8SW~0V%mS z#{JPi?j_>?49lo!yWv7Ag_gwAzSB!sEC z7u5~Ai21#S_Zf7s7Z#KhN0!#pj;?+F?jd@QFXm2hVt}A-aqJ75T$SPTv9L^;d$+CR zIX?{m(`>w*g3pjTpJ07hZtvxLNz;N}f4})f?+In;hnQjJ{0*)TyoL|Z`?XaDCxlZ0m$5$jM);s9S ziJd-qITxn;UR1Yu;!VCT==94#U1%oES^vnzAS<7OM}8^v8A`N(V&FX--hjz%*Y;M; zMHxW?bI7>aA`=hU`k7`|8``}YdR?*;L7mPUeT^v=4%~s0#X^{P5P@43kR3ITWoZ<$ zJfYbU6V3@|%jBRS7_#kISfV+Ra}@+lgeVX~7<@4iTGn+J7iPgxz9d5TL`@An2Ha$z ztFx5>1KqF{sFu@iw`L)!tA7F^n`27?$=z~*YB~mlf?#;vh}to;1$@soOwMHD==aU)HZpWNr(A3*d(aZR*yg27kr5v;v^BDD`Ra&>c-n6ij^ zYN4J`nt6(=k1qm~Hx}u%dTl@zM*a}R*!i@QdR}VB6SkKVP2S+;wA%NRTY;Z0==lo3 zf%;cSUr-exRLQ2fl$JiK;%bG1U!S|NSd%pS%5BCTY)hZ!DM<3_c7&NkKS0XOJcoWx za#BY04$TjQom7ozsVw17uV94?xmSp;ZgpJ9DJcr`{3yvHPEMXg>SMZedl;X)Jcf}; zg_w0a(XxtYIGkljqYhkXZC@j$4jM7=fXY}@UGYcmy%eJU)`XGL3C2#Xums$(os|(^ z`zVVcaZkaf#aL03Ne==xvZ5^s5)YRc?gA1Ic7j6kv?f9Pfhtln>$e1#$x%A65X$Y> zTW?R-h{|q#r!~3JF(j`ATHx34H@JHq=jX;@D(lDZfcbx*KTkEgRBPhQ7 zQUIQDG?;xPt|?#-wU^vK8`&JeVwf+_YA%G||0cNcxLS&V9$fp3lCWT?K1U{BA>)t z8uX~W1c$)J`=V@Z(-IaGMLlxgympjJdgFg+HpYMJ!`eu8)K1Bpqm#+SAK0s;ciKPiVD7 zel;NOf9Moa=7Y&%BmwJ3sb1Xi<9Pf9lw`7)T7~I%^$6*n=qkB2Vp6-ml3QCB5+?6u z(jLf44KeCIO>fD-z-P^VW4~~!nsvceFGX$)OG%O`BA%*!B%XG1c?Xp76W=?7$gygy*Y8lBA4YZ--U>>D@!L#nR$NZEnf5ui8(QX$j0O~Qt^;&fUR z(CNf2<2SN1bC@7hsk-1U2IA)t$8~Dw?Lp;jXxr2^h4?5X_qR4b;^2ZLs_(Zi{^UNzTxR=7ZIV2rh4^fq z<>hWHY|?ak8;Ypx`WyY#8{VVWP>+o`{OQIyuMK!$8sR8ZQjir`gnyUH!epTzKb6=k zeR1iLwsm}Xxq7Mti+VX!^@*=P3|OVY<^e-ro!!yhFnI8@(4G^2E?>_FR=+A76&S`B zKC+)*&8xx4v50Xthx-vt`?`+r*gv!kSx*K){jd~QEs#zuLpS~C{K}vg*cwAeLxz5z z1q0XQaVTC4b@5HQIg>3@PAyLou8jKGw$3$!j5=W1Fm1e6uAGq~yEB9;BnrhkHi>Go zX%;$(OiP0|4;JGRa5XeyaHWo^{Zjpx$yW2KfyWuC*&K@pNTLHWU;*&VNc>F8;fZe2 zmDyai&7008#4}BL3FiYO=Y@sxf!FIIwm>rFnXteMoph@%0o6gmr3=5*c|BtqvP9Y&cZ>yG4Oa|XOM`U)4=fR z2X4>K?5)O)<(eaPtE?L*2>Fal?r9{Kcu17Nv;=#sQ|R@hDM)?#(RXi3m6YqBU*l8+ zq~XXCSAT@RsOr4JDe-M(Yf<`qM5TuQz>Gp5SFVd`!_^i~nQb1{i%^g9{3WC8$lY~w z8gh#RV|Ishi(LaS68<69ki9?{L`2`T(8dj1men?RWJzfIop zlmatRi*H0FaJ9rrZewz<(ssKO?;`fhi4>c?<_q(seuVfwyn1{2KxDCexp#zKOgPi~ zG7k85feCV@lbEvB?oQh{9RZ)7dp-0k1GGcF+RjrybiV20vS_ga2ZR?ji!c2JJZBfp_&HagrWa>q7t|FE&$uASRv)E0UV8?FH>+9q z?%6ZKeWWS*jZ~ZDw~1nM2G9%{(Ir0#8U}hhOqtV!r!zR3{kQl~cGq{Q~+@-JAvM{iMJb65Z?^Q8%L+aC>jN?R=G8#GxM&F=rO+5gLB zv;Plm2{snq|9yy+kK5!z>AtB`ax`eR7|+;WEf7-9XWY=8@1_*siP*%E=Q^X3ngezv z{j?j+qhd4M8_%R;Q+*D8%>0;%SMzUce}AU7r7KcjnpfinH0J4QDqILKO893hC8P4{ zzT4iOHuKih4aDm%JcPAxs!EiJ(mIxR<*Qh;)k7S19nvv$ z`i$L$MiPH9Bs}OxTgdu4OP4+EiM`e)aLi+BAh48m~haYYKz-el`+>5eHK(% zzTz8{0uXaI7pctjgA=Mlv)Icwn!Wm;@p{((POv7tDQ98~?R_`ZH9H4x$1)m@!XfmI6NDTtGF`D$Vaa{%d1o|;BHgqrM7)Cp)zBnrm|0h5A#>H> zcck+`Hbv7D>+@+@xMH_H5>y8lY@QEC3;oHs`~+OKCm$eKN|YI`Zl$pEtNb}0uAdke zC?t|CJU|f?^VLxG5S3euVYq`89iX1?%NeSt7epcaIZnxu-F@VYEAS|2=8Vg7GP>10 z`ukvLEJJT1escP%`5O<@ZQ*_nQMu=PCEzdq5q@kyDu<{vbNWN_Q518n#cKCVV!$#r zP0vZdYblcuq;Ixy&*CK5kf#!I@=L=bkm-F^LL>QSwP4%8<^DSSnd}O?#k@H!Ch|Z~ z@=74_*1Bv!ZRF)T{9r06v+lq5nwT#obg{4>Z#$iXk*Wc&MCZo${+S2)Loq8a^S^1V zCn+YOe+98A$8|iI{pOG;86#nIYaxtWx1vqy+Q~9zR;gy9w92ZbNhpcfw!sCT0KS@A zKr*3?cig+`9)hPx!J|W`Y-U;m;*ztbp5BG+L7%pTXG^Zyuhc9pxBH<=V7Jk_@;P%} zu!;T+i3H|pDbXy|8hX_uZib5Uy5V$H&b^IW`H5vkRmX2#M8bD1rE5XL#7xr26`V)1 zlyZq-lI8q4Y8*D9%v6wG{$#CN1|}pb%64iNO&T3cX_ky7k3_LOw%TY9WVE>?*)T*x zjm{%2xcuTeu>3C=Rs3BwLKjTiL25Y4%xM1Oj~_aRtr)q*mqxQMR=h>9DC~6yvkI)V zk6bcFix+OQQWJNwa%IK`xfa!+y?hq7D=-{MC=*frJxMU!AiAHUIxdoB2a-&=QTUr9 zi!_2^ka|+_qAI4Fcx_7xMnx*IhXAQ#C!-S3oFbo^dP8fTd_5);qB5QK1z&?u z(k0P!L`Ev1qCszSp}3GffaA_!abEvJKHM6T+U94Khc#WaILw*}CP_dUtWaiJQoQRu z6}#M+BwYKV^WTzu|As%=ICs1eff5*P6E@{RuBUJEQ6U?=sIL8-w#85=EBY%)Cukq| zPFRjE>O)nRVnkb%=`Y!^z}A$H;uz%44cUo7R5%%5qj9^K?BTvUK>KL26MJl#{j0Sz zhlVeN(zF%*520u;iY$%Ow)bWZA(pt=WY3X*+4tU+LU4n)!tdOM$$an#!Lsd4G&eV` zkTa`i5-49^fnzApr$5u%shr`3&BzJH&((9!TIEnY@62YdPL{idxY#Z)=CGd#UiA=f z0xOVX#O_0!^fw>tz&t3@52BDVto{5!z6kJ_27-8YLKci4*zp7?8_6pSrz#K0BhZ?` zuS8XC4>{?XVdc$D>oe38Af;pkk6OrTpZD2{rg)PZCAZcdscci8TG+QeIrbe&vmb{L z-+LKQ#f|l9Srv_cpWH$Vg@cVkS1nT$bs5a)Ui4%Q9c)jdfrkvp=R#r87%?P2!E0dAsB{4GVz_UI_yCZLN~AX;w(uW!5zLOc4zTxB@G*W@8Mv z!npi~boqtR8SvgzSG8stKROrIg-J!E;h5Z3Br6AaB`Xok#*TB!8^ehj&0)?OWY`;{ zNrD!p5F4T-0m4AiUhT3AFoUQWr|7fWL+vvko{$b; zXEclt5ysP-9Ysx zS?|6#j%}!IJ_u-ERY_or>CV^M|DJ4~Vyl69VN`QIS7cbU+qg>V+O|m4LRJd>d`OWF zQ_ox6pRJdBFz~jVjGs5gq$2k$bYr?<;I}oq-@%3rAi9`D$vdn%dw6SSzm3)keM7nc zo4RQOy3wY+Hx^5lAq#7QI`Z$6$LHXk=1u($CKgYZA^-J`((Qj6D#aQEyc1neoHNH4 zgTtQKC|L8(HE*}{4=wwy3ng5Tt1~4M;Bg~GYtO8ZV=KH4k$#iMbTlP;{rN>~dik;p zzqnhR*Sz3apHw$GENtD|ccUYFnUzrd_4W=+Q%F2z;HOyKkFyw>k) z_#BBy!T;{YeQ%h%jo#n6)!(nxzsbRgs}fGVjMJg)_KErKPKn*ECp>%#jrmw~C`5*Mn z|Nph#f4EdOw*QSwz0%Ql-E713d#TIcEni22-#cJu&$0H%l3R4}Y_U}&#ybs6NKZ$P zaG_k^ysX;=|6NQO)mWZhvuJH72G`Nn#q+X-9Poa9f4RB3K>3?}wp)tnC&dn{0vqcH z>$JNIuk21~Z(djDzlYX3PJ4Jh7@agT9F?|}-)t~c1VOpu0FT)Q>0tAMfT=}%wr7kW zraftr)(K;sJZh$P4Laq2N7l$sCgr{WUHoaY(pIe)5zzjO$9NcLKvkSJv;5Tt>(PMB|mfH3+ z_!8vsh)ZURfVo=yfZy^Esy)iy!|i9A)1Ua<{ z`y|uN7@GmN(xqcnPL#%GZE%hZwV(lV^cHvjHLE^@QjBJ^M404yq`NK#C9O>L z5ul&+rH?u#PVs)=DC97~QjatD)7}ii29orKbN^|f0ET)7b-GeU`<#ZdRSpB@&+xDj zRHlqlI*ZT9qxNE9hjgL*`Ri_AODS*6W76dMNQTYm38%X^p(EQYx6X#7oa8d8L6^_a zkkGGI2k>BUy7TPc`$#4!aJb-bYHAbu0+#b;e+Wmdmyhblu%kX^92{r zY1N={0;w^fF9KNT?1@GV=#S~cZQ?r;Da{`I%l#r%xRO3mrSCzd9>N91JXVe3m{i?Y zU&2&*FPzA2?mCnkEXMe}8#jb@ii$?Re8R|G^l$P%=0v6Tscl%F%c?KnEoe-gB5l3!r+%^Q6LFDO!$;z!qZ>&Ft1@YQE3fZZv*PMwPjp)ip zh+y(0U%E(RJxZW8G4Qlv6`*5bB;uW1Q1>~Nr{YBNtbv)jV_`>R!DZ?0W;ymzSWm>c|CLqLZ=16{CVPm)=|jJoAX8%SmcI-KYL{jWm^^mV^W2zNu6hE*1VZR|jn%&a`4wavP)AukFs@UHxDw!HxCIBuT2J$@ z=WfQ!G#TVjT3?*STpQB%A_P+Qe`6`$fjRQFBoRrgA(}SNj$C}t>R}@@?gr94gxxhlfGOV#s>0cpS4^tYlAhVO=0jm4l`Z#;A`c`r1<5}u}ttWq_SoL zDQj-55?;Hlsuh7gdJ#qQC7eFb%3MOP%VCW7cg8)>cDb#Afid&zX@3D^?#7=efLGHK zkNLvjP8JNFl1;TpMe-mQyu}itSf1Xh&(D^M`e+^Z&rP@xW&$!H(Af9LXUxvBn$9Ry zqe3ut-gL<@UCz_^mrs8YemA%XjJWFRE{TitT#Zs){h1xdUvVR;xG1`(hKWm7Mk=m` z8fC|e=gne}Bn~5>Ju+ z2@j&;C8n6_h5SQoqyI%*o)9j7IpyQc^j;PuzV}^LU-ygsP{NoXh|ugeC)}7=p;lJp zW3p1m1=;_a%vur)Q>t;8ezP+bg`geUW8-$+uz1P(#G#zM2k zSOq`|L8<>KqgtMj3Mu-o??d%mIw|_B2Z|WY-NXcnmD%Vq4A?Ta#|)#->d=@u7mbF; zDJ=gX_!o2AI^gy(MuF|@};opAiD(s(hv6xHUJEY>hAD>@7>b2bF z2J&nJtE=deXD)wsFsgP#P?Nr#_@@sYcTcO{8tKlR@hLUEpJ=~cM@Sl!NY zfh{W0wEm@kr2b~in-}he1ue*+c~{zYU{-35`ZUte>Ef3)+tm1b*<8?3{a;n|2t(tK z&i;J)G|-s;C_wo70k#QYWzZKjio0rvbso1=)W%g1*YmvSj0?c=N5sjQi>ksZbEcC` zv4@5SDnm{vEGS0}K8LgG9c~MQ&*udr`G3s@NbYz!%KAN#rW0nweR-}#<4}&m%{G5} ze5x+Jl;I}|(G{uP>Zs)|Em7&$m*u>B8^Y0VRA!(%hQ|PV-SEB(v-8y#TO!aR`JL9l zzl&^A^TMRb`Up554mLE9V9duTU;IH*S1A;E`|}U+1ldQM&dv^jSzqCr9^h)(C zG%4S?n|4$$Lbw9Ackun_CS(^MB9gTP#c3C|_K%Gl5PFqw5xAJ>%JIKgwsMYvwTAx} zS?AcKixP#`v2EjwZQHhO+n#r9+jGXY&e*nX+g5IpN~Kcy(zUz#2XyuBXRXbc4ROYP zR1W;n7{|1By|7;WQ-&LKWsa&TJHS3OvM0trTXzUp8@?`6K#i@3;RoS|F#+rzFl@oW zSa1#4Vpynp0ln6KWsGt{!(2K-3FxO2)-|o4QX2pTe3T78X#O?24b>&AyLFiKx@$Z( zESIdpI;b*hvHW9;f9y}S|94Z4r#;3AqenJ#8 z2q)uzH98U($N!!)>}ttO#Kg+RmLAvwf&s?H!Nr(f5C=>NcmY?`onHuuM%ls-V$pQ; z@bC!VV+`)>>;!+^L+IazzL5{u!_W=-BpY>}`PEcH`+3=~k;ZsbYtXO~ry^aw= zac`Y@nu3$%1yb_zvN9(JLPezkMMZ_>1rN;%ZDKpyb@qgTPbf+b&83?KXhm=b#pLXo z8H>-{hCR3gT7j@JZGc#40y2ZcGn2z3q5B4ghQ1v{cq9k{G7_u6k%(r25*nJox%yQi zHr9POwKFn#dQab9NdhK9aQddEr=?yIJp$_C$L0ry#xRH+j%*Pcy=E!1 ze7+Q*sQFziEPM#W#W^@QAV_d2Ab2ELfUUU$vO}8yT!P?7V9u`Kz`y`)2uiH=fS+X? zP+oAs>8*kDd>Azz6$=g$38XzeLpvjoMmKK{rv~sKJmA}P;K~JOATghWYk}C~A1gt~ zx7B^14D5_w)Ek2x0EpJw&*1vl(9q1t&e+P}zzUq9wGliBrSupRXD81haExsr04}yV z_i6|59jhBlTOAv-3;(0kfh;JjiEa3_v)}vS!tB&s@8NFj*jWFwNOG9ZcsojK4~y2) z)BwEB&C~x|p)fUoZ2I7TLlE=Zp-ZE~!=Y0LNUjK_n|o5g6~y!rchiA|#7t;j>$Tkx zy91b+6IlT9pkh+cVDbPR0RgpVXR!Q8{XGE~A%27>y~n?GLlQFh@c0Cr``{80!m7-D zVs@n`C(=OeU7dkE+|Dy1+umD*a9l$X{WNNJq{Ko#!LuCFW@80gt58(eDeB$?? z0xA{A|K&aJR=}E@S=l(Odl#t9P*T!YmzE29F`)aEp!#Ecif~tGVFo(H zTA)4x;-&?TF8~-b8v_`{rl+R&r|6G2!$VI1*IONPgP8A?ACy z(5=jKuUo`s)*A4yEg>uqWZ&5Q{21uZ_rq=^{@(CcPpM$Sr$8xg-i4veYYjMN03iBHiU3qJW^e$;81+MD4^;F9h)9O+qr6Yg0FFrlM1uEGKBsE} z$1DKO`AWYGyyGk02oL^SpVD_ssDDddGpPUP!G(b_C}ZV!$twZt4+>_0(xt%Aci#3H zL-%FOugKMHOIPod?au|^cMFl^j-jUvIH)@JcXIFhPVnWnj+RH~q<7#I@9!_Wu{Xo^ zQ}123dsFXQc+3ySr4LY5?^{n=OzUsx?Wpl9p{buoTN7~RcRJ6b5BFzp+lzj4cVbaf zXd>I(z>@>^)ou4?uS3Z;;Q6%-zwCG5HQ4nh`WE4K@^d%#8@V0u1F5yc(ysHh+~ec( zv-t%OUl|&nzxONsy|4AkKmBixx<8*Fkw*gb*F#}0v_rj_p5v%rEMpJu_YNuHlGjG} zf3{iE0{-g9fVb*?^`MK@YV>vI$YXzVXunB&aOCjMt7k$D{m$nhcmmtDry&$b^Pv%^ zXooh!6V&b-C`n9!l6Kz%tBPoZr!*d9UkX%_qR$>!pgCwI+J9ybH$Rz3`+PYw4z=dgy;_@~vt)IVQ z3ZGG5#KFh@LEPvigmV`~J|dt-H1w<5RG*LtoTmIEu=wi(z?LzF!Uu(r;&rf6a6tZ z%1Q}H*!s8xT+peFb&*FSXk>YXX9?a@dpKtIV&KrwBvpxNr*bo!9M%zM{JGX)P-tEK zs;Z?=RG>jvR%&HBo6pOBuG+y4^@=~8iXnj~KW~{Y%(G|LY1>)8(eZW`VRskf-{s}8 zT~puy{2dnGya$SCnvClp2{v)W+V~^c`@MCJ*h^dq0E-6=N~Jzh=hcTaRDj!X3uqYV zOoI>=An@tI3$_44+q=f)Etp8H_hd8goaPLBfJEv8PdneC2j5Ue|2A8*4apoaP}R)F z(6M3+@9waCY}j<4Z=Y`!rqz8ZJxX>*4^^DefJVp#K+oS(Xb@QFJ4vY6l9gdf+UNjT@GXFBS2yi17{;Txwo)e1`V)02Q zIpqxv)3@#1=HykbXgAzFpDYLMup&4ahH55|wpVAn5PhR}S_*nA;(bfE@8=6g;BRis zmeYpfr0sh<^;k6;c1QO5zbZDF(yg)0`bpkWz|dNJ$EqC9*_P-jYO>jaSS|)u*=RR5 zuXq+$t+k8f4+W(Fq3fr{$2!TPm|wvBVj=JsP!C&n*~tEKV9ms`IY)sIoMd@N9>mrn z4;jDKVo*V*PY$;`C7%kZDx3RYq}#wnk9Oct8 zpsasf;>2Ym6TP_|k&+@S){VC4#a+u-K?@xjN$&=vs8pc%g3vAEd1=VOhmJ)xjKmMy zDj&(+qahv$+p64VMYl6gy9)ZnZIvt2phS}OMjbRjj#TcaOR)6|q~%YFnL9y8u7rjx zGwM16YgKetbDoMOqxSsrS)QbNKz!%~zy;SH6hs^$cm&U9ifJLfCb_XZUl>ei5!U1W zYhR+YM$Q*At#P)&2lu3_w=k7(Nqpk` zce9_%bMa}u4AKuk9@#;j0;{ZMCQq||NWyK9rUDvm)>!C2s;-DjErxi2`CMm5oUIS? z$Q09_x@=a+?vCptn~avq@AV=85C8#qWtucWixx@@oOMQ`8$bo7)CG=xBT0y32wr1< z%N5*+3u*d@!m8^BbpRy>sv8N%{&M#sP^* zOKgyc7ydP4_JOl}aDA2nDKh@${;j*3pv~9va_nJ0M0~W8nek-W?aj0VNFJ^TIx1pw zP9*P0aE1eYe+REjpvQ@5J;~C>wA!!N?!3)HQ{XLb>hbxjXJ0NpNsrU7dSB`@SV{ad zVm%lq#H?SKXMK_AX#8YM!F0j|RF4xMGhSE)2=u1ST{vJp2fc}vP&4{N(E4h)ri4uheIcRu-*813iwDWLHyDc`_&#LMj!OuQ(z|no1C3VPzbFTb^*8H*oSNV-?n# z8{I}Sbw}tLz=uw2F1{`$n<2c94mz@K9>WfnRc!28Jb)gIR^qLd!3JBK>IgEwiJtrW z+bqhEjK-F$B|DJ->IYH|e8z$;`X4v^Jr*{7S;EU@rd_1t;BMvxBZ?5>_KrIR*yo56 zDkynUN5gtQ7cw!8dq^t+vRqsE>@LvzynB~hzSf{6#aNeClmq}A3LP?a0h?9twRQy# zE%n@z4$P$r_fnxVZ&u|^e>B_46;7xWs{u0afKoDokv3)k%=mKui!MHgT-CFL!nYB% zTvMq@)FdK(eB3m*gxtK7mU?K`nWFx3u_X9%jm&Q*DNZ`&r)DXlepFVU(mQ)?qGINE zYo7xAsOC(#l3~&|%s1F+oWVMs!F?)f_BU4!Tt3A+q+U-4aBEJIq3_|`nFRQJrJvgS zCV2ECcriL4(A2cKzoPSwZ>U>FJ&Q2SG|SImIPM=p;TT}n>vx9SDlK9Q3qRi0YnVqj zQRay4E*O%!Y)mqlqow4@3Q>h_-*B^>6VGr9ee7(H^ev0NP}p&?MAdQ00l;eLPn+@R z21?XSn2ub&AOy_}K!ytv`=^bTN4R!ZUkbC8_&EpQKHkccfpe-Q2={k)23if)F(P4= z3I0Ya3meCORp~y99fiN^X%MEQ7pf6afK9J!QU>j^8MZaTx89 z*V6zTUV>EZN88*~b=R0Aa2IxknR}hk4Kl#ld7lP9H4kPvxY6brVA3B3NB0fvy{mHN zWa8F*uEK4`vb>P=J8$$A$2V9&!I$^?%lBq+02M@$RB@A_S7g`c%SPBki-B*z*B2qQ zPe#hQ!j_4#zjwn?qM^!H^?@7}$~VbEZodMwhRT&eM(tcK)iIj7@st%n9n&5kny@$Yl5^Ayn~R$^q+Srmm_+zA)ogc3|w7Ig#I zd>Dr-EiXSR^wP>F$gSlpxBn_;IR8q_p0>6VxN34cqa)=^cV!?9wPoaC`Rq1CS4KmD zS=KCz?qky98qFSO8)zl;(Sz$RY`YrZon?kB(0|6pZK_sd=qimHoBoQ1p66t({lGiu z2hdJoLt4k*jck7<6ztollOd9Tyh#A+XP*tecJ-H|sVoV&?%dLAvqWFoP&5wS#p7R6 z3dgUBX?x#a;RrgOxx(kPQ)+co(I--7EjR>bLAjTsAx7wP5Sll8w8P$x1~2_R(opz< zxCs4-q%A@)H#b0=;|IL70zN#D7Ky3fA1d!V<4X0rdRaV6vX(-$c3FloLR0{$hIMa| z1EuqMa!Accv;cdr779q;4pBC0AuA$G28D!#s0QGoowtAbV=!vxT?LI6iB@tmqWkt@ z4}Y>|4rl$|CJmE%wnry4?8VPkt&Tm4nWTRFzhNFrNUWM2J#qdW?*^NVI^t2_XtjLYggrHN-_u`|JUs{Sjy+?nKTXlV538*kZ~Oq%xnf~xn>zjVI<0G!&~7$_+yFE1TtZeZ+8mh}=@vjWMQ`*cC_Fd< z`lCCWyujY(RFJWA&GW`mGo(PjTSX5=r>84WEycUdUdH%2_hLq>b@6w){64JXBZ>q? zNWzSx2xVsEkVaK`+=`Qw)8o4WWRRv1aR5lnG_~*GQ5}!)mJ+Fzdxx-dq_}m3H}wn@ z1!dm$a*8Kwx5q_S!4u$s#nXp4(*4?cWYcE*s&jdIdp4I=N)H5`qVWcy+D|N-1Y(9P zWS1H7u(aEP6`&Zxf*$jD8$AlE)<(vZ({$#*y@Gjvq=+mHtr~=&o-(p}aq3ldn-=DO z1pc{ZX^y{Oz&_yst>Dd#&5ivzWG2DT`^41(WrRb@?Zy~XW)8TO4Do<0q9l(1)JeAR zM{9Gern0jBINFE~sb$Q|%D4RZXd2|A7i|z18U392o=T%dH6Kj3@Khd;JfOqViZjxk zI=RVaIR5uo$}L!mER%77%GZc0p)PKcpX=x>m;poedqtP6IJ?OL1Jk*CjM&NKa*srg zccR?MU|{8PdIk(%L^{pdfPOfVkJGy_W0Jg04iOE_NFk?_f@_C-n~sj%8#aBB&FVfB zT~B&AqpJOy__`-Ogj}(g9*te27a%32knid-{o`V$*B9;W+J$$}kWUEV`jBAzGB3n@ zzlR652||P%72q}UG=Y0U;lcA0Dg~+-x_}ZtwFv2{0tFzSL(p8$za&ArM$q)PGH*`Od)JL*Mv zwN+4#Y!{L%7i|GE`FE9c{5i+HDEww<68?|&Ch*3M?$D}|r$u15s0&($lM!o_i*M`F z=isoeu>}N{7w~cI_NGuC<8Ne@Inp*-OMTSN2lOWIj1 z1S*te(%Sq}GnEuGN;t2R0OfXMtGI)OCZ}g0sJWm9R?kLqy8TULjT7I~kOgxMhw$;R zq?$gpc12Lc_pY7ATlZ{tA9~FwgiK6bUFoVY}8TGmTHx@vcj3%Q?R zqk-;?eoK8YQl_R|ZondR=r)u4wR}7rX?)rNjYcIm@?RWDb_~`kH$4amx=<`0Cz||n z*#sa;xQ5NO;Lm{1Yx*fAZq<|r#>~O0C(@IsmaqgM*>@x1hvn&gre+36$iYfmCvwovKnGanB0a)-UX2AyV}^P8Pl3p z$@;L(RG|>sW#=OGA26Y7$KrQw9f>UY6Z!ljtt!9}RqqdNL(k2%Wtdq!X8&OGfza6k z!zX4ct80um_&8xK6g3~aGbWXa)*k-$<=baODBQ)5^9wT??n;4cm6L^erL@Sj!UAj+ z&$qRq>y$z{Q8XX({*4#~M)7f6+Y)iF*;flnSNNo};67S!oBi| zya(iD+h&BL?-X}C-EO&*xPUWS%n>$~$rNs!8$LFVr4mWe?tRAYaO%V>xb(sdQ2oAJ zeT^k{AoP}?W>wpIfxh3gh!5dxZN93pZcOScmbm1y==$S=c;V4od!%ih0)*wC5(|=e z5oGo$WmB_o8AegYx79o>Re%qiCU2npRZF<$f-^@Z^@)edtFX!wY@jnt$gYCIE zlSN1NTp2m+Et*HYL&i>Ss*g5^3cvDStCqezm?dX#*~F+Cco1!?4S>rHmuLCZ13a=_ zJIS5FqD6a{2)~TH(Z`ZyTb@@|@vMP{!n}%3fWd|(t-Ye!gjw;GWtLc~pQl^SkwvxG z`Ogq-!3jyN$9jKOn^K{)(4ADzFiEMPPBSC)%$reJ31=9F{2IJWE6`6Zs^A?RKWwdF zj!F8Q_99aZV%GJuKEQtoNI`*)cRQVVx+UvQN^u=@$C<^HyVH?oybhCiI=g2?6ak(2 ztwRVNh3<4}(E|$}p7#>o;0Bo?#ii#goAmlLuK_RdY$JB;hU5oBGfUwR*g6MYx5wYe z$<(STJ9v9#e78NKAuHk%f?H?GEH5kC#|8SKg4Sdw=GC(P9nhUybbl^uj+!|KnNgiR zYlB0c^TxWd)khtkVUc|E5MdS3E4c^pEnmWL{i*dEaB^xjO2DeytgVDt9U_SSD&vdu zy%di94~$P!+4GiSb%JPYsb0LdzNyffG71V~>>NmWl5&WCpM_qyzRjc7MnAvCNqte3 z6^<;U+t5VO6+q#k;P@Nrj_p&o9F(oYWj;bi6KUl*qN;#WZ|QNZRgLY+#Bbiu0#>sw z^oh%?*4k6_>7@j}aIKM7A-e9r!0}T;kvQLb4IYi{oQl@FTl}6@+`bzKB^#Q0K6q_26Wqs@ZWtsYsM;u<4L^P;wu%rU2S3VM%{Tt;dapcK8`IqTd5vTg%U)M{n zQNHcuW^D#9&8f>`i4*5FtpmskG@s~|Zw~nX+S|5#c$W$S91o-)E1ufDMbsDsNy+dM z14$A0DM4ZdfuV|u!Gnf4`&XtDofJKAh>193CHycbzL15BybmFC%(+cxP8}+_%?;}$ zs#H#Hb4ZMW9gV2wJh9l1+e0gt<5c0yxr3EvxIEE^YX-yu zWdY;3Pi+KZe1tjk&%%M3%0 zd_Bf=nAU%E2bZ2h_A=01J8#;)&)QIaV^O~{Lukn&+KQ>9A8*!xz}~=_y+PAIsT*KL zIjg>whElpPXO%)Z{8`1CilCJ)6G)zfl@57R;>WW&hK(Ff2>A}|`V5rGx$1&zN&y=F zT@B^Lg819U8)#`At`r_2I@~p$Ql%XXNOC%jLxOAjSHw+79Nigg6>>|z+S0t49pkla z`2UGJsi1pg0wqX1HpWTRfN!rc-=$_S-B>6)*vB;=TG{pVg;Y0|T8?3l#tpuEh#YSa z&6Z-buoz&e;ix^FvDK;XM&*!kAplkanE9I7blKFF1Hl+G92cZ25i4^K-?zH_5J-ii zxBgM^eu|ZtG-DL#3Z+Ybw4BZqISsPI#3LVFuL!;x4Is+`qU}q_L7uxQ~?gt-hHTM zE)p@eq*`sh#6byCrD?3w`by#bRTBCvic4S&JNub5vh$MqNG1-DaAD@_L^ZT8-MW#c zaCIk^m?)209g`M6F{Yy0BNt>8&~~!kuE2>-|P|#csy7rRG(k z+5C#_6l^;e``IsLU6y3}$HGFyBa7bLDL_?5n!p1@Yq|o=NBQSYPQf*G;K~!%77wo+ zq^pvJorD)8dZhUj=O?;;m@W(P!?#c9w2E1*ni%7`Qh$aDIov`^rvUzP*6xFRQQlE> zg~M4e)kMsp2-7OU`jDcI^kV*O#(gUKnerN?#0?snJe2e$u}})AU4PI8OD|8BoCJ5Y zLkb+vbuIfmmEfNc!h|bSH%6jn`MhW`aq@2qnP+x-Jz*6B3J4EfozqcVMf;g3!*Uqh zEAu~>(~PVNA?$**djZX(+#OoP zQyDAu$mOP^2Kn30aGqNtubb;|-2LM9*43B8D{vW^zc2D6CJu;*0ZZX85anYH?=!x&Xj#FHJeyHG8l`&oj zJ_C%TidlnH({@^EtxHuFjwci1MZBQ~|C9{FM!u6clA7v(?0vs&Hd%B)jbaI`$&eSC z3a{`_h%bhM3vq?3F!ABM44_-iOx5dYTomE$=!NHo{U@Mei!~>CX7X11`(q|j8QFCi zcXlnN>9L@0MaJL?k4&$V04(w!QM^de$CT86n6Ao@h)1q4JTi?QEWV%cj^UpyeVpk7 z0loH0Q|R!=>QE(ixmjQcZq1yfQ>zf;sf#yzCNL4$&-W{{%lr-Kv%WUOOjIf4vRzEJx&2={2mbU@S&-eV>IE5x+P9`SiEl zPlm@%Jip2l+UxN@FMx@h)vNE>){fjf;-hz5y#{Fg;rb-DLykJrvsL?ef15&{p8TwM zjbTD=Jh15m-042vPPt0>bR{4=NONV%L;B6=fM8e0BmRBZ9c>yolI>D}jk$4r$++t~ zvx$NN_*3$*Z#Ok5E*M5IKMrpco4(0aUJ=*q17$gy7JIr~@1}4~%#o~Ug_+W08^~VL zb^z4KU8FZ`YG))8D=@K3M>Rf})tAz2uPm+y7~&84O@NsT9m5n?{4l?U8a(k{ zN|n2U#gg!hV|wvqXFOmtqBhW(2Dis(O}6Q8GDB6j*Oa#>xmdirZu0d)GoE}EY;8?- z{jIm!&Um6n?bMagH5KVIY1>&gE+EAzEv%&bcC(cEWZu>GVa`@V<%_&+46a6 z6{QLZB!X1fw*TRrd&<`H)$SVOKrM^N`*2BBqI&1NeDtjch4`q)a}7fsE{;K837PqI zMyU4;Nh7!r?lS9dd1?s$0*W~(u51rgHJXbWzVhB##}1s>fgR_mtLQkyF#y7+?z!|b zdi#$JZsE5F>dOS*VhvewzMaO6Lf)O6w6+xz!4A8dlNQL$r(}+Vt5spDJ6B$`oKLnA zBo6r7NUz;nj^SFA0c4*SWq#wwV#CntKQ+iT(w0rG8S}I>F^SsugV+=F-T)iFv?rE< z+hcSuy+BGks=a@boa3F*AArAHWh#wDsi9IY?-nJa@tF?5>CHOHW|6xk%Sxy$%5CcJ2hb*8XtflOv;4Tl>z}b(@hBO~9mAwRR+ycJc6i z2qIM)=~yff2tDy;b67qWgFi4jUuI;)DqJ6CR`EZfq05-cisy`iIl83^%~tZd&r2`! zp`y0rKNbe;*vgWea^s8Q2s0orxk7Js2m+a$kZKd<`a zURHN{Md*}y#TRzP`@oV`JyxGXT{ZZXTFsq0CB12xBTNG_JiuTLe!hzfhp6@gSs)cn z+Ti?`*ctWofR1{p*uDU0CPuA_wj0L?ierZUU+Hh_bDo+==XT8KKKgJyFTa=u%svPk zv}M^@rg%o+Z+izO`oeKRjaDk;aS_!4zD@o!AhBP01LIGiZv3P!Vc4-X}SLC8#BSKa-Mg+u5itW0y~2Vi{0^c*1_Z$2((cB0>`fN_AG zte5a2m(!D?uYaINTyDxxto$^DsQ|$eDppt z+JgP_@*c?#KEi(vy@l38Ag7dpJX1?%8;PyV=|5{mXniQDT2>&b^EB~(k^M)F)e-CK zdpvlxCcsmX!ig%(I3p2)^tRP}rTUC`*I|zn;mah(okbmD5 zbMf-o24t|B54N3_Dup3ZHQOzlb;IAMcZhDo6K&MiVm6@(7o9oM%PMnEk7jN>CvdBvkYe}<6ILERVK}YQVj|kZ|0$V*^xQCQ^N?|r7}{3s{Yv*C>(bFx!-6T z(@1=7ozwT%m2rv<~!Q?CgHE6a;4TD_6$O$_ve*Hpvc9f0s(22?bruWttB_*$9W+C-{y8C z|N5B_HpjE0TqFKa0%V5b)YD@N+@$q?9KL=f_Sg$M!Gs?mq{5_GMyI+^KvVz=N8RA@w! z%Z#eCF^myLK!ouX4G-6es z)}@Nh9+Ryd64K84u24Mw{xtPP8$jacl#z`BQmd))PTf@?vrEjKLJ}!cg19;iY*s?2 z^y+xgmXD4~RK8t5ktw>*eEDU`WX72C-^#VUSXxZmo|m^k$GXmnI0c-z4Rz9W^V>$$ z9)2!Gn?IB5R3h}%?eK#I@1zxQB_>ik2o(0~ed05l@Ex1Ss6Y5<)1`PCIDjyQOe!4X zNU|)0HDH)yZU%&bbv3i_Tkj03i4+;?zbP0Lt{Dd@MZ0s-v~%4xl4H4_X7^De%}zp- zk=XR;ewt0B;;g}C#_|QMh^9EIF&Md%nk2mYMt0lp4$72yPhw3gT?zX7J2Z%3ne;W7 z$|*MF|9Frcv#BiFxeGZB-~q(MT-iLbTH?F9msajc z7Mb>r6G)0p&WH8@IjB_^ue}XMkkhZKdAZxOmr#?{x+_(DHmLCqAi#Gbse{vDmMm;t zG73oDi7XMv2n2_^7f=gsBe%&uM=ERM(+V{iDQmY=xQZOXznKlo z)aYr{i^^0`>O@fw0}e}xCC7NjL;FAT*l^Q?Vp>oLGo-by_@vvaYy8+ry&&rMaR~k` z)6W?ELkFHO4)ai?bO3~XwuM3yHa|J~Yd%eQ{G`+B>VH#TE86zIj`ihKM@A}mJW=c5 zHkd_yD9VSA-ti*arpAP1wkg{~2*&)Hi(1?jr?+X-2cNLtYU z(AXJJKXTDXWnaWdNez(8p#$qqP41F=ESG&Fwdn=Z35_iUC;{XqL?3CCT1CRI=bHKq|0M(FITPw4!O7+88$Zv^C7u zC;f2Fsk(#BA<^JM-#zEmd~4cSfY9b9-3`T57DunI*iDer)EQ1GAI=E=dGLI(rjYh= zFk7|i+Ita8CIbG}_?wN>e4Qy_1q+qm{EPbD!CH9brJA9 zD3BoYPy!?z_4>T1*XJ^$Wr_ts?{5x=fBGDh`F0pL_Il%uV7O5ykD>{g~OC9SspOOPTa4r8X4_LYd&C5 zpn~RkJnb>DWn}UFi=8(t?mJ+JXsq(<2b1o9tpF;9J5}9PH=Z85;`e+{)!r2pRvQnG zR*J@d*o=|2N41n66-_2))2#Q#+w=_1%UQ7CnNHwCYy1nM{U&qJ2>lvO4qsS952fk9 z{K7;Amvn1oQU~g|#X)^iYlde1gWx?m)y1*yP`=1!T<{(2YAN;QRwfyBS^TYnFQFjB zngD~Jy4ffqJXhQE4(P)fnoridw14|C&C9wptZHo(CKXFjzAm2Wu}h2kY~r*f@BdN) zx>_^I=WN)DYKZ@VoA1sh*k`78a@39(w)$i;)mI?jkmg3NMg`!zv&Q0Io&}Ked=%1m z{XM>gRxOF#JvBxy(B zf$}B&AywrUP6{ua3Q!hG8CYn(+zO}6t;8y#iwWPP2Gwl9!-mRBu0ZzYh|Q5o^Ftqk zX<(rw9x1;HjJ6}3Rp)(d3dIDH~Tf!<(a`Rt=-uCSAI zqZ=!S0zW2D!0w)&TbMsoRgOOb%JNx4gs?4)%_9Hkqg;k52~*@l(rw~CWcE!DL#OaB z7l$B_>js94p;vfhy?Xkh=r{X};bbjc7Yn_mS<^?EJ`;s<$)1hUjR+D(H33|Uc**Sq zUU)f5fdt}|1q%S@L|MyZdEhgfCeTKT)UP;PYMONyO}bHPC#WI0C>@9uCV%_qwB&Pp z0%%v*5milN)GEjWD!u}8bN?GJ(!k$)kvt`1O^)hLJrE|x;!ljWp1ZNYAvGm!H82;R z!@MJ{{@}jKP=S=ECoF!TwFI~uY{T8kjSWzJ^_3pjP;uOGqKB+TXXKEClzJM7COmL% zsWvLFIpE1crvzUtB_f`{eSRqHs6$Y{fQ%iTr5#FXO^zI0HPo$+-)Q1S|0D%D=P%Dg zUTpKQ#X?EsK~*>_^HjLlB>|BdvatS{PChbKs?XJ` z2?&UQYPi&Nx!}n4$Oil_wh>7y4Ln$sn1cVcntFH_%@~yCWHIF|@qQ~^)}WU8K7Q&E z!hFJMm-grJ6X*UVEg5~j9#J8+{TR1PGz4Wbs6Vz(eBs@~Q_}A6zR-ww9Qv{DF~RDU zLBOUlY4;+P_zupR@~?aDH}FpYV=b-$^po{K`yx!9G^wly?1l% zUo9<+$I)@r0(emlQYGd55KuKD&~GrGyvp5G{b|()(h9p+RMUb`^`&khiFOs?=jGV! zo^x4nu%EJ!QM8lfEDQVNj__lTn6)9?YRMib)h=MKE93W`f}kVDEDJSp`A5_cm`UDF zA`N$qkIC!UlmRB`By!IymqYJl+d~C4O@u3%cSuMn0>IXVIGPU-nBg~;OK4LRu$Dd# zxGR}Xt-b~tQsUEW*4TsBv5wM9hDy}WuKGwvYxS=VdUvMGa9Ap@y9eNe$h5s?beaP5 zra|FFI5%_4rsXte0ZLXFo3GUdPz)(%N=_xggarB`Z% znALZ76q0c!QS8TLnevb%BSG!Ot#Ds5Wtp=#h#I>oqthEB1isA7uA&)bJhR(*Q#K>r z@u%N%cIWlS!x6h3LI)Q_&A?aFTeyJAN2k02#F`dk#KWi=O4Yc<-`D0ag7~B?b!&b6 z6hH!biql{yh%`*9R7efKZVD|_74h~+cjk||dt1iG2qH!R$2;;0vm1boCXu;rS0HIx znP)KLs#$Zuho^cUT5^;kuGnn>;y-+Nw`9)6H&@EixzRA^_@|zF^7S~98cWycbnrA+ zEv5pxenOFtnQ^?F8iMmehn)7tc3t6O7~sfhfR=GYsz~^`-wwiLhxr7-;V)K7G#4xVeGd9NmgeGrw1*2g%QP9;9sdUp^Cd ztEHZ18}UyGj7beQ-qg_=W~^#MPYa!8TL+X-7+q1y0$}|4L%V!n9SAwqD4tMaACTA^ zvt4Mlg(${08!zVL=ub947B3cgI8b4`*e#X*W)^_(19g@J;|_T;$VnT$!`&k%9tcn6x9V@sc` zyAP7Zc4E1Qymy~{G{63qF+6Y?1>jV)<-=Hr%S^_P)A@v&RE2)WnJJ02Hl(PC3*uO$ z)uJWzO+P1|)w?_Whejnb$B;h2Mf3_M)eWy<4u%a966(FO{YWQ&oU`jOFy-h}7GE}9 zU4ox~qY_6j6@$?Ke3z(a8|VQ;O5FRv!d`mH9w6hRJ0LM!VY_=R4A7s)0GMddtKA8h z^|;H5f5=S-@O{e_7|V`3y?%N!WSPSk)QjA@xG#?HUft}Z>_x!k1z~fsmii879vkj zS{`v%+>005)KDi;THxt8A55Lnr@PkZtc)pYcADeqpOUKdZ;QePsUHzcJ;rvTXMA*bE+77**RyrB}fdnb4L5+-ux*dB7?k*Ak|?DOZ47l5Ql(-3uJd9Hv~e&y?6M|A-rUYGV^_VDV zJ2XNi@6LZHruU3+e02&ZJ}IWF2$x;uh94bZV31y}U2dWg6OaqXH5N8{!ybv&>S(hp z;ENxCHpDV-k3)NVJjh3Fepk#liX>cE9?v=19G^gQhz_~BOwA;{60aH*D+Wj5PgW`b z&A$QBRxJ!6y++cw4^C8Z7&l0qY*{O%TK(v25jt?I`*S>~-+F_aCl>c?J-EzJPmq-} zD1Ip!Pg{rl1Xx~j4J;lPZIenMQHZeVEub~Tk56F`2E&nO2Q)cB%U4wU5n091lNp{)UNYlqN%_LyO zROZEE-AbDk8Qp8MV|P06(vEWMR^)yn%QK?rU>=tV19-hhW=?YI?|f25eRJxUqH&Y- zLCk1zh(pwTxqEaK9)PQ|a$Oo@jVw|dPF}=g*y#-_Ab^L&u`gpJ4tlki4DQo@$MCJp zgd>wgE|P4jLc@b!>2qh_eXM#SZ&iVsGCh&a+ES=suqh~X`Pme zUA$pz0!Eav&xfroDoH2h2NA$NnCI zxAM>2TmH3+b>#T_rbw*rgXWdc1(AKvorL7z^d?pied6CwZ)Yg1zO#)o-o08CPKO;o z67|R@X4M-4B|Jt}{YjAJ>5is0I6Jl=w;%7c2k^%zh6r#3@A{|56o~AbNtVZ=$_`}F zQ&W#=KIRdo4Ko+VxB!+M0d@eT2EP1<+(P`!&&K4zF!P}QoAU_+Cei1=9}h3qaE1wL z)&&x+D(FYMcS-KcXfkPv1W52UG7VTaJj*FadeV7J_u>yEXTngj<{}%T$X3QK0D-+5*Y`%+`FW*v~9NnU+XA0 z#gd`~eZ&YF4ET6e!x@r^afLQ0dOdV>-@h}rT6X7x%zYM2Np|FWQ$es3AprCzqs5}U z&Jvl``4az^r@P;@;zjhhjDSpN#7u_eHemW%nFqbDK6B3C2#>#(=5l%O;$JsJYbsQa zs_1_m3yaLG)PaH{1bKDdB}fxT&3)g4h)eV(R}(GOL?+m2LV^haAMWQ|jzZc%Wz9v< zftYZ>kte7dGc6@tD2iqJaHT&#wlJz&k5AwoIjPm6kX*Z^#DoctPxCX4c08uIC%{Z; z6iWX3tTcj37Byj=XbM-{t-@6X+)KwS{+v8}W#b43W-Iy? z-oTYg*Y4y;K6@V#R*>NE(A^)C#rKYCV1D|vB8gD$n@R_Os}_x+<*p_mN9L0Qmo z#(BWz$iJk7Y<*+;Kjbth&1|q>>!hjqm+gQ1|L$4`snRRggw;qY-H7^mC6 z*Uym1YAFr9%0dTIJ}V_v$Y`OWTj+y1|EDD4WaD7|pPE4`fGfCa%Jv33RR!fX+=8-*%t~r(LIfzr8E3HCmUMe%md#Hn*2Mv@sjrTa7DFG?Y-l63&nJ zK*K-}I5^Y;KtzfGkWfdX7Dn^o#P|h(%zG`kf?9hpM9|$mzw?M&p0Qeu>VIUYo#0)mUV938w0V3OXT1Ut;JGG2DJfzmy z06O3+Bm|)R@^YxvTi1YU)FpHX;6Y#P;0<1!T?RM6Z8)=9()#nz8%c% zk6jO8gY*QuLIEg)BMbtCyP-1N;nq-B0BUo9o{Bm^%NYv)6RiFxfD7=~*#P)>`2Jn) zuk2riVDR6`UjmHh<_=_U%uQI4pR)ky2Bb=O|aHJdlul^KZu22Z- z*u8oG+^ho};R*Ns3)sNm);7OLSi3v(8o*&L?obtlzd}$Z{J(9sP$WPI_*g{XF&_Zx z0)To!?0A2b*Y|dY{&s)0X8TSP=A;W6!nMi>jw6K0+6omP=DY5bo>+H z^YHjQ{PElS6m`d{KLH^9un1eEfoZ01?!}|DRQ~!LWb7x&Z#2ssgt`0Qi7^ zxyAVXfCd6J2Jrt5HG=*bS`DZ*%-!j~y(&mBY7k`M zwkR=k^9k|*1^<88VQwIp7t~rChJ@Jtk<1^v!LLzsgu$WO2shZTw*{321pb!~HD3@1 z)cfIv(&Zl)*bOyo$lura3qw)k^v^yN;ShxNueswF5(a=>UBTY?sH;aIA(RqO18NQR z`mJmLFAp4nM5O>woc#ed2v_`H*Zi0tz^nVq^c#ta0C<1Ff1}3$UaP;6D1aC8Z^Q=_ z0`S8AhA8Rq!v75g1OU7UC#Ws>KLUgSyvX11AN@nzU0qQGf6ERqWIJjVJfUhy?aQ+J!Mc_sFZKxX50`35(Svz3i+xwKC9b4uKaO>Qdql$QQh9I-oSWX2LPH&x*8rfxk;h)K-wORb+>FmU<~5 z)D`kLHTToQ2-_%MYl%gW?z8r$&k=(Y6z8+pD}!Gg3Eq#juxBy(*;SMr1qOVS)r+=I ztAu};aPt`DL8nRbdx#%-LVyJ4O-g*J5?(pIua45%!^8~i*vx+BmN7Ju>cZ&g<`7nd z2~(!*dw?Ua%S4xZ(y_Gw&j(GAtTQ1_!odIx$;84B??ua7K_1yTs_ z{2+4~%_T4$+s5!TCGHAbcHM1L;0P&=8+?C+v7>V|+A@#3z^r&kxnHzcR1*8_-3ai! zL+FhRep%*x8eEkSVzrdn^|X8f_XR>{D+4F3E`)8+luuR8yzb#_0{#6ESy-e-8QLQf zc9CZegazRqJ5!%^JY*Fa^qTnksb=JTSyPt3SIm7J2sN9FX640~RsQfs&IZ?9i?4sI zRL1Z{!Qku~f)6P+OkLS#sZewICH8=YC~N~Q1Tt`JZdS-}7GP_)TSaD#&vB_W&ov}a zK&z8nx^o30jEuLCcvIB8SV;JW0Fb7b@>32hk+MwLaKYXbITYh&-t9|^ROeU(ygJq`_uQv#=*wC>G1(Nx&TTl;eLrJ5j37a}F}j=9if9xGE!cgiIOOMmjS5AChU5 z&}FFS(B}k>tQ?O#yHqE4``_JUXY;ax+bVr9mmjpo#&+1}r8HlKaVL3j#J&WePBnA4 zL$i!8bN(f9pKt$pg8&tLa*odhi>Pl7G&TPT6XQvt?RQnSLZVHlfDM@eipl56r zk}0T08{U|@cVm?vk&2>(X$-QyzoiqWui{w!^dK;V=OK_I!H6b zgN7LMA7JJn_s97S)~dj*rR}Mn@3S2f-g(=@oHnBM^?H95L*{8P_Y6tZ z9+nHgVa>$}*%-v$Gjw>rAQ)ZS#8_JBAO`E<*T|bzy*}QX4zHvwPgkAHGpyoJ*a}Vm zPxPG}4(QjjOIIDv6vxM;8Cz)PHJrk>T%)|oAM-L8@7uHi)>P`R^F|Vq%r5y3Nm-PW z2=vk15xJ393mZ?P+!%kTD?MD_a>eXylbC;^LJou5i?ggkiE|{>O_N<@N!t5p6vcKb z@7J2l6GCJCX(TW{#J-#D8xM#DWgi#S556%RBz@r=0^*|8P-7Xz!5EVFEJ?Ss!g8lP zZ|dOMp;$$%4?Jxp9epLWDgTWP-ap!ue&kHrhWaS{qNVbTSo^)WtdvRPir3YW2Csid_u%u8VAX zmA9b=8{gs<%9I9E%9xTOAJ@k(M4!|A{Kli7_%(z9ykD>z%!v~VmST1vCxM^=*K-tZ~Cx8oh`341e&p$g^m zRrRW~gd<4CZeI)L!BhgqIvP-V3=#7qEtDmjJo>p*SuyqmL%Mp<4fVGs8u!3D2>+%# z@r=RkE>*sR+R+qnv9{RjdCJgT`j+K%QlF7B!U7=JGdzE0N=Oxf-jGZ>n#pW&dGd|A zXgb~K?U9B_klhtajgm~kOZ5O=CH@atf!58oLOIl@n(lC?9AG~QBh_8Y>(pIMKFKDF z!|eM{vm$c)9GXSH*IXt31l?_7=9d}pbohxDhGiW_rEo}`s{yU_hFk?NV1EMaKU>^; zJ@K5?I&Xh6?SSWwF%mR-M?dtPzHewB316t}M;3CP z%=AphlNaYl5-YFhb&au79*@gf@dQmLMKHa=1%YqQgw>vpODTnx>5Wp>mlI^Jb;25| zR+b+1yv0njn``qP;!0@MJtp~5|7Ep^w%C8xdNPSLj#__Se5ysZ%h$Y&Ctc;_bmU8^ zQSHO^swt~pF&m0<;|Cg@ePkz!Qr9nLH7$Zfc~c|%7|GD8NK>^|-f%oj*VxB<2Cr95 zO&LEHrzveb2qADu9b-FuI%ghV1We@FFIwJc%^f!Pr0uJ8)AIib83GEn77o2ln%JCB@zxeBMnMQCUIw2(uDM!o*fSQ zOLRq$X%Vy8-jV<2XBM`KYcutRF zfa^fyTa;7pJbR`HW@{4f1eQ`X+&z5}D&i9LEebmRpkdBIRm1j2Az8`^?_9UY#H>7& z5`t4!3-NDfE(u$I1M*6Fo@jq<(UoY;$u{~7y!qZ&UgMJJaKmf$+k1}BqrOb9E+%y{ zyA%8qT_!IpI@)(V(tH{j7a}v55_3j|+bNhIUf$+)%WjX8yv{Tl;=F?d*@`;2<<9bI zzD{wHv#f~Y(EsWO4Hr$Cg4VinC_ckPv)JD=R~okt6~^mMsoni3`;F_mhO}xwVivSt`}a)INA-m&vXL{ z(Sc-vs@Q&L^z)@Tv7vul4Hntz`VjsfnFr?Rn!r}Y1iYT@4)N0uEvVO{X~&>U%rbGa zMQoticvjx8%-Inj_l#$crfJ3ZXQavxb-IkH65-WU6+jt&)ZORgPv~{l7S1oxV`}Rd z=u8u|_CRqdva)o{JTXd3jfvh}OyD`*a*Vo2Z4j<@!UJNMNw&o=lJTNYLG)w zEpVJ9h*Z~d^Z`$Z%CzFqpiaewEe{U7yG35cma#POc+g|`r>Y{UTi1)4X!=!-i1BuU8vVg`|VY0S%adBU&AG-gHX4=mJ~=y0Ad z3H_X?wJfqy!j*y@4&)RB#bhF;7C{p9RygEfppSnHD(N2l#z&Ps8q2CZ!V9YbA#<{z&Oid_ zx~+S6r)O#`aT`kEjbETpIJ?Sk&HYB_%i>q8J+uQhDY~@4x1#hs+a8SM!y_WAZ=X*; zIw$sK_1*sb&gg+?#xb?`Zt_K*M*0w%#N)G{ERYlC`MX!qMeCF%W9_M87$=tvK4X9M z4%u*L;VwgJy%+a4dc{W}Xnr0=Qi1Vg64}W*OovB2L$1x?MUIYuPP!kBx0?7vS$DX@ zuV2zN$*DG+la%|m3*Fs{7KLBdF4u`uv|8t)&9PpYz)lKu_|%D=#K`hqUGwkCeBmVU z4p1)0xJs{4bHCRRZ{$I)3DIVLPGNtAF2Wi)R7!M=K~^KMUgk7BsRQnKQ)C>p*tI<# zlJ~G7lRDGO3p~(|6ZrA2j|7H1%|6riHwu=HNJ4wf{IF5GM%TDRVd3RsrSc&<3vwJv zdg0j5!B_)si?>XSE{|(jmFmmU({8RNuv>fkJJnl?w#0(h(jB4!ZI2A?XxD%Bvefox zdS3|S247yn-+{V8ah7{)g3h~AEp5Bx=0_Z~Pvcs37G)y~OZ-an4(BpI{b=mB1K|fN zaqXK~v~-pZ%u`X++7}CR^_-S%l$vh$A}x!plAh|7i{|0_mCDWIg|oUlk$2azadJ;w z^a)`nJ~*;xqt&;iEO@=4Vb_1yA7)MXd>y}BXG%AFoJqIfS|yw7;ud7w&z4&V5-0d@ zgx@9n_3(vFT+N!TqqlfNeD_L>iu6DvxkjX0EOL$qaze~0B2X-ZmaO9ATsXtAkW3Xi z`%wft$jYvL$dvFi9WAJjv+0bO?Yye>iTR7fHe#JqgNlCP$OPMkhR%PJ&I|O+lpbs= zUCej+O1J*0Lr?;<3|XqXd}C8qe0i{scj?!LUU~$n$=>D_SNj&*+R(cboi+BvUcNRh zh1>f>+Q%2GZ^ndmrO#T&=}a69a9dU|S0mGhr!8(?=K7i*%?wstoW{I&E$<|KQ9rovT4-+XXMGkSH80=4~G9@}xaTV`IpCd7gXZ|KL$`K)ec z>lhN&xd(hdv3Re1o#MgURp)$Jv-*Ywi+BL1d9GtpD~?D%#S~8#kd9bz+2CZzg@Mb4GX z+tx11d7QSdqxfZQrv0I-n@U|o_g8H~zW6az-7as5ODL%_JlmP6(*v@6aw!AfUt-*~ z*_DBu4*QgN(RVb_%x_n#Z;!lK++7YHgf%tcQt%S&QJa5T;}D;FVFf&9_v21{&4O8y zx-jgKO8~6Itx7E@ExQ-%X&GlGl=f4#0KCRhKM zCl(JmBhEbkW!$Rz!#jt2Z{34yrl~ZFo<|37Aht@lTwSKtm$;X=3CVs$|%Z5x>cq&uAgoc(*4+;&W2{RoldHJ;rV_S zm&~M#53|D**w)^I*si&z$!8c=KzC+wfQE+4*xYcu8`8j2pkmScbUVJ#76+!z5p>5_ zHT0<%fxXnTguEQfI(Z@rpO#F&2;59bl;dqi$JBr4D1Mk*G#v3-hu#oZ{4uv_&5(NU z(X`;mz&n=vvsuY5@o2T%*Zb+UA*YH=K>#!jl0BWr5srM-iVEi}kB8ng$_mPl5*3nu znO#g}Drn5Ub9@#yT8{|MXBQSs3w(;^NNW~NzdhPDiOHTtpGVpzDsry_*HS8=q>FvV zxI};1qVIq^w1x3CalJA(b%@ADI6vLcf|ICRSv=DjUp)RWsB6M3RdMB#^ibITLPO1D z_hAr|T3-AINkv(rV>zv$G67euzCDbB_8}7~kVl^2!s^IJ8_ymI-=ujn~3g69$^Qf?C^EN2;23cE8u4(;8C4^mu} z9`d~Y__eU_8#mxp1xTlZ*FcN8Fnqm?bOx zNp>pRJ!|w+8TmK-R(sAmL!xhPo3rPyXE7v%_Pkojq;cz+n(gb(Ezr4#f< z_2z$i)H-D)Y<`D7h^2QU@G;=04yGrY~XuuZRV_y**WUwK*XKtH<F>S5Ps|7IVfJZ3(>%R{}|1Uf>r0bolJ)|CoK= z?W@JsqVpKU`C@N?8Dm%W_RzW+KHyup9vY&5dkDS4-Pa610H`~ z*wC}oXn0su>C4E$*Z^D`o4Pm$*(u^n%}RX&j2Uy)p9}-sjwsDbgWt9LFc~_^Ts9vw z9Etd44b;Q6aCbLI+fjos*I0AXYVcvBAl7))7B7G2LQmkwZhgYh^xdtP1V`{;mh5O- zBV~;gB&D40|) zt9nT23-L7Cms;%Br8nDfi%UATSO>$%_j;_l{o2-jxZxa3vZT5L&8jEs$1ouJFbSOw zqvn5Q@hcAcUK$~KC?ma4{~+%VVc%Po0tCVLrgLIjx$0Xw^TwoxtS9%L4&Zfti4j?* z%YSjQPwe%P8+3a`)=0=jKrzXlbZ9`n)Dg+#Wos{-f8f>=mwp)Zp+cSL+e>+xy#>?p zpk}q+6ti1cJ(UmGkwd~iLOvZmUjVUB)^7^J%w@&D`6XRj+&FmaqT;EPr zK+8FUL49`0dk^WaY36OA@;l=sUq0(%lZ;4nZS>iP*Po_`s31nO3m$irBothQC6m-P ztS!O`mVK7DilJl!Yt@UnejM26>tx3ZVi+2dEF3%gzFSWN%uanKs(d7rXX9~Lsuq8f zW+7-t=WJZ5<2>Pq$f#ZA2L+6A)@H0T(HgEt@Se3Vw-Z6!8J#jNj+T}AVmbunZ25M? zigrJpwHi098APvVShTgsU&SY1(<^Yj|M2K)TFkU#V{Xljd&@xz$Q$6>8Zl@WPe`9D zpSs}Dasu}}uEq-i?N4}nP@EjaXc2!Jlg^U{fN8yS)XKTulv3E)Z|Sg_J_;0=oIC== zTS@b3N!B*{(M=K>v0%q)GzH9M8`n8)946RJgftl+x$rUj0Q2ruY$Sa>RkMiBU+U7C z`GC!BZV*&H#8?f%G}$vf8IF3zVwq{Mo~>G(?YN|MHQ4d$0pP0A-!>LTI}m?x7wc?N z&>NeSf)^tDAj5F{>tH}P>!U{wDg#n(=>G2tW=_+|W8NI#yhuQEB^*9@S*U6ruggaJ z82gf~9Nv)#omKQW43(d>^fnShm~1ON;6Pr&%NX}G~p1@mTbnoe;}JatzwjWN%_>3OF>A;CvJ- zH#IW~FHB`_XLM*XATcmEH#Z6|Ol59obZ9dmFbXeBWo~D5Xdp2$IWaMpp^gD4f3yWu zT`GVOK=IUf#47zcyN1UX70?~`~Pdb zw|cG9XIJg2uj;GXhniejjY-4|VgiQPr=VzV*#2z5)VhaGV0YIF*ATC}Y5Worq^8AMg zapDDt8@pPW0Th@4vJiVP6opz0;^5(AWnt<3e9V7d0d%JH01yuk*V{kB0U~x_Co5B9 zdw_zmvnAN>`9xD=TYwtG)C%nE@n0$E_${5C9e7z-+}zxljqRY!5GM;kfBLroH!EjL zfGQXYc5(%q0e&|OP&Bp!|JfNc3N=98(hB;gT@7OH>}Ko)20R;VtxUo8(B}vjdo!>T z;Q4TXnv6U^$pLKtCt3ba!dt*!cLM-1gZ@tUSM={hR`!1c8=IO!>>P~kJ*@040OnS< zV1SaOJhQXA^IL$iz1eS~f3YnT@*HpMYHVd|Z1PO_qjF<_q=*W@__@Kq+Jl-pSvfdE znW0v;zguMao#y$LCG5?_Aa-_OduJ%h@A|~8oWQ2f*Y3gc=VWc{A#V0we*tqVdo%Oj zO_;ejuxQv@Il6#l#Q&l^n^69-S%94Z96)X^Hf}Zm*bxABH??H>f1O_4!vXw<6ZG5s z+<}jm1H=Jf{@euE$I2Z1{DMVtlR*opQ=>=n_0Qo{jXQXf7$q12_p6u&)dudVrK@j z|7o{^N?N&t&6KU2O)dZ2nLq6szqMv-We-+{K&^g%T%MzV!2j_*3(VB!`2zxdUd%sT z#?WWAIsY-n-x&O?r~j@)!rl~O_FH(Y9Gn1SCnsYMl;_buBMyKU=vkp=VD~>(8^FSB z4{?4D0X+BYe*-XwIHCL=GdC-MMfJDoPs9#jQU3>V16Z{GMm$^q7UO@=v(Mxo!~_Pt+pHBq;n*?M7uvq*HJ_lL- z3vvQjtp5d{qiz0y&%4cH|2JfN&IGXoTl_0I==mlbfBuG?&m}q-J2_h!+nQOKoBxaU ze2Viw@c9~^7y92t{x-S(3qD_l+dq)?xeWI|;D3$L)Wyl^dCq^R?|H`m!GC;A!C-f= zDazs;#FQ`Cx-Piwx>kh9jcNNUKm2j}wKgl$*CGQX=RS!k!}Ub9?5riZ3dzM@kfeci zr=qCie|66H`E#$Wda?!&_Dd!*$sZPECh>DmmoH|Lysn5T<}g0PJnqmfp9Dm0RN}^j0=GwsU;4)S(e@S;#fUIla_6b#}GnNG3Ah9?*VvXi< z0s4Jzsp~-owwH+%ju@_*LO!`FKFXk2L2~mkzTQ10qPBHbgk=)S0X{~1LB?*eCB#4N zhK-{qh&wHJh9b-&(#wp0MN-wjqj^4Tcna@o5q@oW%NDh3qLnU-(%bSw*_og3h=^L0 ze|37bsV)<2xvI%Q2-6RHurfe2@DqgulsMXwRM+lE&1tb zpIJIPjXsKD#j|n!(zK-*_FvkIzq~Plub9PC1S^vW%e5kEn&zkmbBkMY^Hdz%e_a&h zIe2d7Wyl|AN@n}%&u*o+wb{KR(z(CP|8XWWITfKA#ZZG&D#RQ3h>qi2RZ$j6+TWXp)7CK37Z=g=690YVsvO&f6C6z{w_MT zcai_EoXJn`XDg_m&@z=UDQbSYX}Z+`W#2z$>meB~)k?Ij6Ez;0p9S}0C}Sb-Q4Xs( zJ9ag>2$}*JsfJB+c@JmVDM#5<87+NZc)Vca_*nh0!OkidT;3SeaA~)_zoO;IOjKa8 zO>P|{@{%y$dwSe8mM0C2fA!Mwa%837L-L(tμDPa3SPbqLDd<#s7dQq~S}9KH3_ z`w}ReplxX_QCTW$U4_N&WIDWq`c9`Xk^+m@yH=AUIgp}O&Oe`?B9k7%im-=blDU20xa^UO7fuRybWNbAilgT8jT&>fo46%qxE zobKoFpimfVVHIxLAn^BA=MC-FPXRwZ^DpC~FWj^oq}c3WdR-1dnRH=u^X(iRL!5eL zu`-OIsY~}UVbk(|u`ra>_T;tOx*EN@>!gf(mrcOi-DW0(s1-XhicP7bBBjBL>>$U{qg|*ZndF_L1J%uBmX{Isdepz zo1v|`f6KFmTxOqc7B52mqWC#m{OU$zyvb553S24`SBa@<&359oew|$5k;5L?T_0jb zYMz_v2MsLX8A1Q*_a_BYEV{$bco7`z1#})f2;L&i{@Uh*T|gi$~!Mo75*s9ESl?6 z_OdvdvmhuSkaf6FJy@x%?~y2wpy?D%eaX@5?MrLM|RTXr8w}2Y6v?5&Ag*YOb zOF%LIQ!LRiFbmHjZ^cC{Xh17b+fuqO@`F6{;Rdz3sgo};bnu;6hK%Ycep6(_FzuZ7 ze}dUp&T86JgEPS>*o4aj)wM1c&3Sjqvn)XmyQr4AOqw->3-=a;+~cTZ`1mZ+Uq~K# zp*A;-9Zxeh?$T3SY=%(>3lX!Q41oE%f$?hN)GMh=l>%wj2<{x(S~}uc1wRnU!!JJb z(*@js=PbW)#zYi;vTVw0oEL4p6GnVPe-M_p!>Y7Dr22-Ad=FplHAC%k4QcE{`sZZl zFT)1AhzsbahZKC|Kn9{=6a*M&sroyVjwd|Z8g5w~jCk+FB{GzjN)9=msNgt~<5}$G z(=)p)M4jpKfl>R{0Lj5CK_(&kMvB2wgeD%%^WuENMeH-HzdIHw{0^XRMA{@pGZK*;#XReOH)>zp5L#iJZuY>~JJonW4w)4f@NI2a+Os)zWnT>84Dsp=G_sso#_PX2&D?=XK zaZ(zO!f@!Yt;o!98XH6S2CT5Vf6ZHASa0{Pt!0+H;Kj-5;naD0r8$0)kRAdo?O&R+ zn$a(LLqcu!t$WyQRc)|uG285^viI}r z^lWqHkhug+%Ng#(!4k!!-pJA+aUxCTVuQ1cuvy0i@f>SEM+P_$^B{X)6gyJgu*VFdY_i&TaaN_!?)cTzD5c%< zT{#C(Mg|b;S{eYLFr)y~=;O8+Db!Q&3guYf!CQa~S&!jp!sCod4QDqzejn+B);ug) zPKQZ|+?O|5TQ-%qzk+^Ie};v8!bZ7!;e4|`dc3n{RKM_WMS6<^jcqJ7XO5`sLA3vA zY5HO0sjR^MT!JG;mpzV>3h~~Djkc?#sj64uYg>tL=vg7G#muE?cDl-svWC5P%oe|`U+ENf*vZ3-~UQw!U1<1;nCo#x5@sid_6f#alRRT zw?1Cv*&`HNGH9Crz+PjF;#Y%eu@dM zaP@Chmp+c;=S#_dfB(oF#XVuCn{;CM5GK;(!{oVqh8DMEcFf1;{w(?T4rv2td;s6M zbpEOFpVXZjp-%413mrTqj4SE^l}}|qOP0Ju`eE1!t~_Jtb4^o>i~U070oK&KEpTtc z%!JBdAWZY=@G|y8WFFiUI*#^p6i-O26W7;GMB)>3Dc7wEe=4)q=xt$7{rJ|*v8lIN zm%>>o2|g+(j{}T$xsqf&v*NS)BjqR6TgYfJw(td=xa8$a+d69X525yoaK&4J(K{Qd zlpr@MX3ho~_e?CfQ4=!%QQi^pp@qrda)Gve+9wsqp=w$oxikmPvBLP#zrO|^R)htWClA{3EbrrMostCOl zZ>{vgg|_9ZUB%stZ3|eP24dztm!U!hLRS*q=#rns=A$%IPOJ<5lZv zrnz-kUtY`P_Zc^!F`OoLxsgH|@m&}HZ!;tth$*lHYLPl?m}?l8Uh_F2lUEAyoeBkD|L3F=%#-p_Z^8W$%wq`CL{?sU4le+NFzY$<8!hi2f#4Qw6Q9I`*2~ zjxRq4j^?eAYX=d;y@MQ%y)1OQH#`DRR0^+cP2%WJV&uuP=Y{Q0IjKo}9DBtGQ~mZ6 ze>O06jORm1s<_spWF19lnAp>pu+{R;yO}g(VYowI?to;%OLu42_?!ynNE~yGdMY$j z1NUApyFHkCqtMvMTQbTY0lMF|-;SL=sN6lO*5y@=FEzgGM~mxj!&vo@NMcnI$-E`;nt%;;Q z;#-gm|2ZauW|aWl2zS9XCF3>Yf3^qLo{+uJ1hu$`KeSk?>U%mLTh5#HM-Dgx2J68r z>4O`MNDv~7J!v0HI%cgKY`u|MV`id7g)ouv2U_S9v9xQOJF>*im$oGX`ji%jz?V~T z)8|98}LYE1foeB66PTvJpbTT~ke`59^OawyTRX*`q^64epK?{JJ5Agd+Z zTs;ay-Iunql4An{dF`Sey0ttV<4**C5p1>ms#1bwup#pE_C+vzCzi5?$O{VX#r@3Bqj%xUETRTC-E?qq(J8{{_EeOSQy6&1(%s)zeiS7Gkv1Dz z&AaEE-p*~A!H}-UoQ*D1d<;G~c5J_9Oo!eJq1qRfVYmB658j9;Vx`MR*PJ1HCWUur90Go)~j8Z3Gqn1bKOVAoBCNYGcPro8GT zPvd;q=hk?dAF^>uMwB_jmWtI*OUp?C9qO>#3nGy*5&)V~e_Kqr-v*hV;3crqS%3~P zAK`aYXz<=pVm)R!geyfip2NB72w zCLG1Q7?!06gA+^X^3o$YVKO2}eRGs2-8<$^Uuh10z$n?eYHzU~gvl5lmZ9|~h}Nt` zF=KP_3te=nf9+}?sG?eQXh|I3K!3fk%@gU2v0I+K7L*oRfUWXg1KSZLnzZ8LwNyru zC_ZW16WVf;rU-5Rk=jM+z2h`i$}4Nv?d$F!`dHk0Z1$ttQ}k){iKsRLRIv9fu~lCu zk*$#nRuD_nPBJ{C)kV;7pY&D` z!h=6~_RL(Ku(e%78%Z4eCvN+wUL8HKhK#973*j*X@*P4-aw)qR6)}78(r#D4g34!w zPWa!>Wd^A|@DFZ;U&55zGga0WSNCqHv433bX`JzD`Z^a=taI`XAMcCOk!5hPMER;! zbnc!We-;4)wy1jqtk~Sdd&=@rI^QWuf&Om7@dUJsq%Zy2dZmMN9&0LJ8#(rVRv11w z(5Q0sM5xKm82~cAZp}0~{Yug9+;N#Fh%AWxj+T|UnO#7igWaDD`tVk?lk-kaGn~6_upiDR+hOwD;n!3;KJ}t$Fj8x7AZ6mFuz< z49)5r1(eGa=Tny7h(hL1t+Wg|aE9Nf5aJuljj5Ma5S~-bQ-;BWH8aES9{~dT(@s!z zf8dPa?RNdY2*AdVo1bZIQ1;^D#O*ovThn;jhRCdG3llhJ2K23dUTaMDBMhizxII2< zhou!Xa_V8xCMC(h{G>^D2nU5!z=cQ!_ox=bgq(IE&4OtgdNywJir(g=J95T?c~NmW zY}f7{CzX%ddq&Y|Qn(^+Sl(1;5!7W|fBr;~NOEV;$;3vyIxeGH*zW0DDd}2|nJy^F zJIpyh@~a3v1|@Sm4dQ3%3BDhQa7>QKbAP%SrS$~$^NL}D%RC^`f z#H-IJU98^6f%m#6%KS}&o@N}c-mpd01#s}Vx_kqWEHhQ-?1S>90V4jz2ICC+eXTx-9(@?7_Ez|~K##fmQakVa%HTfl-Z&q2ct+zG>USSXWY07{ zGa-Q=drsP-7?}nA$}SnGti5Z5X18R0<$2p1)xCuU>YtE$^x)S`YwFI+zLJ*~rBPuy z;WQ~TReRDG`hE=)NI-ltKv)??w|RmV6o+F;!%(1n_Jbl+V@a%54q@9c!< zCnl5QZNW2Sn|(r+j*vL=;bHf!u%Voh@~(A@??{|E{9-;CMfh^UV`e9;OfwFYk1|2B z#V98*_Tj=L7Be5qZF_iELA2zx3qKU@re@OA?=cSmlxI0A1wPIWPP-A}e*p`C&Ea+t zr!_*aF>D?>BKxH)Cl6LzK;-qe>^KQ7{JFRy=R~&38FQ?ALeFPD(f{h9lTqkXg zUAnTayDsE3#!bI5Vmgz&#CP0LcHW75zi=-%rZj$JwOTtI%51r3<@@C!QMG;R6`{>T zzA2Y z=KChPImCtx$(30ym>=Bsv(VVFYpyDZSTy@!IJIFabUM5$g+j-J=7fEK`*=a`+l*-x zrxtgl*SgI*RrXUkF`X~?&UQqN=JKUM3%a(-F>=?Z>1%@bDX)oT*5YZt-b)6kQnK+_XpR- zA!FRvLknQC5B2`7SZDVGiIN8EYc+jd=-t&gSV)=_3MCEi+i9tNwDQ#-e;~2 zY&iasCsfo8`fAy1zpgf{65E8A!_e4?=6pCCj4k2MouDn(fArqViuchYm1gKJ8LvVu z>a0LbI)lWKKDdm>wddfqBeDO?t#+29(n#V8e+4BV%Qyu0ozf%HrxaKTSIDM*M)%ZU z07F%;^n7b$YUeVz5|8ubRpq-kt4Ead*-7eJqi&2m`wxtko++EciDx)ydhmha%^mrv zu(;05vOQT&e^QoVl0rd>D>O*bw$2+XW^GHKLaS0CYL_1%>M?2xlCv_~{q&$6w6SGx zYtJ55*`k*()|Dz#j2JFgOLWID^!ZwI&E8Kgg>D|d?`q56bhxsaZOZl(DsN^(V($yC z)L2ZxhHFGD_iPo&x74buuU3i7Tlddm&|wR?+?O|je_HKkDmEDigqxV|sJ6rloy8*& z?b@b9`a)bR$Tth@qxp~F`_<6b4ikM<6Cq~eFFJx`1S&h9Smf}sXTxld>Eg`=tnp5S z!XaBAj4vl7?$o|N$As-w{3@qs6t;T^ymPV;%4ztmeLVWRd|0QVxH(!(gomrlMn`-f zBgf@`ZXRY|;Fy~N$SLDtiI~!b^Nyh!@*L)QTRX9XyUd9Z^Ev8qPt)V>nX60& zi$47T`18HspQ--aeU8V{Xp7?cZ7{PlOh`1-)JEpp5l&RF<>O06M9d+9+~bpzKL1!C*wo%%L^ zHi1goP7s&6&}b%ibFYaN<^Vw^$FAW-Vqgh#H%UT8j5O~9ZPZu~kK+D9xXvpS8=z2N z6+;VD-XhHOCnB~G{@$-l)dxiky(+OAS*wcM0q1PZic^E%TWPmzhGo^qXq>sau9S0Yo&}k3>3D>p9RU#4KKAT zvD0&S?Qwy$RYrO;qG3)>s#5K$ACNhO^Ve0}kd`Yu*X&#}B#(O`2Rokyd~*5AgwU&W z*9&aYJ2}KIf$^^AwE!__kmovJjZ9wD@8>cepW4|3ztli{>!4<~nL5`uomewS@g^ja zaVA(5n@CQbO0e5BFlYCt#FN{~4!AsmpGAKC4lI*kQXCL{5lbe6l-`$g&W$?4I?rOC zmvP}d=GgS=-Uv69wwmZ5$?eo6TkByM2Y4ri-)wwn=C`rnRsxW&4phv742hJS{~|4i z1>R|kYx~)=khcn1U|;_UsDZaT1VL@Q+9!va3}(y30`z?YTFd-a-zIB=GQ;>YtHR$?X~FRMN$K z*x}&r+*aUPngcN63b9kBej#H$@MS{~%feU7l;+nrGO9PHrAV&JRDYbfZ3xEt;vO4d z*KIq={Cg;kCqsV`0yAG*Yw|ao;|UB$P%&-HHU(04Z4E-P^Z+?QT&&&-kkKaIK)Rwy z?UVvfbbBTD)?m38l%4=N4YiB!1;mW2revVfhXZ%+-uyd%5|pV~Ch}O9gT*8NaxgWf z4R>C<@TyeCN&Anw&T^PsdoJHSmwZ!4YUX|0 zj!Mv}(*R?ODK|`*pt4k)-vJyaFO9v`?aqp7!n(=>iTQ!-brqijkohF6`#qozb)bb$ zihN@D_bHA~QFl?IuyP>b!LOY?ix&BI#zO_3(+S;L%N+iR9(?`>{uzz6wcz>dnDDAB zoCd`ny>5$iqdq!fB7_in3D@a2DHHmdh6ze$Dge?FZ1fW;6+*7R`pOJ-!uQ1Ufyyzlg#^bq_u$zTNI#uS+_jeUq0DhI08~b!Fm(3`P*H>yT1NWdA6Oz z@Boeu%*(pJEYOd)N$k1&`x+9xbq*pJSDSQ#EhA(KN7uiNd*LH7oVV|Cd%+=)Kift) zBEtVtGZqdG{c_!zq%*<+Bp+bED*u(i%7_9T_ARjrsDB;h30zjfiK5PxHMxElBTu+U z+jjg|(1@}>5L6=|#ra~2@vo2ldUkh^HUMloqbw;?(*7OnWR5i;kMq&;cC{uLb=az$ z5v9Dc~4?nu%WOkGObGr1C88w7#VD4u`r#S)R04!m4$cDAs1d@x-Sr%I8z< zKO=A<&02_#9dL(6Ca)|7=k4>o!8AGfu+vr53RPp_^0Sz}fXj8H4n}Bm14RnS90OQW zq?0`ts%UA&Vo)BL7V!t|aPcSKr1++_GYbf)P7L#7k*F<3VkQq3Y>BsG_bQ&aD8sKK z;P%p}5VF+MNWsHr*WjF?_mh98Js+HejdOKfiFMwEv(OfiZlcORL|8M#@P&ZULBIUfn%Dg00;^(@FPY)yCVE&O*B#5c!Lu>J`?Y@U>Jj1ydggC7kLe|zyMc4OWE4S zwq|-TZug|()-z>Ov8gGZnRe<8NR7{n<&l;?;A%TaW*dLo+M31KM)Yhy2Qta_<9vvo zkQgIch>r$tJ@m#j?9FS_Z-oL?(uwZ2OEKL1il1+C4YIYAH)2)guRGuLoCMys&9@Pl zCL-yiUbEt@6q$M1nNQXK=|7MrW@W^ag?Ts8OkZ2xmsBE5+S>)J-6NODjWl`aVn$UpIFk(bgVXaQj3>anf|_Vm=< zf;z?S1DuR^{}8A-0vys??5^CKjXiiq89z~d_t75py>jmrNey5@k+`97^KM`05-rL` zSU1WGu*PIzc3k#*>Dc;j$C4MUMCf?osT+~ z_Tb8`b9hHPtCqzk;{f{Gj7_xY9++7Sdx;)~$KwgqoGDcLrM^+FwmWdpYz|_kfqoJ_ zw)QUKjYXDiQGb>Z{zckRsxyPSot$*KV`i$ZNZQ2IO1ggU-|`QZRsYJX#r^15h_LmW zpXI((y;3UhciHefxhDCEFihz8M5D8!?VyynwG}x{&^iI8Ed``)M4z2gW6%=(c(36I;W&0t&pSculF{;%%qK^c8 z%ZHEHJ;d6AXznQ*8|fp))c^!H+81i4%T{?rlc7&U-P_Q{$~|7YMZ}W=POjF`! zuN_*R`An=d7y)bym$)G?rMuN}zy9S$H%e%9_Uu=Q!(y=JGROg+UjC8`V|~B~g0Qqf z(N77@sxrA+%9#bCNOfkQ>}glEDnbv{F%yJn_nz+hJR=T!1aI3;3xI+u$qcew=TnuR zB26@UZiYPn6-+%(nue;+C!ROA;rj_eg5LaoJ`gr8wF9uV%3o2~ZUXk(xo?j{>{ONZW1E;f0cb*DGYte7T(GtkTEAJWA2mZ~TPE?{X)!e9S1V#44*{{ndI*I?S@weWni$g*l`2V}w4QudJ%2AsX+En11hp!i2z|*#fHxIc3Sy0U6&hlwV{j6eO0D zErc3yF=r)w98#$)X16^h;WFFpQOuW-8?QXtc!O`6izT!IANq}<(iZJ~={um{*f$$e|u z8>eB9J&3F@6nf}}6%qrw=LFBZT`k+-O?fpM_bAnpsgj%uk@2|2o6kHaqE^w;4bSYj z!|^V030pvtF+Q#ooE-U-hNMpM4OPO4lmk`j(NOk3?nQK(nb<)Ls(i~&5JLRykpYOT znX$E=@Po>+iN+cuzG?dE$S$^@vhlEc@`6{zB&$7qCnIg(t3&KJtH4jyV?1 za4MpqlHNkqldQ8yx}kDe69rY{xd3WV{3iI|H*5mWzZiC;gY)+amMKMWqm-;$+$u?; zso@gl^iyG!<3qbe?0Y(JzUppwuAXRPR9qki74Vkfo_Xh2ifN}1jw_;EL{^cc-S5!5 zLxWywRvQLC-Vh@-6*~+~sUd8Cxh5CdXXe5?NPp=tT*s@zT>;}CtLkL4NCVjaMjL6R zr02(MaGCbHg|k&^+JifGc9+(?EiguAgR0^4YS+ONR6IPrncn~A=U@j_2f9~A+uXGi zp#Hi4qMnw#wx!_8*y|Z5FYz`Is0erWbUt)fi9=tDOtI)R9Poa~em?R!m+COSiMyF>TMK0|B?qzS4+yixz#RJg|Yx=7gg zjhw`ck*_a?)?WS1wKpm@SHTwfFwiM?NJsQ$jhy)+_>oq}>pP+NvkGV&voKr1FEC}< zeh)N9NYNspXKS7y_7n_``g-xP_cfwfsR`JAKI0L9tcXk#L5?$0WQ^~kD+5^1&(|Ew zJ0`t26u4MBI8BvO(V^xc-Wc$$EZ9zAtRx^u{8`YFHGWv z4@_$sFfctM2q))%DT*vy{~wmfOvuj6!u-Dm=sB1;S^pnJ(H)W%$7Z*++S2x)zdDT1 z*uHsrr%5~vexiS!vq%I~H3JE00v>_$O837&F97x1t z0MVY)&ty#qASghIGn*ST*m+T+514z$4oJz-uPiC6tO*wi3<=cV^ye^4Z~}O#pPx~} zuZK|(5;)W=9&{NAACq)y9Xz=5K9|G~V*nBLV<@o^5+iONqIkRDwj(-` zA%`Co2uNT7-#%Q;C6QqvZMtWfM3Xu0qz)t(ceobo?lU-uhtP5 z!qENfrax%hABY7bZIz&zY5@8eR$LgEGZ^O|MbUd7q-#G$krYS+$FQOrlJU`R;D___ z%Ml6evl-j3tnO_0{5#@184BVD4=zLy=^EdV69U2=g0p`s4@g9g&j<~h3<_uv55N_$ z-G$T!@Tfz?Jb`fQNx zL5sO3{#nlDhJy~?Yl%UA`%_)x5X7+cGrJBA;qLOz7Est48peftat^<&{xb<$O8g^n z3MU3kDnuC96h#Yk0qs{nL{HqCkZHu5*Be~`=v`|22L0kg!Uv+*f|?UdLq&TLxxN8^ z_6Jdvw71Or`C2 zIIcN~_H8r%wEgtxB0ICup{tPi?}Gl=Dyxa*0e=e{6Z*xakwOttQ_~>Cjo^X&WDi3D z;65s0=LG6E94Np9pA{P0=)Ovga(nG^Ul@#UfxojSf&4{i(fU3R`)mah2%)ZJ9)EC7 zdPTnN&%Tq7e}Hd)t|b;Xr>|O*UsB(G>H@Zn?9zJwa&~zYI;^cq>|p}^*lWm~5p-OL z;2G^)|JW{z`#a()`tx*tb&IB@lEc9RTv-G13F!fO_Y(Hsk%o4RoJ&yq;2%$UKtZBH zc|Q&Nn&6JZeAxP&yx;6Xjzw?oQt+H$`>&CD#tF(mj403}afdaS6jC6cVvejXK?ML3 zOhRHfi981)pe+x7APTUA&(%NDV<4gqvkMHz_E;JcV8@ZKIw^6$VXs2*0JI-K1>BuD zv18XqG@P!^Pdp$I7e-8k=%`TzD$Hjna3d^*V40f3Cs;iMox+bMMd3B*(;~ilr!=X^ z%13S8NM`JY+UiSh=^>ZRBQ{B(F8jlteL0@r#@FWa-J&mDuVH*`;`e>J(nwBxfn0K` zy?y*P8ncQ%Jm(8s9h57X&44{%75K#4>)*>3ec|i&YDKu$M~D4|-r9QDqgh%y^`Oc| zm$ILChrH>Cuda{CA|X5wjLhW{M&JrR2B++y;()Ojcy69S?@X<@DFWfVkW@>}?ewIUh(J}+LY&AB#2Yq|m z{A0HlhReW`2u0NGru(Vu5;=K6()n%+8ubIV_`iuU&KpLvwHU;bcGNi-wa?qJ-hgdd$)FCEh{?FtvI< zbQ&>Yv)zgHXsOQ>#y|vw15y$`Z@~?-(oJt4yRP#~u-TNUcyCm_{UVYe2$Y{|;%Z^N z=DGLh@ro)(EX@eckMVO#&Be&D>c+CT z1-4OG$f1)y-b=!~*!EQAj{g0R)?VXH&c1w&+i8sAyHk{1(S-rl-GfLkJR=e56zO`+ zRSC#@1{B!JS9GYyH@H*U51xEw8Md<4lgGd0-_+!0xmZepX=0f)vglB;dM0TwP?e>mhk%$dTxopvsWlX+BZS^TwQtj*Il4D59qXa{(dP0n)Mz_;s zJO=Z`m>rC-pFNgUb5{JCMLj-oo{)RmukHX6q~rcL`!LY8uPuJ~sZtk$3PqQg2RcJ~ z`gRFNEjwONO0*&g179!GA^Z0k8$n{=@Z{F%zdK5W!Q>?nwPW0vPrgE=3^>rDq8nyF z8#r2LboocUp=lok%-Jy}YK(OX8qWDoyVuLh?5@U2eOjPMg@bX69~^tqh~y*6EabCNC^%&QcXswfni&YA(;p0!;{f7$DTaW_BR0vXgrS4o?xIDsnKSU5y= z#Wj%*{p>LuwGf&0VlgFCZDOL)FtV-OZzO7|iw&}Ulr7Snr3V$a`@K@P-<{X~%JM4} zd`a~p#xJ(|^~I9^^OU3DI!2KS`LL4iz-{ttq_Vb6O|op-9O!FJ*pHkxL|p;`>NJY= zo#oI|t47F-qIK{II?%Ds*498fAtjXRo$|#s)+2MxX(0@ z*;1fYkYO|<9Fdw|23L6dK$pmhXZZvg8}jMVuEnlX^rsQu7cQ4`#_uMK4m+x$$yrzu zan?%_3f$%=nX`{J%We}F4AcOhNkZ=Z{fnlSZ8^U4ftv#9y=j8j7*9h+hRp+y_m@fb zpefJ0zZG_Ri7qj!)sEI>CVpjUJ5c?3pxbIbo&Q^sktps~c2r(s`_~ee9Pb*%;UW7l z`Lc+#khtqgXba;vp7`=`MMLcp{XEfK!x2R!j%lo)EI}-|*@NVrl{g%r_RLPs=8}mo zo#MV-3LwFlqi@B_bkF!*lBcRi4IJv{rEmzmAg0itqADh6tyU^?n*4WTLf3l%L8NZ& z4iwxCnWO&R0!z<;eS=KPYr&d3i-GP|#cRB#_BL^z!F$x-*h#Qh zA6}V`m6F-`W4_(}w8nWCiK_HMW{(l{cf*vFsuK2J6@6=!iZK*qa@BKK z>v=eE)R=NGdq3km}&)$l?h~oW*QBgsUOx1T}(*JzfUp1hiRi z{B=?i@s`vC;M5>s$w5S>SE5&>F%31OL7{*eu|Ah?^Q56WVoCVVzQe@_xmsVWk6#^N{5Jlg;00q2wOTMrcYW4 zmRWpEdRzr}GAlM?ma)%zkI|8IPih{jU@6DD6qA`7KDLyGL*@P7`kl;lH0kQ&$ds;I zwosDuhyyRWqa$En0ve7fbQBSaNFz{W)U+@cdjGt)6s4SI>_BMt( zdG%b+uKO*L+PVeyi1ALO=wNL?-*~H}^&MTPCUna$LqO9XJ&beK1uBDIa?EFe{&{3Z zFPw`ot3(LAZ6YRq>;&V79I`XhYWnzFN+%3pBbF!uC{=x4SX%)v#uv)>eQ)0?CnKGlQtBHYI=JTksOC&7L>hy*j$^1jQ|j zvL*74<290+Me~^379jDo!L$WcL^(>eEjsBhbDX87wm|*YoJIaai zgoZB;z=uJ@)%skkc4(x5&e~YCiy96!hO64ViDu)b4b?m48&v1mts@FEY(EZAks=lR zsImwXn`qT+#xGepH+oGf2uYE4&SMz_s6bDS&{BU1XXltQN~=0L5%YCLQPwsBzbh+se#Pcxw;u@T`txeDCzFLll*Y znooEL_5ioEMJ=BV22a$}Uo>}l@#KELT5>3iJ`5)0(rd%D=U23C^mJ@hC0NPp;xTnj zGSL%plH>;@Aq7g~7?>;SDlo3@hU!#qFg=DBZz7W`QV(|LZmr;8m@2limIB<7fAF^f zVWU-NcxfZ&`nlw;zd@>g*O=?Uut=asryT7|Sh3?bo<+ zz^osmB$2gdt3s$J*bQ3u{xIw*zMldN;HZ$050@Hr*vpBTsX@3iQ;JYKIBcj*t#A)o zy9;2XJDkE#yfGf7xfM8-5M@wM3I@uQC^YFfBLi2r?L${U=jZZ;Mowh zvhl4DC7(Q?H9$rs*G06|#bXw=OCk7R#?Qst{PE^_@BM8sJUcJyUwh>@U@MB?sW|zG zm(d{1R7T|`gC`&x@}%_!Kcs&0F7ea8if4ec(g<1`*Yq&}P8a=re@^q2gHkkVF{uEZ zCR#{L7jk_KP{%E(!+P=Esmc%syt{q$Wob;8hR(e_XInKumQ51!K6Me3vs!<+5O=+? zst-~QcOc3IYw!~#DB>s)t{{zQaFN&PuEt3vOK`C(F2=_AP{c1e=t`%P7XKM-$IfRO zeyDSR(7&wnD%>1_|Bz=G1{bdLJRua;D#1DHFp77rFOxsXR-hWDVth#kNc|F$)~#P; z1M?o2oV<*RcVUU%1gyO-_Ex7R4OF>@T`+!oOCLhL2WED5Y=_iOd=8WDcnE#uD zAb_rIlnP%;HaoMsagYeM8>ob>zMMrjn;!lptu7G4(qp4s$q$(EievQ*Jy4+-AVD5? zzW0}0bZIo$%kcdDv&Xv%h<)GLH|I8wAjf#qYEZKM3?N*X+kY%z=jNM2&`-0fAX`h5dR8m# zJmH{V3(d#CH9i_NpwMZSOOKz!i=S#!wh~dsq?6^dOJIa7>m?}z@YT(!r!x%KFtMIC zZri7yiL*Jn#(YqVE72ufW;IPJf9NvZwW%bWc!E3$+Yt4S3@|#I6oy)tsF%4#zrMSP zj`GZBi5RxNdFZ`S2e4xHkWW(T&1$KCP+8_l2wb00dhb+~9J*y!5Dd0jCD!McdZ#Qegme7(ma2;7bdO@kG(sHuKS^d9qA z-Qn5LQ@x9?7K0;NN!K&p1Zg~#f8HDRCE$hUYweiQpKnh)YI&>E9fVa{=!&N_ip_a< z?teI&M95?Jy@-X-PKD#gTnxirhx+~*DpuKUA;`omur`nbprd}c@-E4t6AJ%k(QHfj zNLU%e!@uB2Jn4*;lYz@g-fpx!q~&~D+Dcn40;soHe0)Lz?Drp8)@NDgMaxjhrR0k~ zLKS$i7Zs(!Rvpxhq&5cH{Bq%RMeo=@``2VjwwUy3&s|;!YY9zOoCg(|3?gb_l)*C` zBzq`7BBT=myYP`pi8!Tj+Z*Y%9Ol;GQ@T7zt7bI0Q{zf>PdXb}q93HtDyW9Ss-#%T z8r~gQz5872JHCX&?(2cR+9ByC93G@vn5VRyL=-8gsp#E>>2t!Mx(_)^b-U$TBbkbN z5|AJG2K#zt7qJruHHBTdu8e3YsNw_`x1VFirrqWM`c_NPVuh!SN+1rQR40Miv9(0X z+M3(46H1;p^M$DhhNL%foup z|NM*qo{>^;O)!qh-=#Zs%uLV-DEdrAYbikVd`HA3orBKLE#lEZ;z2Ff1^o2sXV#xu zMyIBJhWW9^i*|dfWj5^1XAOUCqPmy(q)EOlK4|Dwlp;zz+JZgy}t~75-68PMc!tUop`ORbp5@M?J!Ig1U~Vj|gko zONGd@O369%jh~H{!Ic|^dk-oam$rJaa*lJXr*Kz@=;HJwTXYMO+-IX6O0#iUnGebY zWb!wb7AYI@SiVJJK z>Vz&3X#Rk*!-il#l=0o#@A)-S-aEYc4D$Y$a+VG2b@U&Mxkb$01 zB_j|5{u=%>AKi?A7>n6Cs}`=KIfp+*d1OpUXUoA~Rc!oYq+ICin3-((NYWlRmZyek zAED#(*FsEVR@y;rIL9HBayj*Hx)?r}XHU794s;7&zg+p{j^$X!PL(t~r_VD#!23KO zpG@CY7Dl3n!-RfwQQ_!oT_|Fh#JcbRdBqmUNGaX<^9^!?qSQQuWn^_MdXNEY%}Isn zp=%f$?h{WSd4t9y1)u((B4J?S+WrgI2sxqNkfF`@C=iXKGue`Tzt?4*dd6^#-MuH% zL?bt@td0wpDZhtIP~9oK_iUgJFovQ+Gb7D`Bwl*!2u|Krf9f47R^w%yR(Twe#%*so z_~tz9^jH23tdhQfcr=-&G`6KE+kk(>(B+KDZ&5ihATubZ_%Y4-^K{Y`n_M^?Y@$zC zplJE(`|>LbGAr(@&}ZW-zSQQAAG-1Fgtc_nsH0+*_e#FOeI=dVjy5?w;EafI!fM53 zc=c|Gf>5NCj^fdp>T%zsgGD4rTVw1xop1~@8Eo({0x=8b5Nglin%$>DPm2Culr&MJ z`e0d9uB}(N_wuaS6PB7tidUrkBS@gb!i&EH6icL6?eaIpeOQSM4d&CW`1IYvVJp3s zz(X~<=CoH{Gq7J6BDA>=U=TNdh#IGwg+Pq%tvLl$5$)F|dsU0)?1IznW`uq3%zSS< zTucc+vC-Fl_x;QqPlGah$eYM_YOTTSM6X`eWR&e0_#G*4+6TWzoAbQLqiXrs;3IF^ zM!b00GGBe;G6hIz^u`+MJqTl9qA#t zmIS-~l&Uf8nA#ypaRy|MJ;`LiaA!Vr^CB}|vO!6Q|>9ljBoR+^j*9S`s0WQxTH}>|V>)SXi9t?_@@fu)qp~Tt zZy_sV!HQeD21AeSJ^*n5WCdxf&~01<{fx+-^VB`A>(b|Ny!Z>` zjWzLQcg#IliaOB=RyvQcUDe;tJoh;vVB6^QTUV(*A|RQ zXCVEZQNLZkgLMWHX-!QH;Q;@g6idrte^(7t^a(x3d-boKOzA9O317J2vV+`ouZP`gXtTI!){G~bewOxpA{zmOj8 z9TcEfybZ-i{dspS*~rFG`^?eJ#bO}G;Et|ZXBp+3E}pu+lZv0BgKSpP+Hq0b7*2$` z0)}`5kjIe33OzLRj8}8+1iH%Qt#tB=mY@wgJ?2@`c^(VBj4Y2%h;RHYJemgrzLGSZ z^>I-B>3Ys%Zvg4~dNwna7iB8e2*r{_S{~tc*gRuMK(Wl)N$P{G+zoT@bI>0tD;4rs zCA-)d!;ahUZ)w#KY$yLC2r;$eRMS~0dpS`mW~-&$ep9h%^G8Kh^zs-Ha(p;NPIz3i za?3|$@NE~?MrAzvB;_5p3AHR#E1EupW@%@^xo*Y;X2K^8NqNg`5B+k#cFm^yDr1) zjL6blS{adA-$v+@ot^3%5-TFDpd6eU8kZj$>VpxHr#}K>bYO06MrL;aaX>ByjtWl# zauc1R6{VGxonkx^6>f36MmQ-kmlstP2Q2-#p_FT5VP@)N@*tIOXs>sq;iMzqwY9ZD zwQ+K@aB@B{eI^!x0U>dv1Bb~@RRf6%JKbZWG#HDj8aGgj8Ux|@1^T1McQxiGwpA#69BeblDG80b#M2}6A0pX%S zn90Fma5holMZ-T*t&UDd?~w3}PIccJt}deTKPFmOpRs1I0xLhFcw65lOnrzki0m41$6Z`vtf^>zTeJxJrK7rtrk3 zw}D3PPvn0jZH*0|Vnu(RD}lco>6w8{oGmVYjzGWX4|CDkTAJ&fetK2DRYrO#OjVQT zAF3zwsEv>Y$wDq;MaL#qjt{)6N5(`L3zv#tY z@SoC@pO~L*NgzL*J}C1)!z*DtW5ms5MOzX@4mBWIZg%1Z!EV7=9agoRV^f+p zXW0Mv&=j-i2!NH{IQJWCfW|?7`ViqSAa`aibTQnL#()QHS#6^WmBz1{xF2{ehW+2{%j4dqKK56trGr2O(od*_lo06-z1f+-sdGINZu z@;i_`87(D35=0{V5X0QmSUB_`AYhMB{DT^4&X+~{3*?A}PnTTaSBQ&IhMs3gI0PxI z=IPqlneUkNgkl$XJ3Xop2l28}UPHLW7ZzO|%Qm=KJ9`|irk8yrR${X?zTW?R-Xz9s~O@?10xUnwN6y!SlZ6D)`i>g zAF>;wov>9bK>ch3IUl{+vRH{=k~~U>OC58Bsehs)H#vLe6S}V96rad>2G+WSfym|T zCSU?BP(ubJP5;k6(=D#p&NsLzDj=|ykO-4VNe$&oT+lr?`8EV7vMozET!s%5AWS}%1yesJ zECkFe-i~hz&XUTlNaq(ARE{YPRXI>Sj;UZ`j$ zbom=Z`S)Xcj52jlk)n_@T+;d0nP|WU2)~>HUeq-bO5N>N0706J*YI>}Gxp8rh8&IC zzvxVNKoZlp4wYVMNs|kRN%A_lx6G#X!%Y((u9$Ie)D+!SN3D&qDGC9W8{kTc&c8y3 z=i;k54c^{qEFKqoS8wfa+QBBbj{^91zwA&|-VH9;1DgI1QRSv5a(Py1h0KGB!q_I?P4?9N{&O|Ip6Z z0O~o8EtW^E%o9Y|q&JmBr5KtJ70A?i!EWnw7N+D3TF}L|5W0!Bw~8Cg#yRMtXEdT2 zvj#_DIMwRfk=#KG$=A+?Ih$iW8-PdOqPSxoy$965yts_bNVOm_hn|4~vG<|}lXxVP zfTs_-PU_R#5n>VuAII@R5BT&-QE?m^psps@bRX0`x@Zoyy!Y->3_-qS|N9#6rUZ`X zwJJZHz4zh=8N*2JkkgGM5dpQc4>Gr9%9U7zmsqxo45CK&e0i$?K zJUX#3crXy)Tr27QvVzv+=N#E{k;}#9U|5MMVd{3Y{dbQmT*oD{fJ*kVac~bUU?{)! zECz0X4IZV5!a=~-AeQfZ5F=4<p_m@p}jD#IBDbSCpx*KskwTYpjW&3bzy*seNfbXfYdZY+L8xnz$o3)s>LBnUD#|-xAMUkd{b_` zIQKAwzr+!K;YIOWf=@Mrgxz`1_K1*oU1$L=8f6<@Z+{!T=Bs7*0G1xXrs%1OVr&i* z&IyYI%srR$jKJ3PQEyu3(3NRkieVD8aq@OLC^Um*q;aSS8CRK5A#3IBq?HW zI#IVYchP(YX%P*Y0KQ;|>i1gCT0Ob~O2MA9_;)XB1C5;@spzpT17futztMSKyBiVz zvEEU}k6;>hIxT4A2$Em(VjV8_jwThtN-;6s+0N zLy3t+!Ip1jY?YRlYtVZo?Bza${-~ppX@4dmpbMit@cGGN0bF)(%CsjtUFibsJW(Myf{|&yk|VOYp~e?rbp3nWYsOwQK>rRW5b zLEXkdJ5?V=nd{oEaKdA2$NDCd4HoE~Q5t0+gkr#e1W*mibDCb%=CzLo984qf@UH9| zq3XDFn$)y+^srndCBCAV*4apppjRa4^^814VwlBA)7;djU zVg_CC0k$nBE{;h50$y+#(;yJhtDB=aidKU*{0uqIH^LB5YvaL;8_9j6`7KU-X$NA= ze#2PIYli=ETePIMHFTQ9JSp;UeA|9y(+03cVaaj@T?K}SJKix!&^}@~o9TX#ou}GL z!F(GxC1K6Lu6E*m-FKs7LLqkZ08`)Jfvk7?0FD?#o9pd9G^30<30(~Gf*s$_n`s-d zSxs~DgW0Hg87i?-$tvM3mQHdhrTyHzeDf`FBqB*&BR#XIheeE_#SH}^q+WH*weVZ+ zb-XrXHvv%aSo;Z+*wV#OF{E@m00U!a(>+C@bwG5@cfm2PU2nP*i^zGMT-t6G zwKL?jVv<=bF_K)bIvJ7OWA7C=hj&g#rhSzW?xC@9Su+l)Kxf4F_(W7%fGa;WwD zQQF`sVo{nF>;e=d#Jqde9)ge_Bfc=aGC`UJkpU-1M0dh?QPx3$SpKavJ9<_Kuvw>b z^l{Ie1_7V{wB99!Ey?)!Z;lvX;nTowJJ+l*buihYI)68q%)Evt;ws@8-A!e&o2o zW*3|t@elLU9OC)PCX0dPsW&aAdlY?dx#N&WO<4gBTITtCfvrL8QHByY0w%bj6_wb+XEET8se&@5~;X5#LXn zx%Vqoh8gUK%%ObqJcbh?D|92(Ezs}UxYaR?-{Liu=t)pqe*`$UVS{*k|BPkt^WIMb zen*3`2(NKpNIMgDvB)950wN`_!W?k`y~^(1ZK_haWOi|Jt3u^|`vt}84l;lfy4@tH z19o7_3n$->5hnA~95GKpOvwk^-n{2V@aDsdKOc@>2pmA{flHGa!q7In569yNuOUAc zbs9@Jt1Y0P&H9SB?nOv;h;2 zHWB(FN2e|NZn@Rzg17g?=5*&&)J zMfAPqP_f{_d<q}D{Mvez209hW0S&_WSwCMW7Y+UfLsxhVQ+Vm%Q3kS_z1YA0W<-Y$RLo-;i2eLH z_#!hys#9POfB@1QG?$CU_h!HqCy7qr$u~u=%4Lz1ls3qO2`obsd%|}*7|6Fn!Ki28 z-;vT!d$eEJ-s8D%j9!r5i8bhzuE=`m>K}r?738(wJIphJ7IIHOk+2T%GXmV-F53d$U4Gf>6_QlOM3vnD+O$q9@}&Nh@|il-_YmDbue2?v zm2|YWWlz4u%Pz^lij@|Fx`A{`z$mgx<_Ay)*YW<_$yPQ8IvqK`9`&CMx9;p#VY|iM z_Qlv&2y5o{SFW+QNIwKT&4)M(?sa`RdFKc4nKwOQ#_>WUjztsGN+ z;OBF|!{6ihzF&-R`W#XaH^c42SeKbW-ls6~G9m(~!g$o!Wv~s2gg9!Z4I-W3TXzii zDZ*a%0d`vNkJ?-Na6@FgtL0SaEjDjwBQ2}0x+lm9?(f8kM7QG=)0u0{Mp*D-lA@Ty zX6~~shq%uS_CnY(e{*}j8i|i*s{6HPFqohK;!|o0{>kEgn&|Ew4ZR7|dw9otubXOx zq}zfyTDTCvLTM2_S@JBd>d|NoB&1N@m&_OAY0-T12|RFxIpZ72MkoGESMla$qf1up zFi&BI#5yw9u#8j*--$_@V}T|0MZ9FwLSuL~o;+-+=$M%L00TE8{dHUsC%4!dNn3m1( zAQ=Lox}Kmzytfp0K%;aCh?lsCMKsCyI?Jp3yN{C2cR#`!H@a*PJdYp;eOzkhKV` zihl~~L$GACAzZ+9fZKwND*$I&2|QE+=)Qa6M!r>t3Zm?XQo53>JI_363;@*%KK>L| zQ>weG@}49}VKGn_lH!~k7lYwF)9}{^o(wz$yC=@QZt2@DRG=soAOhQtJP7ZkKCE0e zJl1^QCFZRuENm8C{HeekQVxcPL~cQ48h25CF^J0>A9vM?i8f@d zG=Ed9Uy5gC;fLz2!{W7{s6#TeDou=X$r)88`h3IY1HYWEy2jL$-^zTL z4EGdW>6?(bfFNKJ!Wx9mSURpE!hc$2Of|7~7KT=$9fji+NP3Ii+ zhjlL_e)Nb$y>goxbYt!~yk~i>;To>vm#SRw?6(bMDl9U1q)4Wd`AYpcej6V>By82@ zOXWAeB=O7%T_EY>9GIuvtoR*9zD`+rH$)r-Gg45VAGVK92Zs*YsvQfzF#V(tJ9KXMRQutOSI#(IV-wtbQ}h@;Nu~ zjAI-QDJ>62Yq6_~iBR{tUU>3A#xVwO@9tM^qa}h~Q=3ArhH?E+#jEO{Z39AQ+hZhdY?cB19ahH z=GLmN2}vS_04vr1%YolX_6YnDD$br)RCF?)EA0;?H0)og@d=i~ z!pF|vc9}_QbAU6_u3H6K?yX4IZg<>wIin$WKTIwxjZsml+}wg(4EBcMKoFwOjL4r> zmp(XnkY#LOGE7t*(|`4?RSxJ#;-v%_^YDyR#>H@KGkid*8{a9LdJr;{eNt|W$g8Rjf6&<0nAIc|QhT{09Pp0#-6aQ+EH0+?4tdZ}8nthLy59DgzrU}2d(Vk?#w zDE1bmDw5A@kJ1LmkvCkuvxuvEIh!>6VBEB@lOXTA-&X^B-lT&WJI^wZSY|~toZmYp zl#4Afs1HfvF@LipHJ%V%*u`x?rAOpjIOn)p0!f#LVR}If4EU{^ErtnR?=S>?t9Us=>vY4$5c%wsD9vQIc z(jWt)#D?D?B&Egk=}sgZjg3@4ywh#e8FYyKI%Vr-Yk#+n@%tLtT4OpM>{35{tJUb1 zM+5t1x9i2*lZO6H3HC%B;11%Db@pdeu{ckTG}=8;Ajq;kFGyDM52~U45Bgll(R%d= z0M;x3g-XyxnyFY@O#S@ad!&j~=L*z3(BcgIav-7td?i$CS2=k5hWt=>eI*MGkS%0+ zr&@(Ru7A6%eTaZ$M96QWCX!$6B;o0Y`<-zFmN-e1mfo{kzhtXtl0AXYnGW7gI)|0@ z_+Y?GXWq9U{?6vIL@?r=Dy$?KbbF-WeE#`KjGe|D&}d`hdMl~CH6 z)nypdjNq82{77oWV&)p_($qMvy%MLOMRqj@OuPP}lcx&`An|gq!4xyN)6Hs_B6bln zUw_LOxw}~}*O6Yb%5K8dUR0t7qeMA@*#mR1c?;6#O0zb~mvf%q3mS+CF}>8JWt*%Q<-`zh&6S0&sRPU-Q|rKY*Aj< zwPNjhh7l1H0ez25OkMn&mEoaVmcpe_?0?<`1gk$78ZtG(j4gJz6e?$uxN^__`}ZF~ zt!)r==(3w9PS96qzvwuj{MEFq(*Ryx@__}w4BY6ZKk?Ibf#O{sy{DMw^_&A7kJz3sM#;O%7)L)qvw&{_pqivVm0V&6{$G4r#uyyr`>_E(>A zQ1Mv}sG``yqh+aX{dKuN1GLIYHGeS(C>j<~nDCq%RTk!$z>K|My%3_J)xTj82}@V) z1^CeaC@NnxsQiAg^74cgoXX2KPj-{!xM;Zl4q0r9*JdnHH>*mg-crpsMu06 zzbJDK1(OsIXd>YKH9u5k!{%8?`jK$YsuRD>7qGNgseu=cnV6!&p-^TXL4TV3d(9XU z=YduR20jdwuI86*=g8FHnV!Y>ISC`Cf$j%rwP#8rs>gn?>Id6BxzVMjC={5p7tR@g1&-X2Rl8U^j%FO+0m%9r zu~?EqADV6ztrZFTD^P>*7=Nt5K;}+*Bk^QNRNiR=MEIfFPJ^B5JrM5}SiL4j?jq@p zi3qREdo(#mEJ;2vM$dRq-x9h0bq}HMKBszNy+pXzF@(%! zNR$EBwKpGGJ7CEx%+DDj?AI_nE<=|fQ1BgWDXNUb3!>XZWjNzOGh1oVyDvIWJ+1L~~7sTKRz! zOb>E8@sG|T&5B;P2DCfveBhmSacXSlRF)BlQ!X}>DUQaAooIPBNj0Fgm!;cYGFF0s zac`sG{nT~$C9t&>^^rg=p6MQoKu`uXU`+oD`l!G8*7K=@G=E*dCL>lYm>l*MDp&$f zMA7eN?ct+A`UdiloaTeBdCZm_gUnBlB zV{nD4Z>L)JdVlN^T=T;(gKKo|k(56<_{e5d%+$Oior{$4b{+%t(m0KsOvmVBa$bj` zJFh}~i9gQQ5bVpL;!1)OGGN0!s8h1?ArwEX{?zrti?J{k6mWF|J-phZqD53=qpb)b zwkV^+T#?P*>nU28aMmjFk1zS+42LMqFFad9tRVP*5`W|>ag?$w8wDb5>jWZ`*@D$0 z9A>KW-ZVJmOMa_ruQL*;QX(%g5&Mq>SfxtIfc(wEA?#O5N(8p&^YPy2-P*nmi*H_c zk=@PW!CEs-?%c3bbtK~@ zy`IPSK3yMjh?$|&!4sY*3Qw_;v^%s7i}08X!P=7o_DRUuvcrNn7krF!>>Gp&u3nV> z;MhM1WQNRjQJRLjIJXL65~mK(bVw`ZBl6vU~FEEK*GbPUE4=zw6se{pC( zC4b2Z1Cw=sue)Joumm4i*7^y!E+ZnxCG`fud@Ffle2p)b(#A_lz6r+oLffW~3EQBa zZAIX!X03K8fW$A!`gz)2b)QK+J+c2m3}Dx$Q6u-6;yn^RQ8m6&gal88{H;+G-YWFJ z-wi6@)hRiTwWUylMby(mx!YpX3c5O%*MGwHDI;diYtQ$^i8f4;Oku8<5ES+WvH5<~ zg2D@WtydR)Qw9AX{ae9-oh*>jnK8?cI8ACpe3ZjmS>PqvFAQFyd4A=) z=g%SbOgDv&SCfN*m%qjd3xEO{B|mmXvj)8>tPz6_^hO@k7ltKO+-JzF4_HgpMSmnv zhZ8T*NFDR8ZQl$m{(wuy;^P)*yk(p+NYh|*VG?`uto7b<59ku_X%P)EMu5frsgXfN zmY=lAHbqc_qlX2H)}4ZzY!B>j4VDGiooI_jl291Q<*-6F0sy$=7(Zs~#Xule_jDDsNC`!g{dM{;yNvH@ zI*|%%XnBAzFuX9N<{^W%!c{5y{w6J)b(KF(yTFv4HTlYBUBIu8age)1L4SNJR;!Yz ztmK?KGhZbN9!Nw`ACwnty&68?j7_-g;dh_MlgW}9=T^f7fsJJ&#iJ_4Ma7Xbp#w^+ zm}t`?zu$;;r6Q7EixuW-2_;`}2tvcRDz&ja@bKIETTB^?j1iSOy&<%=8sFAdQ_)#u zxH>rc>(x7ouK03>HBuR-q<;zy-gn1-)1HJ#A-GMeh}gy?Bx`k>J;NG8>SQf&wS}t?jQnKM|2;hA@J$5KH%)O`aTi!6`wP?l|m4E)tUnnQo(@WU{ zauUCb?eN6{ccyAGahr_4p6j4@Y3LP@P>;u>kD|MyKI1H+#2%0Y@|{=1sU3 zKf1bM?=2_*U;8yI8-KI7uoK|!Si=HNWiwic9;m1@T22xCdLySj^N4oe6o2GTM8jOb zK0AV5TYtvA49jS%D!%M3vh*6q$Q&s+;y&Eg$%82V+t(1;Yt&906Bbwv?=m3b04S!|Bo^@{y`EEOlN3JYd zq!W`vsRW%Yo^P!98<-{wtf5<`fgD~5Zjo2SBu`l|!dZjyz;BD{bv|HynHjC2ynI@StbFOyg}5>z{rcD@q4)E$|TZ+Z=g z7`h&$*%;ieYk!=Wk4~C#?e{b-_b`$#LC4R#nZl1;wa1dK$^L}zt}NJwpI|~jF=n*& zhi^-Pr1{84xcBeavojw!51Ypk5F+jRvX(?b%-ANGe3yMm>06zinX{v`>w^>a{h2wF)$eh@yUOR$!V}G_ZrU}JQqW!?*(I3=t(63+h z2yuse6BD-E#6t2Eo=Dovjmup@1pagSw9Hl4@eso0+wp85bn-oYit#D0U`Zjz$OE~W zg0p6U7&x8ie4<+GUVvGM{_g2+Sh3b=BJbxxu5{r`)hF<_!w?w^MlYjhvAE+g4 zu=|i6OW9@Y22z~)0N1o3*Gd(gO`BA~8f8#@Kv@F6Fpxs-5#nHx9lt@|r%gT)QwiSA zLoshm5Z!G!V)B%yA`yPVTA;BqVmT(8D9}<#Uc8Hze?0?OH|nQGLL(A5qDb-krwrC+ zCx63<*)?T-GU3z2V(}__MZHc=`2GB8yPdu<6GH8`Z<=+x#R?gdx!hRdb1ri$k&Wlr zFJk9h;{pQl2~(?#JYKj(#|+|KA9W*_p(hkE<}Kbxv{ccjrbyX?ST)M_uOdjBjfc=% zHrJZFR*;$L?`s@g4zHi}oO42-8jWvjb$^z*b~S(6CXV_uh=elz02$*-f?1~eK=wpkS=}zDqJsPwg4yB}iZxQV&fv59E=i z6FGmcfE#BrQPqtVY*n6&>5Qc*)_;N~CD76N>TcJd3>vo8u+bm(faA?6Gm9mYo?iOz z9wSbv@=S$51rs@)QRwo9PgEXPv8}Rrk~w%RXtQec@o7*Pp*k(vU?u{aTZiMMgkOoU zL-0Q3Ob_^X;4E=utrJ8)bN1lf?MMr3bf_gE1h+<-dxia80XRQPV4j0$zE`SeDVr7{yNfM|IIu8PrH+Cm zH?k*YW+k+wi-J-nNN3&87+6 zgw+xvi_sEZE;?>$ijdePWQ~+lTO@Kwko|*d=q-w&FjnU>WMADUB^H-oGf45*p>pD3 z5!*s|l_2_6e{8Qint$r^Nh`#s|Fs)HXH04lC;yE?>xwn!-3XJoy+u%76YmWxr`ACV zd1YUu(uEE5ZV?2PdSsHx!`qt)VbGYru=N-p^bT6|dmB~{FzB5B2!3U zA(@+7(Y69X?GRChuH~2ZCiIM&gPrVX`HG}(OMiTWyM>EG<$wEH-pQUavp_b$?)tbd zp3+{k@g<=B^_7zGd?>u|^byaYtjRGI#nSHQ`-_@q@XACQj_1J)x-;+upz>@-@V4O=z0{HZ)SPes($)) zzWAe7?1-Srm+%9U%Rn?~Wg>wwITGzkTtq+ERMFmqfObM%-)iNY&Gn%Rxz+ZT$U_2m zFkaX$S>_$!XSgjzxtYhr6Nhx0xsutdh6UJ@Q|~86sfKP7laNw(?W-O6-Zw=}Z@N zn0ua_7I+4{p6$bE1+DOXak0HvgJv_RO{G&7R=^8DaXIKwlwjeVu|H&){Y8&{l>XIx zN>#EQn|K?^ZpL+@ zWtkOAw(LzK=;<1z(QQ?7p8gv1hOlC6V6SBCeLOFJJXHndq?VRfA#GaBfvC4grHC#v z?|;chItTJCw;x0%);#b&;}m-$GP*`v{3E-3w@vq*XU9Yn|3gZ;K{`dS!h<*T zOWe=qN}}Xo2=%Hn1I*$F`XnBA65z~Ta(~ddECONdL$!)KPQEFWf|EbM(D{PT66rkk zyi*5q^azxw<}D2L?zrxDVt*RAH`gUk*bh8n=CAmyuFTfXtlxK(?eeFy&XdZg#&BYi zrc1)%px`YfHWhzeT$EbPr$V1+V7!|fqtccq)XA_jG!XAvAWgH|8b%(K@UM5ETz^fR zIrxk!jV~c{Bmcc$x;`DCM5kbAXD_`t6UZ91tbhELbrQdsD637J{>k{DJb2r-f!7fL{B~pf-cJRIV>`}Q|qXR*t-z9FjF?ulY4Q~T=br#yO?PBS9zq9Sz9uL}Bn*^pK% zHNXt9L{{ZvZKJa|1xEh`t>k9P;;{nUqz7bnnr^!Wv=GAv7 zUU!1bH~xl2BJ(u;n(9t>n1>>KC*H#{0LzDH?B&(Ow>e%8^0njuA!2QT1%F$4EB+NT z5VVAYxL35&C>xywzA;7OI5r0M?N?{KK)i5fB5+S2-A_g7!&{z*FE1CRooe}B1o@Ao z^HVbk#)L{$7-dF}$)aL=juoLq>Dj!QBes(4BP^nLSbJ-5Mm2cw$2Q?+*4Z!4o2{-~ zHcGOUOC)H091=L+1zAudPk)h|wJr6!9qb{DIeut)L@t1Rk$uE&ZlXPr8SveNI*EY| zByphEd2}7ZB${?sRV%zSgpv2Us|0fS@cA~sGjZ3M?d`4T;5GlgwSXh0=wrS~RAN_= zH{d+u{n4c!=oUIPSkC|iB&Nm=I=BLB^f^ZsM?Zs91^B3D;%c~LvVT^QR0Ee|2o4`> z%g!pGt4Z^{ZNhYaag zD8xK3fHxAZ6W^N7u<*GpNMMkzUV00429%G$=glt!=ONJyT3X(h>F4vwBw@x^Rh>#jXC+A|67I?CsFuQRoD_r_33aD)f zR8&hb2iN8_WpcZRD74!ehvHQCW4JlBrN^QLRP_|{WB?6Uhq==!rUl+>XFlUufsf+| zGMjLPpebm1nt%1Ha^v?Si^O#Wb%8%$D5Bi*U7SUPcnM#DQoAv`B?XZmr_6r7pii@` zP(PSjC{hhz^ufV4u<}w~9(*ykD-Vq`K2+J&Il*G6__YQw2%~*4|7=CIUtr(`w?rdW z4Ae`(R*FY5$ET>Av!Bkwe7ZV98$UJFJXe6fT6pJnW`FCIv*Gva$ARxU{ZN12msK66 zMozE(6EjX?Pg#lXlKu=4>oNE@jF7f&>nQ5R3n+5S>PO4J=_K?&T)G(AgMOqNrO_oOL_OHWX2)^5Dsl5ie0-_PDK)R>@O(cK{>bQH9^8kzeXW z(KMy=scFin9YdiWRV*b`uUUrYxR^cp`onLo>H=2P!@tSv#}!+LUF!PjmwkSn#Yj8E zD0?s>{&^RY8Eq{tuhu*A1A>O}gHkf!!GbVpuzy3J1_!a8d~p4;_S4s}`3En7dX`}F z=}8R=65~3d=B(pNLfG}EiTg~9n7##GQSj#yvszq11jZuMm{mJc=b24jObM7eXMs9} z!B4A9th8NpaZ_uLkS!vpP1o*KR@Vmk4wGhkq+J(^>_80)Hp*~!K`r$HXA6=R1;*F` z_ZQ%N*dm8136bRd#2ap z6N)vA2j@toQdN?3t%U?^M5?t9Wn!`+G>D~19YZ(&qSdY)|7Zp(e3L5PSk-Iq3ai#t zKjBQ0UneQ_+GQ)Q0UN*1A5$T=A>U3beSdgrP#K!(MLd9gUyU^68-IxNjWMq4z&D5X zuY=*%UL$tP&JTNFZBvbEGG!4fbD|&fj%tCO$Hyp@r~-zl_Kr2{k&JUfAt>B*M%tu3 z5NW8hkf14f4Ze{U6(;^8-b3@DsPqWAiF499=!LeXrxGHvZ-?7H>#C94$+)Xe+JCCp z0Uu)FocVmm)`Iin_rX}P#1%s>0%YuFK{?p}-0u+{RvQ&fsS7#O zaJq*s8sit*nO=QdtGOqgcygE{{#G~%=ZxW3THN)|T4r z`QnybP!l@d%6UKN7UX4uEPu%Jv)*97qo>?Vg2s`V%T+JV+GNqQ-zN~Q&qKSu zoq|qZ)i~5D&OO-OzGj-{3fR!9TFn?;;!UoetNTWt>Qa}qU2822C(0bfrUv$;pxFo6 z0)b<{CS(lWYd5ma@lMe+%Bb&vs9mOG1GV&({FJt0g)^F@L}}qg!=* zMP5~*suH(hlKh(cki}$NQU6TlaEs>t>~q`NMehGuQD+#-<7Mcmmu>b^pCj3}lOjNk zNi!b-p1RY9?yD6Nccj33H;e1v9MgcI;}gxF_1FXkafy?60s3n(oJDmWQ=(?Le!jZ# zwS#gG7iID1E%4RS0U}0C-+y-Jd_)${LU*eJ+OVfx;&O@F%rBBO=<^yrZA6)cJhwp_>Ql@r*vkBg3jp2Fb9ZYRE(CPk}Pkr?16RKrR)k!JU zd0||sA5Z|)N76TIHk63WH_n4lHbhCQqd&_r;kVE!kCJXv{t*VPPJb>E9=rJ~=MBP* zN}_Tv!bQNcv)VUeRT6tlF^xNxWYA>~Ri8WqW2yK_7fJ(pc;@PH(R|xGCApixm#j#l z>&+2lp`eJUb7;3uFhXsRMIh9Gm~(OyPl0*h3D4|E#WRnC4Mk9Q$nskimfn`?VA>dM00RV$LJlM7wk}tA8p|UOJ?o_vor72rKM& zFY@aCdx4{)uSdEeN}n_=I$lK4C}Bjc1J9#n$vD>Vr8Lfz7ik(b=5CVaWGAr(n{hJK zkCBGd*&rTEm z@mJV>L96*01G2F!CMFxQD;&FX(~lv63;p;q^8G;OH$t+uI*+4Oid^ivrS5-=>;rTE zb>lmB$3bTbS8kr7aNItzDnYVEQ`?#%$Jm}^$KQMd?|))1O6(5;Z~cRZ*E0qMtt}Fi z8Df$&&aCSAQ3ZScJ5Z;2e^xHHHvS#}PC(m_PG4-H*{UO+KjfE`s6Yqr(bn4Xv72*p z^4och%jO+od@DN+T5o$AG`Q_NcrtlZ0EPW>ta#fJ>TPb8W-EzVvDkdgPZFQq27$Ht zxct)obAMz~odRyPe@HS~9I4MytaHLIv+kBYAsAWLV{Z@JvFn$)9XA3o2x5pA**o;V z$M@E?y>Bb@4MIm!{9VjJh>eWB(b$yNjCU(l#lt|FJ6NiNn`DK%XQ@RpGoGk(Qu;1f+-b?$8?j98x~#HaLx%Ae=IrSjE8M-g&D-aN|sV1fCpN8EP< ze0H6d{U^BiEUj9L2;()uS|mvk;fB;UH!XAs4WE;H6nO7W z@a6>m=qrhWQ zvufFFnkw}`Nth%v?_cV#O%!gYBkG;}u^J;!!Q+t`QVt5;(ZHfcPl_s>^hhb$w>EL( zKzxm6mQr@qKi3DQ_`ei5y_*wuO)N;v`bRU?1s_{yDk$-?_qdQ-n8YdDCY)_2%zrdw zRdWoRzvqxXL6+1RYp@Kd^ObwTogW94UPGr9KsDzy%7??MX))bQg{bZqf&x=x<3F3^ zV=-}|KD@{fDP@IC;grC3O+{S>Q(F?{`@C6QOx| zG;w-byx?lR(0xOykuop;%OI@6T7SFoc925kt;x0CzMIUs6}#32<@&n zM0Gn8vukvD%B^tFiqvCI>IYYIFEFt^79_iX7HZj&_oLDkkMV|qL{brVkb79v-)hLR zz72%Z+i@%Oqc|5O*lEZHqS=_)_xCqo*lu>Y$B;+cmQL(_Pv!fqb01H*5$mAH(-bEm z5ePrxCEe}wC%e4&1p}PC@_$Hrday4Trxs>ZJs=mRoBjKa)kcF7mH2Z>8ER+2cVLuJ z@NdZtu(^K}t2`h!?6YvsDi;PQQrWFTx4^`eW(F3MLP^7_WCE>)9P-zAcYqgg)vU-C z2NTL1S~J$>^5oaoIQFWUy`|Oq9|WC!ebpw{?mUBjp2d2h30HdMNPlfhqsSBG2htQb zH3RgPepd_T5xf*CGz}HESIW4gRz#;BQoQ4f>V>%-kGZQf?6%oPTNwy@nQ6@*~zwG`PId&je1SYs*jYPp$xNkRK<`S?B|v9G_A& z3aemBW$x=E!pg)9XoYQq3Hk{mTe-^e(7>7(+h(WAWp$c%_x3(!Ityj;6Fusbp1fVl z0ysr#;9(ii+M)pZx5Q1PUKnWhO$5li_Fx?7J~jh_6DkYwyMMv{n2y`C{-+RjnHt8v z@7nsr5g&y9lZAN18hSNImle;OrWiIBcXfE)+mI&NKNsSaYh^RSv>O2P(2036g1yy> zHz`W222msi#|k7A>-d$>%y1U5!8@- z_ZY$$V?6Fqm&dzpa3wVZ{yH43RQ5yv^%gUWMU==+S z7%$AJ1Ak(?#r-|cD5corz3oHsBuBH`Z!0msi~MVCYx(wKBj&|LY~IoTPXLlBZPqG! z_s?Kgl?YaK+rPTO(dZo->z`e{PaXIAvwE&e2c#fsn(h`Y>(5y=k#*lygT~_``Uxl_ z8ODebn$1~kx6`01$JiI}vsCohr?M^f^4H_U0)K-Zs32g(8_5Vy znTMVzf%5s6ALX3x*!nvHjH9MBg2ei0s`gg9#d>bf6i4{``4uY_dXpp zC`Yf$W%JT`>HU;5R4*sitS=|6=h4#rFMXgdQb?8`bS|8Q+=M=!Kcv|*UV6?cAZXI? z%YR`KkEY*em}r>|WV{KVq2Ko;jrtqPl~<=Xgsl~qHmsN^v~aL1#Iu&O$QcPVwH|}) zh*VLdxv%BQD$tU12Ay*o#@0B}y>P6{;d*t|i2IgnNmvfyUn{%aM?RI0CSBAxu1eM} zmWPaY4o`|T2Nx+9ltI;3RjzON)4f~prhk7`f2jSEk29mK;f|TZJASrsBJqDZTewm? zNEZgL{3q(5xyoHu^*tisK3jsFl>Xl%L-(;OIoc|r>b6zbHzIl(mZx|4JI=%+PPsVF zRFg}yK+iS$?ipxhfb~6Pf}qKLZ~kXhe75IXB!Ad<*HwOjY(Cq5@W9w-yb5I9Ie%_c zILhF2-HNS^gTf{nX;(l!pLwta^7P|?6#clvMT&k2>$*^*LU)u{KP>_9^1FB~$sCB^ zC<-QMQ$%y<(Yc6Drcz$-vt8ZR=5kiQZhQwS1UZ&vXaI%!6b$cWMo`quu7hl z&Gf2)NeOaH!wiEE*xOBa z8bcuSN~(%Dfl4%sL~)|y8r=}Du>0`I=N_jAC_1QPbG;jn@1QSQgNyw`3uM?*f~$=S?G{Ro5eO zBj$a4?wrd98JqRJlcA(gXMalYJ)b4zqOoyS|5RExV(lP31ao>RF1@mS@WdEHR1++X zbS_`e@IlqBH1c3q6?WsxV=Wk(B=vdK0-qZ8R;3TF~ zj}OZO(2zKDhIB`pgY{H3$Otrpp)k;elK80$!m~9UX^U71vL*J{EBp+PjBuRP5f(5s zBX1zq6^lW#+McDCq<;%n0x-7wp^>idXYwG#nb_~Fwx7UFwR<>b1tn+w+tw#{Z=2 zpHJHv$$XFDz0XkYKUH}h3CG~WS_RX~M6Nf78}2ohlhx?I41biful8_Zh=Y7s&*W{K z5*r=1VgH1o+f!eFDI(CpY(3f3yz0=ZdV1q8TT_~9FR^LStUxCHSY9xI!=66_Q%fvPwVRUzEUO# zi?S~La`cWgF@KqE;)VRPvotTcwfLmpoXl6Tx~^GsPOs`SKS(x*vzs}>h$q9N#Y(aI zeZwt{qy^FMBHs|!aXRqL_5t!%o9*EPB$f_^-hN6G!{P(})OR^| zfwtB&%HZh_HPW~}ZS7e(Zp*PwfZhy(0xlS-`tqz9+J6ddVvzFEt$T6MhyDVa;gOl$ zADP;3W47gGWrRF?u5;>|wd7ln*J%?t31P=7r?YgN;Lo-a6I(m3TY)>^P#Tg`ryTGX(L8R zoxV($v9f692C{!BHK$^^2*}wg*aod`CU>WQ}oLg$OEXRwQ}K z+YGz4!}WeJeDVHQtcfLbNE2fQCgX)=_xYl00kPXf(v)?DFPN-^gAM(3D`QHygfaVO z02NNVK2({V%`s;?BSqWH%(IjufneZT3x5GN>lxJ9HWNwMYlUeLsi!jflRL!A7zvAG zYGC2|Y`5e7qGw_E73RRkZz=*XpgRyjRW!{Sa7yjvh5(_B!?NeyVE9(23VOMDD3TB6 zx^i9Sgv=OcKa`Mi9f}m?eccYZ-&Dc5F=8oplk7prfq0J25uoXtY;tTl`2!>t`+r28 z*92Ax4{TERJN`o8U}n3!2L~U-vxz5wEmMgFcmg$gO<;3K#xD@Bst(u#-k7Pa@xeU( zsobg!XdjB`$=#!d6^WT7=EL#i0SSl0Z#iqjd)W=vEn~N}R-|k*#PW%#OMOgpoy$1y zjy>(>cpKt6;FUE9|8(cqOVCB?qJK||Rwp--eEfeORQaKU_w~i{`kLep*(SdlHa zrA=l-45gM7GQBlR7Wk&n)r8l~>cFdR!LE~?*4o(X+bewh1Q>~nL0xV3FO9B*lk5%# zUw1@rSJD6<^Ef{9yOPQikjL4Fv&*~19kJ=i)(t^Xn4!f5)ow=u)vbLH7=L*b`KO8d z2~8H>d{0r9NeJT_v)Q#1NI|rGWIbc(2u%|6f?i86Cu%9(GnnYN3Wma~+QB_^spv|= zXC}o0FQu?2Nf+3idRapn+=9zTzSb8jGjx9?bXkoadOrIJY72>l@XGzEc2X8iJpijp zIpaPT$az-sdXaWA@+5n{4u6v~3c`(tbNnej&>5o&Dq`sjJUe@JJ&aeR2{|v<{_Qc| zQw~8#S>_4M$d7Ed-ufMBw)SA{mDC#RSA z%!|EV4pGbQ<1N@#s%We_yH-C&dRg*ZsFBy0Fn&YJMrhZW(swlFK7ZH`hY`IRz<+D? zEB_;i)cUII@|XnI;1TsdPg)a2rXt;_86CN&4x`7xMd`%$OqHH`cOMB99xaCRz%hL7 zvwc8n5ghZb7THozwdVFo8}!$Y#9ZqACP)+_dED!<6-^rti+a8uF{=4Zxeb8jQ{Y5W zYU$1p!Ea2QtkccEXn&-FPUlo{AZJcS<^nZ<4E%ub0TR?4tF&OJ@BiXH6G2<{I2-`q z)rdz&GX_v5P+fBDXp&$*@yQl{*H>T00fAK8_&wF=1HTR&e=dfk!_NWCW~nN71t-}BFO2u5+_he**|`2MnsUTGv}JK zu^#6{jv@#;pV(7G&6%!Q*y2^Nfqv;Vkw%Z1i|Y#Aw;%+ncM?r$J^a{2G9-050Wj}` zcM~xlQ07+06n{EGA}Gu;UbeUwWI)DOD7&{#+IM{u=6Avyo1W#f4;4G4Ml;>hPfy81 zPXVs$*CC|yR_~r?w;L3+O9|IR*b>Q9VYHzF1xUs^t@c|k%0^mbccs+ci3J_*r-T%{5K6X>->5B4L9DmRbw!bi+0?YO;eufYEs<83T z?s#)6jK?{WeD#Irj4B9_TAc`y<*gN!W}uB zpb%hkNq;)E{>q_4f{ntP;@ed#c~P!ZZFkqm7Uo0zmb^TsH z+*D>ZsDHH2JioE_?WzrUikdX#(x!NiIqk2DpQWb2?u!zy-J)8{7@%0e!oP6~@V{uL ztgpL7Dgr!zn>KXG^3@m?0C+Ct(-0xO$7uqT9FSEL+rMhjp#Oc8YgU$Kj1W$YK2h0_ z)k#HEu^47td^2r(>u4B4yN9V{`h_u1fl#&ZKWezJ zg4J&}ooG9NO|hhzbJ&q-`!6Z8OPd)D-QmYooQW5N+xI((+FssmZFd;8RNQ$~ELrR5 zPN50u0D*h#67zUm5tsBqy(y(6$B9f2=#j(nnbLT@u@jW{Zz4XA$iqoOv7E54Udmu7 ztbY({Jc7!ZYka+bgH&A}H|7BRZeT&H>1C@BAE_|4sM#j74;EtvmW#VFhe}h$YuY|m zFJZqUiY7*kabC=uQaZj-D#~u3J(0-#EWa$|iQw99nE;2EwRZb?NGYDYx=(tiS;84y z{Ow_(HVCMnOpn+xA?)zGI>wsSatSFt>wovuRryi%`iLsdH<#df?2u{Zr#7MbdqLUq z6vyxM%*=_ZRI%*v<()+Tj`v)wmL8>jv6eznorhIMnt=}S*q2PD5f;WfA!ewH9#KfV z@RcM8AR4kh)=EBmVuojfK{-Zt1?-+*J7#uEkz~E+d3KJX#dz>Z>3hLD_s@j=(SN_F zf6GVEjj#R6(AT-j_A@EM^-HBECd#*Ux&#Uf#~SMJ9;I2TgN^-MCWV0ol;wl_M=9at(|H5^@Gz!eC1sK&LLbbs~@pNush zOj_BItncH-!e*S3$q&HS!(AA%G%f_6lqZ=hf09^RR7CWDSEZ0OK;l?F&N0ck;O4E- z4`mkphY_jykrT0CrS8yj(jTE7r zYs#6xB39an;q?$f_Pu4)BQ#;!r!-m_rI8k?dHtFshkZnlI0dar;Ll}CC$0Mlms2v^ z+)yH2FSHYQgyq{#_q3{7-Rll0aqQI5Koi9X7E4O$9N3$@E#Yp2>wkcD#TWCVwW}r@`D`CeI0+g1aDu zYp%Kk@x=;R3GL&{5orTIhGD_9quEw?-xmnk4x%iP0e?#0+Bbk~66nsAaUMJ0DrD9z zI?(_kRP1~DAB`8x(PP~H1a*%v;eDZcrRw>*9nq_&mTi(c^)Y?$Y&9)dHfVArUIPQg z@0DGd8T>mq_bZsdw8$p_K+)Iee+CUr6NCIh58EB@g2%19FVr{8-=_TAW7_>$_UbwlSLp{~3jA^!W5n0+I zZUyCHK#!csP|pkJ@SVA}Ttyob1$38GWiW|Xa=97Ut|WAKoY{10RE8V0YH}Ud*>9jn zi)>I_(dE7H7wVozN_9gi7M(395UV_`&i;2ATHDk-pZkBA03}QNNTF9=hB^<_lgCKn z)?^)Y6or&y!)p5Xsfw`<1!acapNIC4{i`4$x_=wOmB8TjG!=daFvWgvPifDUnK%3; zFK&P6gvKp<3<(W+f1Ot7fk0G}ey;QOPKNHdhuXT0)xLZa%n&xGX4r5go7J1I_yGwB zkJRQOU>AQbyX&k56{8CDGj_IM3;*2EZD)19ynfHyb^9psdWp014z|~G4k?^U1RurX ztL64FA)d@OTH~{!QUvCL1Q=r>X>Q0iSte2q_Ab#_Y9!I zkUSt1OFL4}1IAe5uH$f$P$cw_HKU_UR+M_8CryO%OOy%MO$&M6)go_(HRzc)OZs!h|4Lg7ImUnk@Y?}(pX43hsaV(S(@i>1rxx??_ zvzWx%&Q5+g=5zxOpQ7pgtS$H~EHeKvx4N~)ind`RsLAYg9dB#zF=S*O<2X-0wCDS{ z+zzwQP9nu!osj|Rqw)$I^q-1`86y_O&Z2L9h)#8!A;s~7J_VFgdfR%i{C8IT_+pX207`078w(9BTvG6WX zI2LeQA&;Vc7OHh{%V?(ol+L18CwqSrOhJ<0aLkD^G^EFOuan|Lj31 zEQopTiv6pMZX0d1R`(U-%$_BQ9tLP=V^KqIX}LalX1n`U0!sDKpS@~j;Y5&UK(M{y z9>>#CjH7Yn8}N(cL++&<@xXulH4!+5hHN5aL#yG_Q@U4Bv*@rWn^4heEG%BmJ2Fd4 z%iC?c5)1alzataQ_}R~TDXT7-Nx_S-4D$u8k5OCHWLQAseqPf+DMrAFc1ox{HJ*C#qO^#Eb`Mux`xF+Fh5nXy?j?U;lts#Gx_I^=IEn=r} zx695oHngwpfW`J*kg~ON+8eEhmwpA_K4 zhqDb(X`t`#ZNTY`_GEw5*7b&s-X5b24Y8Ky3SpDV@%%r1pYZ0Iy!GwvIPOn(D(x#b zHJH{Fz}c8Tm79LL^k4RBM>Q@tDsFA|fV=LwdxQFLB@Jq`NW z1R0S_Xhh+}pnRf#4wd;gd)OJk6+5-VJqTqc}+tvptVHJPtW66{+duQ7F{DV#T7AiVw8b`*)IpkpRni=&@6ZZ3H~sYLfO$ z!}*3_0hwIF|FTR^<;W0$r(Rboo9Xmz`nu@dVb!_;7p&}tD_E9jL_lz!(A2<6r-cd> z`*Sp33q4i#RU<V`vBlL9`VlVSo~Y`Pw&FV9Q!)inw$q5z&~WmJi0i0(X8bPFlViw zAOw_ghiU-)oQwh^qOQ%9qhw@ zKSXWmeRY0KHss}K!hTF%k^3fu-i+s$!PcMYcVpDVkTD=h_u4CzE2K{k;Tmj| z*um9kscDRrUziV$-*SSB8s3*N!m|6fcSwH#K1c9-8&l~P?1Ws<>8jwoW5re$O7HRQ z^=;7I%&Jsc%{x<7?IfwDi-EiSrZ{l7Yo;Axxtl5{uwLg1!L70^CHt3kYs?OKuWIKv zo)3_#+ru9u_F7tilY=mlc&}V!E)Mpr^DhD+ipqxd0{TU_C;Gtx_e0x#3PpR3^Ob*m zs6hv~3MA>pdtp9RpG{;76~i@<`^*#i}}79sCUaT9ml zv>4t~A%f~!lAaSde`l7b$j6mkj*|Gp)Zp934xO!>n*leun^(Mv{<1Tno&jnN)c|a8 zq!~C$_4M)^6G_BjA4_t5Tso$BroMmbT*~>1m1R*ejzrvEUW_&&ZI7E8riT090Q*IH zZ|@6NW^Xm7q`yypQ-!mx$m{hj*i0|Bs6DxT(`b~s`oY6pOk1s@VW|VynISiNg-3*P zm{25p<9O1aQQ}~r#iG&**m4ZQ2MeG3h8e6#TV0%49BYci+*e)xgG=m zpgFU1@+QR@)l@4L*Ww?DwX3-pYKBXXh1T;!-CKLzHC_@`$N|2Xc_gr(%UCZjxHJcX z5OheJ`;EU_WnpzL7N^FbB{qLBnX{FNMhPe@vn}-VJMcD1@TGNFALlH5U*T@(en7@F zpVECqUa0$o30VE9r;in9^EVG${N)SEcXf-Z+*d@13hiIewlkgC=K9z%7j(RR zHuO7!AsKUNep#h0|F;wN2=*DL6_O@t0|*|wnc@rr6$}l95yI6Q2>M?Q zA4TfJmZ$YL8V5~+FqW_>e1=3CQ!HKP7tz4L zzjmkbkUHss!h~)bW(I!~Fq+_C&`1GdmvES*#WBgV%gD{^>E`R`#2mF}w55SO&^G4Yy%p`5aZFnhm}nt0!k6Nc!^UXe56an@sc`NSP>1 zw!~A$B+Vl6yX01+d*T&T=&CCunl$fKro@z*Gb+oJM?L5G^x`kWdU3m8ym|S^x1J-Q zU1@)U9QM3eZuvWr1NUx&$*I3wBg?)>tf=@~(qiA(%aHK-3~%N6C6l{Z z214d(@2TgY1r2Ii&NFQc)Qw|ExKy)C38#E~`?8tI?2lQ>Gy2-#h903SrWs%nYaG>B zxC2MBKjWrYdYy?Nd4CI}|JxIoS%YJ{1x}#yvBwWEA*|tDS@sYIQJiBNyY}G^JSy-3m8| z4nZPZ;V6Gr?<)(_Ep1b!Ki_uG!`*CXe1}{Ln7Yq4n6TI-Wzy*xnUcHG0;#!O-`=3u zvuWq>)Xqvrsh5{eHbt5rMRHe+z&&`ZEIdoMk;u+5#mS~>H6JgbuI%6I%G+C^TGn439 z%@2Pe)L)7*`Yu#xs4}scPsUh|M+^XV7Nd5Iomr}&j5W4%fDRQ)ve!ru-@B$<4%ov^ zN&$B-%zV|%PA>FvlLOxP_X0+0|8b7Bm2&)DG8v=4aTPSR-)lH^T9F6YMQj!>YA!*I zse9KsmE^xUj0OOL^Cxrjr$S;miQ32{14CZTkVS zl${RGU`$R05{R&vT4*b{6&40(B{Z!j%xp4TP{vfnRHACEoA=0=+nMy=p7{HHR*NaG z;`xFg;t`q))|nht!5>HLjqGofXa=E*WCWVZy%KuQQns+4MNZ8^xLW=gxZ{fR47eP0kuu*znsrXW#2A`cYv zjt~!7j5;q%hpUC#d49fm92aoAv;CH}%-3Ha)m;9CY2@``boiU8BzdRU56+~rv-nS)9?n$%pQP)=*tRrG=s{@4o=jI#NvhHwXxYh@)?s; z7lgF6OyMELaR@y|@2AI>2Gai@e@Q|Fd06=Q-oR)qzPBFYi^DEWSgkC?*$T7|FxY#K z1+Th+K*cqt$J7Iq5@?BnSWxBVy(0ZSqxEt+;D3^^qCDDW-LV)t-w}U=!+4%Qb)_Hi z(9e{K4)Tgt5fKa<_xST0cGlaaT-v>^(%9MSQ&^Y~4M6f-vDi^&rfo_x$4_j33R4W{ zk9c(Hq_(z$#ulbqbgz<=XV+cvs)<3rGZv7Hexu7PAU4?xseGkf(8XdQnz6omu-Iwm{K=h;*RSBP5VZ_p%AGSwIn@jb~%yq4V9^59e5%bBB>y^v&vt|Av$zpZA=hQ&866lqAThcR!FLnr^FRK*dud43d+=2W zweJmmttGEkXB{rM63>OZXiOnVpqslJyWC)dv6d(-X{TyB;z@s{OS=OMn_v!ny4sK- zK-^yR40BOYCn6<^lJXSD7#Bt=M8>j{)-op%1ZBi?2*N4AKLOa|`XtKjL)cmvOtkT} zIuao$6fHJ4?{gzMs_}b!@d-cYC_%FHj`^)+;bKXIXmpBoX$AVbToZrtgR$K2YbK?I zXz`ht(lbVk%h!MPD8kH!D>6E8N-6a#FV}e(zk_6mL@FL~x~~Io10UO+ z7P0`@aHC%siNUf6dGK@)grVZ|iBOt$VZMF?;#od$grGN$1TxCBztN?0xjxuIbu9}& z^b?iJ9CUxX2fU~rJWEqB#n;A^p&Rx;cPKxT5t}86-VT4~RUO=1G*hrR2#LVZ>Ctz3 z5i`yXQhBXtx8sDHh3@5_)+hS(-R3M!uFiqCWR2It^=(;r1`fof+RHGEng0AG6YuF` zWYgfCl#d!iF`7}bIaq|2{7y@3!D?TQ)!Pz{`G_#@amJMyhG=Heu}6YZMCW`?6;>C# zoU)N^YpH)TypN!O)9c*Sp)`ZDdWb_N>_$Az`{t+!k;w+BzI7@)MAXeY)Nv_?x9>)* zri30;^2jWqys6fuFMd>B3Sg7P(l4AIi zR@w>?%RJqLD-C8_g=*fH>kjfU{H!?3#2?-}JJ z34MQp)D0sylN_`ni9@arGkGmPZx%!ZVSYcOTW2+QQi7DACalME)jO%5Npug2zHR!k0=IK22}W>XuhqElY4xRODSi!&^$VJ5+m z5zl0aF^rX1abmZ?NfDd1Pk{Jt43tN68eT2zG_+a{eW3{k0>}%XN2I3#ywsmOyU;6@ zf?FRe>bD4ZFsusTQeWwAzt{i~3<_m#WOH* z+g67=JGSklgAO{jZQHhObdpXwwsZe;&OPVWt9rGnR(%+==J>`OwQAO)B$aZoch&H6 z1hF!*GO_Rh)TPuES=m@v04z-G2$YoK&L9(4D+hZC6IT!)KpSKRPzN~zSlIyoKv)qd z0pbphUd~n)f0nKQ8X)bzivTTK6EiD2D`$X~gRO(R70?nO;O_1&;_l+ccaOA8U%E<``2^~0N4LTwkH3JO#c`Cuj}mjpNI*8l@(xS1#|_Nf-J1;5t#p_o2_7k-aR)m`H&>7|K+(Yr;D(`e-W~-CjaOlYH#t6axDKTS-D7Ad4kMTtX%(*+T6tUABp~5 z*9QIPTogfOR&I9xSr7V0kAF_o%)#E)>;G=~&lvySkXcq-N?cBh{(lDecU#gP=wN1L zZvjwu{YOg^XS4qm{@qqFvHFjD{!8Y+ZUV6Wf4^MO#MRl#6QIw+^e=m`{OkE|Wbpq` zVqy-SK8&n9oB&34HWmOY$3HJ#4mQ944_%;}vopxv_1}X3Gs}PTe;Ww|@&o}9)>j;W z{GryVE#c+(DZXN#+vjitl+EDJy-hQtcEPjjDBC>-)i9Jc_0zZ2AK-(o$t!t ze>Rhu#DS2GC#QarMi{K%KNpi%Soqg$zpCcH)JGUzLTTaI0hOSxB5z#NH`aqy=%zR_ zbIxkyoJs}1NwfYmF6-!rM%#&BTfDcIrZu2O&(Qls0v*s-qs>`{6?1o4_>_sH1s%uO8Qx(TLhp?Umi>huTEF)Gj7wUw4N3vUf5~D(%e-Ox9$x;Ze6Y`tF)Iy1V!t}SvzVSU z2Q17;T!?j!H*QxaKWyN#WMee>y3{D7WPA=s!R`LFEQ|L?52Lk;Q*fZ=1tJUD(1utg zYLQwe_~y_%_N3npXYVNWlV97c!xX9?@>B6aVtsf_gV7RvOrKftYXo*we~DM(U6Tl% zLJ07SV;L;3rm@yfwudEfHe2;gl0Poe8xhyn13W2hB5tNw(E~iAq_$F&a|49jAovrb zdgq+Wn;UTYM?b}_hY6*y(wWPv+k?Dadp~*PKIM1)!#gjPm`DbGHx8BJ|T5S z?%(eP;OcoI(ix)CTNe_>e@03p`f3;LjJ#$7l>&QnbN^Bgf2^sa-WUuKg7HIN zKt`L7%5UrDXlBYk45x(3Oa^zEd_VB*t8F5Ad^I2}KM=9(_Kt_T4EGr6wA0jeiUtJ094N3$n zv-RC|pS3{UzHaD3f1N~ESK#%4{GwRxy0Ay~TorWX!BwRks9s!&{?^fo8*ohrUZRsM z>unQ1Yi{lHOrkj^IhW9MLh~H2Dtt|xkrK-TT+{H><#dy?nou>ZP!y{qwAg%h{8+EQ)!m zPcz!9b+aL#H@=Vgtiw~3Jn2V(uFkfL2vYo(&TY`JtD{`(SV97iIfj=Uk!Qh0TnUtr zYQ~bN@q~IthdhX6%R>#Cj=OPEwD9V0^!ij>z~C6+`iYI8D{RA8HhFy_xrW#Enz(Ob z>{)kix=e`=l{N&g>wF4JKg$&yOs+m1ssC-L@oA11 zJOyN!rqa2TP2wBu(50u(J=cJ=qKh&{L@Fxrl2p;?z2dP(<6GaQC*dF`|FMBt-=qtg z-3T$V8EuE}Zsk_Mb+uk6jZC7&HR(mdW_UGCFyIpHbn=z z2PfSQ)+~Xdhgd;;?{<*PQ^EpRt+s2@CS9Ok1WK18A;a!uHWAwmgnIC%sZ*iOG(Cc` zp!IU-e;-e?usWThVS8^5YB1a~wZ-1{lyPJPO+S3p)H%c!^#RY1aE;8cxI)%x74dAb z$MD3=6GZ_i1n%{tWUwrv6nEZm=!Z7+04qzKtRxt=@8J!`T)}5nskfEn*A?M*v<@}h zF{sFwAM_Nr^Qda;jJ1(bI9L!SyeB!L8T#Hxf8f4fto#=#vJSiDaH@w-5(IMJ(I?v| z149^hU-(PHXGMNSWBd)45gz-p+yc;qec8zJV)S>;>m?VNPmFSQ*)w}V1gKwsnAOFE z?ID|ltVF$G3(3cIb>XcZG8Sr+4ca$%YJiBJ=iTVhCYN=WE7F`A!}3X8R@K?^z8}<(A!R-@rQClVft-F_u5@^{Zz{fi=z)!{mL47?w+)<< ztF*s7)8%7IOOPb&jd!;v&lmGgUwwnFe_H-_M;BEp#w9AyNd`MDI@v0@aP ze9$PsLA83?Qa52og_(AA2LGszsyvV$o~I2yfa6|A*?V$My{gVmkq zTW6`2^#q8P)r>ZKV`7CDoe3zHLW;|_timR-(o+V zdz(E1P1E%mmaG+_`IR`DWI_R7BdNmZv++;IPcTzlNPj>Ok|!i;C^tnVP2U%fZ*-)Z~$b zS`0lIzh#M3HBKt7>l=#ZIk>l6wN(h@VEZV$Czfn-IaaEy@$*9YFu-x*U zIX~A*e~<_aE(o8NxX^(0eS!8AEUX1|b*Q=Gn+seYa^elUyC%&k+{gV#^I5LUn7cw}C zygj2M1fQiNWgYHt`YnK5pW_RD1mb+VWN{z$4Y*wsA~kJa+DjdO_)Y9ya0bYCi2HuO zE8H;Ve-yZK#Q(y}e<&fdR4q^9qs8#MDz6f+%<55WJ1W9XY6ZV)IQf315UDY}E7){) zaZdI*U~)$Db>oI~x%%D2bp<()S>9!cxv^VhnpSIsj8=E1qSqt&Qg7uaaJH;}TNSD1 z7R?Z9E{F2#9Pg=>RxY>pEr}FzM$7Xy#5u%s%5?5G5suz|f2Ug>WyBE~9V|97%@7Z1 zV)stoRK{o9G$fR#$<=dVY>Kz#--bMY^z#6b1a->5%YwA+DWAQ;SV181Z zGKqz*yajRW(M&J5A>t>fhKynOOqDms?e-0;Bj@*=&uC0(c!)tKVqu!mY5z!It=`oT z%aXgLI+RE8f2@4zqI$I90z!J!m7}@o=Q(DaIA~U8uK;Si;ckr*ZIrIoN^YH@T!l zQFX9~aT3Y`x0@J))YGeL!os(7Z*QtnSGOL-WtgXRe?G_DuIWkExnNlcKWL=*oCH-e zbZ#-)ce+$1x!;mNHe{=f0P7K5>v?jWN)6Y?YR*QMG+CK)`HT@QlYt(f&0k~ zj4n>9(iF^;YJh9D&Jw^VVu0z?y9oKgxcqi$*R|{kZqf`HK`cuTJFeXbH`j2)4B51C z2o&Z9e_M1IhcF;cbU8k{G3{<`a{7oxkne)g1HJ!2M;C8Tw{dx4OjrDFA~s3N;f5`E{6)7R@*D4$txd3o+vz@M~C12wFB=_S6 zCr^N;5jaIPBa7{Sqk$t}s=bE(+Sy~)i)=g4NRwkuNG2$|g4Im!K(rC}b0T#MTyz@g z6m|gG8sbU8mX*N2I0{1{4Bs8GP`psC%?tANSUerddXKiFF(0-%7|`oD8hp8pf4L3f z?NC#^<(2#KoZ|RKx)mly-HB}@gf68Bj#v=bO4#$bEr}wLwKVf4QcZ9$9P^_2FOt!X zZyHX`kzC6GvIG(KPI9Z?dlFHPwHe_#=v_$C;k`_6dpFNJ%Dr2obFod1SQfrw`{Q(~Nz zmHCrbPRaMX@gkqa=)!601N|_e?N?lNl|FcX?eF?&y^bZJ8Y_qShx10znV!=DRG18` z{FYLK-EAwOkg~jt+>$%=5;Cj>kQLMYDK0y?U2-_Y1ZILbD5Ez9TiLJDe<~6gOI_C` zCu9bbWlyHX@?2b?Zb}e@W)pdaU4v&xl(FqR$221H zr5j(wrCCXKzD!u&YI4Cw4|OGQy9D)H+?OOK1C6FI>rUQDlf~y3#nwEvym59sZX)mB z!&thww#!FkKiJ_#wk>HEe@}Oh?#?y*U$e+wQKGL!w6W0c;6Gh~*&&9#y{2x>SOLkw z(Kwf$xA}z_fBOF#Hn%(8u3z6LTmY3ayt>g2Nf1bVcF1$s--dfUt zd2|D{NHZK~i+UB=`-OLDgUiSZfex5|Im<24H8fj1MXQ_4%@IyvBfyHCE+6#IWzrT) zYl4DuMx08gE$}6h{1hdbcB<|h`hM~Vx=Lu7i(sSRHOUIJCU`%A@T9(H;#egu&r=;; zjdIn`HMaAuJomcQfBQ}gjTz4?=~gCIFj{GBrTTB_3uG_aLtU16WExQJvH|tYSBX%B z5Ilx)E+BllmB`AX%SSqsPJQOf7R~Fd6;9|&kH+c~ifB@jlO5&wriXZyJn#uLBrY2C z1iS~4NJ{nnoYl4{*LxW?U3&=5Wtm1d(xd=iRFun7<%>5;eF; zzgxEg&jKNVJx!M+MeR7eXu?T2gmA`#905fISVyqF7&!tUpuOrmQMcKKhulIrsJ$aPP0y%QX7+p_tt!*!+k57GIbJck&PNv8cG2 zaJGW!^)G^ee{bsE#=9NB>q)t7`exCUa7-Uw1o-sCW;dZN+hJ zeI?uC;lKGeTlJ5Yj0hCT&@Ab}P zR<5EoYA=tNqi16~oYtC%TVoy~1jwRa119VTe7jwrpB*f=1J6#LMtFclOuucFK@w^`ypE+c*n70kn>Nm*jSwv>9+}L4Q_w$qyG3$g zNE&MT6BJ$B+i1xXeP6FtwuWW69T8Lrv^24*k_r*2o(<2Bk+pRBg%MqCx`~5Q#^*d! z#t(VmVRgaOY-P>sr9`2f9Nno zH}Z$Ek)0t1Rxr29m?(N`drCad2)cB+0D*h}G^~DAy>q8qE)3~NZrB`8YTN&$OIY0FhS63jgh_Ac% z^+6AlVVhDRrA9AQn0A`d z)aOL;#z*S6=)aZ{K!3jhIudY`7VrQZoiuh0{mEYgJY3lC;v;tG;O9SWNm(MYe}IhN zv2+Yd6QtKLD);xf4-TJ$I`hH%MH^)*mY@LR-}-(St!b&*rB`;4^SX@ z-0vLeEZbum+eM2c!>L7Pd75U=u=!{O-B+DeG(mOAsyL&|=r;ZBIWicCi+L;$5oU;J z^?wU}Osf;5s~&amQHKcH-0Sah&)6v92}l-+8xJuF#?W7iY;f0sH_*H+fAgM4v%pc3 z?xyGuWlwcX7~_aYsZzluEd`T_altNP$1`tSlwj&9R$0OdFIRvG65uQEt%u=#(<`b^qR1$PR&7XvRr8z;J*XsW5w9gp;f36oBscLE z8Zj-0ffbTjg#m%#WLduUq!}g9!?V!0E-cpS&k?o+PDra*$r#5lf2oj{JCsw=shIFY zCzPBjQUhq2>-xITBZh}GOL$|vz%VKO{+Pnzd76B46a5CIWKDbc*z-EwiopPAApE)k zs4IJh{%Cg}b8CjDT}-h}V+%(L?&vKA;a5oELDE{f8-jXRk%ma?Zb`?NzLOEL?V(&g zeyRk_@pDUwVc=Ule_=@9(^t7Wwzf)0P49ns=jScPbaYzI){k*%pOC1fs|kLjJj1d%#BZsM&8Z^$cqZWtTGufqLQK>@LAoHX?Bdom>I z8R^Tyenf?oDek;}w+KVx?)g|<57N>wYMkCZIkGkR60SLjP=#S*E@ttKX-a1^s4r-- zD>LMAtYga@fAOamw0)mz`np7IM@V=EU`**8>AZVM`aDF-q)tL!voN4YPhuV%apJkW z^8rVnzcMc=0AhX6>*ZmD&VX6iJFZgpJQgk20ImX8O?COC-8gePd`lU;bZ;K}^Zf?z zYN>#ahK$7_2hUMg3n?s2kZ;bE>}@|O7AAFv4JB(bf4&a;k0?p>wWQlgyZ)}Ppjk*^ zzNlcEtBPTe)Uk$Wq&?v6tFEB6LQ$ZgL;-40Db-F;T6tFO>(4wYTR>MEJWFPm<3hA5 zpMhRGG^rEGQp{uM`ji+Skw%eed0QyC%!n-2b_E*}s~ci;PR3s+ntsgLZ--CssrO3e zV%t#Tf2Pux!#Fq(g_mDAR5};nKg3!%Hh!6?z3^l+7-*x+IXB?hIgLZV z_9e}8#>|ac%$E;K`_++uILR8A1uzUs>A5%y#>Qc@gX|&X3&L30BucUuUg!q=mG%|u zF}!O@C+DIV3^9);sDY1~NH^DWhNxId_vX$-f1N*5KJ(ATtR-KG`@AE1H0VgH-8H)k z=(g*yr-Wb=<0f9xz{P&u~ZA|_cZStN^6DgxeUy(P_%@^F*)8I9^_`78X zhOWcjL-QwDKK;WD+{xd&A(iC3id_0E=xlz2apMPHtakf9Q3#oLIP(bsJ0#vU=nL1n z1CKuW^5V&pHW#uk(X`gMe*7lNMmiqpe`=CJXsI+$;&jXMrfIq!MYj_fROUYK87w2; zsBeU|zh%6s(DJsdXG`B$W#_#w(Z>)u{7xljvh%_LFZ(N^^n)PnZ5vWqs-m>TcC6ob zcmT!i=`PAHX{fMGi?EF|6;qM*{E=g#qtk0&Ypjf;g_^0eC?y_FBSYVT6-he+&EHdxSAM(B2AoT9-l}a8W}4zQ*ViTSRd$?sU99 z##Ef)6|92_GF8PsxaZkJA=gj_c&jcx-C1Nk%n41SFPdZJ$?3ieS)G+u5OOWN)}ctK z^|8bs+V3jAff=Pq$HU`>P_q>4!1yuuKPz_bElV&t;oB0|xe{8`70Et^f6ZP8m%JV} zV~Iz%aRPUTQ%tajP=k)~Pb>r;&aMki|H5%r0*EjF$EQ$S_fh8e6vix zCr5-{k|Pl%=6hj{m&qiqmIWXUR*Q|CQ7%?}N7R7dgC(K$jH{)%uU@TXIA2cigX0Q( z*c*RF8F{mWi`T8;sB4@;e~r<~|6t031)f~)d27EGMT^(x&p|JHlqaW{hOG9~Xla?I z)PXtX@)hIhMw@;7c@~F@Nx_lE0C$d!?l{~G`{|{yLLH4+4O^a;T(08vHpMB#j1;yy z+wMP=AKM`jNe0tyh#6UBCE)kCA5vK94BJG}+G0gBf!la=N?S*se`yzuRvKrDo=>oh z4quEsz{)5>P`Q6pRc1BU#gbk*sgYguv_%!h{-t6xtGNWv`8_ygU`tk0CRb?+5jz)s zc%1BV8x};12uIx?Wn_U(M(Wjtfdp@`N4%JdydPdEA?UDYR3n|yc28iNil4r2Hj`9lg@bm$GiDo0hB_4&#P>)08#?6*~4e+n;JKrHV(%Z<_bpvDYJ zA2EZaa7u3bZwbUrnVe(ar0X?5(GG%?eHr*1loOB-UKc|Oh8*=M z2p@FUUa(l-e-GFsVF_>NCff6J0X|JUy1}5`!*9eyxKzhbL7NF(z>_YSg@mHX{yO8Q ztxPZ^AV#uSr{y!B5Tbj4@zo9dpE>lM3jNSBK7|7!|3FwMoO|?Nr z;uI-V==0Dhf9_bW?X7lHx_he)n~s9Ph*yIMbBFwge<6NKIS{9j{)lc~?+2LB98&w( zZB{rdt@`Wy>Lzkv`a^+p*YRhQmzYZY>u+M`mcecrax$a^Bx9cU;N6Q+jyl`WZS5E$ z;u(QAQBHj?7kJPrTzxkdqhWwV&Wc!7c((jCqJ)QS6)ax|BgFY=zz5#s#J4@jzzLI= zg{I-pe=QDCC*nZamHkhb-OVb5nIOhB_n|n;JRqY44@IGTa}}?eO=Q<19L5dlQ~P1k zL<%bhLu7#9G5#+7Rd`(6Pr^<1ao@-mZ|t>>ZPqcira)gUF}XI#0arH;iPtl4jz)h4 z^(iZ8U&uUQeOWoWr)wlyMxi}p6LXvrZJ{6ke=7-j?%T=fpUe>ZTtg0z* zf1Kyrq=Q>UCxsa;ST9-(we~VJSz73+i%rK854A6CFD_~v`j1J^FeZ$flBw+6#HX%Z z^Q~j>UH3$pI_%afjI}0#XkFX|A!nr}a9WC$RZ)M&^+K6zVZrp3Vm7a+gz#kdThsE6 zQK-^_;S<5JkvLQq{)VtLh$qH`5`7m4f98!tnT}^r<)uwTo+2%U(h>el_y+P*Fx&VU z^ZZNCirpm82EoYNwULgo;3BDWQkz-Stlt}SiX!(Qpp41)xGDeKbLOWa>9f!kBSY5& z_3OIlda-}yfqQoGJb8lI|6cyu0u%J*5zeR)$$WK2VWKI@vBc9o)(g=HNDUVIvy; zGLSmN0F(WVITLTiv5sAcGK$<>e;4U{C+|4^2f_7{aeEhrV9U*L#fjt_q%d`LdBJpK zM@OEUd@7w80oV-p@)Rk!0KzAHx(&2w-Pf+he8p4UFNJ#yOQ_U-we1vXTQp!wYy0e` zPgrWmEtMrkV!QY9>4}e3@Ci&ao&)NNLsH1#3)LcNVS~0x4HA8X5Srs7f1KeEeK9|# z5{6aZTZRD~rB{OH0QE*J8^n=JLq9_k!t`p?2lJyFiZ$D{CD9LFSayoY1S!;D%cY9T zCYNw0)q28h&zsZ{fU}eLvzB4|FCDJ&kCe>Q$|{HMl|ZD>HXqJYB5-W(6-*}>$wxo)I+8~p=kLT5Cn z^)kRD0;-uyVq9$;YkmDj)fUJX@GvUg;4vwS4M-1{eI)mavo@UL@nW#%5|=bX2M=C) zTww=s+~+7ac5rMnnOVgZylW14tk{O}8W=J*oQPvnlz)I`?<8$3ETJ1oows{l8Zb&PCYrEDo0#8 zIK(1xEi+P6G2e51e`bzC5t^TkpacqcSt4v`{?@c-$Y5I`q#t&xj;0f^KwvzTlVn3c zk3i`ZQbI_DP|dwdQtm5^b`(^uhL=Sm6Vv#EX*gbpp34_Q=VnBPtm&xns=uZYvTMVV zxN~V(BB>z2Yv-6lt!^VT`@+lpxKsP1Hx&f&m+8w0x4eyRe%68aetEMq(l?>JnD zp^K6w$PO&R6XnMjO#f(Tx4v|Ot)&4FoCW_e8tygDa{E&dK^k3!iSMVrj4eN}u|=#p zDpihI_ZyOa6s2%iAX2<2ZcCx&9S9WNWO>ot(G*>2D zs~vV_WX_<3s|*_X6r4+=)Yqa@vvSQto*|K<2+M3f8G%d9ja&Ak>0%*l$eN-w38=1z z@@Y*yzW7e37WTCZxC}7$M+l8E^e$C+JGRtRn^HeTf2;xb#Qo{SPZ{}WIM-rJ!i?UV zBmE;@nF)>L_ERPft(DMv&QN-v!xF#Yq;AUH)GwYM4H5!24mKR=Juo!6kB;2}tgo=NiT?&FkTcXzfVUdC@N81U0SD$IVt*`mU{Q&YZgBKz4FuyR)# z1)JxT8ff(iz9KaoTA5X@?#z$gWMpR8iw6-?Mw!VIB3R>{Ro$-O$q>Q9iKQSlsB+7K zp(cfyks^xc)(U`cF?)Vj&}kGT;f%b&A2&^SG=C_(4}?<_N=8pdDB|~|0rF{G>|j1d!e(|;%9StbS7vZ74b?`^!bQ|!ufkc` zTDgmVH<6o<2W=Ua9q#Vx-8&!c<*v&a~3b z3sDm(%N$b%-X^P38-3uiXSip7tPn!CY2X~zboLBVMz}yJvX7Qt63;&#_Xiy={-`Bzc`=2y;Co@;Mg@ zzW{5!e&eJr0$bX81^1N|CdcZlMkSRqM(bVygYt8604uH*dV#G{hyqf)Iv78F(0`(R z^m`q9+GU2u-g(>yB_Sy@ocroIr9f}@5)@SWr#hW$rNUBy%W6;4d&f>$_a=$@*Ew;B zwwD(3@LA6SW6AFZ80#J_*&WNPd^FUsBs|6nHBGme5YiIhG?ZWTNp`h@0xO#>hqU+0 zVD9OtA18@6y{@vLeb#`nb99dGB7ew*38!r{Lb6r)%B}-OTam~!nj(lgw)nKmtmXVQ zuW=&@R_{JFt7nW0*QBOga7O#X?d~=bH|yktQ|EO4uH1aFWOewHNcBOmA-6|Ri-pSu z+8j22Y3t2gO=|rVfh4kkKyRUkbjN_=PuIEi`u6(kdaz2T2 zOq)ho_`#29{*KA=jq2c$$47-lH@D2?9)8|!KFKj(3-`sH;i=xpQmsWJ8h`!prT~dls27IAn z9-BX6BTMmkWE>)KO7nKvpMA14E1Nl!U(BIbBX};QeEh^L>s-(y=LTjFhfree&oB)S zu2XrL#FPQzdofc8i#&!mPNoX-T@ZTm>zPUiE|C6M^OrwOdTSi<^nc*}iVNXqp&{2o za1gcao>3ZWw-SsI=1UhmszuqfFW>=7zgV&72J$h!>w?PU4X<}I?CLxseUo(P1|GES zSa-Rneb>|#IZ@sO^O5{6CI0#5_ zunIV_BMsPa8Y_}UV+7i8fxN+FC^9_#W{j-Z_KuT&xK1?RA25)u+Wz|!(_G&qKjUUdAf%1D8lh20Ca+e&X zarbY#?|&r0bglwXi{QS}K(_dG)XL!81Q3j~s7(X_|911Y(%u^Wohs~zE{FD7JqmNw zMJ_}vrOk<=scqU0>3W30DTSDYJs>7zsL*bWionZmK|cb9DWS;#@H8!wtz`huA7kX5 zWrj(tYvVnAJFtYyi>(e75&MWqp`)oR5pvJAd4KOT(zcnKxtR_tk`jNH^h#6IAN~lr zfz(H0|E4vPNoqCGWtN`1>6=8OY2jf~r_H~E_JD5Grq&%tIq(6^I*@`tXU$Jdl_{+| zR~>FE#N+vd%34V>`-|zAzyTh980yxK;W3_+|3J3l3%%)D;1@w;UW^7*LqwwtQ@tfx zv42X*ye3o9$)+T3KMpr7lPHwO$k5^nh>A(dZIs5`WiNlb=i)CcI@00Nyuyrwj(SBTqE*9fZvi zzW{%%aDB<+j&8_l7~aX;sO@0w9%VL^)F091INnxQhMQf$LwQ#9bvlBv^KjtSJY$%+ z*EtbnVOf&u){rahkbp#Nu(RKl&Bp9E2&FaH|A)Z&4@^U4#ix`fOmXYqCjj-sMSoa7 zG>?g&g9?QXVk4}*=bh8A`^^26T(K!}r4>Rcgu3l6Y}0)>+Xc%U;z-mNJe=&z2SD=n zbxI+1t}^umbDit=X!oVAB!gDbCmp}{BGP?V7SXW+Q6xi7w^F1=z%#3wDN(DEs*9mm zY$c6%uZW-J?VJGX*fPbZ8k-jY7k}kbi-mUKLu^*20O;N&Z<_=8oq&g&KmkV7z46`; zS){GLF-iKCI76exYXbi%4BGdl&qT7rZyukrJub}ws^N40@&{!B%3KvvOHlRLuWX$~ z%><&dIAQNPQdNQIsv(DGm^6_{V)rz~+E1g{20 zT_mq=GJliDMZpvbBsQ5%Qpvsu>7^l&9lt7P?|~Bs#w2)`?Dh3fK#t z=KHNdg5mnc2QnvH%-4^mB7g7FaFtbSqk31W+*eVRbq>k5nb_OLb;{HpIl}Hm$ z>MQ>pYCFfOOM^&-Fpx4LGGVMyo323ySjjS5=boihO5{gfHGUrS+JA*{&JWp5x)?vy zEmPba9Z19v8v<{GKUW);MGYE}2wWPl0u)#;&W<6t`IpLNRby+`r^6o`h?gYY9>1?Q z*dN1s6kcZ7GY)4SX&UZrV|w?+Fq->H`jN}Pzhz-MQ+))addb;m1oApeNB&I;N4hNu zBN)c=bCG2Rmvb`)JAbggZcoz6SL(vh@7G&FP^lGHTMBsnsJZX=XV1IHYBDLt`7JqDFfrTns44uGoTjd%_Bt0OX@n%?qrVSn+mw}l$jit=S#@juxCV%G`# z%pKB?2X4XWF4~p2I;Nob$0~4{u_`nn)#bgrDM3}N!`&pCK_ZynL!0$K;6qDre_sR9 zU;FrsB5 z4gSdXi+Z&C*a3y<0H$OLSTf|7@wB(}+cJl=gnu1-^p*tgpAM}@-;0%4aWYW9hKC%! zFD+@2YB0tG%B}^OsZLg(0K3N--wVU&EO-w650VAiR-LM!&hw!9ff$OC$#TVsyjztL?U~p!F4dcOIzvu11%_OH zIJQHTj@sRQLA6~7uvLyoZf+kDrU%lV-$?s?(~k0Y;?PrSwv>yJvM#+J%vLhLHFRDS?e zN4`QJ*#%-|Zz)VUUT+nre&?n!p-qU8>kGVRj*9&`=(=UVQLBfWJYhk(Y{gW}hTX@W zx)#=V%ucAZmW8S5!7wPBUEJDXAF6RM2R99Kdc34M1FL4#FEQLbsL}~P_JOcXAqGTv zhM)Q>WNaZ${vS%6oSh0~Ze(+Gat>u-Z3<;>WN%_>3NbJ^m*2ku6_-3s0t>fh?E9$+w9o3ZQHhOqvNDwbl&ft^X|EIU%lG@OpLwOm}AYVJy+GH zAd$4Ub5Zwn0J1Q!Ff#K3)FjnqSeSV@0L+YRa1<0`PC#Q9D|x~RZ)FO! za|Y4?%fSce1wyC`hP_NGd6+1AipMnAF7p z#&%`^dFg*%w{vmk{Ra&+b+P)d>gWM3|FLY0|6`f_$NEp!$>ZM^BOD70z|6|j1z-ZS zu(E?=`Y+vN?9A-}oc|7+xjOuJ>K{VR|L_A)|Dz!dzzk^q58BnnM$y<72%r|Tw{>uJ z0XhK`?9G5qb^sX{<9{mqZ-1Dvt(A@E{}=dw5&wpZ*jfA|9RmwHBQyKI<5td+Rvthz zWh<9|1UEOf`A4XK#kGL{J{<+1nU$;UzZU`iqsl+$YG!X|K|DZ%g?LE91c-R39Y^=-x7WRJtJZxOP|BJ1utCJJZ&gEaK|5M6; z`~T`DAkYJ73b(OpZ_4+}I;}Od!cU@Tz7mpde%45XZj}XeZKn5D7u9Om(#-Jq8t*|J zFW()3a4yh9VE<}Q=6|7u)Hn`^a5^;|O%krZiuYPVR%zi^yYsG6@YWD+a08)d-kAE`8X%>Slk)RD~OYglQ zK~{o!@0xRe*~_$YI=%b0pT~o;nBYyF=*(U6)$_sCYtr-I)6D!=ef|5hi`})jPfR-+ zEb7;34~V;;CQF^+Nu1TzTL*2c5CPNpH1=7OX}fIOjh?G_odTKeg@VQxP;6gL1!HN^07@5V-8%lD$i3orbVM8Mt20Ae-?u6YlF=Di2aVnBPn* zVyh8X_u@OmEi4XyzBgv8aCK<;&w;Fq8H3dZw^H6T!;?8%$!avJL+rhGjWzYSVybYUTC)qgeX~DaDJ%_Fk_|NaC13ChTu2+$qC-ln3{y9lA!|d<(n2 zJ*FHE#M_)d7buYny!4*?)Tr7yn3g6~dL3L2dr-JoZmC;zhv@K%#na75`X6U?nBBRY z@y}@{YkyDTqL`qdAl)F(^Ei)pv0A5;4@V`q*uK5;Q++jJ+bvmHp3U`vyeHkE)zX`Ptie;1=wisJTwM@eIA>>sXd0j5s`Gz4K6bM z5&m>wwx1T@5ACXn3}Yb|Ef`am^iC#z4!<<>rhnJ6o`X57rpwhZ9y<_v;*IiqJV6&T z1bx0elu2`UD1begF`2nA_-VN56)2(}`jF48ih0OS>XKv)Tv<-rLT@Og9mrk<;uwfc z+q7?qo$n9R!RQ)~o%qWe{=O4k;xN?;=hX45O67cHyd8)RJ)p^9HrffxT=z!Fs^rez zFMoS3CXyM@iyLO7_d{lc%+}UmDne|i0IQB$9?6%$Ot5K`C(?gN9psBU6^guS>Vz?`QFl{Oz@uBj zZ~wD3!GXmVV_yylcWbaM(0t<*p8u*FIe(XeEnSj_Y609B^ASE^$AxrF@d|!ZtO^MO zM|GKI{swzbBOrA;iyyqIa;W7V{xt&DgZO1+XlsCu8N{WgztvOu36d@}^_7*cYRkRw z%pPFU^t#M&>Ll%V(Pl=_mqJW8FhSTqX8;LP+1ip8BxdXFc)}=xQE5tpj4}~%kbl2z zs@ug^W(O*)a7T8MPLG48JF~Sy$ZjECW(32&7Uni?t}T$a(b^&9iP(wW#uuBpqp5w6 zqL#`b?W`v~o%z-3CvZSS1$lfMgswPD6kz!G0h!iNB6II9Zeoop6Q+K~NVT}Zp!HzJ z01dGiNY_T>R&Asxa2YXUm$wSTo_7udCE=frPK`rhvxxaltB~>zLI{E2~@)4HZ zpQ&RicNjS;ZS8Bh&53J${FF|`AD;Hw8boEu5&BTu5M2AIN%NM+@#LF=f`4FHRY^_+ zb1j+>Pvk45#6xJb9DTn(QiVZ0=v(??t{eJ>rgO5soh-sb&;^NO`3q7t>IscA)O+eOgK0aAS%)(=3 zZYb4;CakMcqz-J(8T_un`mMw7%+mTOg;CCT%O}t@WGRYEc zxxJp=4P3RJ6~R(vS?c>;y77uNvcDG)30n0N=e*6<`-cQR{Vq|tD(H3aUtGB7O+m24 z$%H>VLlHl(8_dp8UH5PZNT#YVPJ$p#N#4e?=SilX16}+V&8N^jW(vrWzvEHr%X|V<18zxAyMJ?)SF;DkL9C~2xAlaO4Emp|8OmtruPH^ukcuF9>B30|XT8Q<-GtEIBWh&ZW;-ceXS3E6d1#yS&wh zU7J#y!S^4&J&Z0vy{@w94|hq=g<9)8WB8W{khk@Qrqnc*Y=1J9l=1#h`=w?2{<^j( z)|Rpo+lNXWy|W)1%tvk22+DbNd>$@e z<>aKv!Vd|Xo*d^whvJblTGG_n#`Di-rueW#sb;QTq%@0M;&1IZ#h8#vfXR7zq}s5D zjQM?jvodfDY=2O&5RTb$T>?8SnUQ)S+0?1&0Z6VE;7^&^-6QnJ`F0AOV*y-H7~X-< z2D+Tr;15YTH6AS+@sbbmBFqn$?c6`w{K*tN;E{-q-rh_yvTyOA<^(Z63*LUVbS4($ zV`~D6jfmi>clPyaj=Lkhf*q{h(}Jaybc(uS0SdU?!z#aWIIdi+I%*ZvdY z{n7lynXQf4R)ij_CLkF#q?IXIH}3Gl%^5ul>>5YUkSqbQuoDHVGMgSlhCglP*Yj9VHH_2s`1G?xl_@k;6D{C_fh$RdL=;7qG7`D6XtPB%p^!*VIzWq^Wr=_qQD(Vi!#gM z)qxdk?fvf0Jv{3Pu~xR{lRCSK)5_%r{%|RdGPck{}K?6Kd_Ntz!8CSCAV@xoBl+%1crVkyM{{w&6e8huWNE9ucO-aNeZ(*sX_KA z$u4zgq)nUbXX@{RI#?!UaBcHLwhA0CA%D~E8`Rx{%};My2_> z?L%d1B}Jmok~J)aiAP9pS$eD<5I8j~n=u4i!;8p5B2mTI3EaMa!F`mDUCO+Oxsxd! zXp#s9Jy~ZZOLN>i64|8kCiYV*FulD>!xokUyTs>$upp~eCaIg&`6N zvQ#Bgiz_toF|u>ef>l#L8#$<#U2lrIqx!dg6*Yl>Xf4|3$0q5W8sb|OsWRRsQ{w{U z*c(s%i|*$3qR5JYxp(jRaXgqpEHXE-ex!zjdj*L?MI$fS-Ly^?o9_Wmzfe;wjInZ3 z%AMkOp0osCY>_<@T?P^}rH^YPMStqHWIGmKqnEzRAKI1j=Qm%}f9Yk9n%iA1UGIKg7LK3rsVEC64tB9B&$ z_QmLfGVY&TRRbS=KMxW0ZV%eGA|b%K?okb21tL4D<||rem#wGgiqlR5iGL7`Z;nuS z9L4q8XH7#H#UXj8;bQd%_oAT|MjCi@S}oIAwYb}|wOWm5_y#1K$xjMX(;_OqdJlx) zzm7umLU4`nZ0RAp1rOnE0D5(9@C%a5DCb8zBfNr+bV~MHNSU^|v#EgHWdwdHgT#vh zeCT3C25NqRouQ$6MB-0rB7f-YkXYroB!@h9acN>I`CUeF;|*IA9aVgSP+%CSC*ys= zqtM&CZDHy5D1FQzeDtq&v6NA3ZPB=y(#4GZ+ML}OYd*Rfzi6GkykpY#iIGDF#Q7Qi z%G;TPO$9qO--$HPha#}iEq~qNzzJH1N#|ApyQ1lHJKnA{p3MheV1Fk1_=>4*;nV_P zrxS+({m+QALe<*#LZ{jjeSRws%^!pr8OCouzwUbA#4}Ls*>l7FP70B|mR|y75o%4_1x+o#ozS z?HP#s^MpR;FjaGpLDtl5t118$7vgRvDOTAfo%LvUqfN~ot$Rt{rh?T)ji@7h>;isk zywXFWHke40gR}+~vJt`Fu4XJeJ7Lxlc1c}i)oc{-^?4+PP=8&|AyyoU6LiaGh1AsE zEC1qXXh;`9dFq*DV{=OC0uAH_Anx2#{N5uVT{widJKmGn5rb5dM@nZ5@9XbRBmcf? z6d=0?B;As14wKT=@*i&{Ok$C2zlIK%Gyy@7W*H)q;g<||120312lI@6Bb_Fn-MHOk z7aL2WQA7d0xPM6*i5eljDv6DW*n#OU#pJ%i)ZQJg>U(44+=BT2J!xO?yMmN9c-^A+ zxTjXU^5Tx?KDK-2U8>4)0XjlfPfvmaW&K3Fj8KN-W3YVg1Wbvhq?om4x>5HN!SjbJ z+~+2a6LqMhe{S3&3O4Xb1EoGWJX~6;TSIrO^(0Ys9e;u$5BOt{4LzO~!e7aK;Dkd} z8V`lqJc)aua4Sm|!p?*|3FDjCorR57^{~Q@m$TggEn(o5-eFwE*2Hff0(u7*7Fx56 zsMpP9ovbN-S()VC&9+Y@LD(W>m!`~#ELLb+t+7(o$|?!BJi@HT^LZWpz0TUMks1uDaZ(2t)m_K*SO+7>*%$^y?dC|h z>IGk3g)o}i7sAmcXNf?M!?ML8F*0>QlK+JfC4Z%)l+Ng+|8fqR!BILEh=GqGLPUL3 zbM7ndxe2E*Iy9GgsYij;fAbP@^|K;)q-gS#YzF?}8P!rP3% z%=ndV%keg4DWQHsH@>ayq*AF6O-1`kpV)2106U&6Mq$Oo-%1;Chfrh-&-Ky?n5E}y zWPgc8oq^;o(wwbHGp9?XAa33cn94ZoqI{)zEpmt}o-V{LzP9_MA~T`=+L&9W_^P*~@RX&iZ_xg6;_1!e4dxz`=d*x*HL@4e>%&Sqyd zg%h<#j8%ET>LMji)1BSJFB_}+_<!f~OGz4391-+mybiTi=>yKkOtgk@F?m{Y!u;JJRyWb(>N4!yKQEu(Mn)_Hk}~I+ z39AibKY;f7eRnC*$Bj@7?kJywnhQ|}2W%J?%o}n@GqhSXSRe=MY9R;i=ew%xhG%&x#;lPazmZDXoY>btaXntwzEuarSAC`}rS%IP0vY3a*p7>D}OqC8^W6^ zuT~rS-G;!LHIrSk#}vKZ09}r?ckfXm0JTExPnFm~gKYpgg@4V9KNxE8sU1AXBoDkK z*DX^KHM;W&VJWYjj|bG5*vo4w6UHU}jmOZqdHn&nL1JQa2W`|6uPRX`XOVG-54;~x zo?D>-&CH z;xdbT=djj$&=o{#?)RDnZNRwyNPv;y<>S@nW#U^gxS#PMyXgAz$A81VY_0(>u@kry zX|@Lz>ZOu4dsK_C-0})TK-ziBU;c>Qu8`^}=nY4alC%c5i5*_c@R>&MCobn6*!ppT zFOFZ4h6wwRH1FeL^+I9#NcprGDjwZKut7|a>erOD&Zp_Vwzg(m+e~xx$YtyEc_pWB zx?pO&i>q^~cpWmfH-DNw-;*SfF>St+i#hVABqF^}XC&=|GvEr6C`|u7`R%U-NNn<( zuI@vDarmOlq<%;z!yH*I+-&p7(SZNn!S~K9D)pcXR9{PsDc6s~w?9sKGW{^$_KtBg z-$Vxz(nHEyeB3AAl_g$I1S^zC>eU?o%*ZWL3PV&NHXOcon}2xu8`vRcY%h#y2+wYc zB+Z@yVGqq;bM{<@UDIbu8-c{Wkc&J=M=-&O@0iR7=chF9WZqkqowN*?E%(tNVPG2J z=@{`D@8*|Xn9SrVcl55k;IrwJbG{JA7ifM1J_22Jjug27W>0me5OuN&0vUUGZ9)rPpSFEdg(!i)AFg@>Oxqn1y zXzp(6kAFWkI%uT47$!`i-Oikr{v3pjP{^T^n7qkjfRs{|9?@d_Zg+l?WeAiyAjLwll> zQCfh4;&B!pJRI7h6Y~159>D-hH$?Gwubah=)?Ocd4Y?pSDhRysFyXd@nIK4A*oyoYKbijrnr|-dH-~3=dM52 z3cWf)9MuOMVp|wK_u$jPy#4c(Zmjk85IYgmafrsHGmSKwRR%$DB?&%t&nqOU&(gnY zJJ>Uk*3|6?_7RKI1Dg$EJHKy#HOynH&3~yVi=VaUwMczpc7U2V)uEs$s&9j~q(IT9 zg=ze~!i0ISY~oe4!Gn89RT_PgP=~^M&VB`AtZnRN(2FbWMxw)zLNhq1 zUR$Y$n|4p$#UeM`Rzf}y*~~fp#@Uzl<_V4Ad|`7So$qUF+ys@ntrD)V7E9c<)_(%| zu9v4awuHT8z?hVb*{_r9Y}Ko0A9E%|QUQTJXC;ga^ee@h2q2G+VV8XohWa+E&3!9; z{MN9ZqkYxN5KAqxabD8aV*Jr3qNv~Cwhob{;7;*_k5g|;DtGAD?lfLnpi(T~ z;@2h$8V2J6d%6jYCz;G> zlsZUQ0%}O&*(wTof{XB8m)>J?O}f3|PmGmdafn3H9A3a#8G2kQ`{KrIyjc-hYXJ{xN}AR%@mgpb|E)Gt#K z=%Lyh-LlaRNx4`TIjUorm4Ad&dAcTee(88kIHfr_j0zrO`w0oqeskMji;4(bHMzBN z0x{5-y`FQd34K@R+UkYEL_|##gZ>Jp-~Ac!*lTybAB&Si6RueCs~iR;W0ySDIyrrJ zqujfheEqv?n*Rb1*$igTT_$eM9j?uHt^HdKNQ8_8AN1Mx>Y|SVW`Em71cBjI?J!6E zj#@VKH(@qJLxWW7N@xe?u%ye^=0Qa>F7%WzUu^l1jNFhWD8_f<2Z}#qLJEOg!EBM? zXJKC^Cf-AN75|GO>xY6`>DrJQS@Ml2JE_500#-fdGk>lzv`8^}K^Q-T?vxR@VJK+!2!%XS3%VGO5xyVNsWb+w87_#w z0?94f)2OeYsv9VFe4{%~+5!F?5JbQS+bT)eGU=r)l)}s>e>#=4=hAEJW_2avSWzuKXX%^Hyhs(ZL zk2@5ww>b>LP=B&mJ+r^GD_rGkGA>Poytv-MU8j0aD1VajLmX?1NzD$hy-hgK81lRm z2y_~GVAn?Xg@EQF!n}8J0L4`h5}G=n{6`dv@O&5+8N&0C?DWT#rYQXz_D|2S{BZr% zN^q0ap8vGXEb>G7{V|rC6NshEu~vY0AAO`udWO^NtAB}b?Ay(h#xLCv>GkbdZ2u!t zIqCnC)e)v$S1cwp`+V%R-hFWE9xWcKn5*?^_lw`pzxRZ82Re1w%k!+m+r$U7dIT7q zkXZQ*5h&bvAm$-mC0Fs)_8a#{nMXnOHi?WNo!jD!I>v# zoq#YoK7U^53;{vC6g#oeq1bAJ7gb+~<{3C}$1!m#6Om_?*+X0Sf?|cnnELusydL0_ z@%q&y9HXE<+5?Gi4p(&lrk+n!(h*oYulD#(p99;uykGGFbFiA#SNVR>?^XXELczUP z)(=%xAtZ~$VZ5e6M=nFM^;sX)#0F_(U*_u%>wnL8?tt$x$m{k8{i5oNBdqD7vuZj;rBx`JRIloZyIPv{Y>vtWxB$UH;lZCm%X#p4xN4kTZC48wB@ZdZVidNPmCIr{ibzsosyu**3W8s=4lh$s9MG=yfDj z&cyV9I(x2^wvYhjJ7s~-aexu9 z3Y$QEKmJLhf~u*GkX66}O%hZ9?Up!9A)ZL#eqM^3Z|4#pi~6V4*yXR^ZemhO=YP*I z3N@$ouEnKJp4GxDza2Ods#(Iom$Q{qn3l&!^M*oRy48qOOMgEH(gY|AczN17n!Gc0 zYXl##PJxnspXkUiZABVA2W~^3>4U9Lwy)rA_xI*&cC7Cp@fpY%FgyI+b?PcN7I;jl z5BtvLqt_*gE_*@^;`vrKNm!w|7pO9_7=?#xGs5Y&zJ|7 zjyL4@`RaF6apL}gwfDb9nys{jhLln^TeLjU&l4E^VjE5nUebQI^d}MI41ayWgdx*u zSCxV*F_nOf4lr(cJY%xrm=^MMGp4%#!Md-GUt z_@2BKf^0k)u;a6Nv<&%K*67O|4L#L}^m8{TtvXT4kI9I#7F7$LFJGQ_GKb=OllmtZ zp31ohw<%Na>Av#tSyt6tzJGL&>cvJgT*jqP`CvzUFBm!#OHqwY;!5VnvE_3YCzYpR z&=5IW!MnNh{q*z=GK%ZS+sq~L%SaQY_-AVld3R?HA{?^;Q|0W=Dua^aPo5Yt0~ly< zOS2O5mv7cf&MlG)KWXf@+BFQSeNC_nxrc1tymHq0O8MS)aQLU*4S!LUH@Tw3#fK^I zUUU|oiRK!@`NTz>kv4uFw_(oSpNYDyniE9Zi~Y5!K?v$Em&$39U3Ubt3#MUUfh*>S zqcll^>JAwQ_=wOD=P?iRby(M2T76qUB5)a}s5@_=_L*7~OANrrGL8g`ZYsO5Io})( z5fV{YfIJtbefP@#Jb$EdUdj>DKTnB&U6am+28EM-i0-dah_jsN>}HE9$T9L!kHpqU z+UlfZXHR!1IZYMGSw&6^zITubvdt1^W?aBi3!&R)cHCHfwmq|b%y?1n#)0vW(%=++ z$TnWs9m-HM4b@h3q46HW3G*wvQwvSZVd_@h8OT|mOx4O%l>M&<2;9Qr4&(bWb+L z9eIblsO!BYJY#`rKkPK#lC|_a;8=k)Cz0uW5%cSR-&0Y+t6R!C7||^S(#ceClHz8y z0VK;|iP0VF^?!e!1>Jhn)4Hik`F>C2+hWp_eGS$Lf09b1iD@P(7FQ+JXCDY(|(P6P15^w9)b-ZkyhDaY1sW)%6NRE`Uf0yI>C6AtfDWqJ%GD;}MavXb z!q_(`A%A^mV}<}rAMW69hzb5G0?Ww5;}Pr|3vtb39U9bUe?#LsW0Ib?7#!k5Fss+! zPNfAVhXUjNa9gn65rlrCZg*VI#dhrnzgA2toiW<_{kjVJ zS{V@tx77H;Ku&BiTiId@>e5Sjb(r~o*>Lj`WKJQ(Q>EiCOM+}cDtuQUFkTlq)fwC!Q%b$+-SaEcnO&y zipYdp$^IfUr4DE!)4?Kd1G!tl$FD493g{!ZG2|<69KbLwiidFKiv1Y|iOES;89roiD1Utk zMb!_uB@W!&2>%r?DjQ*&@6p*|)YCCRflsq0)RkgC7~2CM8rs1OazK+QiG~v=*?P)n z3Zu#NNaun_j2=YccgEEVMc>y<1}$E_RePWXX8lHrRiTR28#%;tgIvyl@ayNBgA`Zt zc0o25Z5kV8xZH67vCMBTt((gJkALke9JGe{SEg5%EPoHoFyG(JO9zpVXE^hoA4u0l zH!n!ddq{~3#h+9VXH$8Pi;d>G+xMr}9f7L#_V;at$co9TG27m4zB1S0R#^hQ?W&UC z0e_zT9y@o0d!Bo$AZY8kvsO7{nQf76O+DQz2($*jv43#ku{i>5 zs$yDw!Pyrh8?BS`j0q2t1@qi}E;EMkW0JzHLPq$+dGH~xSSh2hgU(c;tp^ZBH}&o| zQ62u`p^ighcGhj7-55R`MD)zK0-`Fx57w8k+>WrV(DKCQ&pyf51q9y~jJ7mvYRt7- zY5|k-=nUw-FqS{sX)b5b`&Zhx!s=}tlVM;p47gi<`=!@Q^@p^- zOW~Y<3Ki9$QCWe7Pc(C&`zpA7=*s#ZP*H+&eT9O5l|z;*6^I8WV}CaXAL8s637Goh z%qq2eei7^cMu?e(+pAUoi~{sN^#ytmNjUQIebd!~;6q0kBCK*X&n%D*V8V`J%hO{p zHG=SWvn0Wg2j)I5r3fdn*t@1T)AJpHy+mAB;m}y93;0HhBVXDZ-?~-Xx^=qt-(YmY z#phzieRK1EzPxVvXMY6G4w47f5vN2Ns&)O2le{dVkwkdPoCgMvLV`!e<<}l1&jyRx z<#~f1cL86h&g(UF#adnjb9QFwxE^jlGP#H^%dI1QaT6kZ{dC<)iBMVNop%8Y@pY55$>G6??J(w6D1`PgM9n^dGQe z`!WOZIGR0@xPR3MF0xskOqwS2$<3q3aCCYkje>s}U^2$c0;QEAb9L}F(r6bD6=SwL zl;KKEY~Bg!WAd0x{#=xy?DW><1btEth!JoIR_9E{!%+e4-w$zBYaM;iL(- zq3l91U3ZFl>7z2ty6tCS_ z7$BDUqJPcW^;|MMz^3Ff;w;K-nF!0Y6J$mVi5r+hzH+40Vs_7mJuF0C9^YX&_G)&G z5ddc%+FKc`FP`0~%`$;roQDm%C@bfID5c7>?Wp(IMoh`Q>qNW5U>m`wk{$xr326^8 zp#qv^Bm7VWr2pGdi>^`xH$@=E$gaY}w6jY)1b;J`>%4pM=)^Jwy5OobE)U;jiE%dC zC(iv9LM#j~ldDmjM`NQ8`Kz|;ieEO&u6tBgpdaP+A_k0O%v7|Z3_Tyx#pvS*LYbik zoUk zkCfq|+JM_kKLGmw{OLmoZsCjW;Me)IKY!O>NIYtRa{Y&=xz(F9Sw2-F-jm$}`birn zkOW$cxGEtclvb;_sY9h{YB~2YcBb|`)hzgdP({^yozT!Hmj;+^JuA+Y4Nf4$GE(~r8qIM7UG~K$t z)_^1*s}IJ5aV-D)CT&Qzie7v5QCgOcfdALyixJDx+K!A^x6fmXT z0OKz6ZnW0O#bbHg|6^fjfPrD?Y}oYvDAI06i&EvBmJ;;4UO&F1oD3}k6n_`anE(~J zc{hv#BGT&GZkK`!cu+Zp4yQvIJ9_)tj)W)MxVL)MoroIR5pQdM+LzX?pFn-b-gje! zWWT~a2cUQT%96=e=L>Z78)xns4b4ZS2(SnFd_e!oYuxi8Qhg#DT%9BBwso(41eVe~ z(t+KN6wusk8bn{6>o09+*nhlNL2^w;3F^zZ-_D^yRnlAxg-q-o>UG5}ADG8xTezlj zZ_;#8sKb5?MBf}wx3kZ0`H8HGwQ-z^LY;s8rSS!0I?F9L=U1)d^b{AeINFeNPlV=R(iW2rHEdt~?{G=&tt13%rwU zORuZ+R2Y~5ctD50t+c(!<+(rw*g7`;J3Qi)0uHX7GTJEoOvJ&zW+{J5z&XLcqCGT% z9aL7fl3e#XlFojisIbj&7b?bmaB2_eyn;CV@Uj!bcZS1E0{Ux7C1(iF$-IAF(7ht-B_D#N$D(7x=GM_4{lUYS<2k~8qq$Uhss};D7L|?W zCr1RYlV2@pFX9&E}zbcr&nDyyqagm%1rXBePHuohEZ;OjY4Uua(zrggF~8QB|#X0)a$ z?!9G&`mOVsOOVL9q8Ta1OW+v#)Je7N8h7OEjF13T&kH!`k6kLJ_8z*=;dPuvph%*L zkf00{z4^NwFPneUNU~aJ9~=}4UM7Ojyyx#QQrTm2c22Ufzlygi&3jdA-&>(v!QwZv zmgMbB=gyD3Mw^aU_t?Mn9Uz^KVXwihQ7T$swOL;>vmFYuX{5s=CFV>RV7PA&6NRcx zO==Em)xT4M<|u2SRVQp|H;}67g^G|ZVY|jmQK>~4NNs;E8;4G5Mlw(Zz!&>gy{WKQ ze07!W9d<;ZOd3#7xTV|hS4@gZf;l~}XM;Gy+A++Z_eD9uHEbCp3Ve0u2oO{>Y z!d`P2Ol*JtP#2yd&68^AfjY4wB)pDo7TdUL)$6+@=)d`g41W};tkO9}U z#cy4fDuX~9o076m;YfS7$VP{wAjvWCMR{>JgcxNME^K{Qhl&XKA8)#N{Ds zVQwE$fE_=yX#Ye)OEQVV_hw-zPn<4^iHQge@%kb?xJq5SXQ__fT-i^F*`z?$&ps{- ztm?J|7lPkNbF;V~dWv29E8>ifcs4}!E(8|!1#~YVb9X_d??)||Vo~iJrkjg^BkduB zd!m022MnLu2dt7Jm83w}fx9-0E-cutBy2z~yO}d=NF~nLbFLzuQ6`xN=y7RRf5+Jl z;oro0_|amY`W0eXih{Le-=C1H(_v~MyCC;%W zY%jBxaNIC_*=_7M|NCOnfrIZ98npP_N*I5fM|Q<0xVWUg{? zmNxpF9r{P@_Ml=Zw_6v>UBVIEPimu1ZRdjACN$Kjw}K!l&S8=6Kkoq7eSc;WFb;oT z<&d7!iuJ)AN+Dl-*|_-T8jUtbx?;0vU~A97#?NQLRw@8*+3a%fo2 zvdHXkm2|emn=fUNNY*S9E-)_lM0OsR2oD@P48zhV?Il^#PfO-7jPAmEP0?Paa?@I} zgMOeOIxqAo$gPjZ&&MbIs~v(vw_|@%ac7`?tplxbm7UtMf$(L@USzK`c{lB%+lfve z;C^ipB5!1XU2(9hz{^O;bwc9&qGwXBwpV-d2O*ndM+#QhcBNN_{YFi83Fy61;`{2y zf&~*5rUfIpJCiFz#Q`=v)9ofBJv@;IxFfIAhAyVwgH_LL*;?g2E|U1mP}(#HE8SIQq+8_h`h++#xc9h3}naQS*0UNFT|7RE^_ z&DJt=A=TC=ufP()M}X$sHr_}muV2@#*f)RrZC~X}Eu0BfQY*J~M_D$@exrHj_*ib5 zEa(Sn=ww29uY)aQZdQLaSxp}v$H!DEy<(}iSx0{d2ieBG!aRod7ygZQBXv1Myxxc2 zo!@|{_2wi`5G3sCu9*oaJb`rKzP6wgoz@bUl73IzXkZ3785ZB()9m@@+w4$Uaq}*$ zAf`OQCcW@&;sG4==NoZ2%v7aR+u_%b;)sLkSCp=`v-r611y-z?1MO_r5ihf zEG%i8f!`yZ5}WsHzR3vGZcZ&0@u1M3FYQQ76u+_#mh=&=kv!nZ=hhmanQ(^1=N`^omi7RP`Y3gCNSj=Gn$Tmn=nRzL) zX71F}=m7M`xbVbMHC7pJ!|WeOZ4CG?j=(pV~9v`O1H2HK16e zlAQeNm695hMxpl}{8UT*dvMu@X$n)HiYk%YXKbn3Cp;VKROG#Wml5M4X5Q#K5!>~o zj9R0GV#Mh(1-t14^`l0&Blo0veAx-zZT1}PoIp6HS(#n-?`Rw++h)T*V?ftXOuFU; z6>+?PKazjKBmsMkPBp!HfiU&r{n^k~(&3SRA2AW|8(`6Ck%vU~MSZPNn&(bO-~Cy( zYO2bP#ZdLvZT9sNMq&+Vi11HQP{3+GKG}QbrLv*OuMtz6A$N6HH&ZxO?+Y}Mv06hB z7sP&o_l>}m=3*)mIjffeyqpli0xszTql;Q+<8FWMS#Q9>9^bD&Uyg*y{@#6?B6X>I ze2jP4GJYW^f2moqns*@2P?oWX>!2&+e|?Q#jkicw`mUrSE$o@?4c?qrmqa5uXin5Q zy_yf0H*L=_YJRQ>1fP(>KLod8K!6%%2_;_lG8c+_t;qTp2LdO2g=Y>2hv+8<_sxO$ zLy~{_1O|((n%-m>*HdkfZIeGR1_4zn0lb_PaD@gj zAOfS4^ez`L;y(#rE0(TFz}NEweI1}%U?8wyN7>><|ImU6Z&>*}Dq%@8K-hmVxEVv9 z-Q>XtILH!J*4gDqCP4B8peM~qxse8Jj(Jch^zO~>;m>dOg2{_#gFaFyaQJhQ45U&b zlQg$oDypfp4rbby4K*DW!ps`XZTCa2ER#RRzzXNtV_|H&Q#=<@)@K#&L2pH8 z)8HwE6&Pw7ewomWz*6SSj+XA9gK70=?t^pAfyEX-HL}TDk7I%4i9mlB2%8?6ApC2S zirVpE2fa!?cWYz#LTRm|HR_1S6P8rT<6$=2FehjDHmF|#yE+R14c{JZB#Oj>^BE?2 z5b1!I-e+;=(+P#m75w|cHIIqMaBW^cb6WqkdBQahM~}zpyWKIFK>dMkMQ*3sp8sL3 z$ScUh3Pm$Y*)VRUeE5HPe(gPy!8CKN@Nmd~FG z-i9FLf{GHH$~_r9wtjlLPd~TNWLQUbb;7agVJWr(pQ<~Cw5Q-7w0F;8E1nhHq=;@( zrX4I)o9gO7K1qM->D9T({c~xp)2<%-Ah%VjjcMs2@tJjNjd9i<2WyB#ps=#wz*Rah zc?nFK(DNXZXlNk!U?@2Y9N*#-F7$&do}FY9b|Q+YS(B~d|C4BpW`6ll3?d7YRXYj> zpaWNi>A1UquvQvL2X!%GA8wd6{rbHeS(Pd}&e`z&{WO0H9a=khWw8aqSu@dT%bR*&C;v}|(+`-y^vn8B$?z!37g4?Ist=zLF?={YD>pn4Y}f(Om8=Qt>kxHO7~hI&))OhpZTMo<0RPG3U+6}nPsFesta}6 zSg0fX>E3_80n7YKrEn|z@RFCF{@8-;@g!59cw<4tOg%?XlkOB23_y_pu)4;o{79i` zjvvvqH!NDmT+r>$Vsu(3`pTf~N6hvv6*KXjZ@i61>qi|(b%ldHMmS$on^Uhk8lFfM zT*p18Z*EydvDWhHd>#$C`8nXU}%aSU)rbsR^S<0&DXtBu?k_lJ@Yd(Rz-gn^_w zU2^$!PWRVnN_mC|#UNc@rOe|=48vOku+V>*8{=%}qH#f1WxTn22PePg>R?*9LGx^? z58;1OY?a7X&@f9NaJYuo=Yr9kIqa!M)OvFLZqv)*MN)4k87Tix0LmXV;3Z}Bzqq|g z5o9v!F$|Eoe5&;r%i+p>E^c?ME6jgWMXrcgHpR_?8B!xYP!eH zSAOs`Xl!wPYy8n{Z^+%W-Qt4^6u@;~8HRrle&mqbrpf3!$^m}uB_F8m{P>H(vCN(k z^17ta-H6^^?+Hx!qf{_a0;R=nE%#P|4ST0y=c{$(wJ(lx;;oIgU;&Wn(QqawNddI| z>#G{@Z#to#gw5Iwad?6sNI);Q*W6dl2`fCia37+$8sHk5^INdQI3e&(yGghKoaKKV z=a9rd$lPH)16G0GDDT`4#bz9b;y13mIc_<05tvY{*^mh(Mz5293+S{HO6JObdtN1)((y&MjN=tq=yZ5oDPf1=6AVVik#n`)-D3yCAp6C{ALn$wrjD384uf7tZj4G z>d?_f-|^*yr!@(9AHGl@mhWqpy|sVe5Bv50YYq9+WP>K;MA6JxdUGbfhLztbYS;#! zm&qh|O+%R+e4j>P29v#&_vt$cx9gA$3RQ6=2HeOyD#JEIfKGUw+I}m}w0g1ZM_oIg za92Z<_f(z31ac>Fzk4jWZV9vO_e9NEah8M{Q#%QbMeY2w=iM9*1)Z~JB~O1TEklE!BBPIgjeo$n zib)$n@zl;xY^a5Cmx{aB{|$oj?pfFD*SmcNJQXQ|(}>%83qmS52pE4enJ$+@Q&xQw zvZ*0K&0MUm!a5G^!uY+nX(2k#*5GGs>x%L4(ziBODj>Mbdq&r`1bH#bB=g^YN!FX1 zyb;DyotOuc&K3!`5nKHZFOl7l=l~|E?m{vGODze_$rAG>bRe^qi_dV}T{f z8$Qqt(hTmwMFs^O2HO8tCL3?O`I<-6OJ?vBLD^K47yd9#%N%fp6kuPLW0KRP{;WR6V?4In(3UVBfScl}sQ2Nq_xxB%_T`_H>4 zH(D=9!i+>jNJmDbgH4BGAL>cNA51&k+3R@VQiH@vj<&c$Jav$)O%BG}kA@cXZftRQ zs&eLAINAvMJ<5L{xr}tNR4n#FFCy1;fJ!(JCMntP{!96TH23}J)c0y*jiS;%a56_zpDgPV-S;-sgX?{H~33}6& zP%C87FyVi2z`(}Fq6x-@O8t@mo+xPAd>(u+D;@lZyAv6hCTt3q_J)dN+6E_}+{-qn zqc8%#dJ;W+qQ{0nCZ*%~`iz2Vjsg9o3~hJw2FXCa(KWYBVSraTjkeE(op2nA?!*P3 z$pMpSpEn2>=vkYRO(m-|*WARgtfs>flIvF&#LRzHYZXL(zVl6?&}tpH7{Nf4Y$#3R zFw)pE1#+NZHbgh@V(0%w!U`#OT9_GlZeA%6 z03R+|GTv@-uT-k)Un7uev$kD;vnGb5aC~k^%*0t7)(o#MpjTLODt=?la*BL4ES2$* zysUp=F{C~I+%fm`tk-Z(Ih6BkKfxhnI>E(Ctw*z>>{$fi=kchXxsfs4sm=KRy5W{1 z)3exE$H>`7)}J5)Nf;08EI~FTy!rKPY08?^4K`B0gnau|#NKVtks1honYVz%%wr>i zPN81pX!?+jv_i{+%*j0mGGtltYMQ?UO+DZgXU-jUtkJW*3;vUwJ1=>Dx?Wb)%nrW>kMY(8#7)~P}>dg zU;`zUbN2pLpmR#T#G3B81EPKQ@-cto?4M=6`r5H?oFSD~_8&SiQuj& zTe($Om2*4%_Rl2^&^OEKYVq zDw&0k?1_%cc<>~qZA(kcbL3iP6yR;FOBN<7vOL;kHxizwq6R1`lHu`7zlc*G>T4+T z$QHIf+zKWMd($@EMI@}v3p-wq#Mgk@9`#FYI#9c0|(WsUWOsKft<1TxxE}d zl@QAbqm=$a^e&8O#7}<&$3D&_)TpOW(<_4L#`T*?qI=i~59G8&a_GpMc7XGRg|kGF~`F4Bdou?I{7O(9uqh)@*;w=ON|3VE9T@ zlPTmmSU6vH4!=&8HkC(werC!+IMlaXmwTYfy#BMd zfTbiI0}Er4xrSR-Y*Xcd9?4ZteCYSHoc=B3z;y4GiUjv?ge{2hfBE`w2FBI(cvu7c z#xq-Iyv{U2_1V-0DusXlCp+k8BG;xE`l;x0^P$o^)gz1?3Up0u5sy0CDn!9ndeVnW z_9PMYpKCg#?LK-n?^iL`di#zF7zg&56RGo9?Q*O^6F?6vx^{`?eBh`gVN`c_-9}%E ziW%%JJHz<>gw{R=Xy@RtyL}3Z&W=Y3eRYNzOw)LucLBpgCsKbw&Hbg4R$_|puw zfM+EQtHpjD_&`w`e|ziuFk5qI)kE5EmE~i!_8|d@(wNp1KmYZl_19EcB_f^&%L<5b8Z-Qlem|UF zzQDbn7c(<8j}d?W+2KFn4PZI(3}^T;k|G$DE3-SV1EN9|RmRYY-3OT%`6h`rzDi0~ zhpEgO5tXnrMm*Yf-|FW!t5g_?9;jasnk*oaa#X9MR~$|#rp;@3Ir%*(XSzAJ=LUd^ z9KLq_J_bNTx~@agkF2Oz7JU(d=-DIu6FsK|#We~X(E5LZ16Rr@f1VV*THGn2H(s{? z>AQ5={v9<58VYDX!RL7nHo&guWr~D;+oN}dGLGRSx;9%{HKTWT3w!v5REuvoXU6tI zOiRm!S|!xrOa)y+$=xz0mMCx-d9|DZk&FVYUO%TOP7=spy73dJ!BrQRI=9$ms*Oj% zbOnqkYBaB@)%&y1#sZgjHc!}hgFqbLXZ%X+oR;?oT~ zD`z~90Io{V7NkX+I*RBK!ktDo`)2nEFl%$RO}u{`{&Euoc3*R_ibi-kYrWa9q1+?t z(kHZh*OSFUSE(b3<5?k$ev9Mb=)!>Ych_484AL;!*ofj7Q3VnxfLF=UxCi|l|B!Sd zhH}ZbRXL;CB{0vbC59#u!r5bx3_o+HQp?!%{;|*;kh#NlYwDTR_D?nW#~4-O%5qFR zUH^Z*N@YunDGDc^kGW)Q!IAioV2B=@Lr5>1X+ydlhApy zu*%HGGRD~j4$J75DVrE-&jz=^_-d`Sg2I#$UrN;eZJJhcd{uyZZ-b{n@pW8!7pCG? zagahT!+U%=KS0e3lIg#0Pq_Vs0dS_qxt`{#tYyFN>KGmxrN?zi0*&* zylnuMe|en+^jfBdWFmkn(V9)86QlAub~y*{a?oTre~X+U%D`I>i)#1B$3o?O2nbO@ z7M{|yhSr5_M5ok}IYIt9S(D*IpoZK-QK?({?Hnetr7g?tw;r*gG{k#Lnbj3UPHe?3 znT%@o5Ep~A*A<3Yq+%FZuEWK;i2i@ma1|P%T)9J!c=N{m1@Ca{JQy9O^%|D-MY@(2 z1&t;Kb0)wr^rBH|XX7uGYmLpZSj$i$c;V_D?2qXjo2`Yv>N4S>21-j=6jFlI*oWu9zj}Eae04g#jyE= zRiVF?p11zpN#LUqAbKU^4<6?!(xIMIqTAHw)StM99jIk^R30VWkjC_j)Sa4uw<&E8 zJ0sI#WV+VX3;ab5RK6Dl;?OBFpRma`wn!gi{fX+haWkpkO& zsye)pe& z_O0H52mBQSyW=AZy{W9j$dM%G0}6@;2EYg2{~O>I(1cyb(=cpYFa>`NPeryk#HRXn zlcB=@fA|F%t~5W4CvNM59a`947UuCQ6LQ;=OF~Dm!ECrKo1Nlr+4g)!)V!$q+nRL_ zB*u>8t<*HHY;$W=g5$eo6~dx_%eS*Ql{Kf2VHFObxKo-oOTKiIEi?oYud(#TXT|*| zQfb}LURhe_Z$QtcEBJqR_o6gYN4(Abil+Nw77f94FFdIZE5~vivrpQO<*l%ysZFQb z6O|&ULH|2=g*5&{bWbvnkITYT0BS^f&u9cgz$3Vy9kuV80X;OnE1@bajEDncTLEUb zk;>RxdEU#2)0BJrtVcqZTKPi-%UA3NSuTLu4wkyjh;%@#);oU$9u@`GiU3z1u1|lK zS)IXsCdcwPjWh1d;N(!WxOLlU|3Vc%PM?6>HE2*Sq-HM5#mN^t`GdB0;|TKK(X?W7 z)x9xR&mP4_afJVt|NBS}*#b~EB(xVE!#Z5sv^7MM_%{r5Et}f!xq2eUYt5fO`*0&3 z-+%3@JXCj*7CV0u)1n1_i%4*gKFU1fruHV@2QY4#PGrmCE-Z z*|cGJPk2!v#8ya}qAU%O1o|mG(dZuiNqIVo4#T`36qkW66qsS$Ok9WR_AEE8&Sh?UkLtY8?-a8;(q3Z|3jm%Z35P=Zne!Osvm z`fcEILho709Ah_0HOrY%v5|+=)n-xbDNf7%B^Ir z?D)KJUY{KM6!WytEkmX|RuBA-@+elFQ;vEOI_c;-|3rK=v>m zT8^-P((`uhho$6_f#sR=Ug62#npfbjJA%44c3f^5{6%no+KpC73dyPj9*;+CSRr4@ zU)6uEq{~X_&%#~taP=kQpy>~f{s+)+dV--7?G@h34>Ca&V}M^o63=OS_X401a71Gm zC}x4_CEHv=rvFkkfLMSmS@>fzT=NXKQUt`rb^(-+ymFSt$Rnt@>DUT^2urRIJoadI z(tY)#bov^q@>t%=Al=lk3Hu^RS!Xc>O=5pD*F9exus}(!nA5<5N7_7C2OUkI2{t%w z)63J;!G4#I?G2kV$6>iUL}tOc+~lLqk2Oyt50xiWU>`S0OLgikp(%2r?b)>{!L&aK zYvNiMPR63mdJ^+BUl*Wxsmv<+FL?;{RcXR$g7?-K%8yu2*EJ3Omvg-u+W@m`{1<YEwJVpPZs^gd*pVVS4Z6cGDxhgKq3D46HS4 zD~{trdDlNVUV3|HDCBE_7 z&o7L0`2|$Hck9BQ6+M~S<9L7F!(eozu#VxV8w2hX@jac`4Z111g_lJ_T|5IR5qKFV zyJ~(e^LMN9uC-ZRF~Hn17OKOx4-2O?9Q2rZZr-Z8(z;TRq=@PI7pM$3#Lgk^5UmQ4 znXx^6y>}OycK-`ekLo>oaeSW(21O_-Nhv0v%!3zGv1=@=} z>e#S9arENl*d$_Mkd-n_2{qgaeW{x>%#%JDGTamF)2{DTb_4{y6Gif!;>tqoTwL`e zyDIX?y^PEa$_%dxsDYvmEwg-2h{*QV`4YGb+`EWtqO@ns#dwLYq}l~X9~|nyvrDX8 z$lEyJ%wIC~v)8&bnI@?C*RNQN3)qufgA_)3Y3zwYg{kF9@s+$h@PRC6vC8&)*3 zz4?V45$(})!E?iEO4tRdv`tgL@FaG*(lOU4cIGWb>sQo!0@SMv&jn=PI0FT4mkEaA zSQQI^pHp1Ga4Z?X?T{1cJf(3k7;y70T(WLW=9wzNUxeuiNai>hwXb{-K3rr@U~@1g zVBh|T&apd13rc@0z3}#UWNM8n25Ir|7Cn9x;W&_S({}v5H*ZBuo;1J%Zc0+=@eR6l ze&3XTfvR5&>ZpkA$f{f!-BfV5uP;tFm)m!G+Jf0pEgX4!Xx3Q^j35gU5=b0`tMS*_ zya%^zjWu5EX#!-w`E8TQK@#lqbZx^;EHm`4#w`9kTLpiDx4g7w>xQCoh3P-Y{d41# zoba6uP93yfCWbct*qe6oRy4&D>G!g;+?n)fPr9cnYk-U~h8 zyu_Yl1*O25Z#W$iI~XLCFS$oS!Uq2S9enjf7MJd2CAiUs{>$SDd>zN=B2sz`I~TE! zTX-ygzMFrBi3DR%3fy#vh|YSba)u6x$Mbgp;3K^6sc4q9RuYgPs1+^;LgWt}Uea~x zc{w2hc4UWR=zLT#EQ6;AYfKu-k9n19A{+L|g&Q|P!@kljDI)WJ(gb1x$`|rHL ztysZ7u-K9wt^<8vh>fGn>!{C&9aqe`=Jwl>5x?Yo@gxs5GZ!eE@Z@+hE$gbd1PemX z6?}ivB+>#5rML4yA`G4y)iKd?O-eXmHE5#gFw@!S{(^*VEf+snyH85QI3b~9pd*rG z>HoVJh+l-F&yP(Wm|o5ReCEe97DVD`SdpGIZ0LZe47Z0Sw8)YzS0`(p0lWfS$)9^( zPFO_|Wd#<41oC-;Jq4mN+j}*X5{)RQK2m?&^pc1EiWVY3Qu6_!LqBV8nczX)MYp(3 zi{qJUbV9pu*r7?1vwJOJ<9GR-A|nWhdiD46p3P@=2b0w!j)EVAdw|LYnjvB|T)p%m#*C1h(^my&F-T7zcB{&80TvP}*IcwXR+MbcT2WKJ;Y}h-ep> zB;z|FxaXiC4wo2r`m3Nynv58t(Exv!dbAsB02!7qGlWBD(pCu7J9T2+A6Lw>`Dt)A zLjXWGIV~6D!N1p_X%rq`ls&AfubrNa$PC-elPGWXHF@cuIhZ*M2c?KnXduTSXQ6*e zP|r=ZG*-MAhomNhFy*w^kGw3#Z`|JeD`IRzFN$I|LL?y2%dAM4=YwWL27S*H0;Q=#2RyCnxoxS<|hTgE6|<}rAs&y2FG>!5$H z7cCetiWi#$3qM(ZdFk{1d2D}dlLid}cg>6l)#&y_){ya>l-{*G5!9on17Qfix3o+v z3BEU5sg2JoHO2X$cFMA=o_yHNpciWlCTe#i9lhS|J-u2kPk1dqRGtmGe&%25r`-BI zZSPs&w3Exf^!6A{6x1$fEQ zn^E%t7-ke+5J1ku4O{+%cumSeTN9F6yy8bu1#6-1)B=LcZSsy>S-P)pC~pojJ0Q1; zLW2)X%4^_$NqojWQo5Zv?#y*d)J>8DE%MGE&g{KW6)SxVSPwa^S{ybp#*Ubvdo|-4 zyO2h`d3Vn$ISTyEQ~lntUq;&(r>7PuokSxLH3`i!YH6zNphpX z4S(J}!CFwo&GB5Wk6XJpClYx7pEzWRO?Vop2Ktzm0SlPki$hQEAPp-20i+bdz3=|R z6aPA!VC1l3Un{s3>XR*Cm_BpNao_l2Z|;SMcXZv|VWEGFK`ehs?w#G##qQJty;-9x z$@BPIazf97wfe?uxI50@v!98)sc7?;1NbQSruqLKCW z78uD30(VKaXhlPNCxETJJ+T`Uw)BV}>2AFqzoeKpSYKSBi_OTG(+K3v@ynUJ(Cry{ zv4;wk5Nbdha{E*HhYb4gr_GVPo6tGon)_UhR-# z*gKvN67a8erRA(fT|_T2FAd%k!$~PktQT-!oZ+a0)D-2~Mm?m2OT3iqN}e9KLqQxf zc7grp$z>&7dYYC`RI*AVmM6Ej6d<8(lQR)njX|Zag`NA5PyCpu*WE{k4TjkJRxlY; z%|sBJsiA+v#3=+Nl_liPz4Sa9BBNdj^k~?hz+ng(=C?{?@czKkri`%+j@^QQuSf3a zZrXOyxKD*VLIZzEAG3C!FV+F$pWpbEoxF**ab*wj!>g>uG>jko+R#c&X7by%< zW6zez^Hq6n?$rN13CrX+P1OeH)5iXck6>Y7WP(jQ6%~p;4E3)r8O8P4CIY6ILE)lE zN=QnvrFCR@-U}Q2$$~$X3zh;c9ywY_BOVQcTSj>WN%_> z3NbM>mo;1iA^|d&SX=`s2RJb?G&C_emxx>g90xctF*GzWIhU(k15GqDEix`PEio=M zFfKAOAShI2SRhPkc4Z(kFfuVIAZu`8bZB#BVIX#8a&u{KZXh-;GcGfiGF<~G88|Zv zFGgu{b95j!IX4O~Ol59obZ8(oF*K8*87Y6gT-#C{xw3udE9&u_m@rkkOA!-0!p6p9 zkMVenFLMb$w4n`sHqZ<-W4yn9XRcIrtEwp64a|u!YL%qQRIa=zQ_$8`Q>iMZO3|mc zRjRbJ^ix@*GixhEMyGFzTl#zs}1NSR3EL?W7|@`+xh%>?SYrm2GB z&sY)3plCnAR3VTM!B){EdUgbp(_4RmNt9l#8xUb)FDu` z($t~F+LAa7wGJc>%;C?su>dX?8iQ`2&9EVVphNpjku@-C5RMALsWYsDk1 zH$!xMBJ?yVFf_D(o(-A}hA0PP?3Usw%Ss}e!86+Q837b1yDjAFy4Li>w~fufbs zXd3ZsAFOQ}jE-TZPolrYa>vMfWco3Yaujci)DX9R{Bf&(_w9UI)o&(8)2(`EezusN zEiNlV7X5asemlLKUtJtbFUfzrF|ap1oK2q0ud6>B8t_CiB>icNUcaFCh$*l7*S|n` zmxxtA{#ez!gtO%t?kbW-x`ebxm)6&BF6IaO(?#_sZRP21Rll2FFRD*1sT=pGRDYA{ zKAR-dqm{j_Q8%&{rSI5&T0x-ZJkI)V`>ecn4eO~LPpr1w*Q|c&lLvol)vh;eAGsgc zp6&sU_I-G?y$?R+Mhkp8n3Vf3@L9>ygSo`Ez@&p!iLGI;yA9_%Vr7~ER`EVqtz$o> zZIrSXGIngNz^#Kbg3EX8@V>TWY#$$^{{des@hNc|wX0J0(l!b_J2>Bn&s{MI15Dfl z*~~gPbYxrulkekDs^x!@%PE=k3bXVaA-eBEBX?|0IN8P`4hZ~QiI|}axW^W(N>^o=SSpG3~evG(7 zDSXFL?&|_>kT*JYKNlF0xTEe7wU&`^42k>Zpl*<4IeS0Nj|qP^l1`OEQt{@(4e?@W zLAML}XH;R^&{kCyyxpcMi(HtBylvE|jtB4{E!8*MR5Uhjo2pEkwo~rQcyw;tc4nEZ zjd44o$F-v2vT8XeYcUp^<-19F>f?>&N}0FTZ*yI2w&SO*KWUt}7A=iYfl4c+wX`dp zTVpUzJLFO;(2jp{n*z;B8;mDP(mIVx;G#c>%KB<&f;1igdVVWT}^z7N8HHU}b0Fe|D6DW|dUzGQ;X7wt0a=dc zgEphjxkAIi>Ta!REbrwD_wG0umw+ujKv>W!Sv?<{U{?43ne3{7XY+|Ao<3@WV7;L3Z;|L0gAmivItLYiO-3G*v zs~VweV}jrEUM%Gd$O<{M@{vW^16hBr22cDV4F_q0od-sfkuy0Tpp+4LCy(%IulQ|_ zjtWT(XQm1{3A{qkcF0%~La^tkVaeM$jg+XNmlTZT_el?|sQWQY4j%SUAM;iRNhG6* zk_*3ViHv%(E~NI$03^EM%7YFeZ;f4aq46EJ}z5KnKIdDn)IBa@K!}0@xJz zREy~23Fs8bE%Bo1Tf-FTMGO2l)p zPbDcd?7<=fREX`ARCA^$Rf^a!qh^q_^Da3dmeT~`gijpybrq2I+8kdg;WYtod+afB zw0111gFWUdwSh#*=GBx1Gj)IZWWDehOD5SXPHiOD-tjD-S4Fj?C{Hi48~? zdr1u%U8Hud$d%Ul(cei6oneobYMm3Dpm5;*N~7tu|A{3+Q{CO z;McJ+hzoL(^KB2$1&4K#EJvKGQ7`Wiq$FiT9IV!3)@Sc5+Z8Gn8IylQAY@x1`!k@3 z+{${kCyqkYhLH7Wkd#@a@;Xo67h%;AWf9Scu&%}+TaxpgW486|X>6IKvjAQ4NCWjaSzAQ-Qtu~gk%DqI9aSlZW8&HA|~Vu5%)4pZc zwdg6oTdbEglp%j{i#s>bTsg~#Ne?Yqj6uFsww#OF+~RV9DkY{vt`q!k4# zCD$fvxHa#*M56sE-MtJa9Ur-!vIK_quGK40Qpk}w)Jkikl*Gj>%4q4!?0s6HBdu^L zTZ;oJkMOSp=@0_Q4V`5+$XzFX&%qaDxO&4XgEN26;aH%zk@oOkmWDhp6#3mu8&#yU zm}{1+(2{oD@C1QtmdpxaYfxzyeVuTs6l*dZ7cLWlgIv zkLn+FaxqH+;kT$J-zy^a!(bw)X#^GAoJ6ikBhpV<6HrU>eT8ZJ2{#j(16c%htV5en zp_G3kF5p)NzCi`gwXXDKTqu^aOxLQAIY>{(P|V6|j3u{xJ4A!u=IW9T=8eZm7H|WE z{%Q^qd@B9|fPYv2bb5JkF*{$(FXVUkuP3K8^Yr(Ze>{Kv!_MBb-&8{rCzGSg%F2o- z_)~yK+E$Nr^87nS$7dn`MZn|B1N=n*y|RBZIsa)oJ33xe^uSDb;t`c-TlI^@FEcm9=7V=@*CDDB5*vp;NR~5PyP8~axguaepx)39d#axr_b%w1ygv^ ze<~l_rT?BTN}{XB&hzK~^P+s3UYAdc^Y*E;i{iOE@Odz>=sd2dFH!Ko1Y!dF3(RU-|D}o*Nf@d;pL2h{$J7E?u;-Goj=?Ao+ zUW}Q7(PRqprvj+GR+d2JbZH7cn!*?qPnO2;NZHmLf*v)8$MutXr+!xN*3avo>KFB1 z{Y(9({Lr2bqV%n5&v`mjEno-8Ky^!##mGCx!Glpem+NA=N!r~h4_ z)$@9OIz5`y0CzE)oE*-+e5udLR_2HGWxc2u$NbXY_4Ta&5A{kUW3vg8dmnapc7Fwu z{zf2`$~bDP9tg+iMsa*AIMp)-0T3)YvgwUvd-Czso1Y+Cyd_?+aFh-_l#zeLTZDVp z8p3U+a75DopP0c7MzGTT*ZR7Hjok#BSC2pb@#Yy}^LEUEY|}bWlkS7fGMf4{ip*1> z@aA|{@6V11mm+?3qD_4;xtO2T2eXTVtJ5zh6pIe#gj;<$UrY{|e?6_Ie_c&Z>gn~t z$>g;DGW&a4pUuvu^_+f+SXF-ns`~uoihSz$VmhrCg<5Mk(~AR+2@h5##W9yrC=YufRVT@3cr;*+SvR2f}v7qB=H@CJHX9GeiAzrp@Wbxq9T<`X}DC@_GcnbK)&hPiE@t9&g*Yw1tik3|ILuC*xfMoHW2Lmd86{$eDy*l(J2(qMP?V?%u_mHVj} zTb_*+2&L!ojdc<35STqfOlv<=37GtN0`zCwbhp~ zHDf;UcKzDrsnQbj&!kuU!`H%Lcv?@rn!AvbRN|^H~ng&W~xo@X)3@ zLNQxbB|E|nO(>f7eDa&V_0F-}?~K`>qN1Au=tPBpjGEE+{4}mCaS*46p2%%I_yx8J z(}tPns=x%h%KBQxSg+^v^nJHI4he0h-$a6aLer|KODb4jw30;o-cD71UK#8LqXYI1&MAjhw zp5BYAB7ltK@zzihJ_Nspwjacd801j7VAk3$sNM&aEijmw4M$ZHA;8vW5CLC0u#UD@ z1wYL=P~&GN$vHI!yDuW)H4z?mO^=p$98YO)z!s?&Rju+rxprRLq`JAN7|n63AoTV5 zJ^dL}dzUZsK~zCb5RxY^SS@{@u{@$SxnT%+8ua31>={xPE=93TX4o7km0y;mQM`Rh zGkeb2#%=F?yL`$R$40Fb5kUhIvX0=mYN+uA;g5+RWkxb(DPyE4iNm4(Bc#v0K~v1m z0R06`Go!*|cpjiopG;Wze{&|XBr+Lf3?NVuYVcnY(qmx=1WFAa3=2oV>|lr;GLS?f z?~ryd8(5$k+$SlHw1e#bhcK}4qqb-a3gL-GIbx9R?hbZXqzBR-VTbgvb+<*^*tmNf zgZ;N;&rXqFY*IWK53}0|FEMUbFb7PBeBho@x?SIXUBXtSStF|xFP7((RXzG*OgJLy z?CbUrm1TiztO*!Zb)&a^Ihs)CXj4elgW04kscXOzZE_}ZSFclcfufS{qpsp8oJ=)(o*Z-Ebok{SF=60}iqOSyF2$3{SyavoQr5J|` ztsYZ{m4{IW=qAyW$!_9lOW)kP)JrV$gX>pNL3wHdn}nFgXC^0;h#I+i0#RRgEW$Vu z%TUcrAA*@-nRqSUW9-X36h!N*iM103gTdbLcKt|Xbmnh>UgZ|FoJG$Ugnci(o_iLa zMkb7U#j$HQIg9bt3M*Ys8Pvi|ph3^X)u{Fwr^30~f$^JbHN@#BF}>iubfp~1gl4?( r9c1){Iiy3QpNZT;hHSWT0Vhi*i7#nVMn)j;s9($W?l* delta 133077 zcmZsiQ*b6+)MjJbw(-Vh$2L3e*f!qSwr$(CZQJR%<7B>nW~%09s!r8Dx941~y`Qx^ zu8}T}5#uSqm`T!DLP2SOjIlE^5G*Lcw~rXUi4byf?%#2fy!rbR=i>ZgF>tf903#EF zz2WPUF8Ip6$}D!hnPbo%ie{)q>UfC?vVbNE*Wf2mCI(+@0J~Ld>Js-~qTEpyXJReC zJ*1Sr(hn$jf109}Wg{{fIH+Ka7+~lOKT4J7mnF!9jb$@+-a96!m_vpeC# zdzIO4cbVYBVv;a^1fyKMCC84iQ0kG!zn!O1@vM?q;NTRhMC9G}5-1(6`ta_OM}>~D z5u&uD+5C6Tl5OTU2xPW6bP_Qr6$BeA3)}yB-wnRC{dW8P#~0j77S;@_PoxR*OMy5O zP2}!@gLyGDMVQELimjd-rRE~9Bhc4e>hf2HwLKc&uK>T_0uncAV&N?%6~lJYjDtW|^C$XXkL;a&#b;q}yyMt#SeXHaPt!(Pj*mCP&~RX4p3L?-WJ zXk5cU8cP9iy`yqWhAxImH}|kL{w)rA;Ol!&pXD#C`fYfiW+MH=AaI}@_|*1;5|()~ z40m%+ANQR{PtL0ApJAiZTOzW0P}_%uO(+AM=HNbaa`?=sqN1;vrRSma1TF?n>;~RB z8HENKy4PFxKIE34({w!wTXI3Ci^j>v55+RKwh6hR4zgV2aT^cY_*=H1>G28;m?~zs zM&1>PW5nP0<*EZFp1pOw7gi|YBPyNNIWCIlD zZgAYiwXs$t_*g0p-oF>d5{C2$V5TbAD|?dpRW@_}Sb!fkO{+8aX!sv1l2_J|WHOZ) z6d`IYR#|{y{53MJh!lSGxSC>ERfdM;t0$EX zDVC9lS8!iH&7wvDQmyWHE2Y84|rUmVh zeAiu;06e%2g6{s^05-O5IG$}2GV%i9hl85mxpaJuK9nMczS86xeO05=5??9FWpCx= z4%T!3{C?8GfdPFu9$0EEi(Jqx^ju6=+hbiHG*?ulgG@b9P{K?Tu+zm6wU${1obWc` zVK8b*K$1AR58$7_3SAJ~1`s6uYI`+m;tNhcH0WaHB$+cFy8+z>Z_~Ezhe1VX<;6w| znr^stOZh2(Y*QDgP71$q>w(O6g;v9)soggDD69o!>8U*8CW&1xsQ5|Y0my$xb+BB} z))xso!%w0Ir$a*n1F_}d?>i+hEnh}z;T%^Mnge#OwhA9Qg9efEAl3>zO!5f$Il0@o zNf_jEaR@Ww5-kJ=vlRcbHGSTDz-?d+%NiRud}m@HfYc{cF50Rzb=6$b+Y?58NvPL` zPES?nx9?)K0Ka-&wPottYubkIYVYc|CfEay>DuPfOCXzoQX^)iDMhX`Mr@)4KbncY z(!pZfAZ#qRs3Oy}qudXvbeSSluqM<+OL7GPhSb*xh~VDfH}8Oos!$8I&NWS1mr$Ak z!PrWa_$0Z($TtjZ0#8~Fkc~zD->Hc8B#N;CxDa%tL2zi#b{xMl4N)%N5=T5Zklxl| zR0?)r>bCEILGLZSdbE(*XM~qVgQWO!Y!Xp@;>dij#^IC}D<}K(hbhj|PMm+=^39_J zQ~(E_%Q<%)d%hexK?zM{-Ol7{r{O)Xnf0&$b_!(%0w&KKL0 zl@4TU=b}3d_ z)TyIYjOJhb3v_OCZ1>NcrHhuIKv!N*oIU%keOx)J8!qY4 zg=*uB4Yq=BEskwMPmtaG;Td%#{mixuIg;pKIbZutZ$TensJ45oZ=ftJT1V3X+g3QEULOl%fF06kzjD(AyOs^!aaK z2FSr7&8J4KQXS{6yUH!>{TD-TC$uVqYYs0_B#rKM>3Xm%Hof7@AkRkF0))t7L6C&t zk43U-6b-d#)6fVvhnfuRX9v|ECzP`YBxMB%id$p}Zf zvOny_f^=72*B(y?b_{?q2@rk;w;0*TgC;U|H;SO01;^0~tD8S+9s_YN-J*l2=Bl(t zr~3*S(re>$YSfcQriB9fR7AE+Q>NY-5;vxH!K#on*aXX{og5bP2v!SHvG3==Xq*vM z?zDrP3ZK}=xG}5biIhHtYUs`EsU@xb$CG#QFy2GZsxAuTd#r8IOdIhbEU<*d&QQV= ztLvK8C=;*U$Nr5-dyo2xgM$JYoAm&IK{R5ze*h&Mgolo+v^)5_@gq7uW!bZ|;3BS{ zTHf$icR|F=VWtBieS?&TfR+w0y7i7U0GiWT#%x%c_bDEZWf1p=Vo4@k9F1I3RS|Xo zIWboQia~xt1gfv3gLP41<116Syf4XX2$F?Nh2TAW?+D6?^;zinC09J+I>@E;D?UF_ zYmFf1`CQ+)8sL_ag%dvQ`Z*?;f%9&X)AvXYa-s8cs1I)ds00SPR4@bk-HgUh2OS!` z0|apKy*|^C+JC({p!edIZGYDyahn_InP(O35zW<@-@p4gk036Xo=dVN$S)y>Vi>6T zMjdlQ!zlugpGW76wrhxw;OEVeZ>g_^IZL_a%(24+`P-3b62OE#>W0|Jl9pbHk}z(s z4lFs8c%xA#ZLM$)@tuJ-qha<*e9~bk3k-oXr}M2R2`03umtVy&Lm9ddCv$){MVT-( zD?+0;RVPCxCoo6o6@4qWLnUG0O+kMlSvKkVMmVcc_{-0=C?bKmf?g|0Kp zYxB2Mj%dsK`1ky_IAC7f_PcDFpJ;2TNRQr`GwJHT@>Oi+0xbM|RQ;{VztZ`e6AUFQ zI!jZE#y~DK+4a#8^PRDez|Jna$WnJJxT+#;P#p$O*Gw}dPO_zsaE^S~7YHQ{apuGu zU+*S5!4ZqP5Mmuos2P@%b!CkT1$urlj~rMQl-FE#ls#YZ`6^0Q639Aw_okg1<+3_l z@6G}4t)B<;8)zZn`T`0!tjYEK4o3$Oe|}SqqadXwDX9`UQ@WjUV{_hVagH`Us9nXRt;o;tVGOmlSqA0E|-r$(Jte6TwS7dl)c=SZ_Np zrk*et@pqUc*@qf?>S+?N+O8-xA?+|5MT;;W)}@`urMdP2ZF9eb`L2)&3mjV6^`JIYK^Hj-5J2(FN;gwQT zdCr&nA5_$PZkNF@x;1P5Vg1#RGLn#I!PKbr8?a#gsW&=eQmvgh)|r3)ZW0o8)h{IJ z*P%5AsDV4&_l5R(lO||hqOPwDs>9*=W;SQ1Un$Jw!vdNgj7|XkZi8fp6SP| z`<}VO5Ar}Bao}TET#)5UT3}JkL~zf=nMFYMIb?03T7bAbp5vhKMMUFVnIq*Gd|6$k zI(Oazp%R8jMaLciimJ1}YIu<_-#4T1rS|31%*)x{C-!>U7CD@$or$xHlc|yI|J>~V zSi!M!BsDmqgK=}FHROTQ0(XAv#2vL_`sEoM^iG^-9(*N|A{n~l;qE;nr4d`;7dgk)Kk z!It>Ab!GO<`qiGo4>Xzf2G~zE_8kaJRSs2dpSU_^_x1Qb&&bw(03YW!0#ysMVN^dG z>!xhq^11<4J3a%5bD6icy;)7w-F2K*#vV>IoTjLCX<;u@ta~smFeIHZokXS+c-Izp1$K-*Yo@Lw+2P&qou=+=*M$74OfZPvCqm#=ZdKPplhW*4 zfzvHvu`>R=AQG)J}7qPn_67JQoqJ&kponvO+IEVO>rhMiv@(L$R`dCSF zS0kW@>Y$W+uv0ihT04b&vfgahU#B zl=y7hMA^3L5E0V}`}V;CQx>*~K}+0q7R1ZobYG$!E&$M>SfRxG$D`~QmMJ*BJ3aGo zVAeidHDPViOh4GD1wly!Gn6EYmt{^qlC2p50n_AVOP&&=rdU(1MfRAo9e0jeP1P`J zB(j`XME)NWAStEfRTJB<>_|bz#Xz=F;hmj&JW&KE2_p7x`pGbk&W{{TKUb|HOgSu@ z1~}s_Euv0T$dK|0z+72JHz;s^W}Y&bHe4Ay><{Mg4D!my4jpBz<1ih|Ld7#h*=md` z^=h-BLg?@yrSh`=1g`BOZrH9Od%Nl!u5tlwjMU%}7HD~t_V6xeh-;eHoZhA^xRazPEN=?_wkzx?FK-Id;>3xQ z{!dE@J6W?TG!_K&RH^tBGa6mgCBc7vGa@!E($wQ51tnC5} z=Tvhs6vZK-^aJ&WIr38sW?5!{TnU8#qZK{x9zo&{a$?*15t};^4prMfD-oV+$R)JB z`}qMS%Qnsho`gENEoVvNp)r@bm9=JnVFM`y>;*HTsJC>` z%UVr|S6M#XS(9_2Qes2q3AMg}RypwZPH-x7oG}eY{0hb51%zI;W913{3)9*F{w38D zh~JE}&GHw19Mr$;sc~3~OFPD&K$5ZQ=G#|qI8yKL;N3|nFXx;gr4HI^4W*F;63cy! zcoVig>j) z{HwlHOE`=_q6HDMVDFk9D~_{}3iq!lmJwP_lE^zYs?LZvuZYfQR|rNixvKrnt8hhY ztiJ_TpQdf&UXSBUGm?e=F8PDyvu^qCg!I%{VX&7Zm&cLEj-=UeA0mw{8pm_t1Y)Ir zo|cF@!=Cl0ohS@e&7dHU#}aoAcvwVzmS5Jn#(WQtl%W>7TWl!+WN@1T`vA8j>!38H z!qU^0U!#ZN;}H&_zJmma>%?Xrx+6TE9ayUq?PKP84R2iv`WTx#k2j1$({kRQaU+z- zWhjc)&TE!#gRFIEylwfMz0H@`biKIhN{~orju2Me=^>p!KC9BW+d(t~(fBpN8{YYLNl<5M z`*}JA&&pLZ!)BwWK+nz_sH`}U4Yqvxm;~yDhN>O^_!fOpnAKbuqdBMqGVzCKEh&<% zE^=xHXPu#1w?(9j3s>icc`;kyl6cHhylg)7ebQ4xSB8_9Y{Xmv8STZqY328w$gV~} zD-^v2gdX2nLIC9iT}}MAvtz|tvCL=h7Ze-|`R*v@+=xY^@ z9%}tS)JHsI{=AC*C|cTp??2wKBdYAos9x$BsVG*E!K9ooNuWw-NNgXv$83MULB%uu zXndqj@n*kj2l7*a%F}IX9H^Yjk^TX4WKH8@Rex#|`OtDLbe=G^@?a^Ivi-9sYM^h2 zpnB}M4SLR1i6gLopQBO8Qk0^C8}kJp;o|tfpB@XdbJW$4(Z}Bsk<}3p@smL$VLb$9 zq)!7*j3G;vr65^37S3*t=x^K0*w;v5*5;DFSY~M&2$9}_q0J!SP>lB42seG$VGl#P z@F=Lg0vBiQ9|FHa?dO(ZWtYZ4J8vHE?ug%r=x&I(Vu^(a=k1E&ciEvG8eko`x}lk% z#$nvQh8~sHh!@Kd?+A_8sKTZxoTP*T2s(##6esSR8IR2U0bw#WwY$ybfDB-^WaoO8 z4K~2*27DWMGI0!#qMWW=fUlt^IuG&0S{7jIUKVoP+DzW8{#xauy_4dpqKzh;Y+d%w zqBoe6SVs9t$5&v^u&r?)$~+PSfi#KF;kDHsfpo(#l_}8eI^AZ0464n}|F0mX>mi|y z$$d(+A;xkoj8Nrsy{DRmkotli?yV77G+i(WoG%vGI&xXLc7yCx$%bX=E0TcRfq9EXmg0Cfk{Pxopj9Vz;Wx^*gxEofVl4`zzY(5}v zq&E}o<1?cH$Py)2|7i+iUFtM++8ps@AYgwkiUA{D)8HE_@i}aJ+)s-02U#MR|CR&p zGwujTvg8kux%-$Zg;;OK*Tps#eslszh>&zDkL zl{`O3^?Hb~)ae*EeI1zjoP&dVgt!QE4-oIP{HSg|s5dfse_1kayv$#;3kDNobzbih za(uo;KW$4~SiDXw+`dao5nU)XPY7vbwmM;2XAa=^IYJ?e#^QUFNT2idvZDkhi&4NW z9}({<?HTU81+2bJcA_xZmf|aj@f;|$_2uc>|@oNz8b@!vjv0|a=Qn1a!&6MX64^f}! z>Nx)oQSTWP^e!x6ifj+KJS563QY6W54lhki|7{&gv51OcprdF>1MWG4C{b7_wXN^k ze*6hUfdPX)d&q(RI(crI>qYgFP)#hs&C%PNj;5fUGow?bkl(oW;_=S-Z11AKbV{hJ zJKdf??wY|gm)6-{_0-Y8U(9P+0|vq@o~6uQ*R&T+|!@QkdEBk>66iZ7rg*}TI=1k*1i>5 zXr>T$*cc-8WWpyLB#+8hB;Der2T@sTW%Mxpelh8#(sZU(dr0i{L(=l?Z4ij5cMY5$D|%SMqf z4Wmhr+pPErCd)RVn49Xv9WRpzyNc+OGMPL?j7QE_O&V16Pc(1LOcj?wb;wDzkZlg} zC$h#K>0<$EHo?MjyFJes9f-FcN>mHr%pj4we%Tx?h1IZo;WFQ(Fc>x~3bioq9M~Jy zqaBu8f1E24G^eWZr@-C|qe&$&5 zT8rYc!}MlEGy?sL18ktSKitkjE4lxVWz~Ge78=tuX`dgR1otUR!&Np}lO{w`i`eF+ ze$!Vez(`X5f|Yk2cVg8o22%;5n^?ZzL2w~7ZrGqemE#A~D_y?Kme%S-`yT(4@U9(X zJNwh*VoQzRAAZ~By1<^>wRBusS>zR>OeU<&@`qPB>dF|39jM{45$A37K5T(5_ekKL zNg34%Vz^&%04S$9RiXL;VA+P8zKPn%gD4lXf6-S&XEF~Sdu|0~sAVh3Eg17Hi}@$J z1^+&&*;?SV#|y@BbEn@{Y3b4vcc+YCu_CFD)9iXn4q0NbcVH-Zx#=&+0^>7GEYB~?Cv=0` z92igAAg`XaA8k>$-|UXg{OL#)6U7!LALK(e<^>cHGXtDkk#d^zNU)$v(mq@n%dYuo z5~7>Ng6`&ed;R`>uw6sd2Dt{1feisb!i^zJfsQZNCs!`5!Nh%eC1N0Wp5|e@GdSgN zG4CbgEXrwzG`0Kr5=UdI*+V=3bFNyW}L&K>4@_R zKxA94*&vv*z?faT^srI(xHC~*3vR7thhWyZek&6aPwH_Ws7Wc4FcYHm2pEq&OI9Xa zWkvdj%L;M9e*dJ^F@7){Kin+Ip^9tVJ6MR@KJ5CQf6)bCHB&C>93Cm946!50B>t&} z(Ah9I9UoPfc3Eqt#D8h<<0k3WmZ-69fbJmSAO$>f$6%*_15DFRhN`pV1qZ{Kn>azw z(+h@`z6=KnWQFg)USaS@Bqc!N@l4>`!BCD*(UC!O@WkG5c9+6?2rnS_>wC!LmuPC^ z&E{Cyi7r71!RQj3SR!$YKw~?=L=o1A8Bg(XV7aFJq1NtQ>Fd)U2kIx5=>%kLfPmSW z&?omUoOnzme}(!G1Y{5#DKQR6ZauH$+MGX}TE*9l=RMIih#ez1QC;YGbXr7bs)G9` z3gE;i3k{KG2(!p)?4#TAntlP8_}VHh^g8;W@>RiAUK{-GF90dTm^KZ*EsB_)v1yG4 zeF<^Bz@n;Q>cp@)OgT!oeIiZ-Z>pJzMXm=6ugMR`^;PO#F0agLtv=fri+ zI73`yR#xILsf;`;eODJ-eAa63V=m2}Wbb#?|EOmfwLpD4g>n2|ulGQ#4VdolVH}Y1=B44B!mQgqDkdtC|L zWF1_ejpy4(-W#B*ekCjTby~s;iC+-cM>VqT*t*w1roVZ84Y=}p^;@NuP=^D7C$+JO z^Efuk0Hzo4$Ifu9h?D<5W2ZO^zP27j4W?_=iik0hi%+MA%Kw)(P;-(h075IWRR`ny zBE_CPztKmtx8p_=o-jaP6NfP7(tkSM#lEessByH#Wt2eW=PoZyV%X1cK6JEtA+2#Wio1l22~~m zGSEPhv5>ch8wEqUZueK`&hP4o^_sN5vn*`v-4o8mp@b}12n6-^ioseEu=&3x|6*1l zvRFb*?yw}Xkai(9#e>x^-9L~aCaqtR;WB5Lkao+jSp3Sb0gf$<1w<${#DKz>P}Nfa zBmWeEq#8JR99Xk_kd}mF#mFacd=#0CY}a<=TSb+jCwMW=-IG0=dePv2*tnF3*_9GP z{cu*@RxG-;EqI_OalRzFogss<1*lgbro9F$!j+<@zy$VxW6cx- z_S)w_`7&JN>}+MS-fDc9fZWnogMGC@(W@QKzO(ere)aYL z_Wo(;K)+Xx@+u6by&Ynf>WhQ!RBEO50y2g!=T&t&@SBrI7F(+HuJCra;NASIJj~Gd z@xwqm#X#T%PhGj%!98)vTL^b0n@Nywk4WO2S&~=DH=mU#dHDOE>SMRDLyt~R0k^SS zNE+@Cz;I3RIZGgEe|o>SwZifqO!c#e?QML2gyGo1`g3za$~T8y&6sYJ|_Y zzGcbEj_wQ2FEKy*=f0k^_3$WGL_O`Ryd&3$1s>>|tAxa0*W9F`|8vt`k5l;6_*@k! zBakWw@iS5}4_E!lLeB~tF#AM%(xQ$E}F zPrgFWc|=M7#Cx`9r6j)3s)YR_Yspw;+GzHB>wEd9;QH@%iP!s+?9uMx!2KZ(I6jTw zph3Xn^P6vinqMPllAMShhYMmbVC>yic}zYCMUkxbU`}bGzk167LwFJ0Gf7$NvuRV|WeoP%Id>IqInx zG`qEQxCZkGO6}mhjmQ~1Re-I_sk*n^Ao*Y~WW?sQH(;9HZj_IXiXBOgRLgt53zrXy zK0gw!av1JC6{q$`sM)(pFx9(?XuQXix})u>9O&%`@!1){q6lDuy6TX0C zJ9G40@V)aLbe%<*U=8?232%HUsun@~JZP-=Pm<}P%i?>9f_|xCa`887h&UN3kM9pX zD;aHU$8*`cK!{}EoN5;pU%b{&&5-UmAt4M zmiK~N6Q@MXC-C5L@!lGU_{u?4EKmHZ44W{kP&L)gp`5y;h)`u=$Ir?<&{Qj%A&6%| z>O;}13>xGwZieRahxM=iJH@o**mXXA3Irjpc;Eb=mKK|hgqh@j@*;kII3_t$J98Hc z5;j&2p8u=9>1sP4jiUOk)fw*gM{?(WNKGO)&;zzw9MS3;6;}Rgz{!fB*+dqDDouWW zJQ09^T9Alz@gFA}h#4~DxV${M0GF0(>S_VKuc1}21LKCGRGMq(j3{PiWHDkmOA{-9 z9ys6ZI850q8nei19-ggujWa1cUwvCb4Kk;fN_v1}6KmgodJGThzfDh`zE)lgd_+w@ z$URt#aA1c%Uxnm3WE(G{RZ^-~RV$OAy~&g0L4yWv_@}UXDL?Fa>r#n*_grKW7Y+Oz zzE~~V^|6i0t#0|jL$@#k);svCQx8e5v_v$s8|us0U>K9EJjoFuW?`8xAC z_(vzmfMK{(kv68D<^C_*s9?U025lFAXWX?6!GPhw^wa|`pIU!-(!{(b&lZ5-``cls zfI+l$aXOd+0rV~Nh|zEHt}J1Z3q9%pV`HGB7*7qKdV>)TYkokN5y1xU+u~1m45AF| zV(~LliQ_x>33Nf6`}h{uWL_B?nR;UcB2-#65V&w;DCB%wk{-y6U0gaeC z+iZyr8`~^9zoy>>%+EP#on2AW9O{rww3{154Dkh4tn%3Aqc7|zqN+Uz0E z)By?eA|ShuUl;WR&@HX%&}(ipti~!RiEIod{5ZJ!`KN~im4F+fhYbGjcTjq~$>K|- z(|{4^l5`bzW?;1A!w}weD76v@pQSomYT7}iIgxG=M;6|6X;bd*Xpr<81nMq_TSeRH ztk%$qB)wq$!pJ*dv?d>h-U-2OryB^0S{0JlA6DTGm6~ab3)r^VEIS$F``GS^eqQXz zfa!q9PNzVvB8RS-HMJp#NVmb-GBZS|;p08`jIfLr3FZ*n8IuS~p)_r>Tg!d(X&FCL zQ179srh+I){>5OKu;N?e!A~-d)r$zQZz8h*W0O+dQHR7?6oHa>kEL((+Xfaw`y=kR zeXe_^==|^;Wm5@lxZdtIo9Mmg&L9jv*SyU4Qj(!7$uS_#izl3R7wPHYgPP#`As7=> zM-$JuBukOEWNi@#%{Il(ssgfSt(Ww0Auxt$D0|RwFT7CeGjmc%JBLM?B9jy59D>T+ zUcJR6aJ2#?M(Ut-do1KB27ss?bj2wbQ3R@H_Z8S#@SfO-;>GhuM% zSIOZ|w0`YCuaA#p_I@Z>4$J5Fqki*)#=7^LTT3yHDBoJ9h|TS)TGShO^{mH%J}yU3 zl?VLzGhf|Ym5d`&O*Zanc?>ZXimh2KLv>^*i$tqn@f%Pv_pOQTe?X4cQqKfWYM2;H z2i^}ZsbC|qWD8sZR4z0%etYd9DOP|t-Gy<%vttWZj7g9rv>&IXHkg?+gGSqkmp8ij z3X~zwMNosHOWKnv`#vfgqFI1|p9>bnD|v^aOFfj_kOuavdl>i~wA2JZ5iVBY0eprL zpRLUVN8sG($zfW$5lGU4YZm-UcSto1@`EuSi5YrzpZ5v|;#Bfw`JR(~c@Ndd$F(c`4}yqL zfqc|!k_`=XLYYX1XwukSXze*}Q3CdNPHoYaHONR|-yA=h7%-B4FB+Y2jiYe0^+Wui zEho~|bhp8TtHFpjpeBL&j;ltkY$T#Zg++XfX5|dkU8JN?pyX1Av#Z56tI8FD3G|dw zYGB#l10{7J?hPazvgLy5?XnaqKpSS-MBGmZvOG)U&6mEHHMlMPS70NHf7B?bW}1mN zRWrEf4anTPC@|$zc}++a!RV}57!WCNGQ<66o0pC9iKu-zmI&-}a)G3Xr&VlQ>-4A3(B#G>ai=T?e^XT6uB?YaCiW~-(KsE zZnc&$QZO}f6$RAyIYGkea+Fq*{B;3g!>vW!V$6Qo3;aa^CX8tsuAPL5bMWkmr$q%g zoN-dSC1Nm{9iK5QaM;Dx8FO+vU$8h&Qzn)`Y(g5+cHLyiM@EtAMwp>RD>~!MhV9wg*X>p@tl_*Hu2DI zW&B0t`V|ddd>xvEKJ3XXVo-O>X^EQc=R9bvsPcP^eqhh*%zjAkdw_4+qgD4cELGY} zy88*ah?<2CHhs|4<~8ibm^@DsY;H$e3FAzO0$400diV@`cMJ944*u2^@aY3Cjci5o z9K{;XU`6uLZMoQj^K*uBgS?>1lD(H23?%zOa7V z`16tS_l{TvSXbB77Y^|(PmKPJDPv4IrZ6(eX|>fe|I+-B0-o2O%R#C}B%05jdM!zn zG$7xEjlW5Y+XcXZTmZ!CAuE62WVzp7yM(lBvSs(w6o;zs-w^+@Fl?=Cn!-s!GR#HU zzrxwnfP~E8j1pjp!Xtz4TmUm7IK_&>61OBoUtaDCo*4<{WHt-VXZr6=h2BOl=6D}S z`h;<|&LKa9dD?~xsy``P9V<;+ysv2zLO|i*7&M(vTiwp}DM6}C+`+>E4v7Q|bMZrg zpVO5J<5%Wb5RQmoyJ%iqZgmVo^!GpApGQ06(S`_>Fnz+VglC@wx;1kZ5)JGEx4}AS z-H~#a2;gQ1oQqOd?NqVEGH^Ca6UDFzi(JZx|6y5?Ld-FnVvK@aCl%Y#%`^-o5AZ1W z=!9-uo&e`iPkWe}80+77?1_5w_^M(iuDot)abnpX26BM9r`y%*xc!!zmuXw_P4o#g zNcO^$8C2SbnbH>W8ni(W8;!&)iD>jz|u3VjtQ_Cf1L0V$Kp8*Vi>pEbR_Q-zLwK zJoPJ@NyrdYiJK|r{e^CgHr5o8QO%J=+%GEadpFfPthUn zqW!XsFH{4x=yrmgAx~Y;R)(PM??0NEBOyNuC)Hf{#H2wxSv^vm13`~3-~b^U8xWwQ zh!d^(S+g4!26Bk0o|+PfF@3>SHz~l>uszp?dishx_vb9<{TvGXpYKWp^@Pny5_YWG zdi+cqlBqs#eBP6)?XVu3sx%KhrwmQf2eS{zF{5t9rbZbbG z9~~ux#OWqkoggZHAZ2zUg@H*$PvPvsW~%0vylGCI?PEdz;-1#*jeSQ0W$>M&d)toK zS}ll8;rW}>$~$GCm$~jxhwVOvgre#Y#>${)Tqur_3_e*51Lp*z{HQA$MRpGf&S zw7hxdQwUg68m8iUf zwgE{>IYF|%E8#`%x6$&T1R=6TY040R2$usHm9C>wxejSpxhackRTc`K3%j;a>R^PK zIy{cPOPF`hI~s8YKmyQ9_YW0ic!ZBtz4=@qZ;u3#+PIUqJ?mj>>dG!|Io>0v*0swpf!{ILom0tNit+7RBvd z%{@PI~BB1)i@y2%$WPA(zr>^)~l6zJ{ye0EzQ2O|N6 zpQzg>+bo=(A%+*hTsra0;F*H;f?m1g>618L3zvqhf}8%zx8|dnU>?k*&JbCSwZ5j; z6&{MB3s8@KDDsP{CN)CjoGy|Bg0?}1hd6jhgbf$|cY-MQ#!`=^(7)IJbi^$xws_gR zS1dZdM@YzAu~nvsp;cEFXsqU%X5U2{f?bjv1c`wy9~O9_XFmF7-$E^aOP|Z{{_4Y( z7ZQl~6OsyzHfKhUCu-lu9;vMN%Ph`94sl<0ovi>ta4hvc%V5g}XVA{{5mx^3OW1OBZ-A^uGY@GU6 zs&YFR;w+LR@f9P{q~PsVAW>_8#D9AXFbZWcn!|kIEODTa>m%PJL-A#C?;^GnndqvD z+~!x@*EEUiVCKWo6a9g{B%;z}{y$n&OIcN#_71E;w|-L0hy6W@cE|Ey1sO81#Ml#4 zRR*=auKf%q7~q8Ybf{?Ub6M7Z`5=Gw>uK}Q4O?eP>-@5KoGB&g_NgxA+1|Z(*iXZEW+R@ofsE z&kU?F-)YNU1#v$59PE{6&o+Wv2g*2iNums+EJN%L5!blXm?e*%Lfn*f7etMD+xdk{ z*qeK!X3hAAMg)alZsl@M{1b`VfuvSCFJ*LM%(T1b80G#W1p**x)_6>44}(B5iOKjz zVey5`jp0o5#(x3oLR_=Jm-A+1=Twn`9NL_^&@C5(*X>1QKCO>?Q0?4+$&!twu8Z8bNjZ@*n=gwPa>N7&@l94v_s5=i2HD9|Mow z(DQ^6p(dZG(8L1_BB2t4nejq=gGIJst&HAAuT*=rt}(0-@8ock{Ok*UcT_gd7qIb} zDDzryL!tmrhezvUR8ah2MGHf7RE1#TNkN}lr@1hjom~eDL!;v<24Ajl>`9P~2nbj? zgdbN$RS3*mm8=k&;#y!9tWjqYV?NMV@MTCS7tNQlirUCtT3MS94X9A4)Db0r=i`%) z66s)x(re(i->&=TzdKUiQPF_F5h#=U$E&E}UK0b4!q?Nl@s4I|oj;e+tgCbxGX2*I z#Pn<1$s{o~kB8KUxCilua>dC7d??JT1=Jyt!C+StAmgwE)@vgoEbMyJ(NPEgMg(19 z$H%{{h*1OzujrsB2zQvlQjZqI5^A^R7q%l76ZGDiGjmc`>RuVs_ocbto;7mpc($W3 zn7RU`vzKMuL-7c z@^g?*?ZQ2t8?OKUx;&p`EN~jkq+grpgnb3V_eO;ap4s`+*;8%?i#g6)94$InyGe8^ zyIi>)O+b0T!~Hyft9|@Q*NtIATdCyzM?wqLNG2T~FXqDbJ>LRZ3KP4EV~f~98~@ve z0tM!=NGfMjEG^})TC_-X5;fi5hdN<0$Cqgb{M;V`cwv7(NPIz945=f-XH?|^_?LU2 zW0;l6t@P94q2etzc%;aR6C5=v0=lK3^5~a*R=9V1kX>o-$tPj8Q5#Hku*IbC zcmbtSBnVT-b=hZ_VL*Ql^xeS^^!^uC8xu5QC|+o_?*zEArqJq<`Jk6x=Rn+ijO@WE z+u4R_eM6Jg49lzKyeug2^6sCirK~qF`S-d-K-Q0%K<9IPWBMBq`o0*X5)pqeiL|R| zeAX-9@TF;x$fBxQYj!miC$m!{rF@+yF`YnSm|tR8|Lnk7E2HV@MlVb8u|xoB592nV zRK53PZLDh>$g(#bRVzY!05P6m9`!BxL;$(O9|tXmZ%xEgCO9$MPbUn5*HjPu&S5eq z6gRZV9gH~lt1ND#P>`4=RSM7<63i#qVQpJk!ufuDTg zfkSedDxoXl(6;!OnJ10%jTAYzeeLTsInQaOPiuvl&0|c51=vy_eb?J*sn2_$bT{3o zRyapdsM!}dEQq*f6w}#zcH@PlT#kT5*!{Or@Yp&r&&QM9R{~$S&07+1fFUO7s#X9M zol{cm8FoK}RM{0y(Yb+<=9)wMvX+3vc$xDnL;%p!;69I=z{Xt^M1!~d4*^Vh`#!t5 zwoX9@%@41(qK)|G$*%&Nk#MpB8kcBoe7?tK_6di`%~mSlgs?d$N^2J!hoFhSbR1{u zqZ7$EH}vFrSBOVfg_95n5Zrrjj6X4I4hWH^DB)G~hKwNtk+rdhLGQlOIEhzTXJVt<{*{Qoypb?QGZ;xg-`@Yc9)%pb1)bRJ zzS)Tn1wdB$lmjz4^o>N+JvtoxZ!-U9PIQW3b^S@X|FlpSc)1TOljU}yCg=}f4f)J1 zzVD3wC3jy0b|6mqyc~3rUp!BdlwJ0pT;5pVra7hlyE+>|T>X%R>iK!wNuVy0=ifqQ z_srhf3Sm)IB$Cf#Yv;^yH?=8AiQ9mk2A~RVPQIgZN@(dKhj9$BT~cx>v7{qAo7SnM zw&PBXBJ^nKis=OW8>KMvvC=v(w)miT1(kAhIXk&hT@Fz6rNM5xX&fo6XA0^}o$^TH zfLa`JV6bL4ejaA+pl*{0dgi)sjDbKlTG>xrVNB~!G}8KL(NK!*DRE7Ji{#dZ6pyaR z53hxT<3XIoOBxG6-sKY@$MlIuxP} zYw1IFX8gC!5mhpRD0jH@2f9I!1CTWb_wk51^=CEEw908o*p}zqcDptGqq5&>5)@!&pDP7x`F zj^&Toj-oP7@l{@7e9O{1vEJbt&i~sNNy4Xu#pe0{gaFL!{}+&NbYzpZIMI6N>gIQg zBO#Bz%9k~6yrybRkae_g)lT+bg=Goi=o|y zRzRu0D;De3RzfZUw=c~z7S~-5a4^LwJIN@fThv#g! z+dt%C#C|nfZ@2j}o3L?_&%?`Akd9+3q0%;ma;}K741{~3e+y%T7#ZRW^+OC{FhCHe zTp08vwR%T{Goxu^Shkv{B@&}*fmuSJB1Y?z0wrObMFQVUri$}%aerU#xZb=RuR$rL zCd-fI_%|x#3bnNi|DUZNHha_@2!o?Ak{H|(6GX{U!nb|4!c!?0#UkIqsR}lJTr8L2 z=^p0F@N~k-g_l|Qvs$mF#dZNBzAv(J{A`WmzE6}IXWK=#nw4MK72Ex+*l%HQ{wBQo zGMVC(vuwXB2Nm$?eSi79SfNyWlW!mL`64UI4_fO@oQ4#P=)?K{MmbNOh}ShE#@I0M z_tcS0rO?Cz@}~@k^5Zz5L@-+k{+^V|tqoGm5vlM6Ek=z|*=7Uk0wc+`@K<~N_`eUR zi~X`#Y?e8`q2tXmo8>zK0AO}}J3%ukhpxTG=Xt;fzVg7qhkq5k3(&&U$L81@#m%^$am zU|xLu{@co9M}KnAprVXT0U1odGYbQ<(nl2cdn!I!SA+aj#|`|4gjNdZIPNk3~p6cYnw2qJLoxtlsw8 zL%dW+D1UcNgZLq-8UI*m=3R0D+^DN+#x}Q;%^UlntZh;8YJup29dM$ZIlf?ddcg)F zjBKuWfPVg!+)<#a*F;W3KVQM*^!Pj_F~gclI&amnFMwxmWxQ~Rw$jI0?=&SO6&n0S zWcQFVZPSzsoP=PfERmmH8JsfA(-^ft!e^CttA7doa|^kas06!mZ7z;`Rv(-!v*hAFFpYAPu(4SY-W2N=8F|RF z-F|{(dmdh#&SSaMkOkHjTQVW=BTJ9XU4k% z&I2EHrCxXnN`y}561TsDkUG6BAJF~bA853;e&u`3@} z^SnH7cq$7OVG(y>M7d&k0Z-fT7!KTo1INiKoiGSaRtBA@ii}_-?Dxg$YY8W;!<0yB z;t^{v-k{2wN>xbnrJH8mCYdf92>VDZ1)!)D{Ex|0>Au|A)4hxM<<0xsn{PMx5`QTF zhzkxG0c0bZL)0409&SE;rlUE02Cc(E&Ww@Qsrq7J!8CFBSeL)KcdT~YBr@?zrWPDId=VWh=hrkceq|#w zCyh)rWBrqij7NN6IJf94AH_z-v;bg=k))t=IJzfU8G{3K+>C^SNvn$Fg=Q8LSV+^D zX_=W|p{9M%Zp$fd;ig%;@@;QNATte)m8rgzw)gkaZjgfU({65F-RjRzifi1GefxHN5 z5&~4F<&Yyj&6vl1S<$yR(~~_#!u-2wo~dgvcXQt zr5$|%n@nL|3+XX;&5l&3__*KY$&kh@@CFQ{*iEbHbMoR3XZkEHe4I>eb@&}l%0#0w zpi&u>#u~5%>oSnex)Xli3U$;(jUZBs5w}1VjY~L@7~@E1c$8WBwD4rd{bO2l;=p*X zYEo_7G??|%cz+!SnxH*RfbF%?u$pn)WwWAsl@%SjS9Y0vL7t6gdCm6XS+?sU>%E-> zDHfA#pl36K>PO|Mp6-MqRO{hpe3r;X`=VC1+~(Q*&+4M);bv$TWZ03Y_3->&ieGTk zt*$)zt8M)?$A9KcqO%fi*)ErVmKgg|WD9>8 zH{EMy()znfvZ~mgxF~b1fK=ayv~52TU#2Sk1lW^{vqA`Y;Kpl{ls(s(m13Ch^6J9t zc^SIy%g_%Vpud9Ho1~j`k{-?Eb9B7tCQK(uhY+A(Ack@ui(x{@Vx2R+i8{B~sB*r^ zMCsAmJ%47~v=tPhm2s=QOXUzg6qAiJ={j(vSJ;$eC-U|S?zo>(XTw^o;B1J4*T;#^ z6fd4jY=VV0*9GqNXaW1ViDO5J^kwyTAddQkOO{ve)tSrM2sEyn2z#DI>RyW!SP%n7 zjzw|7pJb2%l4z{wam?YQXgW#jou@CLvB*$67k|z*dO!_%m>c9L^>IHb2l&ZOF*CKK zhOC!gQL8}ddp|MAPc#;F)L3k}5~duH{?{0e^J}D_C9OD>gR(375__R9;V+tm%2)3D z_W%Vv0N%Jyw4gg}8s%hjr{~?yxP~dTNSTI1G9#pdm0uAlQl`@BH_|e^2renu_~F`n zd4I#byl4b`w7wj9qz(?0cUz_fyT!u>sBAJ102nyo$t$F?gYGihAwTA^QFST7T-6cg zsw3vw%Jhvd8vqNG)i|0CN$RCMGUl`#uivr2gwN+bErAfX;9sWn75FXqQi~dtzKQfC zdaF5s4KsiWaU?G=YKHDnY%hiJbyRrv``6;Sjh+BN~cU$N2Z(V2TmcKs?7Gs z$nkY=GmWP@3rz8R;C4Z!fx|Fy+)c?B zqG?kIPQi)4>Y`%!;t#n&!I*tJb=vA$0n=&lS)gV|39I@frgDP+2V`12`U+)kWDj$6 za%Ev{3T19&Z(?c+G?TD#6azChH0j0`qp zc6mM10%2xm(ny3con5YGAB%U*X3l7FRn>MiUocII4?p}fEZ)zJD9UBuwDZrGe|dlX zp2{gRJX=tVgkgctzvh}1*1af-Wm$(sS8b|w*{<)y*K)aRcJ-Xc71+J(a;MW8Ni2ug%i0-~kz;mb1}P;@2|G)Y0~r9n2hDD5Sl9MzAH@UE zy54S4v#t9CSafne5gS9-*|sqksKG?GMf&>)F{aL9Nlb?4ZJsB24$rF$PlE&_Glqp%B$4g)qdxa8DNU z-BBT_qam2{M9AkH`Xv%X4<7EDfY7R50{qvzRYdFv-QmK9UE6L#Fw}oTFa!vHsRF3G zctxZ}%INfp1b%Rz>Za=ACEK>mw)|4|RRbdGuxEeSxs5sykJmRjCJ_L9OS)m*;9$=z}Ym~b`1gtxTrT1BlFc4%kO6850=k)nZ zj@yx|sE;eA0d`;sfq8$RxeV?M2Ra2kSPIT(6hz2q#;ke#axl-I^I9nNe=rY8e0xl@ zER+tCG{;EBfIBKDz~}In1e0ImKl2Q$ViHORX1Opl<$Fm}l4&~8Y`k!F8oTZk$GD#hLfpb%h! zw#{|UN|H{CkL!H-goqr$ch_$F;rPK29Mb+>mbXECUu*1>amrqJd_*Ewm@?_Bm<&S* zTzX%CoVW%r?oxe*OVwE}ZE?GpODfl8U6s;uB`P?VNWwFPe7c zi+;|EUA?qzUsivyafpR2JlJQF+GQu@vXc$3_sw>(w$MoAtid3t%kdBa+ZKoq%5j_Fvmk#)Il zZMljsxvqb8*V|Q0@tL#vRvGi7?H5Lhk5~I-=L!`YW-1rlhuROrH&}LI>AG_lE|xam z9$^UqbZn2_W&ui-I46K|CZ_@PSj2|&nlU@Q%U(`p&WP9#x($aCf?YH33UE7G{XVRs z|9DZYYyg*|8-pJ_*bIj9-v&7FNgvM-`qdF1)Zc%NP3Mrijz#=f-iIstDohjZhC2sc zKp5)4ySD5qKV*URcD?(u@Sxdu4=!&zFRyntHW1fsvl->a7l(;L=#-%~4&}e2X~L&( zFhYocZ(;awIHnmJ43|7=Kh=Tj+uClo?z1@^mab^x25CdSp|(oX#9@yOTEsR&;7otO z1h9XNF_DhPfgBOG%6+aOpX6 z^kBI7)8)l47cPE)bD#`>G91bPt{4P0GFyLcE}dCGKQk3$6pU3?$CdT zJ%li4Q&S!RUjpOotN^YID7r{lk?f=go5Z%+P_>{^ASjN2GF&rH`cppXY4-Hy`D5-b zdcWgCOQf1X_SB;*%dCr(l-{O#3Qv4KGU++URF5MQqJS2&3E@#(@^f&>&L59HZGYa8 zBh$BgpzBK@lPTqg6GxyaPD2xFF#~Bs`w<--BGm~~Jt+wtjk)9ngRc3;p!>%gMogs*S59wIH7s?KOw*&iuy=C&ldvY;!RuGoB4uc zR($AeyS8q=z@e%C-p|C`{=dV=4{;24V;6rd%Yp3Y`!ES;`#|;g@bTj(rf}QYzK?W% zaOR%830#`muGeK0P}X&c<_jr!@wdt@zO>D5JI?sHZ-h?$9x)AB=}Vv`KzEAcgrob-x->!K8Q<<{9qwFpm_F zeGRyT8fac)OQ46e`ad4oUt|hpZe(+Ga%Ev{3T19&Z(?c+HZzkEsui=#gG43*HZ_wG zsudA5HVQ9HWo~D5Xfhx%GdVXjmrx1;6$CXgI5C$Y zU4pxN2->(e(zv_32X_nZ4#C|?AZTzWxN|w@%uHs!|F62YsA}G4`PzG}7pj`_gR&Z< zhzZEZR1#zdW@Kez;RA>%D9Es~09aVqnOIoZkSHnDEx|UX|CS?BYMMGaS%U2N{>wtl z(G&=NlZgX=!Ec5NAUlApvkici9l*-P$I8ve!UAApVd4F^A;^&rAP#h~Gyy0u0c1gT zrcOwdVjz2WM@w@H@LQgLKLTisX#uRfyxa_by8}dQO&u+bfp!1|AlSmx_AR3^&<3Ce zGPX1YyZ=uJ8UYJ1*q)D>+11sR325uY1adV0NXr0!aJ2+m08~w#OdVZJO#pwj3{V8x zn*OUbCL~ILx`n0FKMFOF8Q2x*XbN}}*jO5y+BvX0ZR6!cK;a5 z|6{-a_}Ae8SeaP=6YgK$e+9C%``a04Yz(rs2imz?+L;5)ENx5yN|N$SU^g%W0BC3O zmm$!9#tHQ14|D-q+5nB-4E`=12#^#}0RZ1R{8xWY#*UWuU?(OgOPjxXWd1A6+c8Vn znTUaGZB6aKPDp>%CvNFzYW#NY?#%zXTx&a!tDWb+$;{Hu#O$v&Oq}hRHS8=MoK0oK z|7G(gLi!^!Hw6PYS$MeFc{l;44gga(V+-bgzY?gs+nfHaWc^G0)`PdFJ;)wl_SS}} zx22is+b<+fC!mWd0PN^&>h1a8ivJ}fR#t$Cr7;*_WNL0{hx8}x5B`uWe3-rIzkfb4AC|Cs-M#mriYTH5L&^#5x4KT1(ikQ>00k(~{|$i~Tk z0$^p~-~n*IJ$V0b9A%*8zv}oeUl}_y5a6$1f7SbTQ2(yktx|KFJZ73KeR(*JKolFl|Zf9q-fG5G({18psB-2Y|q zHoDH>w>3}zy)A>?|25Sz{bzR-Oie6*oo)ZGRt5}wTL%$4^S6;^WaVID;rK^x=_G0C zW@@5r2{yL)XKenFYy7ovHkNj#${;7pzg{tKUMwvCNB6d6#@27I5vRA={6__JdRsa0 z-xv88o4zg8|JEU4XACm=Yx~$Zxd1>%N1!{>+vUFzC%}{SZB0!~-Tt0#05g++9SHp9 z0(k4$8(;=mUI4Sie~6m}z%2QPSOLsZe~1mh zEd7Vr0n9Rg=q;wgA9{dsF-lC}fp|>b%e~1IXtp11Is@D8NJOJiT{~_MD ze84~SrZf5valU1Ldwtpd(f@USBg`g$@GXsrsSWtQ4c@9U`!9Se%lr@iMZo_J_?F-L z55Dafv)zB;+qr@MgY0kaAX`)O|8i%2OK1P*3f}6m2Rec+fi@H5576PZQ_47_Ls=zKgjl$$<6YQ_RZVl-{$`_f5y&#j*f2w`uB_D zZ8-nUfBz{kHFYyJMp{|~8S@8O)dh9j)rb(fGVV+Yz@DYuePUyrEYwE;4@k@!Y$m8> zWiHE=OD^@ZO6ps6D~dYYWv_j|^xUo|ZE)wfVI-B@HzzfUTYSBNoKN(;B_dlyZ-L0u zN)aXDD{&lvP$rJV=s^^JGBF=eqeSdHhQi z+-fwezQcKiN1gM_Ha2i8N;f=J@e7%pK-WD|f@?L##?a{S3T8iXZ=}DhOTf-KMF<#E zf`6DuoCCgEb0r_`DW}Bc=nIyokrcM@k;y>CI&I2bo#KVX_QjEZ-Uphb9&QW6B(o^i zV~=}cO#2la(KN^0g53y{pV^_L(9J_16K|a~`_e6?zpYjNBDR(d4VH6Xp6{F4cyg9Y zmC>0R45DFBNDzGax_#{3NZA?fVip3`MqQJFxh+ADn@M}k~j?-M3FJF1IiT9pPGbK~9+e3ABzrw7MN{$*E}DAlq$# zA}AVFi9t{Y1Ur&{OR0aKdZ7gEw<9(410Fb=i|0*WAS2c z23tDsOerL7D+!}pcr#-Eq=`Wdz)=|vJV=O*>JZtuYR!qHovS6BKSAjz74%17;w{_D zJi1~xCnUIk%oIc;)#)-IeKmRo8N53eCDJThe;5oHgKxUfA|pM)huUt+%J{Ycyf^@T zmUL2zrwvLfq&zcWyJ&TdQf#lBlm2)u?tOiZ@G~oZKsy<&7WtDqLMp2j$_F5}&MP$<)j{P8&0no*^2d z7PIceJ{22loy(vfWt8yc++(a20f;;n%wZr3w{?gOi?#ANIQhVOMnAKRIR}Y;tkqb@ zHfj%l$`pUhtO$qha{D-H_FcOEL5EaNUE-$K>Wk`dgby?QBl7k(?jhhy8pf&(&$h>> zl?3~`tDKB1=?|K>EB+=;ADaC5O*rxk)QixUIQba19$aw9jpbtLRu=i`J*M8le~PNc z@<6o)yf0LlTX!A!2y_@U;@V-2mU(EMl*6EZ3KlY*Ubu}H3_CPyZ4x-Ql6#7oqp)tV zxmlw$xU!|t!${}dV(bsh-Fa^flppgYSh-JApHgP^oc6~iz_H5>k6Fl;T=q0l?;P(i zgA4g}l3VE+E|dVbH0n>zBDrKBQ28 zk_^+!Z?flUfy?nR0xJSu-&MT$T-a29<;n!DANmkzX`(%&zaiY+D1=~-V#&@=ROc@` z&?-V~`uIpPbajmaJwsM0XMC`0fP{4Q@oD5q9W*0YNJoU-GBWnyUg)<(ZjTK|k*+aG z1T6Ne^ULB?Vf)O^hnLk%I4qzoHRH*8_iC&ugI@#9MPuNoKz0`n4mR=g3tTOKS3C+~ z(=)aNZr*TQz6zcZPdKKxySV?Xw$P{Rm6lto_0qlip&jmu-AJHtRKU(a*VrH7!s*Ra zUc_7cz9xr^3)sTP~30)IhTacd|VS{^vMz30IHLSUAgtwP-@v z;ET=aN7sb4Plp1(q_v}K24UQPT(CN^z5TW&87VTzGK_FO&@_5ji>s&_f%)r)&kw&*_xQ*BYgAA*NQ1=ejrJ#m z`S1F~Ab3p=s3di0B9Zc+g74$*i-jifq8%Y3PSQHs46dqz;W1~;ln}Ik)~2DhN^?q` z?^#xFPhW=roI7k(i6*D|ilYioWkH#+9{l&v$);yiAJ`%z-vy3Vie z!>55B`M9p8yS$-zjntZ(j4gmdsLg}AG|{l#?2CIwzp2LH;Omo9un5dbW&|jhopjPm zj}%a?m%hDA=+WxGs#ryTl}wN%wV=T&+!(^d%nQXoG$R9fI3?+kL{Z%3r}2YX4hq`l zyBU|8!$vMKqB~NZt9NaHv@~-)9p%GMqh#yE>L=}5caYn3lU3Des#`&wT4x%xu6rY` z-Fu<7Y|Z@u*(Q9FdpLU1VM1$QaIOxn$I7@_TCE>e>UT34x>X&2GkifP1uR_lIamH4>|E-W2$%;~B|&Gk=`qw8lEd zyA@P%%~yKi#^rnpBPZlb{?3rEVSp>IEEL~3H2PjqtZG+H;by_|YyoxoV=@}%;M8r{ z4$97NcDnCYlI0`;inEb6ywOADSg2)e&FHSsyggr-xkQ~;3fE&En-0PGNe>+)&F{L!1_=y=i>@MZa*p`Qe%J>VvQ9F zL_oe=6qz4bcekMl*pi2AodUP#l0u(p#9^Ht?<4l$SJ(=F&(h&O#;N1*#{HCNg(}ig zGG|;)S?rBMuaQ2m-^D`%O2d(mA?SJ(K7Yeto}D8JlCaW*^~_=ozhoT`RIg3elz*P( zbk~ye^6;Cz+)6$7T5bZv7g~v$90Y3$R(UM3FZZY~%KCKd>eO{LzAUgCKD*?;*xNY< zYM>}+YL#by+%WB7YcqoP)6))WD(l!hvKD^F2NgktA_=H*fms`E`d1CxjlS$gK;*PR z$Q+~mb4x<%3=ntY!J6pM+c zRS^L4ktdmEgKoQQ;xs7%<94}q%Zr&mEmxw;r)J83qMT6smO7#Xe?2fct|8PwlUz#Z zlrchoeQrL!M%xc8_4nvZ*@<6@9LcROF=X2X!4;BIgg{mo{?Yy`SbY*l;w7t*RdDVG1GTf(?M3HA6TM>_?>%B}E zlP*Pmvh8#qJh+*J(k}b;j+@kXE%;(m#b|zsiqknYG5zaa`~W%lQ!b1ik@eg8Aw$FM zE-OA}WT^KLpX+1&USBkdDd`@#2z7s4Hi_lyvB?0(sShU58W8Uf-BJQ;lmvZSGiN3c_egaF>0>5Yp&RCx}{zmOi(<*i!(1 zsD5JrOVArAB+3&crK4>jXxHDb6|%#A1+S~_SZ3Hzuu!^Le|Q#4=kwz|*fW@9Z1=YI zk)ILXJNfzzbxcaIU%$fQ$04nCbw;ZtB9GBr{GG6q{`)&OsaK}>5CrriJf+)^FP|e% zt*W;qanx5jrcoIvfM34k*LdSR4Vf=a}4nvL3 zA{oT094`B)LY_ZiAITJC49=&)ICkp(Z2A^3^7`vh)f8mtlCat4X!71(=y+B(EEvf5c#j%{51AAZ5#)tv9gt#)}Aa2@gM(aCe7)!yp z;I2fxaCKV}(;1uohGTsZUk(ki^vAEJ`^(DXtM&8z)we%}zUKvb+iGPVF#c{-*c6%c za58i<@{Y@nT6*qtY7xdUNObC8hDy!ek__t(LRU(V_*Ri>a~ip3p(|y7Xaso!B;hIi z(o8|Kb}_84!H!++@TFn?`fTe`43@0o)ulVK<=W~66CzqDE$3lnOoVu@d6$!^)QPW4 zZ-|gznyo6hvrfpSyP?h)2W$HULb>Sn>Vqjl!OufRFl)>YW&-A+cq4(3qq7t z&vm$inIurgWG;44?8G2{^wx0^j}#?lxcy|u$kAZ4!f(F0&2Ls~fT`5P=T_>4MIvo;5)q!Xc-ev=KiUKtAs!J)vCup+$#Jx73gLXS6U+o?>z<4FeFDt;9?YEdXm z`pe;f4q{Cz(n5l<^Rs)ahN{2y26Wupe-7-K+)r`L`XBp@5`gRSS+7&EdCIfyBLOG=txB}?zm((zI5R!`~( zAfZK+a%ieToJP!QDQQ+7?I*>5N|Uis!KN|VMZ_2%{jMBgMg~y-B8ATPC}y`sd-g7fqhHz@d0!m@ zVH@e7409a;Ww#>8m5CZWgF^$LI68YL6ry`niJ}{S8|xAyVLKK2%W;0y_$a&Vgm5iprs~nlJVf1HJOrCj*~#`2d|j@iS=lqV62@4_i8*~=`vhgK55h}i zhYZh0l0MO@x}B{h9K=EQyCHJUFfCh@k|VThmiyo(i%k1^ zC9MlX2#4d%kTmO}AtWw9>o=BirdOEpTzHy)+A2>`5N$Q4-7ieK-N5`{c}=R!F3+9K0}k z5`IC{3>c}OzP=tj7~E=(_EaHt6yes_+Y`cD2#v*Qkw68%ux}~vamYvOOuZh{u8gXG zf03jkqk!c@d1h)^Qb)tQrsfX2lt^gT9j13MB$L62DM~p|1%hsMMQsDHk;|w*iVb!L z1YZ*|p6OGoXO(z&LPWgB@$z($H{JEo83f%7qIxSdVB2GR*7LZO5JIg)m$!I?f`x+i zcEn-ZqaosnbYiaD#gmr0;cc~w4agIJj3R-rDPFF$m@PbGu7mi(?g1MOl_cvwU#~ij)S}EtiTY-rW>;06=SAL7|fG@)D(_) zjdts)hjIG+RrM4jttHfNTg}CFny>O-Qns|rBg-IP947^tYtg%@SS8iHCG>uGu;;Cp zs8JG8DYUpp7ifzWCLtQ#Z?zOh(<6$wzLP6Jy6prIRmNu`7D#Yy6WeGxh6=!Oyxb{_ z8W8BIho$>ar@2%UKMJY1BUx>K1W#udZYKHmBByyV))>oUzyw`2sKa39oO<{SV`4&O zz7onm5QK2g7gb8pf9@H}5sj){kLW%WY(b!-8uwS{uHfSTY}pj z=I@xhPc8VlU&qXO_9TA=F)sDqMLj` zoGm>bX5$RA=-5AN^O9lWbnZ1&Q7*V$44^gqU6!h%GSqZH^8|m(k;sXcT(4gexE2(E zqp)5L3L{3~l%g|#6q-<#R47H==<|D77&qUFIkfLFTV980~(?roHOpPBl%60HT>u3XMGVVd*UDKdU>lxP_!=sFPFGXnd%cOh8 zQs`+Sq;!hCW$W&%rm;n~9-a-=&-FaXzE!@~Zx~922NdLg!x0D{#Q91gA~7L?DQThL zae#PR847NR&%;Ax2J)#7LPXz8u;?E6LKj)i*z~yFXpY-B?2)UKc{=Ebm|$EuiL;%? zj0CP@>hw&Ih!>?Vn}@6;ytw<{ALi}@iHNzK>IP|Xjn7ZtS+k(ykgq_oB(&<`SF8!#-w+e^qRH3gQ0&EDPELhvMZPyityh$7x#-tGN=TewrGLTbJ{__dgPcdlXTYC>pC z8m?WpayRO=#BcqWa3&#B8TvJ8irS((#vd7Jft=C6`L0U*90k!jKQ%EW@7ZHi@l_C0 z$^39a%qI8{t5D1+5B+`e#&vP%tHpcwcw4CFlu7QZAnWPn@2_m?$gqbuIJSkQ&fUo! zVOCCm%brrHZVM#SR&3GGAiNzkHqxeN^CtC)`n?~C$5YqY^>*X$f@*SUlvqx(!{l^U zy7>_XZF#b7cPf+*FRPi4yTo~*Sff;%zsbwQF=h%{@ih^&0+bkuAp*@eKE{{rW?SQx zeMU}x4Nc97KdScoVt$yo0K=(pWn*axRuoNtGa|t{qq61FRFdM?5EBhyC4^Od(c7Ta z6Z?%$n3zrea4d+a4uZx+15U*PX(QYCGdgdqjkcQad^clKdaw!149#p%`o^G|Qbhu| zH4yPc;c~Nx8{;MC)#hnB``B+KgzN%v7W|VW8H~pK;Jw2)jJT0w35~K@rZ|NVBfP$U zJkQsl&6#-`7>(B<-X#p!1VDUpR9Q}%E=aR3A{hM z0JkT>H=P$bqxL~r902&#U3Cbzh_qqOIOqRUoIPq&w-l29F^}0JjP*YX90n#G*rh+plAPoHLE^MI2bN{fh4eYa|Ad);Xy~Q>sH}NQ=GQxxVna z;j$#-A5cwy&JcU3KELi0X*2&QRK~GDSNT0buEZ+CF@H`935_BLo@)`2Ubhl+q#7?=Fzx3MsPanL7cU>MJ$!yH9mzVuzso8jeh=pyV+Pwa>W>Og1xH>{16t(=nYJhu_bM_PlRRJc zpirh?`~};dE!TsJ<14^_-kogrdScxGdMDixg|oXQDuoms;Zcvo!BfkYvq`uknMckG zvMK^MB>miX7ssJOg+h9l=^+mI>kH*0`p})uo>HXNmRnIvcsk)XKIqq3_A}Hnwrse` zFv+zii~y8%9l|=JD@VsvyacdggMOVnhdhkH)yC2Bu^emOa|vm)6UWzQOz zqNOPt`6@(2r4xCR`i)e|_{aZ#M^@G|Y0fO|iZWJs<<(?9PHekjYBC|i7GcxClcU

qaYRi0D((HyGKglk^$8}ySiNrZFBUE5QgbH!AmGHXNb9H$%!tyP6$z6{9y ze9W7%r`E}P4SAA(3(9IX*;pn}N^TiK;Zgd@@f+TFTvA1OWABo(?M`H})eTwrcgj}To!y-fs@$kCpG`{>C;v)Q;n4Z z$S|kS{NYv(2d`;;Cl!)DnI(#prT$VyA}U77M>p6qVt6}$#amLaEcQT0h9=beegQXqG2a7qe%UJgHMAST8Mbhq zTc<6uWzvk(0n-=vNF6X*tPW5F^-@3hVgD9oY8K0Y|bQF+aJR&vcv6RFBEY9XG*Q}^LEhXDu5Cj4N|=$FhBGj_r)emHl4NzV|b zeY!~|#W7y7eQ24EMq{M~FaCR$+~5!NoGDvO?h2THg?CeC%T!T}39#wY%mYk%-V6-7l|RRgV9Wf7OJj!lm30CO6ixBMhssx2GmbnvvNur zc>%G1qT3?t)kJoYLJRS=<0eV39J5Ut^CyQqP_m96+e)hx7qhbZ3|FnIyIiK3=W3VE z$o5+zeRk|o0WQ7z{($o|uh@B)w4chjv-Mf|;m?ul^i)pg1_Jb;k0z@s9~bV6KeA|9v(^U z!&TH^R)u{sT0>t46D92e(2!UWCBxa;SOW7*+4G~O`bEij;Ttq9T!nySu3if-X;u$t zVQn}48ztUZ284|H0f(A(nFwc(GIK~L@a}1_u05NsCba}GkV-lGELjWsAb!;!X%EeR zs>3+)y&{`2eX@HN3DWRt;ob>zBwiS z{CE>j-%$>>sdhqqWbzLz6)m9^&jg@*&|@d~Jq#3LX#g-2<17~CbS`F};5SdnL52BU z)tB5A&plYCSrX;;VRXjsL}(=%8qS4(ckLUp-n~sFz307JMDaBf3S~syCEreeA`-RG z?3ZtSq3Zh1vtVzAiLlKQWAto!NWt8aGDHfJgEaYN<3bS4j79}n^L4_{99{WqJQaS5 zfX3Ia=g32I*G+RwOcO^H(Y~ToFS+?v*Ve>IjMjFIuAt!w$d9HJ0pQ?ul##@LrFnx5 znw+^0_2A@tWlX^`irIW(3+tGth?&wpE5&ngJXErIV|;E~&$n~`Vq|H=RWpLnpE?4` zbN!!(=BWcji3djoamH``u7wXVo$?3@55@(7Auw#(W1+kU)I z`nYFeQ-FG2AKx7?T+_@IsR=26$Gx~6qCPycqP{P~kH_?D7eA^#6z8>oQCAQGQDjT_ zsf+p-JIcmD(KsO%pVupmr@{FhyfP7>cZ=pbYemhL>ZLaW4#5p=U8rICiiU?Fd0p*T zrbbso1AY;b(T;$~I!$_}2O8giE;zQjB-q}<9DX~W6>fN4-*s(I;+`;nm*VGwXs1{V zL&E!TTxX7Uy%^z-L7+}ftgAbR05L?fOwS|T97!@f!INKwMdMAc-jsyjq$9SJ`G}>;bM3y(doM@_BG%lklL$_kGU zVmzmh-e;UFGocHZQ>Z~NSaxTWZL~&>F=@6DF{{CTO;_nOIPGqeCNmt6eezb7_dXV* z)LdTMSt7Zh;t1@z$MDMDHx<`|$2I(JYk*ow~PY-DqQ6={sM! z$y?hLEg!BHYWCp8$&64NdQl~cGs{Y7wF>me zMNfT_Mu{1JXg<+|1hqieN|%|rq>XcR+;NCQHE%x3?A^+XJ}0z=OK9@V0YZ8kP7drx ziz#Obki|bz^#;-##38C&vrC^54Zv0+>*1bEPey;Q^GsAJio=70@~=xPQTiQ6oB4Sf z*X#W$w%&+qnbMP}BC$x9a+?ATJwjd9`!9INI!!x&nqh%oW?@7$H$z-5R$?znAHqiT z7Wpe%6@B*H?!1BnnDoJvsT`yF9E*uz(GqPQD>e`mw_a|<=_dR0p)R-M8A&#Q_wD%J za+o*mkEw|PZ@GUcHl-v+X)8fVQk5tF<2^*}nZYirgeAl_qPf zcbzJKV7)bY5q0{u+KvbK87&PZQi%#p6;uZiB=$BAH%e|%E%)nVmM>7n}3CW{^*PY5uVm8m{Z^|dK;=?X{4X~>99Z3 zU;VTUbMO;2UnC^ofp!`J^)))f;;<$a1oWHJ($7>>xOyM_u&+d3HS}BzBx+JVFb&tm zyPG|1V|`f}Q6hEPlZj`Yk^VX%kqiYhq_1`ch5K1TA9;9P=#j!(-51Q&x#=);WJ=dd>)E%h%6wJvt&A?`g~E z$|JaKdqO+KeLuZkt_n*HtVD$Aocuh;H8jvRm+`OU{WNvushGr?xl$?U-JEb*YwouO zZ`oDS1nh?J-n(+EWcd(?RI9=qckOrL^(F%UDDxR}QNB{#Iy~Sntkg zgB`3rY&!u=K{5+|YiKT(zn8nLDy|oUsdmmEq1{RQNHOX3%?Bq9^=b60$|o92oDqFI ztVX!WN_?1PS+Iq8lu)mf2TYiM+sO=D$vrJ!!$aUNvmF#eqRW>bDP3%xLtvmypk?EZ zZQHi(bjP-B`-|PNI<{>a9XsjRww=sBZx%C)+0~}DwWxdVISS$x!igw7b4**8T+WLk4e|#d8PKJ9z^p)3`u8@-rv{QqTbng@L!~mh#gk?dEaT(BWa6H~$-Ug77FC6uiIO+}{GWZu98*B_ds8T=Kze zAjl7&q!tOX=9X|mP+aOISN{pWlr2zSgWw7o`(!o{X1C3&2p|G?drw8aw3TID@+5?T z&NN19Dk|Ckt>fdR@B*TuPmwU4Yd>D)W3RWU7QdFXKJc1bcK(Gsyy7JVQxG4MMcki` z?kPtJNFp1a*)RbOCO*ftQerb$7Tn+%aMHVG326cv6B$%?Pb|hHS2zB1i3YV4SkubN zmoNKqV`VEd;xlQ-nZIfKebSuTn>o*=u=}hPI3GTuQrI@^;eVE!{(ar=H)QDu#gm+& zSP8%&m*Qx3Y-xcZHl zPdjVlCYlJMjnURAFjN2IyuSo)+3RY~Ez5Rx&C+hndBOOUUmbFfKSz+#?e2wM9(3OHe1RV57?*vpAG7gS9=F^3CNI14)J zHF%@n%Gut`*uRUIlH-2!@~VRqRthN$dUW$nGyd7;Fz?$t98y=yaJh&4HV_{Bl>r5kqfSo3i0f-y?1&dPLYiknKaHVmNT2Q>0g z_Fa-{Ca1!YiEuxU5XQXpx&+#FJ2hsCexQtbQ5$4rYdIC$5=kAgQ{o;xCC>w=Rwuqe+6yo0>slJa1*>$AhD+ekZI5kl z13Tw<`}uBEi&&%B2AQoc@7hW27Kp?FiU`x8A6y^N>*GAr1SpLM`~ zqo)Ji%c}r`NB;41X_56mlk4YjEz=ejH*tpFEIkVnIJw?VtRHd~xsuISzHVdx$`^>W z2chCk?_3@R8H0E?_=ds4Os-pkUJMPLv2rEdtBaIG)^#+RoZTuF_1KLScXOk<%4Jlfda2N(%$Cqsv<2qGsZAt9wXjbM%Bijzw z1<3W+v97OgFeXaG2Bkj&yfhgO3UujsT5oVW+C(FA(|G3U4Tjpr(!rx>z##x9+{*2- zQenT@qdW32Ki;IfF7>n2ydC#~DWa8rKAFfuu4~Quy)|=kndtH@J=T>A!K;!L8t6!d zlKWyF;40; z#4#aH&Qc_#j7{6ugP<&uB8%a#vWBThZ@jmsFHj8(CC|Z3| zIA1BC7x_bYY8Nnb-Sq$|*a0gfMXXepM8U1kNBI#tccC3VH-?+QDW;zLn)!};5hLuF zoSv97NSZZzfir{tE;QB!!7Ev+`P9Xf8NB@?DQw*HF%%`~6K}_fdG2yme!LBvQlcfr z)?HtKry$);uNa!|H|Kdy4kS&pn6hc*2%z^Lrmz7{W2HtW{}*6gxmNV;EJ2dB;w?pS zA}-p>nGc_RvedATz1YH4u~J&3=v;s9=KxV#DTZ^nigKB`K)hhha@rRb=C=s@$-E_G z+J+fozmFj3V zesz`|38PJvja)w)(D5fco!-fI&VM9Sx~H_d!B&X!CI%F=t*r)~c0iT>9G}=N!$HfW zknae8Cpv1f!jVMSCZTfm`gU@lXSM{0-BJw*z@XZMkUsVCEAF39fVt$uM+C8cp0zwL zoh-eXA3dc^bk~|}ayX$BTO5`eIrN-fFRa=Lpa}q*W_t$mD}IFA^p4y`u6%=N-ouU= zM$uD@uhifVwCNu7ex!cq+4w+Y)O*B8;+~4~u6-qAv#jk(irWfFeLoLK!-fWUP(A(K zA_2T*62y-=#zenG55nW|@b$5#YQx%)RY=reX*}q^Zk1p8Pjpt;)guk?SdfU43zk;f zwWz>*X$^+gRAB`wfi4D?o4DsMe0kv+^dVj}wP6eCgvHvw-7q2ca&4E9rhyiUaQJvP zmXf1_XTe{7vSxHfL0@H`lGrwmE<*<%Ox=SC5({5oDB_~VD>jPapga;8`u49T+c z6^P1~NO2{ILZ5UDgxC%}wN6N97oKUk|2ljs^B^+J7caC{N#NNIhN%R{*|i*PK-PZkOX=r`t$*rZ0z5|>pB`N#JI2{2_ww1T8kMy8c#x{#iBN43PP($Bki>SzLMeuF4da2rV8%$RdbBfB9 zDqEzQ{lqC6{-DugjFgn^MYy3c6h63&4Ia^w{U9$mjp0q4{RR3WF-CZ<(;4}LnXH4O z<>>A6PrF5KeM#xcD14Nf%&d5^XGwSSV1&0-fgnau}{ zDIVI`kZ@nvA1ODC9JqeEhmL70%-LqdAl=WYJXH+Rd2u?y?d0rku6Lt$gsjN%SCn}3 zt(&o@z!7u+?}?@6cEw{739aU zwE~g6zYGlIsuLO8jyF^v_IDyBMlbm}+urPSc6;G8x{*_Mu`k9j9yccvslZPxkpt}X zGL|~D@lpC3?j>&+S9Zb9dtmDfZNU|~r}x!~-!tWdVDF|hySL(X#SKWutfk#I*o$uD z8mESIBc*RlxeY0Q;bQBmfIBRVuD2!a&!+OxNVItoO5baR-#;J@P~&@_Z(2${pfd=+ zV?IL()bQcPuW+1}(Q|aiq>ykGC@Y$S3}u;{l8#t9@;=Vxq6J&})VIGBm3hW&q>lz; z#63|P7d)Ky2Ib%KfC9XRo+;Y*mW5Vg@`Kp?B0yiP_ps>HQt|3T^-F5Z;2vxi}{=@%X&Sczk`f^F(yO(nrYAwEd+>b-`)mE{B)A?zDa}n z*?6lcM?bK0j$pQ8B%S?00}EvIq{*sZwd$>EVW_574Ucs&Fav^HSGnp3%{HMMk$6D~ zDDqFB4ARQPb@m4JLylwA7jGabXBh4H8m{UoJs%JpRHNR1c|zdF zX)f1THvpN&y+CwvF+3%s@1@HO0-;RRIN60)+dj|C(3D!^j;3uw<`9=p@$C2wf4M;p z-K*SYd@$;s2`__-AKMg|Q&)T3z-zKn<@TEO5Mr0V^yX8X>Oj2{L#CvxsZ0bt<+tO^ zXxM*|V8bd#pSk=h;_e%=#0~ZbeE$_wmiiJ~vfG^|0^lIqeD#KCuM~PihQATHgvpv5oc&|fJ`fB%Fq`U9@&T86Ez ziuP{kU?e-gak1zN7S8n79XsOEDz^=7=w470x-1W_ITy7(kYELH+c@%&em`;IyI-Mjx^ zbP@_XGX(J`DxT3cqt1#4eOBnL+AFzt^=uP!lq|46LmSE3d>Pi7S>j0uUxhp(oGKk< zm22I&Ke~epx2b4W(v&fF*%%0F#G}nP21f?mo&kbLzQezOLdEITvC0^ROq>p!QOUl&Mv_F2XXI-h^mP>>(?>9b!6s zvBDcKq=zPL^)B>6(E3iwZ{=I7h+~k69Z22x$=A0f0%pP^2xPe=Bf;jQTIedn%!u`s z@xTjqG9C6x>`#`Sv-e8z59g&QiZ4<-{_5Jw%2($CdtbojPH8c}5ES z?i3B`VySqehvFeUGwLS1ozzE3fUl@^I@tewjyuuO@Ux7Fq@x-XZy(mMhgY?=zQoYK zePwBY$mPScXRR;%cl-z$#3DehI+dnRC8UnGw&DZ1&M$a^`6Qc9d(UjfId9(N#GE7F zhDqDarjFDEAl+yCDFqC;?TvT*-zAPWtk3aOfG(^`T~E`DlG4O)()ESf<=UX&1@j$;^s zgB=D{+}WujEX-S!AXx+n0YO6}f=r(B-^2VZ^!)K$<940V+~ehO{dsll#iL1hem5qP zpw7&U8h8YL3r+z7i;G)P079%7K?IFXey}qeTu5LDl*91A8&YF&qmtZi&muB}~RY&Y^dL9KnV6_KdrF2SJ@j9DzF8L+Py%p9Ge(~e;k2{wfE-*7=VMbGY}X7l>1Z%ASbH> zdS54Q3Corqa_H~@O5A-U%pq`;0~ny8`5@_gAbM(U0jX&4x1(C0ao|ilwVj{=FCyRa z&l(T4;*LYthH}slrzfV7Hz8!UAj^(Fu!Z5OrsJN3@4@I%W({If5g7sLpIyb76dV2X zu=_WiE^;86@_2@kI5)Moy2R9NXltR{kXJW0;(-QM%&k=+0kp&f1V+$JaJ#i%=)2U| z5H6QFU;w90oNxzO*Eed_E_B&rElFODJlGp_TO-|1wOb~vn5Y|vYy@}&WKcn5G;a{F zzAR8?q=@Ri+6V6(`8r^GWZQZYqGwB9nks<996Ft812^oI?7_X>H5hc3S|h#o8Q}U* zA%zG8QRId|s0&){LkR&aM$3$r0n^DlB}b$H80269WRREh=j$XKD1Alpf&P1k=k0e4 zMK1Q`#iip{w%cC2yE|#50Im|s+&pMx5L9$1&>`j@+km;3EdcXf3AeMIUjc1H4g&G9 zz;KlDwN$@u0J8HIjlU59P%elYE5d<0ej+%l{C79#HQ;Mo@tfeTm*hhu^&9TsdlmWL zQvYu2pYzsFAf16=7cmFmF%&+J8bKBYkIV<%6VgL40;DTJg9r2oz85N@T85BC5RHOC z*@&dmiKssSDI^cjK>@?rQAhTnCnVFalSe>l3N$uAK(eC`=w?W#CcY7}#r7AuV7U&5 zgGvK_rZQqTc6&`>bgL83;4y$J}& zJ5t1R>Bu1F<^};As1h$WQ%De?V7$Gmy%flb5X1n;w+=)k7{qMvFn}J~R-l+(<8K1F zFxPvqJsIB5Z-_k5jzcca`nQI&?6OKbb}QS#PxWlXf9+2K@%Bk{Da46jvCMr6#O6iS ztCZPJyFT(uxn5~W*S*$sDbjYg&!2JHu&h8k!gfDA*(DUtoVzVA8 zO~Piy4N#GgVlI`^$lAssH4U4h^-muz4}w3eZg|y+O>a8?SdjqtV{CZq z*|f6MB+u>3Qd>s(U{IF_^Ow1XdpDXcgs^h4?_Hi^^UL2F7 zwc@zIwX=OtZuSg62h9c!s1W3-KL@S`MI$Z!JxHH+N;e$Zq*b~H+GxDA6CF)pRHe=% zS6S_`ttVi6ewAp9q!wq6=3oK5P0rk|*XsWTdN*&Zd^$ThWj9a|lwUM*yS$%e%h|+v_ zCsB12Rkr8L=K5)OGX!o`F(f#lj!vcjq;r4h%r!^O{fw)$lH;#0X`o7DHSa!gYGUcxM-UD&O*DfZ9@6 zbk|%P#DdE#C}g-SSOQ@x9V^$z@xa>xG?saXESD;R!{QTW`zktv_fSJ2`2=kQy_D=G z`KnfIS7ENcjBzJ$C!c*QWvto6)Qvv9ezM~7i8fQvzq%cb8%7HsMva;c*53t>8^=9z z;}nLmVNkNJz1u#Y#p!WpuTo3A0+riBg!yAzpOd2uYvXwDMzs_uFQoKl}jFH-a9$+cFO^{=`7qTT>cz}aEq+*;}~GO z;uYAsMYRatj3zx7Okqg>dRs{kWj)MKW^D<%`GHUmmr(k!V(|L77ro*|)VXtOzfiw% z)r&DROQ@=$gc>b4xghN`qv>^W@gAYnZ6NjCa3 z2a(I+=h`1Y8L3y9M^CAiHac*f7hmb>>~tKSCDYk;et z!o1?tIhw%M9k;gW@Z-26WjqVoeQzN-7iLivlpAnDGj-sm8e?BS{+`aogqPPvtc-S? z{jLMlU>gcCuMEs>ikEr~JjY=C*1g$H#d4jLv9eTj>PBrR%{o!bo0htEP9kVqreX>vP{A^IEh<-W$u!3}}yK-`Ln0PC{&$CxxvBJ{P zrKosmLDpUw?ITd16eSGZ(qm2L!L8DK~P* zi{&}u@4EG9$q6V(J^P>8%-NU=f&RfiVc8CKG)Ydgk-sE{7hro zMw@gliag*Dx4GmVw~`Mah6VHK4d zoZ>!QRj@b_C*AJ|i})uaG~BFop$n5XB=eRKudWt_Phz9pyYSap3hf_&c}%w>^2xis z=OppB9;s31EHkCAADEBwbwL(XX*(K)+_d=^qalqO*_e}Ye7eif3iQ9B%@Hpj4unji z&}14ZuzLaHBo|m_TxfqSf}z&nPqQ0s$bV!M^n})11W1Rw`1g$)p8M5#PV(M$SM_&~ z2+!dx4lP&~*UfA`d%pWX_I7UX*~LF6xqEA4E$A7;=ouV>(>!wvf!^`+g!K$!rfGKk zqxMLs^@#P(gJ~E`%u?=govx_e<@Y^sI248S;2rXi&Bn7BngTZZzc;Z=^QFhs+)Ezb zJxUevGPZ8z7Z}9NB*J~az{7BFyO_F~Mg9oef%3&1ZsO7)A>3F3s={-uD#Bb20$-%( zl&FFwrV@)D_JIaM*V@o}VOT7e4Vx@Iw}RK6q*Os{dI+N@{E2wn_KMc|pQq+HZ}ln; zL&KtpRl%3>=e9_B$avDPx|d-{mlJ~Z50ueiLlYVTrzYH^#H>$U)<;V70 ztJ7Bsy>xni4v_i-g=)ri!>rITZz#Mh&}a@$=OegrjdV%aPvZ^b9F6|{LV%t8N^ zk6@CX&IV3-+*S1i*a~H`mKnJzCFElhvV~+{RaCkxxH1pBgn8usUQC$#_uD#69rp=O zG#l-o!~a=-Ti5w15jX~IcbCxI$%66@uL9{k51q*^0F+ zI^$+!bHYzL!$bTgrM?r0nc!#0_97AzKC>|go6v3LeT^PiVg+9rszBYpW8ehwKimkn z2p&6-hax#}ihcnv#obl$#w%j2t~MzmA_E`-b`2v&f=BFOZ~eZP6dR}9F^-BS|7~p47pSWq`N)?*s5{l zzsf;Cz}vM=-pJJt$7qPuAM)j@DksSOC|6%skAWNjZbPf~rO&Dao>m$sc{fFa+BFw9 z3H1DWZCKFY3s&1xr8v*+`QQltdW``$CIJPf%>s@P1B5!%I@iBhe;;*HbTydAT|EYG zXI$x@&)L3(q&)k5#vkE^X^9fDBWtLbd{0`LM)xI9;U*W9foEb+L(y|c+foB=<@GL2 zTgk|P#=V;Irt>`bwy1nUW%rlZ#xEqHC)+r*7Yxipm-SNuij0UiLXbgGE!j^7mPGxd z+m@zSe1$Ac*~tSRiI#Us69EaHOnHK!QZq{6Vd{GQGB=dcVVS?3h}pX_sO)lmqX~`|$UXaIcKZvjN0tFV*afb7W0t-}vquZ-OCokQDo!f@gBJh7r(?Mxbc` zjcg#U++E?^;^CQz{6($&;+$bwL`%#d#rUd&sRVW*%kBu&<)S{#a^wxj{iZ{msUTYf zuSKEpY08`aiFnde0r)j~c=P+iNnQdnnt7Vst)$S0m9t-6FOUvcHn}PpESFxtxzWB; z@!*#Jmi?3c^>6Z1g>}YfONU4wZwq7QMgF)w$@f2&l3)zQf1T9~aOa_~gaZrHIo#j3 zo>CPM({o;hE8IzboC7jV>jCmyx6|Ia2iOo3qt()HUi8JP?hTyl{UqPa6%<9l-+s{9 z;g`Zw*(68qb4r815~wDPUE2FJUhN*?&|~IB+B^{&aO*kS(iqBXvExIQ4Bknu> z^@hfRzkh*x9~)BUxMr3l#)Uy((Ag2>`;`xsi3T6?O`xT^b`d{&cgQ{Cwcn)WS6RBJ z(p)j>;hmAB3#~6M<=hDpsAn)^w1zGHG}74>4Og;Bsoqys*W5DKZ1I+M6U~2;XnP_U z%U%b=iMo=^M@xqmCM9aFoe%t5+zs&9`hR*D?rRD5cH8-^d2Vtebd>-d>U%~l{!0I=rGjqYLrwPg>zGdx>I!BGV}W! zy};j4+%9naiQ*1OFr5-WFFv{U=wi(px2G)U$P>L(`8a%-id9Ibc;WFYiIge7u_y(p z=2(Tkd}!ka+*p%{%k_}`i_WS$d?qqrXbSRt&z>9al%w7(z#Dwwt)!m1>{-jqoh>bq`o7MD-8F&30t%-5JCZsfOGTngk&^r@<8nK&~ zFE(e8b*dCEHGY|y(pBd|KH4uqSBNW!?1%c-##5{&QD&+71_a`+XOO(L_E?08t+Qs1G#E-Q zG?q^*0C#$j&or$PzDnRRnZ}$i3BK6scw~j!FN+Co7hs+H_h|(sh)m z7(a~_J@f$)|H>P*-p{mndiR$lLh`a6W0-8s#M(0-rlZ_;EQpRODvN)~(3o+U_g=1g z>k*G8yZkxKR-orw=4*)GN2yIC{Fy!VK-5~X)GCRF<&g>&wlg&au?QyK>1wX%+n|Ef zWr5V@`?43!<7iOA7}Iu$3Q7l4p$sQGVK3FGGxQHg!IcLati*G`8iF*qG5cXJWTq}~ zuNRqutXs(xHNNydP2>kBKsWYvdmp0qxW4k#YNHEoZDGj~H9!i!oRG=1;BX+OuVlv6 z4j-g(rlxVFXzKIoB3yL$ka41?t!;4-Cp#70U_K9u$6?*gj>7)zR`Ih+NhK}nR4_~7 zIEWQki`%aBKl+vw6}H+y7`S8yZSi;@ZM9}Px&I@DUZ2f`r(H7JYHyt zh1Iz!V@UFOVaBymH7AF0|K-<{r=Duu0EHpgAzc56EHbhSDdqIqpxJ_^NWTl+<}(kl zt69Bf?Flbl{oGHuMXVHBFYNl)ij;C7-8*6Png)~K^yc9N%NzE)xZmDu0FJKkx@yy> zI3{TQ_f8J=mm>O>M)HTFh2(*J!b}7Fr;U_fA+3Psm4Jau%L&Ku&6JguSLQ2LD9^ex ztXD?HfL%`>rVN;lnM_x{WY?TGk3|E3)h3}|y}&tB@Zun%ZoquI12H+OP@+35r!`q$ zhWTXLgSXWkj9u`h<=toSaV1t>K#10+OraefRuvty;>mE@S>%XhoTK3`w09MdMXaGa zlPvV>gSel|H0iH!%Kw$4;bZ|Qv*+x_*YJTU`{AWYLLxQXL*2`sp1A$fDDO( z@oA5xVcuWU#mUteQz2??RB{ z`#XehsvoX&U<3}*g{;sAd5G?Mzmp!bZIlt0HTxPJ8XX1Kt2egFabf%ptba)=EpXdX znBGz(ytC^v1760{d^;NkyVU`v6bZ*oi{j@ZI_A5(3X1prVf@(Szco^L#qc8FI?;OF zZ-bY~17pZK9kwIZGfdu(ga2Y42qdf4HF-PAp46_uX|i{A6?D2OG?zU|?1XGv)E$NV zZrXR66ykVf)8cP8Wa4oeaiaLkc2zgFC_7sFilX4OxxJK$+YdxrSR^_?s&B(lleAXm^unpS&tr-I3}Pbu>u?_q?#9ZfT1xqvD5 z95{CQSVU$lRxu#3gK$nFQUjTQLel!&llBl+7`ben)Q{Y_e#*oA8mLd^GL67z+wT2QT zTYGRu<;6HD&S(rKIzb3)gHcU2pSN)BpvVzTLKoW zdBkA2+lcBwfBCBaF0Y@zM0v&B>*b_W!BK^06MM*z!+Fc^T-U%9NcG$cGQYN9_dl62 zlB=_s(f=GBjICigdHyFf=KOz&(L7wNEdK`>&CJEa^FP4ow0Kxh7$AN}K1fV#f9*G< zhX)dJRUj1Z>By#Duw1|n1RN@RKZ&qoD>AWX00i{aZo;2-Hka$~+Q+T4X8Byb=E|Om zH+KR_-d_arG;|@5s)V2(`w%XHA)u_**0Mn$$PsC95PSW`ri-ENJi_0sCM;)Sdb&o? zZ8yEptc;2g>%qS;_kgE96|p|h@he0SW+o7NVt9W_crZ{;VdDI6WE92$5Uq$GldyRs zkcyIh`8Ap`tk6^rSn0p3*9Td?y&&r}8^HQRMQ6Cbpnpj7i0T=pB6ABP?3u&4`Et*p z?t#pTXb$ArZ+)i(Nh~f;P06HZt}iSk!R?)lhdS1ySR8_Q4gedrplga6WzjztVQ)H( z0(gf|-YhJ1HDf^Zbkfgr-3daPGpU9kVLh3-`{?r>SHht^+AtO&ZydRWrDQPjb|FH) zWz;{D`aoZ7I6;`PUanmMiEnv`;BOT8`X+I1UXh(G<~D>r+#?W3%fFS*?OyFpAjFQ9 z+u{+ybbBO(djM!4k1#zUG@yzI`d7{hlo$!&YbmF)7;bWGDrExW=%!QRYTJsig#Jfs zq6jyy=&pT@X771YXuB{2(a6=*=ke6qAWDwoc5eU&yuI0HCk&kjmAwG>Cp6x12i&JP&DeT)N0;cQSvCOMs}?Nhhz>^y+GALyMzB6xY{CCLI=M*1cEX|y~W zE<|sj5%B|k=V%Y{@%giLzZV4)8@?_`s{@oikCT~uS!k7LQt@2qcJQ#XuM31p7-KhwG0t@IjMBZ5) zjQ$2nfw_>rFIw;ig(}nyTu{%QZ>6ijtS^;@Q3F`RR~tS}(C`0v-nYa$)B%S?DR{vz zBB@A7H{XrR-_Wn$NiWy*-&`r*4kC9~h=@R&*4NE9uz@U<9{g+&@?)u^Q@}O=ch3lE z=UdJX@zcd-DNmi*WAyuxwq1mfQv}xjKF?epU?#$fxK`ksR3kisY@QEk*IN53|08ti z-Rm(03Kecms%z9M#E7IsJp27Zh&eg`wF|!YMm#B`hrIHiI`DlT7ce;)6#VocaCVdn zS-KwH-^BtE*3~86(nQku4tN3W*$GEz4)Xpau>;}4!ry&D2J<{wB{KZ&*#G7?6~qq$ z*k5j!2%!)K=sXjVL+^0D;K2xhJBodYAPGkI&Rxs5ReuE{SykmB+JDdf*Wa84OpuuZ z){hM0iTV)UvCu&r*FWI|#n->ViA={4zVYq^O+~py?Y>g*Kaj7UkbJ2hMO?oHKU>H4 ziT>Wl&z>W_7&JD!dN_Gue-Y8$GQWHSJ3>8}`C$7XCrshNFGs`FNIwoLMOTPfeir7SCR80@J}vQDyt)ihcW;elExe6nU~H zB##NHAUddApHwhRDEY}!6n&fMtzQNY2V7x()8M#lb(n~rNM<>?hIwOlM_GeO`&V@&@4{;_1S8eb;;dqk^^=$PjCfsg}@MS=cFv~eB!s+YQg zc=p0f#KSJ(eT!q~X1M^`X;Y9w@#Dnez2$hacWnIHJYZZmD$^xzp8GWGxMRAJziL>;!h}I`7U`FP&#QoOJ6uJ+xolMy8*>ZTSOd9pjCu%lALRXpK4ecm!?hgNT-l634J!4E!baO zLX1@WJc_C$-A3Z_!ls^4rc=ZeJ2{*k%r&s4A~>O95a=gh_dU#i^SAM{Iuwy!IJl#Q8x?CfHh zs1Y1y;M{A>@qP-H=!3{ln@q;qJx(2`^u3QCXL=Oo(rwj6KJgyD0^ZWPJJ>4Cw65mq zx>r|65ffm{W1Euok6R!B0c>nyn6oO=mhd{92Rb)sm5bpYAHkj2**DuHS7Awsvsl}z zM97ia#!>TsVE9bK;;F_c_-JPqverEAk>;(0Z_q^yBcP(|LGz#t|H%5nZT-RLQof>E z5oz-1)y8M*^e1;+fPvJMLDNJxb|vY%aJ*l;7h!mCW4fkN#HjZarz2yDkDg+-7y_>M zF}bmi*piZ2^7-^x_em>Bfrg=P9S}1dtad&=*LZ}522Qh9SEl=wtFR+J8@32wZy7{6 zZ#iznhZ?>5cqZu#%j3<}N}L3mMB$J7HmJr|VBt+0S)Cc1z%YZz1-w|Q*T8$DZy$=j zo%?!#)K;A5>$ci<_5E#GND5adXBMCRC4XsQycrQ}Dp&pkrw2c}>T$%$aU)dYl0yd1`u5&j z@acNqdwI74!II!kr~C|Udkc{9Wxv3$B}`*W!3 z-~D{ofJ9o(9)oVPuR`NC<&6N5>mj@7G@YZXJEF&_8mY5xj+3PGK4#E?L|M|1U`sta zuP-kdk(J&rhVx^^meLGM&m{&s49HdC_F<Lfj31QEhg@Y#3s*p+<=?uY!j-I<@KTrJ+&3p($36qit+ctNubQ+rGO{ zIvIwbf(xaln3e|M3XZV2q3k!h^gwZ|fg83tHmNM8t3UrgByROJ1&6MT{6G&lutl(mc{FPCB=sWkeiG< z@2)nwG+gM!&GH(+sg$J^V--4@O|G1kom*EC8|W%^hQJ*zP|kucbBmk|o^aZPz#UPT zsNpS2F;(Oe1GD+$--lQ^du%A}yi0(cVtI z8Um}04JLKeYChd0_2kk(XjcNUShZx=$V{hL5X2^3py1R^z?LRYOGfwV|H>T8tX1k= zz1{2g?c+N+jQ&e)w=G#3wa{mXyGJxpnL~B4lxOL>C%dT4;JvcA=teIEa&9w*{S6{= z?AReOutUkuV%QivFJ{okw^oXk4_>c?Xe1!% ztWwt7f7V9jR)(U=Ii&Ca$mtgiTbCbbphO|ac_SN*1)ooLBgKNVm?o{MA)Ta0P!`H+6VpjO*o%Pb%eBnK{P{vMO!&QiDevqm#HE z|Kbl(+Wf79g-Y!EaV+5@f-iF=kC#oUH`*q~k9|P5ec3WeLw6*7sI>e+=h)!GHDuc&kW3#64sST)QbO1A_d~nSQ8|$PVcl#@1ZB8AW#$ZjL zH9wIfhPpaaY2y;fCv5d7U2D1$OvZw~RTFv4Ozcs&U$FgZEz4&pTl-{6_F*h@XMu0XTjLK+p&Q5UsVb0tp~v398>m zT;Ic}i_4qnn~T532ccLaY)mLJV8i49+q5+GWA~UjPH=MJqaRQc6dYS^s_ha)5P*~n z<3css&$DXboX0TwVuMzTMb71HnMqjf9a`0_9q=Bau`YjF%|B8 zJT|-XUeH|vDmj;*D2eylpjXY0HtyU?mgThuui$E$#f=!f?^=zjA1U-TRau@S2}-Zk zv9NIxBBlxaWQfJ6;7to6+$m(jyV-^r#s8wVjodp=-m`gGWWDsHo>Pib2P{ zYngnvaKWftv6{PJaf;1lGT%O1nT_&>GP!Ol3 zxTmJOqY-PBZk1i!tN!`vR~)ol3=gLs+q-a1t-Vik^sKgIuQ1WljuR7$K2;VB-~IYvGtgevY({1y?+yj$-5$TKG3 zp{I&53_I4w_5@M(!w=umcy2BKIlr?-pU;5lRrmy#dcAm2MDP(8#Fj~hZ;!I-g`eF{ z^@Nu$*zEBD{$+REhBwYw!p^vmER;^Qh$mD4WPvceuXDsguFwM>xQHI*n}z!KHg1`! z;y>`yMXi|JTTu;?7-t}FXnb@{%+qUgw&-d-W>fcp;(9g*_ z=<2TOs{3BoB`4|S;uC4=@HeyUpFj;sR9B&hiTzemuzOw3dAf=S5^AHkd%PV45Qoh1 zPzHy=H0I}w@XjpK6`K<(Ta9AeDqS0Cf5G#w12nzrd6{B@e4a2!o&mFz zzt?UUD!>3=#JP;YLEZ%{Gf^g=Pkiog`V5#M%-~Vp_~glLh!6W*nX#Qg8zq1UxEOM z%2|LKT4&vlDJg&|qMm>dGfUd>`sg^}k4_(&h)tEojDM8v`O?KjYm}-z0RN8pI0L;E z#pcm8%J}hA{^B^z?e{-`un~%tfSrpXsvp}fn=zx@pK1Riev2x#{91=hYez4g!>H9E zp>w^e-L{ICmud226cQ8=s+xBqg@QId9_f%_-CsrD;pR;CoZ_!7h#MzI`aC;N;qq%T z-G(k|%>OjD$}oc-6f^0?fLA=vpg-gNpI7Vd9I1@$D1FSuC8_$ocQY%lQrgT-fE zBcLMa9VEKTC*JgTaNL)-HM{|#;ymv1$bh{FKOVLCA|vh+{=55bK>t2vjB68%p#%*| z0{fu8dwV{{>$}$I^DtkZ1L{U=vM`oD!YbL^-O)AQ^|wXrpSQs@MY1^*5cV%>rc}ee zei_0KvX9i4hTqVwgJ1=fs`1tl!b{S{Q1;hJP5Pgd#WrrBT#-99k4C+xk`5XC*Rp}y z3Wr|K*~OP8nJ`k)fKeT@6)I}6ICcivwyQYXsNzaXI(ec}73c*DE`bS6tZJ6?k5Vc3 z7+#peA|2H`RAw+f4{DwOL_g3<`-9w9^Z_S@5c;Y`NHWicn2?-~BXW~}KO^OOh!Ec< zsM|X}+$nO+imXh={=_cgqn3%g6DDp=zlv);j&BA~m7ot<0CmNLScSXhWv+;HBc8mG zOJoy+mcqIplmP9+--+V-#m&8r663Fy!#S+P!iAJvD2N%~i3#Db_u+9JO_>iNGj&Pn zYT{q*(IC6{V2|DXmRecwkbw}OHQDcJl5ebF&icZLWaY4eHC2^y zoymc1(DICZ0L;<;I^tj)rpjWU$;j~?6t<|1L}lp$kyq`#^BBSsiDa}d*2F~Hvm_L< z`&Rf=(b+4ZbYlbKDzbbL?u($vgv+0VcwX?%Ts8 z;`{gNi^$2d%(Lu@4z!JjBbJi4;AU@%4YOgfmF^T%u|oZ%xuBZ-<&@X`1m_JiR@gE%MR@Gv=Wc3|n0}`eCrLDY5zp{25igB?)Bjo-6}v zeT;8z0GSZR@3;F+!I*G5Ifuc=h8cI6(+ZEj?PCsH%P?20S@P|0z>EAd#RY-4PbAvo zmsr~_{cdJvz+NkT@FQD_R%Fgh@ni*4!7Hw%PYUy-_~w^c0)K=xN8sFVW ztFt~aEoPOZroZe2(ZG=+quFWLqbcqr+jMdQ9yLF3M@!XvBhuluvv}(CU zc_EY)UpP)kciz2%^+@DGU4M|0TMo}&fSsFbApU&xg=uN)v10=4S{h0bu(*BwjYeXr zErynb z;|@lXzaNIBX~;d$UnWKFLGpnjzbb2)1O^$DqU$8M<4y*&cbF@DA~9vFTi z!QKNc8VNmgOiXLOon$p^E||Xx#gw9psBD}Sm*ZkyBg{rQ$XLC&=j*)}{x;K-vek@{ z!KMPEK3*7^cwz#DOPmwJv|YJzSiZaimy}quCI+tiT4yJW{AM>r)P# z#2L&?y+(xT6)D9FsfxQ!P*cid9tR{yCJ?mFKEng`ePIdI{Zb;dh}{X~k0hdq)gchj zhkWKIlV5ecXfeKbgwoJvizjuTfWQ8D_iLhJizjYPy?VdR!%NrN+$;(MZ1{(AN98Hy zni345DFq-`BQ6*G4n*}^3}J#bwL8`7nPxa1opM3I zdPI9kI>)_luY4fTbfVI;30)IC#RxNngVo{lov?3T-YyMY{a ziXO`COy_T@0=EmIIFi^0#5hkCm0!*YoJp>BY3M5GBbu%BCD@{~8*0$bT^&%6okcYH zC7M*`658;ZsJKF4b5_#pLl#oYEw#NF``QSO`ZbOSxOHKe=VJLtFVJ-S(|fv1{VWMg z8PeGah=z&W*UtW__}C-_n0gv0c)05ZQ&Lx0qIwSzgr6l58IchInj0>R2xD@8uhyL9 zgiI}TNE^D!ZD{25H0f>WsFrSo&lyKIn`x=IE3=DhXlL~ao(gYPj%i&DXrnTsQ>6xf z!@`pJHXZqc8%<6zR7L>|x~CiTEDo)<=6s#;2XaAecD7@wCFP4qwnUA+ZI{BUFzMWP z83r*F4H2@GZY!PuvX_!MYd;ozSTX_JdwdOeTE)3Q^t~B*+a?-FIKJLycZqrav(DD1 znHi5b$nHuS$rTw=6TSLxK=ITsLR6$P@a<`jSPjXzC zM47oGYxm8!R8OW9_h1_Ie;U9Jp$vfsA~r0f6~P%m*&F5OGD=-Mr!3_9O;zJveOH~x zU6l@N3oZ)*4`)~XRpX_@ufUhqSBhY1SM;>I2fypxKFHxizJ3Rg{bhMN7Hmu2&if^^ zOku-2^ak4_3BOOu9q7jz#ILncdn z*c(d<6=v46h6E!JAQn!GQQ=&0q}_|%L&~)WEa4dq=yEZ7>Woo81d>4lq9JjH=%V+} zp^_p@O@oL{@QPq1>$=B-;gJy?}XDr%-Om!{zdj3ll3rx2V}|`Q_tc(F4wMXPVV* z4$BA!z_dQpF)j4xi1=f#GGlC_a752Lbj2*In`0`F)=BZ`VWSTMX3AUwQeEu`){)%W zO31WPq7=mqOC+zP+Ck)rD!wr0;j}fUW4o!x0$UQQogT zvL`G|e>&d!h#1qRA}WTc^V3QL5hcM8iD=nOfakGIDWO6BsF?ZQ-K}}WFXh}_-wDrE z2HrUWi0r25Z8;+!!KM}It}%KQy4=bAI5%_mMU95X_C?jLv%XHw6Wyb;=~N=HnzuiX zFBAlmBaU0#<7jB&FpD=u$wrDD%I%Ph0O?Rb|c@d+3wTU zfHjN*vhP;s)*v;5FTKWowj|PB*vykasZ_VC;zMN$r%umxnzRcLd-(q4r;$tFibYyd zsCESKsqoVG@Fr;lq05~6W#gGp>$Xl-(B(9o&w`k2uJKgG+8)gD9D}C<)^^i^GDq); zyW;7StVjL}>mTlZBeoH4`7d?I*JwsUz|ZBA1(v-ytg}onq-kO##XS$*f=~Mp4;@v> zWRbXb{x+ZVo2f#;rCUYrjD>?&qp+I7Y72fGrdZg$(j3Kjd!ZZQ(h+>&8>wRIb;77rt4R)+Fd*SLa zLMc}&9%O?_E{&&%0FzLQD4IdgIYNnP2#X9-fv--Idy?f#ndcIs;jAf%blsRUy+J_> zrQp7^=s`q5gzcnGxPtoxwBHZm+@z72c+_?;xDO0<)G=VAJ}yDHQhw-a|26cUW6ClW zR~YKfzmM%I)#~cdjn>~z&xa?JS}SGN@FeO*9hbqC&Ca}|+%vK%j*+Ek=%SOCHs zfZy8K$R7#iJ=Z?)r8@LnE?Nk;F&)H2L(>w58qhTBW!Q74B&qHL=)21SS(}hOY{x~J z@>9GIFfmlyb zJPbCUpzuKRV8jJ*HDgdKn5*4!k2mQ0b6a63=m3+SETNC!?O{hZeEZbGvLEn}pI8Ma zpNVY{m+K5R>d6B<408(o=P+oBi#dsk8Gh0{D@f+E6!%R)_ttFG`~H+2$1RiG7;t=_ z%@aLMjH_Ht*c8rF*jmLwGP}L{Y8MYLd-xkHpU6i!{vh#ufxFY!I&nY9%<<`Ze{JB+ zXum&!^yzLPrcHH%2sJ&h7GAz^2kMDs;;ogK;RGok897Nc!Q1v#!V9!dw;r?-8Jg;m z0=7sRr&k&vjs=VkxhQfOBtP;np;BaV-*aa{FKQ?^E7o-`75@nPmc7|(JiMo%V~1%1 zeckBHO=B7RvsmZ7AhXR-4J3BF0Pyfi<$NB{os_%KhZ9K|nP{i(Obod!i>l*&aji_M z$k6;*Y4@_d5)@(|S`hSdp#Z-)H8RADx|NgakQ)myK~97c9>`AO(02TiMz+=PBSf*p`L z%(DMO*v48l?X1vZ93Ii-4i$kIcJpa3l~7i|(xMD1XApO~Zd&bwobWbomRt_+HHskl z5*iPX8no3$BjQf+j$e?-UC9SSw{B&9$L};SEDPlpsH4@NfLrH z^1qEe;N~u6wu&xKHgdz2 zxS7=Vw_bHJvi%+v=4aD@f~<#T3YWd!ndUOD`h_oSmB(RIa|Ve`@y$XBApBIFiu)%3 zJp!~P4Y}B%vV_Nc13N3IbnRxV$=aMGm?}S<-Fi*m(|rSW577jYD_9F(?x9VbW(r`3 zZ$Ko9MLWG>_;KKf^1_WPYt_$PaS1zh__njtILhSpmM%$V{K&J$OQLjWj-5Rpiot9# zw0J7VHQ~y{C|uopjm9z~kE^VPg?b!N;M~cJ#OlQ-?p`C6AV@`3d#V2D%H~;@?q$75 zGD{*OO<)Iwm|YhADqPYra+<}1Abjl}WVJi;sG8PM??dmpldOBplqSQk3$4Ggt)JeT zA>H^m)TmVcXXGoiU}OcMcpeQmAQ?h8mHZ%P=i=U3eT@UsvUBA_Z{M1P*Bl+tw-$#2 z$CB8+rkV4Et~Z^ce$=PHEZo*L(tn;df^m=<;f7iCrBhfGx&2_|^C}ghGRz0k87_#V z{Zvtz#zJq?k&k!BwptyAtZB(9pu%3+0sNHTnK0u_@ zcjHWUFK*wB(xgkuyP%{w@heLKav7 zO_OlHY(i=GKQ>8238au+nx|(|#u+>R!XFe%Q0KXn^SU}hOlH!~A+3waWu~p!>@r3_ zIR^Xp01ewIf;cM-fB`TlBRxT5YSiJD)|(d2$kl07L8DwfjpH>kDO5xwC zj(zVoG8ryHNYei3$ON{!d8(eMOZ<5Cm%Qrl^GOa2KMTc$HI9ztBBdVugISc)e%vz7 zVp5>KHIAiaFYx1i@01Dv5%a@nN@TJ5-AyvM1qxrk*xP~^O$eUPO4Vz4Wafuo(ALzV#U+7;`y_IV)Gsx@m+ z7uF_>SCU;b`!!bO6(dlelwxQSaNM(`a;J-l4~|AmvX8tHmlENaICu``l^NHit4DXX zzykSH=xPPAm+Zc#mRZ%eCKaf(-f&*2gYrML^yIK#)4(BQ^x zm`0e4MUBiy!G!`&F_0l%&|q(m-c$C&d^TJP4I@@3>zE9sIx){wN3*_ozxEoUr-i`+#{?woc4B-!Cec}G$|?Xv<=S_) z-(%XFWdbFIsZ}35!102;WttR9muy(@&ZrZ&WHx>>`3ZpXi6YAu-;cE@U~Mf1F{J8Y zKGSi&v$za*xV_`Lc3I(C1!&g8&!(NO8nG5-I_2@!FP+A)s>YQ4yqEKZ5u%>`#jm4; z90t&adFUeScJK$LOt%!h`aKGclGy}k+BHI*5jF8(iGt+J`1U;N0EqX_O(J4^m)BZ) zmO$or-%oim>)_N9{%9D!FSHsVg4c@2`UxY1h3qpOk{v40LSeg8 zqr}2OHZjYpqkFLyQ7p8V&xIMOqLTZ|(UDnLr5}9N#qpjjYovWEv?kA72E7 zRSu^A^j2H=xPa*yK{#0cb3kNaX#;Ls5~Po6s`{5M@E zo8I3imp>oAJp8#oT%h&Xn6Q*wgqQi}P@LL=nuw&JigRpmV%0}11yxDYKsL^_0j zB*y~G6q6z0fYaXWz0d%tsL{h?s(lt&>GUA*v-d9GP*EVkWG2C6rh=L%4%*_Uq;Y`MTl>u|iBC z01e>zVFmu?L*xViYB4a6VVXy=xXIhYM)h-HkwH4jI_w%g-nW zXzhv~0w%KZEc`j4z!H-aAq2O872yW8PBk1*Xp!G_s6GKQ(G@#87!iUXxQ=xH%B!)8 zn^Bu9pqJp_c}h8ofSsS}*OM4sP0U@OpgiDbMGDNU&znNx7?>1rVacc3Gm{&iJe_n`sW)RR@G(=!vFwsFFAVWh-C4bWE z-Jcms2m`>XzMB8{^HMMmG0;39a!Bq>AKd$^$@iZqtq=6ooR$v^zD^P7We2DQA|i;e zm0<6OV-nEuX@B~ScJu@E3Ro_4F=nx$w12RB`i6$GV!gNQ0e1$o% zI0YK|6lWBaM2rU{ z4Fw1@DMGzXqJj|Pyw}n&oeyTX~azkKHkmBUU;l*V_ zd4j_@wqqRMscVWXx3Zpn^*V#S()gu*tWFDbB5NgSg#~fqm-UxnQq^m{U6()E}LxU{KYToM`JdX(MY3d`` zq2TO`sFY$dv-Q}8bxt(()gR0?W3f?BF)B3}eyqn!8a{MesRH$^4~|@4dB@`0jv0>m||2`4Akp3^dU&yM3jF>`e9m3tiH{G2~7+Z&cp z@-pgs;2IB|y&Awdc zp456&(DElfKRZL+Wd(L#DBAV#Wc*M{>RSknRr1)Dw-^<4kF!T=bS3Z?DK zI3FtNCeh+vjJb)5qv_%7UdC(6J7&^3;WeEq@h;V3KTM}<*rPfJTBp^|Bs}De*ORhX zmxDiVrA(SRpLPShakam!LMu8}8)~A6jM8>?Xp)KRboKv;u?W)>^rM5FOq2id%H5*C zPKFQv=H)d(_dd%|gHfx^_WHm(cxx*zOb^w(6nx6Y~No`Em@@x{+{ zmZ*okIPa3NN&fR|HyfaylzrZct9E8cTL~e6$lo8CM(g6h)nb4*X3bYxGXo>dhh2tL za~|AV%EmbenJw6{PF{@>Jlb&9!2-h`ofeyG1~oa-6FM!0&A-gJA*)sGkMSGfpG>ud zNUue6mqBahykeW}#8}d+%IsGQPie7b+v4qdmk8c*|Npq#4L9zUlBQ%XPi( zG~_U5K?4M<(_a7?O?9kw3zMXHWFyb9YWbm`e*o+0W-uRGkcgdpq?lvznvGxfRH++g zyDCD4M7!;5JbUJLX|a>tbZ+Uyh0)% z4EYeh(|!pdL2ZSUmfC_@dF->?ms)Vws&{LiDQO5ZBw123Vs^Tp(wb0y>s zvpsV`nV=in1ait#rt|g2@B4CfcwYAz^Z?P*ya87H=MxqwrFNDx>3fQOFWecd;9m>B zsmrn^Gh@GQPb|FzuZcHmYZm zkhjzyW2Ek54)4sm*jwnvGsRE?Y!6ea>^VIChBN|Vl(j*=^6q(@MFvfS!Ihq0oAc9R z2oIWO16c2tPZ^c=5b*52{-}jCRwQBldgm%xbYaV$e9@}nhn(>lrHE|dIeQ^?`aC}Q znLA|-kd3Ab%^~#<%NR_u+qgJS#16CcH0yAkgmqq; zkF*Db)iTtjB^Vi2u{sS3prgM)ByAq4v2p@=b1Y=sa8J4{A#;HH+-M-PC&Q>C-|9rx zV>CaMRr-cQT1ZM}db^of`gSSSVl?S^u?g(T)JRB>Z@_-UWU`B|PEN|otL9Rlwl~P9 z-jU9Thr|V6mw%SHWWcglqx*g}HAdlYevScr#9o!TsugfwS4QO+dSu_(4eVYDt`EPg z>;3k)J*&HdZNAIEPv%#4gmt~}XKczj%S{E41=Lz1@MHRl`?A06dYoIGl9EkS!#ha) zANH+Fgyib#A7N8uWECq}-^TVK){F@UMo9e5c$Iz5k-liwbx=0A;jkV=^;#@%?nVIf z)X^hhc!S%=X%>=11_vrvmfx{X%LxrcYWqo=OXtg8L|?9^)g*>t^oob4`M4GF6_RfY zkJk)1c>A(^Wlh=gX=bldT_zkF9%B|54MnWZO%jC5kZU^cwB}r7dnnM~-{h7!5-zX; zmW9rC6|v4W2*Ob0h3>G-ym<@JhFpN{4RIvpMA%B#0k&|_xI%OYZMrk>?DtT~wUmp1f8kMtGR2-)S*?O66&;lhq`CZ%^9rl7GBTMmDMK}E$pluN+>j$z zKMlBOy<8rzTvvrc%B1%ve#AJQ*6m3#drs+kuD6C5cq~{%Z~*<3+i^)iQz}4B3-#Xp z4>djON52=WuDsfGvwM+M;0-nAJIh8`8HOg3?W_;O)7x~&dw1upSAM=Xg2F+0FQ4rfhmZ$t#!oAalVHMpJ&E0Tfi$lfa7umFZG0sWMi(!g) zF7lI}x(II=kD|982kV0EBr717K`lfF=jO83a#$mw(n|^A*fTzXv`vSwK}sCXhJNUa z9{Nl1y+P?!=oN9aojLs4JF7W;$K~6sb#;zd68sbK?QE@Bq9<8-W_=>-u_ie;j9pI` zT@x`J+D6XioVC)YOItwo%PbB^yso3Rz)t-F_OcIgTbZP}OFMnangdW?@U!l6!Q*Kk z=_XM$EckJ*KTRs!ok7N`@|!sxj()rOh+l9hamlEwwq#l0mF0LD6Y z|L8tJ1q7j~t#gw&_muejkCPdRZjvVYJiodOUIZ_cZ@1p269}OH;A%tiTx}mp>J4qa zyl0A?`>Yzz+qwn)tHb9vL#oaErK!%0@{VuKTf8J|U+;Zzy6*>j3BcHrwHZqvNLi)( zIf}G!JoWY_opA?`*%hF98-7U9gBbQGf~-HWp*mQv z)8oVUQIqGBxd-qiAm%Q% ztG36#D^Ob5E0!U+6kQmq+J@dA{;_v^NYK&@WLzdtwG^#eu;+5_|u!I8Y2pHKdx<<(?T z{*IMqTsvZu^WvzXDA7Sls^MKx3-Y&Y!@l)6Y5H;V=UymhI@rt>&zMd>wR5$2KA*|)Qd!qv# zoA1-x}5U6`a1SSxa zG~>Mat<~hod^^6jl68hE!e({uwprIi9s#C6IaYc|pb%ZY+(`3Y*i~lnCQD)Y{WQ6V zkrl9Xh?X$NW!MKgb{6A>;{~`lrB@@tT_`dZ+|)&~@w1&LszHjG`;nBNKs62eT~EX7 zP50UIi7dee50iS~^|Bi~rUSGWMoKA@EV;^o+4gqXLfAsmx^)YDU=<}jeOJL~?f|yf zwK$9KvyE*TX~Q?GKSPY?+BPVZCm{nw%)^^ff)st-oCuzeNl4awCnEhlmV2gfX)mMRG$iA!-rk56>eY$r2+dMISK3tksP1cwV+<;@}%V>mwEs?)pA z39?Q&?Jn``iVO=a98^ zspzL;X4ifMO>GY{>#c1Q+pc{lYA~o zUe9pOD54-K#t!!7*s$}P$fJ^OK18NKq!8@l2~tYzAJPw&uyvTu>{}z|$pF}`T%uJE zDrpZzn2<5dF4<|9nKo#_9k|8_H8^9AinG6bwV;SUD4n3Y`?=_eJZ*_bd?e4sMU7T`F0{Nb}#-Y8qmyA*k`UAM3)CF}Xe&z&ymbXh-!h>?&@ zA3NUe3-0?JG%G7z&-g1~TMXcz&}b(y8>w(K{*s4=uT&mfiMQ2EP&o8L?JULA(#|l| zDwz}s-bTS|C2yJr`ITxT^(c2w?ksguk;#W zX5S{yC;rKol9S>OyZFso{@SSam9E`fxN`128wS68;C08BE(yRGYY%^mXs>FoxxT6} z9Zjxr?mBF$E%R~+$h7#V2O)=YGklS zOON9zBRwDh5D&PGrlt- zYh|E8OO<${zM;+y89f=IbE*O|4mwFGDqFcwP+LD3lT^&3No~hNzb#=&DB>}4(5xti zYqkuf-YD^h&YP*GZZY6gS%^cqu;M6Sd!QF@oSvp@tOHQ?)|txSx2ct4>h6}alKMGL zPpnf_KdXuP*`R)y(J~%0vUC?=gF?%v{!4Sosfyq4ndqbUnsQ=Rl0{DnDAbEeH(t#yW!FogD8tU3cvxwL4JEup4SUG(e1Ph0#7c|wBgr$Gc!b)h zx9{dx02-SMu@5}uK=!iZyRbIVTJ_*(@Y)~>AY}(2d;{_R+euh>$L(?$`e*Tyq_yg1 zCz9dYG3-H`u>x0mg}u#eN6pmccub?5u-MP2-4eh@{cPR^efMOPOa-I&>C+zd(T}6g zlQ2rTF|%~1laj~xM`(6P(dyjJ#zAMuPgJ-;#j&Hv;m|leuhw4;(>>AJ=F!{}Lxt>=girt9T`!f@ngO4e`hMPsYX*WI{va$%0JK4ikNy_Fe=dq1e zfgh0YVh%Zq5my==8LHg`3Kmi{eRo1&m6Mfm3SjIMx5IRj8cECy%s!!4FF3gRESpv8 zYeKC`uw@G*G1P2Q1oMDis6F~wwmI-l6J4oA6FYI2K~eF;h9HkbmGZ(e$F?oI|J~4 z(}jqWE@YjNsI~{W&AbYQo`PZGOH}@-GG-EFF5rAoWT+hqHz7HtyIMh*cG51$WL5A_ zS16Qa)T?eZ5@Vc#q4>cC3u30LdeglKB!o5VYWG(o*e~MKk@dJvzo*-ijo8eCRy}|Q zPYuK3W>j6z)Wj6qh2)cPj0tLB7F?a_L-6~z<|5*EWTzd4^OBFs(A19g zgZgr`Jv$O*PPPg2pG@al7FEl(FYldAV^iSHIQdjpa zD`oZ(m4Vsa*6-bJvr6+a=KyHZhZc&?Ut2I3${L-;i#EnL=`2S}J5QyZqrOC3ebTCS zqOuxmh2ikfcG}`+UG?Q)A#~YikaOW$GiXSaYGE`aUKu;S)5{9XU5f6^*Zjj`jS7#j`=bn{AgnZblS|`MV|WC;{y5si(!ok+sSt zA8(?i;i10dxnA$r_s1iu9->Pq2h(Pq8>0kOzotiwlS)F8ox2~idFMcV>8lX%F|j}R zT(HC-Z@}FP8XGDwg&v_p${7q@*#2PS&TT%J z{j79$Z~XiW#jGs((iMV+Ky=!_7z&)c>=i2^v}K!K;ks7vuD;My8c^rzyn-(}%C-o# zCchB6c@R0)B|qrNuhLEGc*H39kO0WE@kG7qwP`jIWPV9JDOB)UnRK2AHO=4`AYnX1 zrk@yNm4b8sFIxM*$r{^#lQpPN;08hvj{iDETIPy@P5vGJ%Zh1{839hk1>yYP0Pf`g zxCa)5^S=RH%j6C45fljLe+HnmjJyJ~n}KltX8=mtzr(K2SS=j!`z6ZU1{+nG9*y*>1?ISKjb>?{wK` z>*!Aj__{1wbj7GQSUqMWB`Z#DPm2vL^d%>xCd3B7=Ft|DPK@@B!5HKjhZ2#YxiPc3 z)HSxCFu5=tfs|%u042-e0Y%FKkwZX;V=DXCb_JCr6}5%H`UCp^-0RExXT;=36jc?W z2u^JeZ%@syg7h97ACvDMUrL`Gj!V2KB-EEt^$zu;8kkuc!yu+=%qAzJKq`h$lz|M& zUCCy{*#f~-i?gQ=17XP+tMHhsNc*REq4XZ_!1~v9Wk($S7&sMwU;y!Os8FN<{L{JC zHb6|o)WC)gj{vGbfBPS)`+-DwQ2e6@1&-Y4r*(f!GO>Bqz7^bAfzp1o*+YMtqQ9-b zIL;66?4#gA6OasyEH6R+J_B;Pn-_LackQ-H57Ex4j)pH^Dvv-h-!dBPP zaQ7*o^SvFgPBUMpBP%-}VgywC0jac!xTq`Xwx8FwXaNdRms&YX+j^F#<t|S z)Z@0F+5YmoCtvGi=0f{t0zItGh3=*Vr&s+!mu-6R(&L2wC#axo zF@{Vqw)o9PzV+*>gwFb@DcLKwI`Yy27aaqfF7G1|W7O*RWk5EbIQGZjZ2i1Te#Y1D zs^F&)8slT#HcbX&tsv@($&jZ?v+QAkf@{nBk$vpfC!=fF(4=4Hf^D=)bclEj5We+{ zJnYx{kp-f;YkR-19gn<=cFE?VHvni&GmYdd^uHJ6{z8qC!sv5rVu}4*h2_RW$(?$G zp<~|5A#$II{T9)Yz#H8Fj3b8WD41|}z4sfR@Yy!}0y6m;*;K?_}&ghYSzcV_a97(F@K1ttb*VLE?pP^okLX`JX8i^50&1oiOoimx0eA=>T|f2&kV2?jK?9Mc1p+4 z_?@potmeQmWp7Bre~X(bk}LUQ1g|Y*k@*b-a_`nXf-5-~a`M7yKmp~V8oGQil_XM1 zEe3>RBPcAK!8LK@aoR!qr}ePIqm*~mo|IX)*<515Fzxahdou1X>6{H}QK!@f!wA^e z>(elfTBuaq(REk-243`7J_(P!%g4n9;9IWzA} z9(I3;M;8WKn?`NED*({?N|bgxoeotgF+{*u`lBTLC*>?Tri6%{AG6t$rl`F>@OszH zPxWu=`gWqF8m-!a1x_iHN1z?@S_vk+DEC6P_@(Q*;q3?Aj$e1shAzuNDH1(+kh z8hKQ<^J~-UB_hxW(YRCdpuRhcYiL=c?C-1=T^OsPOCluQ6LEu7!obFL8keS*z|`fi zr0gR-I`~RQ4FH(-c$uy?Qoo||gS>thGx+sP=(8%^ivVy5?{-1!M*ADbPOvN~l0E|$ zY(DB3aR$&5un$b(Vuf(PPiR&9y3fO9jxOPPzG5=sPGEP?t3!e+O}g>drC-P1JnpRx zrX#5wHk!?M7FvFD{BC3u>E6D@u@MjQ(t_+6PX4>{rvsqL?n0EOH^NEi&Oh6xuTz;Hn>fMt^hX5| zdzIjgAV~WX)I+p=aOFBntu=RnCnQ|b|-!>ZBxypE3O)v7wALo3WQ^Kk1QD|}jeO5Km8Xn7g zQ?aInf>&@M5A#hAquS0BMiW#-kj)jhmr6sZhfSB8C&=?R0YyGblXVNkzv14?f>TbL zEQkRAfY*Fj?l=SX&K|;Dga8Os%K+@Uot5I-qh*h&-DQ$q_irI3dx#}yG#2_DTOnxKI6KA5z6yv z16PShZ(~5_y>)mS^uDg(|5z?NL`*&uCZ6OY%yo_x52_yYab#Xzn$A-mV>mF@+H&gp z-JjP=5VqoT5wzQIF5Wl^8vX^%>q`Uv_8z|(_&o__LpHxAHej+v%Y?bq>$>P9OppMA zpB+W%A6YP{jvMij+iS2!_6jtdqfOkYRU2+|GnfQq+UhB#&{I5p``s-;n_q@Tb;ia$ z+fHcALV2(eTRtUoPkDrjXM=E5u8ZSV5(m17D^ZdDHu%Ur8-ZQjMPOpGFLvNAl$a(@ zq^$_)4)d>^8X8Gx4q+bN@ty~NX<-1Q3~WCgph8`y5xxGgV~mxz2!G!)pALOIie#S< zgs7#|inRoPu}IN*YQP9@=aCGeAKJpr&a+w}>O_G!6XBcZaHx*7svp!qss|4=T+`AF zB{aN13p$5B+8uDARi*_~FeX^%L&s>Oi$!;a6;D<9<5MdxOHkoTuH@=claK-`ceot5 z9oqf}H$ce0(%(uUS^?Xcmc(tNTacI2^f#jK=V5=|YlJUgWdjoAapM*7eFmoFC~z8t z0$jg9E-aZ3?E|2}Lz<@HPXzvc>tsPwPjrm)-dv$X<#f=b5gRnw8Xfp|uR?-_quHp< zV*>pg5KM9H{*}GuNKSb_-{n)z=pp z8jA+kICYo61vy8_C-eVCm zj-j*dur?^G+~+F1%MT9$*T}ih73jP79;Lhx%M||PNgY%pw6f9~+0nfUOpLyrllOPW zPR3E@T?dS;ABt2bFi=OtfBT3|Bg*I(uK4`u1!_VdJ2*$)=yr03eMMoA(NY0IUB5k3 zVJHDfhI9Cb>Bb){iibl~;jwREu#&mRvN7* zxpo{()VYX5614kSf1|$4D)5G6c0+&BjK#3B&ong>bJR9tt1c~#^hvYBej@Jw?Cb64 zx8KByc_G0(G_02#Y+Ze+*)GGQwSuid9`BH04D>G3d5Mm$?ZC}*7KWFIO$rl*IMC=@ z-yU@H?}-O!q(%$#OtJikXq;RgF*2q-@biJ$W z0p+OA)k|hK9iYMsF^dyS2#TWAM}>yJmxtg%S*yHS7c~APx#}7E9y~3fh7@@xbRVc- zFE@4cf3yhVYjEv!iV6=hTrow?wZl1!b8AnRO^$QoAW*lfB`HU;OT%#ku{wgv{&dXepW!sY!n}&Z}c2UL>OcdJyF`aZ27+ zny+Xeg|aE>HPp^!G19Q6B*h_{M&ZT|Sbv8CdR3{TBRhclZn{gkKEM1m-D>K9afT|h zf2E$G_$>uNuX@j(xM1!^tj;SRO7w!DX`a=2E8aT>6^rd#U6ir<{BQ5R-`R%wdba`c z_2W1U)KpdWYuQ}_9~|TDRtoeq5AEJ8WKeeGaGGYKa6dJ66U?+Iy*Xoi^}dLCRj4^M zPYuYe3%VteGt{PFoJ|g`hhL-4#q#P#yMDyAH?*Nhoh8MjBuS{ zuZ}Q4#AIy5*`FsFH=%3?yHYR~e`LU1WAf*wkaPaf0XA(ZGAcCvy!zzlU2O!@SqF%H zbSe1IT*|U35?orQH5O;#DE;PKh|AHsf>_MR^U?8Bhrv_4G!Z6bO52Nzd#t)toxk3z zjHFN;e+kIF|^09StT@F5A59R$PZgc zzx!dl_Xc7|l|~v>BOD2?K`_lkmi#8Y{2O03znRaL0QU0gh*D1SZ%6hSpzz6EmtMld z`4*%&(2?+_tc`|BflY{Sx=r-lkR@KQrvM56EQ0DVqLw=_c!RsTI$14POW573*R@q z9nYv`9B(!nX6~z|e+SC)h++I%@x*?5&Uq7P! z2Yqz7>}Mdej(w#|o?-b7nAhTJky5C{s{x&U!~?zQ%A#Ckh?{n&1~CJ)Cn+@j6uR&y z)1iYpAgu@m)*l!@-=w?pwWIq*gAS9{GE~hI0ev3+oyA}re?rTb{_LGwRzF>}tRlR2 zxcr-DnM4~0YXm}R^}v%Ac&jcBMq$d99?^AwND5iXcA3}1nezo-3Y?S87OXdSjG`&2 z5a_!kyQ*F-+Etni0Z0uM<5pM{+%0zdb-_GuHGTJjU$_^+9*$ppU?aB_c_tZe{N-8q-V(gL<>8fYm^Zi} z7v3Kedn6k>TaG&AYsqx3tww`Y?Ydy=G_VMIAG+=f8cqz|p6AbwC|7g3F_!f*?H*G%`69Aha0Lp_+MgLFj&I#VJqXI5cv{oDVqADj2(hfnDiB)bWtg7%WWObBZ=P<(BKW z2K~@QAAnP=G`(RN`GaM4$Xd`N<6sV@;D zlg{2KwKLjPeMuas1-mc)@rxWX!IoA>-*@hXf1X5mC>keAPawP_kLMvO1fNk}+>|M6 z?ehJjGa~*&a>?m3U>ac*4NSoDO(G`eHQbgxWf}+~bF@L_QZxr`yznt4$C=07g(aG6 z%r1vB{v$3Nts5ZN#{Gf>iwnyAPJVcLkoAMG@>a+RDxq7H1ZFVV>N~rs6`{L*7L$uP ze<>4WGt`fHS?Sg;3@hcS=4BU(cRv_eDBud|3#x>L?F8l6?l~MTgZaVPc*jBK z-ETv+rHFAydgFRa%=?0IN-fDBv{S&In}r>3NV_VapZs`{a6mKpR$+6MP+ATRA#)Jz z!A1@!QlejQLuoAiz1+3IfvjPxG4@fLe@b}bf$a2x)e5un?y;D{NcRvlSS#*CvXg$p zJdwNEif9Zum$Wr(MY!F)b8{VGkMC6MMDKWRvU{NG9{rrN;p^Y$%#MaS;F+VCyTl2@ zAg~=Hi#Pn_Cpe&6JvxDVNz^+4+095T6}xn(s33_yNxMMhVBaJX=9f+4Ej z|HCReDFk6p6RCa|47m$oi`?a->k?(XSr3T=4q{qBp14`HK~|2IY80kb6%<}AO@Dvj zX>8&Zu^@mQFau!bU)(X)=;_7>f0|{4RM87t-YEbAyBzxwBY*ivZEe0_bS}66G}R`1 zqfLcPVqbXMFUDC|#*Ww38kkNBOG@@ef^uota7STtQb{ph1@N8;W|@`bzPbVJ`w299 ze_mtBzfZKs+=@+b`b)s`oMy4^ii;>Z)o+%u0?}3D44Y#M7B6Ik6mRTWf02nT>uz$p zIXvjh6r9xhygGGj6P_7jBmlLJ+?cp44UHvnJMus(>qzS5GD)G<4urQAdS-5Yt6E=y zv(;-YTx}p#uzG&gPDhILzB5~sLF>F+kzl)}}JP3c8; zpF7T+nRfs3r=)CzOLGhqfA{ie+J|o@&5~_SI16t3ob`5A_@3&vq_M=x^9CkBQW_A? zetNA%Ht*<~VLblF6U8r3y-NE+Ew-Bi`Rc?^KNVY#i)g=2ZYK{(Rev44yM$v8%|34! z4qC9g-h)EI@k9dek6-;~b=vR`VHjrhM!X`po^)n3G-C_!-t<@Me`tQ3Hv0w_n5sx6 zj{7citm>U<3jOXsnixLTCXMdn-t!u^4E)Qm$4Vt`UZ*m=SUdJx)XT_w%AUkH?+;2` z;pECw>q2)*x0eV@l*7ENb3rp`aGYytI~6ijS@wHxH-4eA%I*4RS)aOL@paP|pYO>A z9xrdCT`^U2Ir(ise>V}tFi1ve?ZKO-#Vk*CNEl1C1w2jly$s3DnQ?6euv#2xQtO|N zk}%sE5z=ZhP+o!Mr&W96+wK^b!^l@6QdT5bIzHlbRXUx=6k1x~85(K5>tWs|&N1X{ zfy?@yX1{gv(n_UVdSROoTJ-zSb**pNL#4oGzLwSp_3yT^f6svbpTXfQdco2>4N8F= z69m}|4&cypwH0G*K3=YHmMhzzc3u?%2iArxngt6p0z&;AnuW$i@W2d-c1LyS@e7rZ z(oRwhx7!<)$q8)*lVe7u=utj1M;_%iJa8jTgQV^2B3=|SYiyU~_XDxe(E$J7*fQD; zynrro!Lmfwf5a_i!CYM|a-Wh-;lW z!d)+CU0f-Hh4~Cjp7mgxY=FP-iO2NRYciN$(MW2y(-Lsd&xq3E#8drjI1$iOUCO|p zro%vXI72qf!SGOjB4GVa((S8v*Dof5Uq?lHO=o8mB|P2oAu$A!DP% z%YDz3AB|ChF;8>Z?Wt;VLK`YCbS*U)#~CCYYFVt=4`EOM_>qoOtULAa;^bB~V@?BY zA}x@sIE~YsZQ}vEMTv%Sw->qy29a19d}1VBt6phVC;IVTCewBFau6W&^4z=(-v8sL z9-n)ESncSIRt^nJCAT}f)nlw^-ADMcL$P%=QvBAMUEZ&b;J|4rw;GOa8c=P>1d8Q zyD%pfuHpbFu7#lJ7)Vi(Jo^WWSS>`KpDsFWe<4mNGaMV!UY(VvuEYG6iYQJ*}(_|;Jd}S6Vxd8%*IjLrfKaLtS1n5MN zZcj@zA3^Pz5VDRn&R0JMq)ivIBJ4e(TM!p9b>uwn3wieA9hX&Ic3Pmf9KpbOM#G{O zf0?_uK|~GVaCqlg*4J^xz%{K$jxT_ajinL6x99MQ4W5Ba!3|3h1OBOK*S!_!S&xME z6`4vO!Do5jEPNbZMY=#eiOKctyEe-&$f(=NpNFaxE&T|OV@hF?ccs9)&^fq=C_c5XvI2qXkGe|~{) zo=UWUsu0nT*a4BPWmArmEK<0IN{9CP;&pKSS6J|5YE`4E+6(ataR^HbkG)9tssdRG z`T8#X!&V$BRr2^7GOm?EZCR7!=ioB89-msMzk?}L4>CjKU|+zB5kBcO-Cjw1ZJ1_Je~zOo4JnQC?U71n={nz3so*qoveh+K@yP7Roa59G z@NXqCOV`j4tDGX2C6GM0M%vVo@W=u-s~Zdr`Y-5876(><6l+r;lq$)?FMvn zowoawQp%;FV_&^^3*A1YhVPy|fyejO$M<7)Fqfqu0tsp1IN$DYyWc#?~Q1? z;Alvo_9`E;2RG(M*x>?ue=C^#+h-xc!%Ljv8UtR!Sk4G~;<}^=ssRgeo2$7feuPGq zMz@#@T6bT`ry`64Wk@~{sITM?32y-_w5M}Y3tjQrLGCTS2FU!oe)~aS_Q_)PTuld` z$4Tv%?<2!*7`~T&%e1V5QHWJLSFygdZHXaoKgUhu(t+{#i(hzAe{JQs!p+e;?)^iR zraw+~HooSB`~Mlobc(_&9ClozYuZ$G(X>zSX-19L!cI;5cOX7uTA<{#Wz|i@9}Zb* z`v=JHHC$0*Dvi|h%XT(-))%U5a(Bi>53$tCq_KUZMOYx4Fcc+^oRw9$CZFg>Tk-e|r19DVoQEuJ{hdI~vEa z3jzho^Yctf>XNkj-239-l8G22_*nOeLiph0d(J-|KuxI$+XC9mIUk({5qT>C^My|W z{^C@XHWtsjrzD`p%?>e+y^s+gNOHX|h&BojYT^A420TwMtIqP0@BX`e-!LbHB_; zCF4VBTaxzS2fYr!@`~pie}2Q|h0N~5OhUQsXl1;xe=f%U@0%hRx=#I{cN(g5IH!3R zWcpr=VN^-~@7sDFfC1{uM1$@UnlXKmmEvNC8NDj^^^CT4p{)i*X=+~>`L&dsvs8lD zZsC2*`uv}1ic%6mg0_=nPJ~I#-UTEHe-#9;5KsYRxdvUy@^l+-S0dILuN65sZCQip z(y9yIe}GRF{sdKxx|(biB#xG8mzp3oQ?L-y?KyksUNZ=u6Yz18X&4HRJ_^D<5(k}J zYWm%JM`b3hOUbmG#p$@igrL4)FAPmi`hHjzK0Fq&&~JE(f|ba{buj}%*Usx?wNuhh zg9*LwM?@@qYDkTXyG0vN%RswVZ^Wd-_$#O{e{qvF8md(c0p0mOW`EWG2n(CRXF z9zQ?)YD7iyG#2?@W*HcecYH4X=tam-IkrbP*_yY z-S)dW5B&$v)VWME{=+hVkrIcsA9X0Le@#nc)*W{p@a%epoM0#z&EL?mwk_JaaYDRa zmk*d6q>HG6_N0UMC#Ct@&}_Gte=D}58e|j94Y`GHDod40`+j1wi{_WJFR<>fk6bj5u_X#eDxOGprsnLzZMS&8ke#LzjoIMCkWlILKnPA zlhiF^cM*L~!6@Zu%X(6?EQrR=f2G)f^IqHxT85R?=Uk=rqqTc&m%WVSABe>?{iFdO zoRUYfNo=`CCMBPZo$N=2IDH1M|37=Rx6asVr1h^Y&6ug2=2qc_uOwNe|W6eVD%b*W+* zoJ7`LkvK+LB@`Ubl5=J^p|PxoQ+s6u>z$;pkNd_OQ=P_3v7y#T4TEY%HbA=|>2A5| z)pXrzkT*!K0FwgSVZri+D7#HWG!_A0pyu!O_>}JH z-pkSUUhtUZ$uVwuqiTT9H!Kd#N#D3*Rf35z>+BNKyhq8dm7EHO^QP*)>Q|y4AJT2D zF?4X1xg~_yE);f4)}`=vwZ)0c3z& z;?{5&&eARZh<~P(p-tt&$T1Bp%%e|NIO27YYEO`}A;NsYSd3QDF$;*tpX3w@nFWL4 z=sQ#G#5^^Tz;2=`cNOTSeoFx>Fv%_J=ETq0m^JOn-4EQZ#{?Ta==+mp3D+DCc13QJ z1?(s*gz(FF=5gZ^e;7m`Q9*~+%}L%#YhR?l?BOU+5~s|Z;{()$mFIHc8Q_nGE}kf_ z6-2TK1&ZHL+|^s{@vbV2T^3Od*wRH)aAifCoj8~|O=QEcc z_xuNZ&$$~aXipMg23qy|&l1;$zw}k|ujL$bIgbbT0cPBV@Y|riI{XLSIZOEoc;@6N z39lJ=az{1D0dOi9F3-;~|i~J<4AKbhNpb!#U-fAY9`6PttEEo}j zWeyOUe_-689?tpHK6enqZt6dN*^%IJ{(mlZ`K#3Gs%(l6r+cI`h4&G*bI}ND2$dWh zH2KJ+t6I_RF1{;GnnoJc$F{((AOjAZD}%Z4dEu;5T|*vlX{#(C&c ze+id2g7AQwenph&ovT*BZ;1a5PPvcQR1u@OGl4ecXen*R*}&6F7zzCXgTkEqDMTut z;z2!OtX7z)g>2k@X*J%?OiuUB#o@R6zv5Obp- zC!PSIHT;==s`G!KDu7;#hsnTV$9+(J#uS88QMW5s&9gQ{CG#Ide}_bPL{EpeGdKv4HyJ)SV)>C@+Hd&xC@CK0?)o;U9K zZG6_s!abD6$i7$^o$7)I!QPoe?z&tmS_dk?nA=A7^Gsima&ZChF4jOJV^c7YLy!1MzeGM^j@=1RO)mp09FnBM8Erk|kpoYF% z$+Ar&EYCa84I#s<67p(HrnoI^0$2rX=hyHj$(1pjd@+bMiFBbfE)EdLaBr<&dh96$ z4@t(g{)Q1!dicX9B#H4tfsJH13@B8$^EuI3Lw;fzQbgyN{j%%tZFoLMe+mNGj6mh$ z=>x>?a4=ph-UR1QnLzxEd3h{2??I4yAXZ-a)0@5JpQEM+-#bVK*=7qc(9L5jhf<+G z+q}WvYR8j;udDo_u}Sv3`)Wk zu23yObcT%ll)ySmsPN{se-)zv6Qnb5SYJhbtNHPq`CisRn0|n)Q`;t=kU+Bn2#gf+y)DCAVm4v3D?z z_yce}&CP{=Z4bcvf=R?)jF2Th1%1`z;S6CkTPOjEp zG#O`Xq?+ga`EBbJr{W@Jk>U|i+zl3>gvj^cYmGMfWU`UlaCe0;j`%poOy5alTi7Re0-FzYDq&SBYkr`b7oO$xJu&~m z1HIn`)#3t7NJ|}AO%jOo5ZPV3ZqMGNT#k!G#|SAdhH7&j zPz5O3e`IwwYd0a83^{(l|l|}SO&Bvw~(JrqYia`j8gu$5Oy_2cxyLo$(k=Ju)m<7@X z2%rpCG1;hhqp$^I={t;+Y8y5s*Xmy15m8F@f4eCKG7xL4h+it|JHMKfuoz~g^)*Ln z{h|q4IK?Q1D0bQ8=`2@@Z{;w4jaszfWaIHbq2zv;HguSRxcy##@QmiI-uRKgrR4J+ z@IqsWS9Z2YrXQU!N~-lwPceNuuRw(7;Z@XZ;EDQU3v9^8nGyF~`l0l!(E@68E&vMU ze>q_M#KAo5?5SqCdUVBBj3nbp(cYF~w>ki0b~APk(f)RDw{P|0xv7^aSZPDh{9z82 zkIyrf^8y}rxuI**-{XBJxe9+Je-nYhEm+W#nvP4E{at|sKE@#P$#W2+bFly7 zlzva^K*nBVHKNXpU~_8Yoc@Yi3YJH)++2sUYMI~4~BgN0I=c63kAg2_SGpxPaqcc;cOjIrk!{&CEft*i~e{Iqc zo4a#;bvlicReB~8OEKcK{W|rG^-+j#gz>6z!V=Ype+=3w9k_n|0mo*q?c2`w71n@3 z!E`}$m`x163`q!i(>Y-Id!F=@+e>-se~&kHmBUQX8XYt#aVLMXSn-sV`+(p!##0W7 zF`d&jhxiS!Vx`zW1Y=-RafLVpf8e_ok=wPxLs9R9`|0|=APq7nUXDP%0IybO0XDhA z-OVIA7>3_r4!c!?8AAXe#;4rX#@I6um6h*gMSX5X+nh)YsekG_t#?W@*+OdDF1o>G zCcs;ekw1CRic{X&dL+xIABo3A3oK6SQOcm9_GDE#kjq3RoKS-lcy(pce;1P&V`l}R z?w=qb!!M;B+A-PS*67Rr7%2ja8t+O?=6Jc1!5(ae?gqH{xx76H)rHhZGIzVsZt)9yxfFii*oXfU~ z`@7Pvy#9q|%3$vn-+n(U{P#|ja4BOT`m0`?c9O@{W%!wYegTh-e{6~>AIzQtq_yQN zy@b+;^VR6G7RxVA+W$L6Tr?RRBQG<#qEPaXRPcB$NP5wM6q`|UaTzwPUydy|P%6V)k}c=PvGJwrXL1sVUSqOk zt?@2~g&{aFf7@S>1!gywvBGvvMGi#DNPWML_EjU@M2x)!ul_daVQUN=Vh$#duyKJB zQHW%V_vO5>3_{ybOr+$M7vQJ;j!si94(;Xt)oXMgD!)e{82pNcoQ`ERRT4YY9_t4y zKXHjd+)5J|N1We!Sj28a=kz%dHEeYo4umeju3Dq5f4uUU{{oLyGMr<)1^UI~zTdoR zKX|v)#01or#Har5X-&(RyYb#&EUInfnTF+J2YmPO$9Li*|Mg8cNzQQeS9$2jL6`yA zOe+pp+D=tKvY{FIS+fq=6FsnfDlV@UdS}L!rp>7TL){m5YoBKQH5J}pzVUEHf5^w+ z{58#!f4%e~)3;}A^9`26HZ@g(m#A1g&1zX0@en&{b5^>{!Iu4tBE#skF4QcY{aOx? zmK>xDy1$&@in~vaUD)@Ub?tsZOQNt4c?lBd^waoId%%N{R>C|MGrv~RAz6sUO9bb) z=$#rkWDyuJa-OdYV$F-nOJ(mN5}mnS6XK91e?utp>_V`hA@>Mjz2q^b6#bU?!7sH3 z4mK!dUDL2a5~8j$EGQm*^}$5J5+(Z!$ke6t)F$UVXnn)N<$ORlMLh7S{|Xg1h<)lKjwghoCeQ1*a*RRuULbn}oAE@vMhL~_{X7=|%vqr! zy5o80KTbJ<`83TP24gajWfXGidzXIlbM#Wbl;EBulq?VaCKFcbvGMKLbJ96d-q|p! zriW=>I)@7?>HnVQI>$(|Tnl_d zB4+0Gk!-lN2LeqTNhWe-gHohe+96l172EjVeS6F37hbRk4b`FKl^$zhS2pB_Gp4H? zPzV3|1YboSuY#hPC;C#7e|jK+<|8$`z_~*uru>bjJylZX4`wj94kK^|BDD0~ z>z8b&hlWwcpe}W}kT}Q7ig>zaw896tl@fN_jJ&EH!o0-+7PgI9v>q*Lpz4qtsX(FZ zJ|NCZNB}Pq`w|J9o}RF;p0C;XG;mE{Ece|Bvga!5KVT0G0o)q-uI;0le~09M$|z#M z@j^u!`r{3WUrI6%J#nBLLiYQPg3N2kocl?Yji3`fTvLzyZCd555*YN>gTS^1Z+r=$ z*tf@|k8F9e2fjP)gplwZXd%#v{)Ybr9j|rTP1(>QnI@sUMzKLz3+9D@P5!zGHFSBt zkYExfyf4(}!{5)l< zTQf@k(t~T`(i8|$nvG!EJ@KP1c@W|$`GqjjhYRkveCM@xf1@+_7b#k$?vKMKX~*5H zf&5-VHDmgE2VwJ*Rs%MiI5<>(vFl*}{7Yn9Ong>n@#&})@=Yf6WzMK61-8t6 zS^byE6KEHxf1=u-ha3J9mxL_Mg%glZrwmQ-8XG%sH~P1htY!Ys{?J;t&OFsoIV6xy zZl(Q1v)LDfB3C*BupGz z_cOhD>bf7$c4=UDzM-WDe(y?iW5F~g!OKlGbE`QC)S*dB?!Z{=An~W)@Ge_|J&quz z-i#lC&x{oFj5y)J8gyzOvq7Db^wn_65hmh2`esa8f0>3XyfYo-f8HPey8R6pK2wM( zdB;jxe{_DWm_`YVMW2$Oi}a%rbFtayaod!V2Sti98^*?v_ZCOd`QyD*q+Ln6q?Z>u zl<`?;iEUl<(M>cUYJ{hXi|Oy9;T=a^*TFasO?75>X4h842b+MatZ+S-Lh_`FtQbYi zi}?Ls3ip;<$55LE^}HX+R4Sx`avq@+(Xajv))hTZGK0l}lUj#j18E^5)>txYCk-)o zfBn3!F7FAl^E9?uJ;N+$S~drv9SN(OK2Q&@j@N2F6&(`Muhh3|rF(Xx>qiAg1n-vS zUnMy8JAbPNC2h}~R=}XP&HOjj0F+M~M$atQ+fx)$Ygm^G1B%{5nmq#)j{SeRooe8w zmFpDv^=tGDy6KZSsj*6&%E-0mb5s4OUR5 zwp2C{Eq1l6gcbH?BTP}dBh9&dewTe@E4#!)-wmKT6VoJ(pL>{Y1$@a-dE5_2GG|p5 za$J`Rn(%olKo5GUuf(^)`2d1%}vMIe;)dR zS{CqQoQhfm>K$KeW;{vZdm*?{TP-Er_+{@w#8I86cUDAmW$knxg*t<1(62NKtoX-N z9xSAo_Ew@vp}vd`ZHQ?&8=r%gi|UD3q(&BMVUWJrPrz(@&KS57Z?uV`0PvC z5l6@ve|Z~1_Qn7}(xunZf4K^U0YrVRt_J4oIK++|EV3?Fpj-3@q3zn#j&nfzFQH5e zE;@<;J#dYmfW0VW4QPf0D(7cP0I$$YhOX zd_6yLA)(h?{hksvP7u%na4iQ&S#Rf~SqfH{`=f;Bvq_a3#RHMQnE>I6d{x`SxR79O zIemc;^R5YuHY|GopgQ^OBb;6ykRqw#xhys+bYu48q(|&GY(DKcDzBVzv30e}=xQoI z&Wr&W{npyNC>sz1f4An2xx|SLdI2yC_?kRQ%{kUVQzg7r;syzHXqrxPpt(1?M;pq?+bBk+KQn#?jAFjs9hIe`ITb;yKh!%C|4eY-=$P zy-oX!eXq;_tHdO+cE>n}*~PSGTn)9S5-M#_o0M4y#wjt} zL9ROY)(YYynlc-k$xjF3@{q5Tudg z^kvDhC+|AkmMU9|G~kw(1p07F1l5jbaV1taV9lc4Uz{lgrIyckE7P;?l?DNYQ6{ip z>`0$mS@F3A;5&k&bUNV`&I5ki78M3&W|aq|=QVMuq%WeQ@F7X?kuL_l!OEvv)xUP2 zAm!I$e?#p3dOh7eYGS@+H@a2IgPuGmv;CCy4l0`=PxulGuuVy*LzSkc)&ehOnCBLy z#zv^hwQu9pzhU0N?{M8OE^}U7>rIk*OL;v2yORL<`VKi@?~&7QS);gB6*xu`fa{oT z?a3Yg+J7?}T$IQzj1IG7N~j^M9o~etoG3f)e^DJUZeOr_0^Rq*C!kXdmUf^p3E9_< zHO=gmkTZRtq>OFrqGX|YMZ!V2U#Q<3ACQv&$HY;vOgTPBKLn>Tl&=5W4qMdZ3aA7V zG)hZ)FMOvvQ!E<_vpVdMXE`G-%NQ-kZe?-tFcBz~%9J5o-Wk;M8pdGL-xWB7l38O! ze_%F46+@>mc=W=$rv>o3X$tUAhKOTr#-J#Aj>{H@IX5Z)$cKWWk$i_Hplp(sl>yQh z5t1_J{EYpJE4fY5$>x8Oh^yhY#U;N+Tz&I&aHty8(kMKiWgHy;6jcV}_TcDZ2p%4a zyZKZ_Vqr3UcXGoj+Tl%-=3K`~rh}Q#f33nh-A?Y#J&C%XwqrItnDq*-e>s}f zJQOj4#X09!*{{_@LT=yCObZ(btjs-bH5M+E6tFvdT-xxCyn$t_wM`T0_i0<7$+dPX z1cwtTb|oG?&0GRN7r*B-I>HSay&Acl;DdcKKCZwtdMMZD5R_MWDr0x1#Or~=>jU#Y z?u_Kf+^XrVIGOJ+9e>R#2H+B=fAwA5nKa%F1J|4u`k+<$gfwqRjsUy@6V123d%3KAI>%{A?p5Q%f%4Eye4ezLF5WjYG`3kSf3fUZAp2>Miugpy zCsMC_@Iy0d8%;;5^3znuWA@VjLz7=T==dJuPtxVV zV{(?eNaKC!T+)v&1_heIH`ysT55{KSwU_tja_3LQq~NoPf7~n!U+op(ztQMWzhc24 z4nG7((k1rRMQk>FnDBaKBS%Ga$2u`k3OJ1ayH>uI?l=AIrF-wV6YyO!j=9HRLPK`5 z5Ne$DM4HBP*y^LT?Pj%^MVGiyTCbzpTN1{p@VXDhX4aeT9?#LDARghI5ElAesqmNI=Vd*SG--@tGa%G#n{fqbeTSG}jq#{P%x z&S6&Vf9Vqs#kadgcP~d65yu-K=}4F8myV0NDYHKGC5NDmro$Yu6sOv;(*augYTV?I?a8( zo667*6jEWdE>b9}><3NWT71fAG%qJxvw!+awygtnHm1-E>4H>7V)M0#n9iuOOchN} zzt#vkFIIt9T4Xlt)>{dO*rA%zB0PrN2Gia7L+FK!Lo?|CPK$*g^T0b9M zEUOwG;(up+Q%~7AftPy0M9fUNP}&~3d8MQfND|*z9N3PshbvCV;=(SPHxmjPDky5% zj2#I94opR|wM86?J$&voaj)No8#%fWr&{J70k(oTk6ON;RuZsG?d}YA;)9HZi&yj| zPOU9#A1bsXmdLt+6!7~=7EDam-<&IGs$iMA?tha+{5+I$jKl(iklU4HYki#ENED2+ z3fA-i7>_r1piJak5A?ld<%R0LV%~kXG7zC7{d)RhuylY`tS=lgL8(;~^ar^Ge)zLl zeF`?d3{iixk6EUrE0JTzBKklu0?PCO)FAa6V?@crvaYaXnx1!O@A%NNfiTBqHvp_ILz{MQg8I>HY^@AAN zh)o>MgHkDK4 zgzr0!Z1?@~lD=U6d@sAsjBV7wg!q-@4J67D2fokSSF=Yiun@x^I8q>@u>(4c{&D!z zu*n0zLeG1f_VW$i)svUb$0i7~i+`04W^yQ0wWnjpx6RWpkp=xHs%cN{STsRZ;zYbU z*Uy4AZ>F}U+WOiSyqMGRn|Kw7v2_=^9b;N5e_8}&1V4VYQXaDJ5d0R9wtuU(&~14|B-4-_KLy#9x<1{rXY>0=`yV=&8$wpMdlig; zyq8s_o@VitHO(=E)k7^V~Pw5B4NTGjW{#Iv-IU6hfA6v-FfZhv3Wca82|XL4BB z;1h8-iHuwlTV6N-TID{yez(9=IWJ%;JOJ(SFlRWyo#v2u#yq%gG6Ba{${0(v6(H;< z5jU<5p~&N-j+l!n+y?nl*%F7%qRapGhb~LA3 zILz)YcNAtCI}BvY7lVgI?Dk#&^|@8*h~WRmd6vn8Ne)T8r5l)ZI}T?dzx}?zrujzA zR>v6rUmavfGx-@gt=+SuEgc8vp;Xol51tAed$nHb``%8~`+v$52|e(7@(117g(gIv z;3F+pSHk-)x4L=!98ann)l|gQiCJKg4OZ;Cv`^+pgU@mmD^Ju8HOZ!7EY+^AN1`^U zwVkdOBJV~XX7dYsn@=aRqL5%s?n+6z@qh8Sodi|{y@Vy}gEAQawB_lluf%e$4^U8pO4a$>K8ERIHQ9guT2#3ZujaQ z;$W}G!Febjwk*`aK*mT^0FT|50kc@nAMSC{iqub;Pk(UwT@nUO0D|4OArIjk!uwYM zXTG8F@;eH_&|FhLnTHashoBmo%{IoHa*%ZeyM8yn1N$l1Q&;w%>HF zC5kPNq>#1mlg0;fq!6lb@JcscwrRbb%qvWSTUTuC|6D2H8{J$V^y5qa#I5Lmi>T|Q zqBVbuwHhA{x7E`&;76x>pYP`LV)4=*!g^m}M1K{>lVz7Ln^yoHXgfMq|KVgSa2t&G zEnTV`Uj`h3-DO@9+3N@yj9Pk<0L&qiRq+3l=tub#%6(d0<;7W#_JmTgXGP@h;auZ_ zY}P{f_}__)#4~!7ilCBb_53@rdWpBr**hhc&fYTD~@CnZN^nI@Pl$1hCr!M z#eeV&7Tuy!L#%HI!yIBx?t0}NgtcJenFo3e*ff$~b-9dPFBk$g!WOvGrM*X z;Z548lOn2)ai5y*&~_48fIb=Kg<7F$RtA9G(0p2mv{c2Uv7YRcHG3RR zLOObk>pVi;=4eGb8G=zhmW~0(I;}w?(tmy$4YBmy%UW{7(E7U4C*g5HDbv;}Ilq4o z*S)wU775d(fHOAq5PqK*UYUXFSOSTL*7Il5HvvW>;+8R#fTCY@pEkWk@)HSIY-PpF=DgJyXn9|ooInciGZq;k$>~3 z_GHsSMzcT!cJr>*OMrgJ#6(@tCCrBZZksMjP+iy6qJPq_DM2t)Oc#Ein_JcxT%ze&{VrBv zkDUAqPl)4e@hpXq&6o=n48c;b=~655~sH<-iTjJvM6ZM>GKM0x?3HB)76>XYhq`J<#f5jljSg4 zOz!chL30y6ArSnGxS!kH!W|U}!w6eXK4Ks91@y`{V(Nhky4q@-RDTJ;=EhbW!V*cb zIozr#mXpq4)nT|GlJ5>aa5XvfSHAsMUgpvYg*H3%={kV6@X-7cDroZiLsR+O2@}+& z@ZAi-D|}$N*V*V8F+#3=dY$YB>*3NX68DCTL&LFxhg6?G$blTBNA0}t_=Vs?93TvO zsBFghNMqo6nWgex{(sqQo%KQ3@=km$=pjJZ^YXvRm)3sq8j!z}rX!xbc&0|~StR`N zID9N}nJSyj5Q~zx`r!j8I}Ktr2}bJDf7l5ve~F^PfA1{Z={0$>(Y3zHg<;ZbllOuf zbD-%Ef75B?08R6e8-=#!_8*S}&;+od%m-S?^GQHQdgVD^(|^GOyOHGPJK#_$a+qe^ zExQ(QWqO%X1n$cmvM9hO+(ZR#kZr$_f{Sd9yL?AuC3DnQ4KNywoxbU0Uf7nz#)l_v zn?`B$5ALFaO#t@aO7>NNvj?If;twlyeIs@d>2^x}Hz}aPNQeZIQXaj&n+$`s`<|tQ zY!ZVKIuTc(8-G;+i`*QQb%j}5MGpPMkI5A9j;oukZr|!_f=NV?*4}Z2L5=|*7ue~O zpo{;&cvuX@Eqj5TL8nx=E)=?EXKV+_E)LWUg+EylObh>~tTCM1EYT8BUK(#SC6Rz= ziPIoBU|H+8<@X6XGs}+3z=T2fHa+?>MtzClTuW$5eSg!>>B6KR_;uB43FY<$<0^5f z1w6=)f&`9y0I_# zh+L54MAcr^9L|h2)aH#shk8eOt`Hr}!zA{X+CVMMS>sy#L66}dQ)}~M(H?%EBrPwi zMW~^J7JqSQNyUVU@4yAnfdj8mUC|H+3?c_%#3-|e=t9ATxEHljnH2&aX9efa zL6veWn7W!#hxiILHFxBQ{%<#kqnILzC~MI9Og*{osT2lbs#dFbXY9)+p56TgD&8&S ztRp?vPu9*d>Mgt^VL?t6Gzh2we0@6oCvs`N*nfsO5nT1L0P8JTscSHOlt(VqLV-1u zRK1_LNs=%JXA8F^`7?;^=yT%*u3@K~j5F8y+4d!im6kS1{qKhZ-OP6Z9efi}@VD}n z(foD!f z2io3VzaEXrwUEME_u4ql_BhU%baE3E<8V1l* zM5vXr1|1q@1$ydgPtAzn6a`6T=u_G4j(@!Evak+eG4OW2t0i5Eh~bN-g9A9Z$OTt& zPa%b-_rumWix%Zk^c>l&3T#_S$(yD3dm?>iJnqkYs@>=sM`Ta#K`R7X_K6N!EIh!> zvWM=6;}ELfI)j08=_X!$B(!pQ)m^W??B#aZ7bHAV`&U$pv~I;%BJ^0qB!F=DX@4-! zAh^Rv7l9wp&23|ZB(Rn zhmjW@UW8M6dV~LvpUK4Y$c3x&pnnxwE4~ZJ!V>@lzS0Y>@dQP)JiSX{8e=b4i)g$Vy}EZ$VR-_061tpg+z}oWQf-TLPYRj zW~lBln4~;WriYHut3u5utcd+PFS%@<*kWTiOd_xprd-D_D8%x-)z#5k zvk=7yT0XeefElFtsRo7!`?q_kJ7VBPK%JgppyrwE6!u)PTYt-h3|-6DC`!9vjT0sw z?uS-ISZLe)9xs{rW8+@e#$x<9X&07~2_BHIOqV%pZL$`+%oDZqjt4e}=1|tmnhwV_ z-MqLuPiF{t9ZZ2Ol-Lp``ZajDNds&#Ma0j(`kIu=^?kS_>h zWXgYUgnrhSGXSLKCkjkx_`ppCoAA_^t(}9e1NrF?W&}xH)bTDMfpx|KzjKWsNORs^ zQ3XcO;pCc+yQ!RZD#(lcytnR{G<B&Htp+N3j>S&`^Ln3^fx-8( z&cb43v`C?v7JoVI%%7hb=zuhpe_vb!*ai>$k3D;gagf3bs&+M@vSDeePBXJqWiHqy zA%)6JgcCZ_=}L+r6j?d>-s>bbJbiHtylJ|gapjlhNEI&hq6-J)(&^iA z$L?7v`xH7CJ1i2Wwckt_)w}4^se)j{7~0pVpo1!zfskvP-(#R{y$k~uP{)gjp1Rk-Gx zRj}^lz$X-E#_3JHK7!-o`yDG&tLPXZN!m7=NN5`0dVv>Ww`=jn!mCy_hpDVP-LmM( z$4xnk_kXjrQM>Q4o)`#vew1Cdn|@^#0<@L3atAVqZJXo_uc$emHSqxW%I`q_LYb58 z92D15xI2l`y7j5(g73&1Ivc(o0Mw>yeJ!8)j{_ULsTW)}amc~=l*P}RFH{FSt6P7e zbjRnjFbty1@BjwB3?kPeURH9-I(Q3d)xG-(s(%20Zp(mKk#~je35HLGhs`2;uAxPv z&Gr=+ZqI91S&S1m*FPf1#kq=)Ur^zmTLReY_aqWblQ; z#U+8ESq`SwkJsOcr#iatjLirv$xUA8qlho|9<7EoS?;03cB)Z=p8~UPsdUO61Oam` z%p`_?i-wk3^Q|WiSZfwyBy3x!`mVJ7-fu!oFTsc7ZG{bSXdd_y5cH?d%><~+% zMln)W81W=Yc5r+BQvz*pYZp9PW~8=^D`B47+-DdYnuw zb?STDiHjPpX1eX4WY)~#jJh&y3Fum>29hzL3S6^|0oe8a_mB0Pmz3b+fUStna(@Al zxV0?7>QMHlmm@U{%^(w6f9~YvnMlQYcWG?1EcYI)@xXQE36Z9-H{7_l{_oHidShz; zvx6R%E>&rnjs;#iQ8Z)(+e|oih9=0iF!x7vr43$mCG}oPWFYpZ#=f9gdR}quIc4eU z`gE!!8@oP<_R%#WE;89-3Y>c>&VOwFJ5!yde>k|-ycXXsKrb1U^IXrwbE*i8PhF{* z$xEzBy$G>vzRFaaGs73!rYVpti?QO&p0vsGqK~q;{|(eKduf^dmb$5O!%?tA1c1yF z`AcNz1V1dO&@Af_Feqf?s-A-m^Ed#$DjK;?XeJVl#R%{=Ymme;k)qs`0)NORwrjVk zY;RoERODZv$B_aIx#%whn@lb^f1p0DYvhZ~L^L`#dF2*^?1+ZBrvVH9CBz0Xus2uU zOXIyL9f1va`8aB@3-OuM6AlEEA+7>%h?JG*dNdxf1FgB!k0VQ(L|DC??3~g?lCq%X zL3`4OxMW^Ho(6UXwc&JD7=J+oG?Evk0V~Ii4S3$}z%JT`B|ch5O8KHMH=GdScS6e{ zo9a&ld|$r{6mc>IupQM^#vb>fge~^5{0O&F|1p~vzPb83M$#E0citvlFK)@pV-6DG zibJ24@J9ODyVG1R;MVaAd1*LObV9fVy>42gZ-2pww^@UxFF!8hNq!S zw2o;la#F&T9Z&kRt+i<1>_EBty%?ZA@9m_ikLZe3yX&mo)F88N#tlwJ0p^}M-QEqI z<4gIbbY&228v4WrGo<~v;qvAX#5)S}bMT**?dEA)WuE$#abB5Y;Yt?bLAZdIu>9&< zElgAE^|4IJM@Y74oPUJEM(6e2D5}3WJtx~d&@M{f=|I^gZB%7hLYI1faRFgEj1XJBdU3}G=WJ?7Gwiy$s+u`0B918HyJb!!~y>NBB^%pWJa-npn z=Prz3oXqhhTLg$@o>uHOZ2nP>>>afSQ6deKuIatp`A1at zS;o2~EGT7=eSg=VH^5d_7>&x~RR^9E1z=4XuCs zw_LK@tICLyu=*~#j&JBkHjC2ib z0QrjCwsZsYQB$n@Y*s9|793{c4%+eGIAYFUnaGwl=T1N8W$xPBawr)qn0SaJO2?`gtd9O-M&f!pMk~oN z=E|%bN0~$OH=}x>ygGn;%$diLNjzq> z-o!Q&GUVwuHi(V682<00IActt6tFTh`o)gs0P$aqRroC%@u*27PNx9~l2ReCwGTre zO(0~lbJu2;KJhLC{rYE7gL)R>x3oAxL&^<;kf1ojD4mU?p#38#VS{Op1GI_6ZXvkH zvwu>K=INxMlqoGuVQL7*{fi(q6a_;|Zc(}P4>GZZs(1a8_hZ;B6y}@-j}t|&Y~Jjr zwZ#|mHmQ{vU^cuJmuFb;Td;dR9ZSul%728qAQ1HJ}jv;E-)e;T1CGLQ}Ey z=+3`)zL`rNn8*gImt2h~f-Le+eg=b(eSaCXafiECQn`F|j?+7$EFHUa)+&S@)3m7S zFfW5LEpESXywW>pRva1go{|WH{c;tQ$Z+2y4uDN_?--gfcpPRkLT&ql6Ypz|!? zwwU#Y5>UJDrDl#O@8;d`RMu{>1m1ztLL!^Xe{q*AG;;R9{vwd% zq8s$)EeE${H{(!^3T19&b98cLVQmU!Ze(v_Y6>|qlM$*Dm(3{y4FxeXH90nyPznJR z1T--@G?yXd0VjWLxdU)z-4-nz+jdTDc5Jg_nRygOHYPS^Rz855l&S(7J1Z-ImH8V26_vO% z(8LwwU@u|f3giQ50nGtwKt})@JK!G(8v+$T+`-Yy8DxKHqV+bz~K#0kqPJ8USga zJm{?D>C`JZL_KkI*4 zXV3pw%m{330CSL;E5H>S-(fzAL02XmmaJwVmL&cuKIzbF$skgeDMFYf;$WL-`E(LvPS z@*m|`{}TeaNP#?o=E@+~f26iBvHeG)f5)|e|JfG>pgG9R?mzXwfAsigN6j7VZN2{Q zlK-^v?*&<8wAAHQlo|dv0RK))+M79;gX}E)(efc6~8inZ!b+} zK!cH~`-ueHW2i=(u?j7`G!=f{U4;nG58gq#qQW<_Dy;b7co430$4T45yS>oLbS-~- zYuD!S3TRRhq}4l&i2uo7ZB2NKN+zTofa&a^ct>ne&s}Zo#AMv@8m#qw@Hxsx%AM1? zgK45oHcrf08bsllsxubBb^B4Fz(Ye?I2P@(44(#V%yK3QXJp~pT!}mwG5TwwGXdL} zbn}b|HuJP|Nx2YQ8qpurB zRP%?>u0+eKP9tn1HgXr5#9c@7TYgfh&o`LV!@lO29qByyCKUi@>p%n)gK4^|+&n zqxVJL&|MEN{}Vpg=f{|(dLgldc70aUbC!U)DTxcQ_R)sT>Xe5yJk}h{KfW$C-%~R` z2czJ&&#cPh{V_u6Kylw4=y=VL1#RepK}niq)``Bk431qHcY`@wioF!qHmfj2YWw`u ze2~~59+O~ngddZqAb$10wkm(|U-;LgLMIRc{NmUKi_7V3b>pp}iJXm~o^guDc?Khr zx;lU-l}*IW1RF+xXOz@Ns#0EnkQ)SlQdIYhb46o4Ztw7?xb+~B6m|wnMRn^BZ`bZm z9=T6Bo`BL6>sqxp59E`S#WSY0Bh)9P&dA;Sod7&tPegh{R0iuJqS${(X+&SG;_cBE ze3Rl)mmIK8T#@0{5yTC+rUx(8PLcJtiJ!Kx_IW1N7?GSw{BunE9IqmLO_G@! z%VV~p?y1A+CI=c*F|AY(sBR3>f$Exdc)O<*jya4COxrSnGekgB94nFP^ker(2tS~! zuP^VqH=o%Z&GdgUO}>Agc5yj<@|H!hNb_k#d$n#fg&3)<}nG4d%b2Yt5+klA7fe{}uh17Dxj_V~;9 z@=D387e;?+bMkbCB*hNC!^IEsYxob*Dx*0HVh9=`Yr5fLIn@8!uamZA2Lsgb6~YvuF324 zfqoGv9STH@+v7RJ>^Bfd47bcXNATUu}vzA=ZHOqC1o8e2tXlluO6m=WfP~m^M*k`v|t2) zthBR}Vc7M<>W#UAPC;q6zbLLN!|doBYC2<3kuN_OC~s#`Racp6BcpJ!AxwCWb44@t zypeyveZScFFH&V4wkzON_MapO<@7PeTc`qqnYLf}OT(r`enw-S1<44Hd|7P(XhXkj zWO*@r+h=uCiY>;5IXmoGydVP9u0PCw$As=6n*=XKz2OMS$8~hzFYhxIX_5EaH@2$- zNuFoj7|_NSbrvhrof<+5$Xu2-d}wLNgKmHDVe$P}{lRw48*ZQc3N4tr@JR*&hO&Cl zI)AexCFLm^)L;4;u?kE{aa+U*ckQ!Lco(krdqNuU5NV6fGy=c5Y>W7Q&_D*4`%IN_ zpE;Uw`gOR{`Oc#z)Kb4o7LC3t4Y$CQ;KN!S~2Z;qeO7o5EM{>IlfM|KmaHBW2RvlA+KOfs%n7jlP zuXdR?qm62w)mG`p0*JqgI4)oJd?tSkX{<h8btASYfJOpa}ddnms^9=<{ z5jIKtD;IXslr;ejXeaDG-y}Ch13bi=5Gx`s0BdtBl|Et$ip&^+i**8;m^m_otnt{&z{{2yVHef%fh_e7Y5tQX3&05JXqwTRoNI3j-sK^Ax> zD)aO0p_`!!TTIN<{X^Gu;xOJ~Y6^;_HNNqGfUAEqat0q`e*S>5rP8?l6zbqnZ)vQU@Y$yGw@`jCKr8hkqsJc@vuhwmYR($zD*z z1ZGjtSkgBc=nacv5tZJa21tLXhh-EMuXt?R8Prmp2f*Vnx}Hav^68+alz3Z|Xp_KU zS$q=)ok@QKXH(`CT065eOj{R&uES_3B8fB^yD|@CiB;5(E3fP7i)T5wH(a%p3FTmW zs5-|MZ1Utns6I6z46yK2ppVFDD!Q=U3YC7-pn)RHlP2fIbxU+y0o$M*~FA4cAs(iVcx)|Rpkb2vc{pwQ#^f**o7-z=Tq zMSU~dtO=Hyv@h$XiQh*TyBC}?vQ_)J!LrSNoPs205kac^m8; z>^WgNb3lx%yW4;6mQNLNNKOxngG@WXLzdLJl|PaB*)j4xqN?*~0IPz$&n^zz46IeseIC!eUo9lM_ zhTWEXFyk{EQx+C%(2iJ?ZgkQ+6j-Z!HNd*yZlwn0Q8IrmUpB86Z8(RJ5p|^?1X}jr z9yEC{gw&{H^9e}Aggup9@bG$p8wP-(Zm@sF`*8?;;>4Gu!)uf7);1R~Y|r=C zf$3j%tUM`tQG1U8AID@WGa-taINn%r*;o}L&3$HxN?Bvc{>yeP!}%_z?5IsglB`<= z>$HGIeioDX0`sd#vBuKX-idnHl;FX0#~+eT6eYh6lYgD8GkHf|zgDRSS$spE0@@d0 zxVwKP`(acp8|sdI5>kTmJH?3}6IoO1GN@pyeRmRrhW&vX9=P;P+VR);vgTGXJ8X~H zcyd<{nv$I{2`3khlMr6c+P}vW^1jcmsfLJ*(r&M0AQU-rR zjt{O#32DD(;mF82fQy^$WKAu_0_P`%A2&EfA~dbQ3931HZ0{Q_93gY}Z~V71CZKi^rX!0T;Xc1M(YWVRf!+9Wxa8>9Hhg{6SjLu2g>?tLPZI zV1&*))4jhG-W`(O7w2=q8!{y#K4_}cI6FJ*C$F5MufFj-pXKn}N!kO$Ad&4?Ty>Qm zcyH}N-K1{Yf=~^}VfNv?0eGtGv^P-J`R8g&<)X z*(*x)wU{mz+8z9-t65I4VRyHwTO)QrN>DWJrRQxy5$50CGsDJK$J^EG`@{lE>4c|l zPx0mah^;sZ&MR!253;YeGbj9oC8!BeRvVogBGBc+&_oFnzGlLx+h0$A&mJwly1}w+!kv}mK8xsj8j(gg&L*`g^7jkxvU-=H7eZ|?{|eSy z;%jL3c*k{!E4ebXbtdQLg8^e&!mxGbUaVL>1&j#ey*^eZ{)lGUcP^Cw^X0 z#!;+8&zK{B(HiKm$|qNca+eLLYrIN=B7)#CjB^1J$Spnxopz7&R*h# zzVv9QKBkN&BR$?yivRNvubdA)hK9sNi;;-`AQDNXwwt@$66Ja?qpD*M!MP~Y;6|1l z;ERfKS*CRHM&*Cx4Qt|RO^utJTHvN%V|mcL5qKI1Y1Z}UlC-!LmlsVq8J7soxSu1S zxDfjg))zBZ0BB~fGE3a5=cWVKni#|Gd?zXaK;CUE!rrjC_a&4Q#AS#+qH4^$Jp$bO zt9COFe|;$AvO z7~tEK2(d}J4S^18RRnPivfQ3VEgQN_%@)RPct=}?xJumdtD6pQGIk{`Ez!i_i{Ln< zwNeAS=?;G_jk&Y)#kXOB<9FyY-ACx4ZP8!LXboD6Llzi0I1VSZCgRpu`v?KD7}tO? z`##@J*XL))CrKCFKq(iQp&m4)%2s`T6ZzoWx9cUBv5!T(QSAoz1n_piI&b>%moQ z&HnDgUEcIjW-WwhS@Fme{+q(y>Dvv`3q!IH)1ScT+U^D`p6L5J&GHp&!_9~vMP^ne zpem_gk?QHNf*4sVmjuk{YSVRGlyW}jsd9eEJrB?Yb0f%_*UOVs_}5$1I*!e7e*T9< z0BnDx5_!Nxtg*;)*>D83)v#(*a=sTk}-cgQY?zNmefUT{<-p&vgTbL(S14HhzAPV zUnIks(lJU!Q9}9Ncr%e^@ty_8zuzjSnh_>`O?MQG<+$s{WbP4yrluF#U)1L76|MJe zWK84!%qzYMbKA;Tm&p04mAbl`nHBSOcE3L8Vli$~eGg9H`*6txVi2m02>E0Z7$$!? zGCXa7bTY0 zzLkGmaDKi{l;B%-)q4=2w3;A*FT zQ`Z|$=;PtSc^4nD!vH`3X-mc$k!^p*q>rt`lzE4soCat$*ExUH`!*dYcR($G!T|& zwy)0qyz09?%EJuTEB5JS=hoaVfkUF^ZXQ)&Ab}LG+4Ra4oT@h|Ryu^eRPBG82}LZu zD~a479fVzn=4E9nMT@0^42m7f8%ZA}g2(;Vq4uIZma$#5ND7>4WVWYi&J??k=8yZT z)5LHxGaD7o<+07Rg~_e><#&r=9oCb5s_M@j7L@mCKKa=Q~V9z zqG4WwxvNBZ0XwYXJIoIOzKZTT7=9S|U){@b{R1zO5a0QS@8XoOdo^DBkl^)naqCQe zv&YU%k~7FD`8D94veVQAQFybB8dyo87SJ&eX?Dl4?a!G8>ME@>@Fy^8z5BGEv`$Z z%q)XesZWMg^_&jb`$gU)UQ3qB3%NE>WCYX`ecb@mlsrSiTir+88sX{YQ*G1P!;pg7y32qB zl~VYSbXM+$z%DkV0kYq>WTOlE%@R_R zyIK4~Zbhxfb049`8>VjIE}!jlU3e(RTdZ z;uyGdr+!$16aJ^C{>SUCvq;vN^Q-r+{PmY~AVrfq{ONUR=UY=*IX=S6SP{C{XLeNPWq&209o>zA2QbrvvpyKNMfwJUCu z*W?=z(o(nk{~G<(GzOF`>ni^&3V-_k7CDwdzZLFp;P-^y|1IHc2=)oeZ#U7hpW_Qo z2A-@u^kPy5+*M)l+ky+5iRaX9Y}4j#ANkZOItL4gQCff1U28UDa^%k(x0XRY1|u-1 z@01=wAPvwQ6z)28pt)^&7`}?vIh;xN;8Ow<(|580_okBvhYlf3KFMIx_hjqFCBIyp zpy<288lOH$Qx;M`(9+l+J3&~M%|UtSz@Voi5!cf5BeE|4T+2cXkL2OAz1#*`9d-rt zAus_+jJ|)NR(0nzq|VSfj&#|kA4XdjD@s)p@8kPGb0)B;DXDP)&m`9&diVB)LbO7r z{CSfTFKF!)(a5n3j z8!@HC9x)oGoh(oFb4d%f;=$6BV_wXisj#nBzZg6}@lU6i+#;HncxV+R)k=cHuvoeWIgMbR<75+w!}qH=Fb*X z+f#qY56~ScQt2gKrqU)5yuuMz#GCjuBu=~}C7lJCb*buYF^zC+VV}LHpUafmsx0xJ zk8l5OTqu#qV^;u#T%i5r4raLswbpVxWa(B21W!UH$>j*E$G z5#HEIS3%`#i$w-V!_zlQMue}sSO2$@go=L~Dx)Cjq>%&lSE!@SlmvG+B#|)p(N6MZ zN~Ac`j8bZ-_DBxK-V>VsM6%u01_n>Xcb9kVq6EQ^Ksjodu5NL;Gc_GMiWMT$>hzQO z$=ZFb^j5eBIN$CV06xQJv;BpJhtVkTWwZvV&O46Ze#vuW_R=cc4qarSr(;9kUN3)8 z@q<3LOT(LeO4REb*gznQj>~`5C_>)Dpg|*ssi4<7s2OtjO!P`6OD_qJOY+gBqu{+( z6gD*nOrM8y(UGw z4dAo#?VO|ZwQpKti$o~5Vkm#4sK1Mv|J>cDBcPMTTGtDmvgq1IdH-CDL|k_5eQ*T#4pR`&Gt^T%yyB^z^#KOJTUBTSCHULY@wNc3MBPBjA|na zF*~8V|-TxH_cZkycR!;4D+$yQVU{`*^_^O+%LSehKQ7-wb5_{ ztJ!&f@;te=Bo3_pWV6#|^iJMBER#191$g$$)--fE>}&Tnp&G`)QeR=dMdVlGv=6-# zfquH?^V_VxLwMsa;E@)t#WoZ@XQEx1FFvxG%yD9A_<^uc2#63@5UNPD`k0E3-PB(C z9OzEQk41-@kj#HdVdBgZcF}^ml-}p@9iPYM70;|r?dmkrEQ3>b@G-b11GaVtg55Qp7G5eBAoDS_5;vJd)EuEW>t}Bn-Sv&bw zeH0l6iL4&Qgm_iC~rw=W)Uk~B}as?mIXKBVFjbn^!nVeVV zL&~~k!U;V9UqGP03=Smaaq)V)i$dEkJzU>z7lroh!vpRiP@D7gbsP*F?nTz8dVTZ) zRb%IW$Ofm{s+|5@92F!nT)A3Rj+eD5YmhrZpyX}(W*MGE*Oh`Q5+%t*^5CJ53nEp1 zm{`pxZWCLH&cJ@TZB^VmG2SRmK>KTLmsO3&-ha6Lg0(8b-o*&jVxt5Ciyi9d) z%o-XzWk(3p0?9vPC(qAM9Zeg^JI!5q@;BUnR65VBSaIxy)>q z=EO_tCMwEEqm#~rRI&)7J*|2@|A3=XU{0gq(x;iG<$Q)Q&@W3(%@^5oyYG0kyx7FY zMuAJBoLppKGc>ncbQAO~wfPlL+%mtf>OEsihd7y=nV90uO)4znQGOMO=Ho=Wg6Z9V zCXm=ko_(sq)$x@f%R~rg=l~K_eg8m*R;6)0gb0N=$lg8+3l+Hw9eNyHVVdcRfIZ(o z;`4sREXkdYJTt4edD_*L6n1k&x;T6-rsQF!s!YSF;Z8;*!#jH~3q!QE?81_Idn_UF z4>i6uiA%UNd*kXb-%*nXRQoAkjNC7O#HHXQD@2)bJR8;iMjUx5vP?n<#O|SJR11>4 z?IBE~*aizRTtJaio@I)inu}!ZA*84Rzw>b{C3+E@S>CD^_x+tpB)cXqH%hj5Tg5;g zqnz6&0|wEmpJ1>5*i@>q(G|rWiJcJOCJwULkCh>~V3Agzjy2Bv=jjzJ2iSrW7)24c`wQ+6Mgg> z7WU4xTo5BV;7UCm+3O5{CGZ7G(;wOmw;2SlnCz%Cb&$9|I^_lWjK_`7hlYM?`o&|s14BrZ zbn0$H8R|_e-sq2>JuxnsWfN3+El~aic}9-E`4(LGT9F{*u}1E&3egu*P04`!Z8( zGT4HwBv?cKei{~>J%%Y)JN#FG_XXPJFqf)r05$%ds^^hRZok4MJnvj(QaKs10g@s_ zHyIaHyfd{EOH%89zWM~Vy2@isOO^x}EKb{WZ~-(SK8GuLYg|+glGlf|om>g|cp`Z7 z;t18M9Po#5N&j?mu#J_hETSSmoj~ z3Q2-ru10@<k0(8& z=RCAV*NVPkiT)~TTFv#CROHs_bdt3ZJk|k!`n8t7)z=*xxErrZR4&S}6@tv+bzTm< zuvHFG+V88@GbIxPdh#|QC%yF^EDJ2zPn_M#RA8RfuUJM?*#>?@QzXh~V0L6(p`oG8 zn!TcQqoR98#%|7R?xo+zzq3oM-_XlYuNzz)RF96SFLBLq8r@=HG~f`fdS`v(syo+z zuIJ}E=S~SI_x8}VG=?L|&B4+A#z5~^T$o50SjG2P%r?@H3G}7Wrpz*0kD<8buN0_rbpJNCNyJ zqCGg|d9=zrYAXE3N7Nb3*@C_FB}Q+5*6KUZ=JDV+L)28HBOt3(5;(}UWzacz@ZnWG zZC?=|IV;EM*#M0gn1RcS+;rmcC*&>P1rEzF=fIgxmuH#qH`_Zgk4F(mXj7MdP^vL#q!GY=) z7DSKg+2Wrufm^LSDtd&DbT@du45fj;EML)t0V)`R+ipoN^cdyx?Ep{lR<%7}znsQ? z5?rV6D@42R#xI8#C73^2v8;p;$me!3kM4c zzBNk5A!f1iHNr5UZ#+?(gFXv?P^*f3o%j8SzL6Z?-7C#7r75<#88yM#k0}eaM2#~O zkSv7u1HBVrM+tGHUJpaie`{XjqcnX%=Y#6-yT(Qztjc|5J^2@s9#X{TizHuHISQX$ zTMMEiU@Bt;)|`BkLTa5kBqLD{=lzIz15_6aiT>727ZD|%_TIFvTDGo#avil8)uNe@ zIF!QLP&i=Pj<%A3&SnR;a0TVoX6g>RsywZT*;g9uq)SJu&*aR`2U9VrHWoD2d8~6z z9I#kuZnW&Jbi+Lv@33?@pJQSszP0WU=H_)3QIah%tO79epOwgF%g{waLsgBymj!-& zzvx*EXaYL-=Mw%6jlk-EZqVtZ$Uq(iONufW6++;z?InCiB|pX zx$C#9F+Ze;D=&@L^HRq-J}}vOMNJp86DDl6Ah+JQIi+Bs-T~!*c|KJ@BF#!339NqH z5>6NfsaFBy{@sw6!u{IW_f))D1nbh*pzNjOL5>n%BwSr!Zdo-bu-zBDQ$!&A?zlo8 zVzF=gY*&z1fXOHBcOsH*kKON0VTc7ABbREm`pNwKsNiLY^1zqt)& z_W)NWIv-X&Xu*VkyY~%Ox9AlC`O^=A{uW5f^ZC~*TUr|%QtuE7fLhEuSiYkBIP&=c za1OdPYvp5ha?9wOIn-r>;YY~*jvi6)I=GgS z42!9SlAF(wX`h<5VKc4z#1Q1KbE~SZA5dP;4#Py!k{W@3w2V$Tb)I_m9g@XVow+*b zHO6?9+#@fywR4a&!dX!HY+MErQ*}h5@Mq^st3&il9ipRtdyi9u1gnGJvOABh5sM>> z+et72smv6gTAGkLj7qEDzxS}Le&f2gx)l8LQY?RzK`mtCsn%3}1N`>9i40M3Y=~p8 zDVmE_=~3u^LyIgMLlQ?)1Y?~Dd8%D{A_w&wuI%8i)>}bOA{;_W6X9mD{Z4>|Sl=sU zJLkwtYS%yjqqsDl#N8_9aE(%dd~X}G5}}Es9d8~|B)+WtnmA6aDud>@k{;7O1fpb!jxYLO? z!d`k){g5i1l;)`su|xGQJmwFY!%*W;ff(ws^Vqfu1i@_hNsS7F(dy;5vMoa6PG1l3 zW(Tf+$3K=TWl%k_!fR|EM6FwmuLFfy5vEhW{#?h(3xuOAgNjdC@oEc27!ui5uREV2 z%5cc729IIs{Dx|^6jeuR46P?kUH8HQY0}4C1}9tZxP?=$kVm6ysvkIdm!l-OQFeM< zo(d!$+o4o?SCY5mp(#W;Q!2rBKhpYO6&hD zoH5Q<+8r%=&`G`QHG!kg$kbRL6W?*Mot%brp77gkv_+YM9{XFukxR9~S0t2nLF|Xw z_zVjtrvt7czc#2hBk#V(oNK9KU^p1jJ?o?3ROsIA;CXEf9uq4pH+Xab;ef;9fa2tT zPnXC-O5DuJOwr>N(dqsbaw|)wZg8%3i5g170KI5arB*Xh5p8TJMh|1vC%9|SXslzn z6NAGdc~|$>Oj*0H8ol^z056edzC>_3JD5|(|DDVjk2Eg(Z*Ux0mNCKInnSOyjiS?f zN4y9Q)R@1Gc$04!94b%MC&(>wxt8sJO^N>o)dAzWi%Dz^)|PV(U{&v@xeBI1lLbjE zVLm_?#v4Y=Gv;|I&)ziKp(|N+J1P((Q>vCZn>K&`m!I}K@$_B{pr-kCY|M1JrGL}S z-xCgp25-=yW^|NtlRhF{+{RVNVlJX|z^Vme{=i^tRPusRj;11>9IB;l!+H{bMd+@~ zKz8$kDyw#bSfm^$?hKi* z^zpz^KKgk{Zl4Uo9mIMnBio6CM_BssR6*kan)RIy41wutHX^?clDmW3SM%Q7=$p`r zm9Z;cBvT9MYrJ2vn{Of3;c4A}BU}~E;c!1!j(Yt+Q;mgfQnRU{98Q!zN_ME`@-*U) z7pO05tQL1ambF{XRnIk_K&rK}7394|IXvX|v;Gm!bP-&>gi6yJR5vFlSlF=q-}T-a z({I?b>!3=SA&Fbf@FS11DghdQK>U$e<|i;8 zsQRmy$7a4JW3zly5qI(8nWSzQ9C?5IzqJtz5g4Q}N(=$uYyRV^;n(Z8@7k(~#nc(& z61j^E;-!M?$sg-mw{hQ%q%Zp~hsBU? zUUi!k^87bB8AbMOAm)5N?_8OOB{kx0T5pl!yuFBbYRWoSdb^lN`d{)190)T{g?FT4 zuTE!g{W}&gliRYnUiAn{@=2det@I<%I1$}Q+GE#rPLqIMd+-l`&{*|YVrf@}j0>zV zBR3RirbfwjUO;j+c%RDgHiBi7^Cl;Jz9lRp84vpNHguVx0}j_;wE-;g`?67La0On5 z()E#&;FN-NUj|Gz{9w)4c9RR|k1YnFRlV&0+#Q^$w@=RukCR+HN*{9}y zWear!kgzTruEAn|X2EQ-O!?^z5p(%ZKG@}il{?{3N*}hD)MJ!mB7Y}*$Vk|Y>*u9! zC!|hSmKsX3dM%d*O;ESUJ1PS|(6imh)Stxe_Ks2tyevYx)Ge3j9^x+s1H*IzIE7K` zkdR=HhxPSX9m9Fd05X_151`b}qAgH`nxNek@c>^wn24)?sq9_qj=C=>=MvAglsmiM z#zljECu=3i=(*7MXe!_mKI^7WA0P3WT68VO&SVsBDnW9Z3j<3dj=()gt_atWxP2XO zc7`|Y*-+24YIU%V%C2q`C5BGJZ2F9_;R_h3#Fl3i2FCGlT2NzmE>EtL++nKX9Xs{W znedhkDC5&50}aUT-{1TQ8wQGfXPiyLFB)&!Snt6FlrZpHf^;eK*R$9-v_FLZp!x;A z!?t(?s0&&j@j*W*w{s!F)OPAQ6jAk>gXtO-4os(ii#^S#izC4_Qm`xVh|WJoBTF z`Gu(q0|K*8@e_bP>Hh<#Z9jDiWo~41baG{3Z3<;>WN%_>3OO?%Fd%PYY6?6&3NK8P z9jXVn%_#%869PFklM$*DmzzBU4g@kcGC7w}3IP-aGBYwUF_$6a0VjWKx?_-FO|~^$ zt}ffQZQHhO+qP}nHoMEVZQIt{Gjs3Uc)s}J{MlHUx%bL_A|pXUAZlmptn6WL!a&17 zOV5d~B&saIK+nN~PfyDPNkSszXky@OVP`9B;B3N)uV!M5uViA6&%lV!NKelINrEqA zXYb)?VP@`(Pi{oVg z|55Ob>}-uK{uPrG?Y{%Cbv1Ex{u`L7qn!=DjEJ&;sGO`azKDMiow5+VfvqvVwD{lV zw$4tRf6*pJ&KCd5jvC+jzmm1Veu*3#f8)a^|H~l-zOjkvU$l$0wXA`S2|l@yosGSVvxy_VjGeKG zqb|08)DS-X|8@6oo#B7~bQuF@M+{tv#+eB) z_ z3zVmvWX{Sxua$Ht<3SK(h}JLf>;r}0j$d7Pv=yV!Aw$g6{DwB!r>cRUH4iDgHspKV zTLTKq588#kA;HiyFRTc#KMd1&V4)EEEeu6=^B{kZe4IriiOXw^(DLU_4?8Qt^v{Y@ zZ`sSFd^)w;rmy?Gyb$koo#51M^5yg1;MI5o~`4r5T750xA8F-e-!C4cUV4a}c>u$e<*v zb#0o7u~K<`?=b4_UP|%2ft}}T6Ra?b`k38yg&S$Ow|xH&xqa8rn@?fakNbrEo^YGf z=Nu_qfv5I!j}los3*Ew)!XJC*{on9x3^(L0S_4#=#lq>v1ig>bn)GgLPFSZD z)>x4@59oz`Pb%+6sll@xE}o);4>Ew5$goG~D9E>7oMl}RUlLW6B9Jnz9xgx*wSaKG zY7Gh?7=}Z5)8L5^m-aAm9Th(^JoSHfHIs&S_HdgrnBz)3s<;J_Ht=U6#MG%I#F7EK zNu>>NqqCqSj#5T@#-C=2CYLQ5D#2?0_!V&Fv}`W>HQCkt5v`MOMOu7X)EGt;4^nX- zjE`g^jjW@byO{l+ZYmy7a8(jdk8lon6NII)tE?5AeU{MNICUsrgw*|%6)S&VT_xm! zgusM65~p0=m_~zW)Z3fWinUuaNoHzDB+aP6}`U=$@H5B7Boinf2No~?z@5+K-r zOwu5h`Bi(vFHxItvSuvp^^1$0BK8Z{k18$}j#XJES?Bs>)uu6Y1?4cxW*Dp`C(3T0NM2D#%7;&>8f*2Gij?Rjr{zBcP<+v1J zc2k)7^7e0$PgI9W!#3iTw1QJY#VB)jIk)dVAEOi5Y)9smSu{Yo2qGC+$Ek zV6H+9kqN<3o)iS|vV;=JhPyS%cNbL++TxAUGrbsJf#_T^wc^~YR{U@^rTaO%EW6eM zFKR||i$_X2_)vy`ojC%hC%U|7{303-#7la!Y=Ba^AB|=j-Cx~j2mPLh2Iq)~5>x3h7P;QI1UTW?N`bAJK1?}ItM84n-kH0=OYzZY9-p(4my#9IF-0|bc3bD*; zhf5eVQ-VHq0g1HPGlccTM!v?yFjLDu>)oGy%&xLu|Mq{9l&1=0o(L4Y3n6u(lx#m@ zq%D@$;yUOKmkk?Pf{nTwm%!%DBwG}Pc>~WyPJ}^3Rb?W@LhvGVHBa0ZB%12G1kdH= zX00f>G0zsH4)VjUo+Kl)o)}o6dIoC~Hu45W@lM`xHUoihyv$gI+Jj4PSuK8J=f|bL zlrc){NK=2udAOnoS&tH19?xk@jUmFtui$n#BjSC~KPXW%1B4;LMQHxfFOhYzZ@|cS z7-|IWH#TcM)gcH4sz^>H$PCfV|uJb(>w1Az~(S3 zg8~P1cWlI{DVhBTID7HyJt(e3%dXS^RKb%Fxh#J>prs`C1;ONj!!Cy&<0Pvt5Dnmf zcMYiD*e_Bm!3}U=9s4shtRuKo`4>JZ>Nb#A-6`2lg$q_O0S^hE=wI{;YdgJMLD{5TJ;v7Xv z4fKDg4+Re5%+5Srh>pHQNn98sfQ<{VQDt zm}p|6D-k3yRffDmTF2fYit1})c(G=7$J>8;m;13q@hvu%=8j;7u)+aRoc(ZF=6!QL zZhHk8Yr7c2+{I5)K^3DK6;4GsQqzFq2XB{o8m}^qgL|_F;(Y-sYxg9Z$rdRh@0|BHHhI_pO!il%ggXZP$MVY66=2qHACfX{{TgT+0`Z1$!d@U?no&X%Jb(`z8Dol4S3Xxi!eZ>ra2>07Gv= z`<*ARAj;Yl8QARnPQ6$f;@XBgZ0N&W2rB_ictzhyedvWkbSHAE^ryjq{WYO48I~P& zD*pRZ1;h9)G5u}Jvuh$MJQ@`&WSs1o!HCJ$aFFOjcZ?#IF<7#&)oUNc5qF$v*;oC8 z!LWGT*+{WZVP){7MHoS;2lju4Toqpzix(9AlHC3WgWE*6QBilrVN_3n&EM!Lk$Os9 zXK|tzMHHgYPr201elq^?ne>f~KB3|k-$sV0!%Z!Q@UrVw9d5sJ#RJS1OkckWcCGtN z!T|EL@~3;RmHfigSfVv8sa|ul9C7QY2Y5nYrX>fKv?UV29NZUy>zZHG&#)2tcFiR?+Yc{`8F4~qHYja>$S>SQOwW#!24!8w^Q1N=d6P_a0qZz$I3d zy3SY15nrBfyc%`Th>)u5HF;BJ_UY$I0EX6n{aW!v#M$mnsC$1hxePE}1@LX-tr7Cc z8>cmSmJQN5Rn^BYS<#e_E(&{*{)iZ5&#kt`HeDc-iRZct@gPox+lZ#+IyoO`HXa2cte3TkLfGnKNbcTNjONVk`H0?M=lL$8Z!0ai zEHs|WGYl|+Z8ihoe-H$RY;1HcE+tt#h_}}S)N(KqsZ4(yDHZw0r$UDFc8ni~4bgId zlCLX$%^M#?=M?nq0`tWRB(?Ij1Cma z{g=*}UNI#3%66j{Sf*H7Cc2Z4cu*eVm3nbyPO5iB3}q~f8?Kb-?=rkCXn87EaEL$` z%#-9x-NS$G)n>y@Vr%q%?1vzKM`$O2y_KPZWmLRpQc)~utuyV*D^T4_R=(ANVBt)M zPmA~OH7J^kU_}*G7t>CD6{Zq|1kbR;EVJyQ{T=HFN?wkq-u~Ca%q(5g+tHRdW03d6 zuCFFw)#BzL7>Qwy&%J?@6I0Q1ctoccA1~)`?LB{Igjl6B7NiYrqJ>(}KksfmRdMb2M@j-dHb_h{fL@QEZ2?hOe_D zMEyv(!Ef)*AZ6!^uxpP2^>*hZg9yhXygYA%Df}6eic1EFC?$1toXKf={F{mSX}HHkMV5YaCUT-P zPO`)^hndShB*ilb^Cur8bidwQYBE2QzZ1!=R&Enabm@!iiOFY%an$RmG8Zw2VE?C9 z`1lq%P50$mqq=TmbfdI0i^?Q_vJ74cKIMPx(*YC6U=KRj%|F)l3ah%>qFIM{Ub3zj?JF$`I>K=?9R?R*JV(0)5yEboe!d8=Y)v|n~8lb-{4 zvz6|wUXr?Xj5<3ihkiz6vL~Yo=Kb(mFNsn_^62&7(Qo8xj_V$DFQEj7=v^nRmN0)f z9~SkrjE8x6N1!XO6kOK>NZ>ZOpFnYTV=s(Ijtty3WTAy8>t0bNIEjs{+ zBk2Wp=IPXX-|=;lF5l3K+Y&ppd}?JKvaVw5z;hQIOhh=DU`j4WR25%8QyO$>QA^X* zR{&BE&@mNlBYXGlLM}Ih*!Prju)u$~i5UB}vLnpl`ensv)@`qyu|4|{x1-}rt_lMn z-xbGXx|wryPb@h(s=-ISQGM`iuEyQ?7OKvK4ka{yy6Ak}_HiIJTc7MwPCvM@%xpZD zP|Pa}NWk zw|bMm?FzY6F_~|CipOIE5lnyIk4Kj4mLZ)M2QKMEUP3v$mLTHrb>k+daMAFZD4S}+ zq1y~CAvfevzNZ1dLJX8MEHwWlX#9?Q%ypqxWWHSVO!oZpn?>n$_8K4aMS8s=O;}x` zwyk1t&j?&HMUISx_`9$4p|wcB%>&LxG;91EY7q{#JWC~QNYH{iiwb`XD_G77G`?}E zcbvU5Qmdsj>lkf5d-qN)S{$pNC9R_%)WYj@a-zIHQH zq+#;c52Vbky7^Ot@*jT|1~8P=S~(?1n-A%-A*K{xE(7`+ZxL$VVojgz z)y2*qHE9HX*RiO9t|Zrid%NYvK3++bY)lv1(8FFSu3RH0$8qENa^irS0>j99s5}I$ zqxdhOfXwe4F@%3-;qlLzoo8qvGDhcah3P2A8>{ljDiWWYVx_=9o~1@BtFlC80g;dY z?iIsb_5M9?IQ72_#%qwFlhSEJHnatL2YXRf%mI7u{mmj?)Ued(|^MeM^NC zpRJf!y6=U&?e6=W`sWgl$43phJoPF3kPS@Kc#6AP*DDEvi?fSp9SqV=(f6{$%ZMZk zuzjA0)itGOWMt398Q-u`h)h12?|B8egy}wfATfV_Me&Hf9f1MqAs5k{aiK1>3x)&x zM@76?7A$#J)C ztB-$q;szdGzZ7FVzSsR#RlLEeY5YLQA$7!J2Uv!W>aGC}N95KLa}&L&PivI#W|QkZ zXZ(#I8kZt2RQ9~jy5dP(s?>)*ocbW|#q+l6>6xfY?!1X##{IrUXI{oz2qjYCkYSD| zJ1lFh$of*q;5&e*H#Dq?Nxcd!oQ>@g+Op?; zv>1a{!YEW@Sjmv&0>^+LO8>UGpg7)LBm;ku z=2|>zRpgAQfd~=yGj{4i)ft)>Iw8>XaeK{X$f(02oH1r_xM{j*K6qUalYg2x_ix+I zVY3%%;Va6L5Kt_^IlGY3B}DM>bwFs`I_EFSwSAGa{+0}n+YlM(92vE~>Imv;VB{ep zFi*#E=MW)r8EJYH#)hlO0!%8;hfseAh!Z~!QU!-P*5;O7UfZC^$}IZbt#{64h+V@r zY&Kq0u$jOlb7i*>C-05Yxy7)jC2hwpZCY#qI!6#$<@ZfP93cXzn{(Z9K_Za-M2OK7 zq{T)91J@tF7H9^<^3OFsAGdlM zQV{=l88$?6L2k{~${u81V>C?N+@zvi^-!2-4GY3+MlD5Z5T3vd(VEQk(5zx%I8rZECB&E5O50sQzFM6& z293r~w?hAcxm>->WLhawQ2Cm;=T}=EpIXocW$~9POk-2-X?khAhCF|dkrYY))Q*@s z*PjRp6Ik7@jcXsc#&DgIa%nR+X{BS@kVp9faEH;9sFd`&6!gb&0?M<6hEouQ08y-SHh=-lJBfi%4~{HiYKTd# zR~hkF_%j$iBVHx zaK%y|0(nsSNI!o^mLnR(y_wc6F4@OUQ5-cDhe$hqu0f_HS>6W?bk3|fV%Ep& zp)(_l^z%Ki)<7~35Doj2EnXXiIm~Y zp$y;zrOo8J;hItF46R<9G4w0{5fE6iXr^f*a#0H+W-_g^rvI=HK6DTUyRPjF)NjeK zvg7FTC_i@RsgF0-9lRGHQ0I!n1N5dTcIWH<2#+&E{1vW7@AvF&OnB?LEyy>hL)(4? zh`gV1AVGiAAVtwIP*KtIZOvKGx*Elh&s55ztKt3+otuDD=+)19+uX-mux$~J&o=$ydCd_`an12Lli;gINLdusF?qIS%&x@ z@XUl+I>9Firw!QM69Ow6Jy5+a zZ&!*{do}n)L~A6GQh3ltj~$Lk!Vkia^MCUPKNOj3-flcurF;!e8gF_Hq~78ffkD^i ztP6j#ebNASjw5H^)dW}jqQt)M2^0g#z+mNKh}95*aS547M=%pqQc=yf zqk}|4*w2UTd-eiN^biJ@N#Lm! zjahFJhaJ>WD1q(-4L9ISq9n;3Af`4+0^v||CJKrGelC*`>c$KLI60G_y+oZHI^b3c zJqRv2OFH|jqV>qoHotNHQ)nw_RPlc)GK5roFEOoC^~Xyc8TV!|C5ZeYY-zE^(~-9i z9JQb9c81l8fE*b{pPgga(1-LOP*sHtScDJsp_JGMrWP=fz{R)m1(rdvu~1(|mLC03 zt`3`Z{=FVnSh1Hr{=jxe?y)_1cSdV8Y;sJN4=%50A2`TTLocUkK4G%Ohb@0j@jm-^ zTsq*CGR$0d2YHu>kJeYArMN$br0y!&^=%`(Pbe|A6gy^*(#C+P=m8q6T!Wo6npxo1&#izRdts0-Uh;PCyxr{G;o$*x2~nnSmYs6* zkvbDh3AUYM4e(no;_s<$F5`{c2u_qQA573j;E}zjOM4+;BrjFP7OY4m&_!=YmPe&P zD7F();&Y^w-{N9XmRS1kxahn}Yjzq~%26QMQ*cxwoW-ovvCy0hFvx$HW%FCJ=QYl7 zBhc_=8k&6DPi2t;hwb;7m2H~(~PaF&m9m{ zk!Jq1`t=h~28^&G@V|jBiUX!dy+q5!T6W!5fS38?s0_trArAGxaE__+4Wx>^9<_9_ z5C#W(K9SA}-Vp@l3TJR{)nm?xEsg*#vNsztH)EOF*ocu5$tb(?8b&67e(qm8+ zR4A&o+8qlCQ^q=TM!|-+{&b^Pkx{4$3@w2w&D!WX(z7<+hRlC{7m@8eA(1y%M_m?` z4Y4L6oY^L$DjX1uW84zu0B(ZXYe4b{U;UbJd}-_$)>y%o0}s6u)(S>SkyE~4v&xeP zZ)c(J`2!NYCwS%yh}R|G##DHFVy)58z`9cg=1W^do;(s`2;6jenHq0CB>tBX9>|}2 z1Y}1{s-M{|0PTNmVi9p>`}@deJ&K861`#c)zw^$62TgBlW?!^Fq(yL8;k#`48=yXs zK$1$g#v_y<#%sz~>OnK+{FlBdaRmueC5F^szxI%j`uM_xfn;xp4f21gyK{?%I0 zX1zb~M;1KlGR*Q1jW;QuGQqxYlX*HlQ1-kPVvQ6-T|TK#KApiTg@h~s1$MrW)lq8C znF4%h3IQQUT>gRxO#$^av3ygB8`a9-j42wpps>B&3v?Vz#%$Rf??BOa?O5p;W4^a= zkkO)!|HFSsTgVm$Vv%UiI0_nOsZ`d3J+Oy^VG(&*=InCCqTurLw2Re1$K$sH%=L92 zY|B$aO`g6dd%6Xy6qH%fA_wtZH8pRi=96|e9DewIAax}iwxY}BhFE3|hS(^&-&Q{W z#)+ky>tlRb)w<*%mZ>J4cM>{jf!Dq(b_sgPqZ5D04NyVE%bQiw*?k{hM`18~j4F)2 zDAF(<%yHcmW+J8OK6_EWQ8dejhGPt-pP(RM11k?O@SN#Y0X|m4(o>wJ%=ksY-DbnH zISnLnQr$*$934oSp%?*E)yS1&q)V@Zi*2%;gEMuiL<$)%2Dkq{Lklrcvc13yF^nRz z&ZB=mBkh#>)e<`w_Ys-ldSbW-Xm>@wt6IYmy`eEJowQaE@|8GYA95hv)v;wUBp0O{G#_o1G9|o_vn8E-Y$ZzJZ-RFRyOGwdKmW!CHYCh=B+NA z+qo`K`W*{EM!;H5z}vV$=UZT}`7cVe!(Q&Yy@TW-g>Cd4SC-BAiN7Z!YR=Wx8TdJ zv!^0ti=tqt5DX#p-T4fF>MdRHm=V9qV90+qaroM18C}U;Wzeohyk)Nu&AL!?IM4M#!rL~1 zflI4GBRcsU^0UdUOx1muhHhw9TeCpV?w_ z#+t|csa0ohB3XZ|s|&0O@z&p0Zo#jnyK_7$p_f^O;TIoz(S3L5+7t2-NiU;B4G&O{##+GZV732bMeQ*TLrq z8b8DCubfd%b9AsiBg&Py;2OxN7nBd#z=$QIZ_^M_ReZgQ!8~fI8g2qyW}~iYEbDG_u_j+y^jH zkFnM5U_=&ca-O^27Kq$e%#Jem{o6ti;%~URp}KdTaF#I3!OcP}gb5uive$Yl93O;2 zw;+LecwC{9Z)JVc4X?qbV%IT-vna0+ez`L|n&Ag4HEWTRfb;5&=B0lZHO{*6A^!BE zM{du~X**E(oyX78A(UxJW9&Tl*M_E-7~Jg!dnet8I6{-^+=8fwRNySf6QPvoslW)g zaguV8wJ7XkO%V=bNi-A!W9(|Tc(bJ_65x;BNIr%~0${r&b4Nl1$_3jVR zHLoGZId|PptJa!Y`>9eERYK5J;uj(;noBup_l7wtF-nCspCW&4b#XT_%CM@fKUnH4 z@@-^?ozZOS!YB>SuZ#s%X$99cTrpEV0;J0n;fNc&{IIQNijm-H#h3raoyHl(7K{fG zu}PxlSUz7Xr9DO)g2O$2etfk2i8(8JYFSl^AXf6$_28Ye61^&3M)O=lV@{~7&Ko+x zTHnOg{1e^m`v!mMr)c*sND#E%6kb8;rRVghfMJ2%Y9BGiZ`%aSaD67F%Wyn-X^qTj z8l6-;eyQDA{u9neaZG$)b*tPypw;eE*rFCs%rS8ep0JRA4XK3s_V{Z6;-3p&sTv1G z63iq)8HhUHcOrs`j|{a9Zj-4AmCbcl;!zwGQ;p5mcr<@$L*95N$9@R-`Wlc!U@)3V zRAJhFtH?o3^d*>bZgPo*1(@hBOnZ`Z)sq>;HjaiXSUj-I9kGw}=zaRAamt^8o4B4# zXD;YAz>czG9Jx0IR-gn1(}&X}iFyZ!MlUFKt`%&LD%rFYi1NrB4<3f(^GPCCYUW3B z)f#D?xF3I|0O+!$NTY=;M?G>iriz|`s`l(t!OP86cLy)8yHYr*Gb+hje9%-FwKw_2 z{UJT$^K&aI;%o~&-1sA*gWJwKw1uRBp$2glM*#rY%`t?Su(*V3tPJS=d0UcF#V^pk zt{u=sKJL z*O=3HV|*8TZ5;&O=;}@_Uu0bPmyCN$6K5Q5- z!v=pBpPOnMEhz!wba4n?Y9GD%X>iSa@;yJWfLC<$z!`bU#d>Ng-bBCk7l84gR+4bI z?jRStd#@a7dGfHTK9)b&BD920-l|~;ZR|%?Py=B-LvWj;E@qgnbK7&zUx*Bdd!p@{ z^7BLglEp}qa$Ddn$FqzaYLa<aC zPrAT`YgQ+_;1gXCpDE#>xDD|Eln7#4>G~s#P+g)lM7Z1Lsyz3rbrMc4$X4g=L;=b@ zc7T=NA3~}c~30t=GCTC#FtOPNgRfr;OeZ8 z<*cyn^Tql89-6bh(y;77(QU)Kwv^5&z8jq@XlePfI}stYBi_dDxF@Y!SK|*R>ez~! z*eiSjl$$()z8Tm+P^-U)BkzuSliDV88f)!;9NSMlcfw^!Lsjg&Kn-24)#sRRm$G|7 z6Fo@z<~<~RP>KbDc9ty5Q(+_R__$(S!0V5L$6oQ`L;hCUAa8Y8hoysaWFTd#7=ieD zvp%xn(qaEhWSG-d<`E<7;ua$m?^fK@OXV8@qkXQk;M?)-K0;Gp?`}K^xk5zuU2zQAT21SQ&4Vy$&3hn;XgN;*qCJ_1=26wPPiF%Lf8!9#P6ydm!i?zD;7tbb1lYtGF16jeSQ1~ zV6I%;&vY^9arpk()(}I*;Rvtyh$&v4J`)vYlRW^(9nWiaNovD08=Wc z(uaL3$H1Mz3|M%CYBhYqrC+kOcB%77f|X-SKTl|d=!RTx4fbR|zWGiCvG*iG2=CIv zHw?^8Y(1rg_Tetg2M`u@gVsuaw=EhwImjR-o{n9&fD-YGavo5rG|bk-ErJa|x64|S z40tzJrKxVJ>LVDJ;pyi~(SSRu7qC%-Nao)*IDTyJZVU1GH9sFExDweylWghfpe%ZI z{gS<*WiJ7O?q4ygl|1(Yo}Q~O5K$x61<#2Ezj>?pvT(828H0KSr4ZhK{hY-%%M%D^ zVbCGWYf#3f0KPR2@Wdv~aG|fi<_FRX-2v)S;Z&nr${qUSYlzFCdPs*0K5A}?!{>~7 zv7n#7P4SmARY?0z?!TAdv_IaeRR>a%4=!rjf zF|>K7{&cWvn;FS%6+Mh@bXb&xzdW&!*F!=j6n!7X1Q_{I2tYc_=Mz((hzcB6@G zL+O)iEw7m8ks53TKg&Sfr+E1{wANYRsQy#c9&zCyQoWd|1xvy+Z03f`X5T4Wcl@nf z-hu+&>fD3Lj8D#>uE153cz7fzz1cLse5(+3r+zoYsF1`t0LeOXF;gADxzL4R@NB_D0H^^FoS zYp?|^sJb>OlHo;33av+VBsQCWbN2#-Z= zad;U1yh&r|i0S?rFe`81MSD(g9Qw|G{$fQ?ziG;j*d-2Jn&x&Vi)7;t;8Nl4U&Y*A z*UjS(y~LLyLI{d;zpyzo@1Qi{smcp*Pqt-}1;J$Nv){YdoEm@>H)G+{Oh=9^g5FDg zn$2j|hszXy-gzjiVqep6F`87b;=;2TYV6=~Fhd5TDu=Aydj>lNLR{t74wu5V?PO{J zC!?pq=RZ_Cy{mI6!-AJtR^RHTT+-5a8SN_0%Y6)I6K}lNfBlJTP(J~S`{xrO!?GmD z{LDO)#oCwHcY);BrodGK!|1X?z|@dY;#k*|9Yke+s9E^=~Oq~D&@&{m^FMLx3$N=v271|pN?nHgQBihinOMK`vy>8O2|R9ZlziK=XCD%c2kh-*BIT8cBi~T= zmv|F@c`&_l*jPAD%dv!pSfKVGw_NYNS9s0@0`V5rI0*dvQ^muH112DZqeXRPmz@uK z<1Tf6G!nU$zxu$?7dH4QQ5)9*G$4HE4?WXJE(8LTxc%rdd^1S;YfC}v^ybkC8W>|H zC3%Y3Xy>VurJv1pX+-segSZ7@h|t8QOg966jc1i!owKrVWL}|VV#kHhmxFND`|)^H z%aC^;Xw(HQk8aO`>CMfUr|+@}edM`}17`eSCEOegu3+IzpS2TtRlNvxon)cn3x$?y zT5v&MY@dk9c3bG19?-1(f#;=q%J$dv3Rd~F*X-X2k)@9zIENCmv#$etV}6mOB=7lu z59@kLSs*T*n(sPU4b=n`dFl^+F~bUhbon1u3vB5%AF)~MTfulV9-#I?1;`jH>!l?I zmdL8#N%UVgCchLFA)0N!IH{-k2jjVbl?=x{>7*hUoJmTsqOw_cJLBQKa}GwcqPRqi zLRU6S0x3DcKf$cauLw46F$-*R;1J<|GXuft|MQhqFldV&e_)r@mz@2D`UOXe*=rUM z8ljin&Nc1;ZT|oR8H>*iDYf^~AG<+lj}d=^c3xmDsi$LS!3$L!X`I1pc|VV$aw-%X zkRRKSVeODQ=&2a3KxrG*aJ*Qjbg>1|b*rQsE~Sr4;I_to)-IEOqmB2Bj^VTZ$o{jft?xZyk-4aKI)`oX~h7byJRsvw{)b=Oy z&TK+sQQa7f#lcW(f10W2H*jBH%&x(cVX5+GKbdeC{q>$yU0Y?cOritu<%g^9ysX3I zyEJw3SV#IDbwpQ?KH%|K3(x6)AA4`@I&wQ9LcT}Rff*cI0|i=nUG9|0ir`H?|liqKY*b5Z9z_TM?!fTi^C~>z~^Pcabx9fcwq7lNw)~I!eQ+j193!E%hLJnu1P5* zhF8-2?W;$+m${;K(w+JTNYwW1?YvY+Vex(kch~ZU_lgB3e7-nevk{Pg;=T4oerg#t zjr|6*F5ndEKyH}po`<8kP%di|tPE7`nC*Kl>n1&2^g;Sn^0Ge5007F9GFT@nr_;Fd zts#Xj13ly+gg!Q&-142MhmwO^pIeSIy$P)0a-^ebWG=Jp)DY+#aqy^Gut)8uR{BlJxDrqy<4j^1 zlh9i$scJnfl2`EH99^B?6B#e@;e9;TvG9cVS!8Y<=fQ4@9!p9|jtuwr?%y$OQAkq* zsjWgch$lyN#K7bUU@3({0|Uy|MTgsDrfG7q#_4Pi_C`=HucPySAxK6{m+FlW3 za?c+vNphPV2>SO1r`#~)3R(}b5rj*ZDX z%BcvRz^0yZ`dE3MgI}2Xj`R3F;`WHMBm}Wnb+Ja>R!(O}sJWLF$bI$HqHOM`=1!{> zjs(YUI?Q=GD8Z3`fUuG?5QqwJS;>ZB8OMJ-i!0D8R4-lMC16)Q+|~w~Q<3028N0FA zh0JJ=MjC~ByK3f0NeBkVbejhA3Aj{HZUDeyxL2IY(R#!%o-ChV!v5xMJ+D}?MhhxgbfR~K*-%L zlNcmGd6Y2;jXo93Swi^*c)1;kFHi>_W+&GQApyob(gqu9hd46C8P(#mma2us`Z|f` z1aYUD&~rqvjZ;jT_RjXalNTs^*bjv&*ye*6WDr~v^?Uz_Ko1ROQtl|GEknPN^B4Bb z8l@B_sSnV9t#7!AErdhJL0F;q{dGft9Qiguf|J!`6=Nmp&r?qD`RrjrjO+EZa>4xjc-*6^R80ya9VZ zp3vvar-us4`@)y1p`XUS914ca-a*-dI_iUCBSF|`D zB)5q5Bas99Zw1Xb^d;HS6m%;m0iwjcNpITS>uuCaS9=ufE9mDhnQ?P@N*wb;xblh= zU0ZB&DAg!fE0lPjU{x^oH9a2n7+dhWeLKJit4$xS9xh`XNSxg#rEeU5lY|JyRE>dZ z;F-dIOdJU zN0bAY!)X=ESh+6F7P6Rxp1#bn%Uw%T>yK&NuEk@3>4(R;WjvA)YNSyZPcr zYsRdI5#8+EbX!{Hy+!i0;&bhK^4)vK{jQp?I~II? zK;rj?$Q>wB-$uT5{f;SGk4s6Gt9;Jz1YBX#{MG(P?9LiGDr}{sNC&G#yNF~&{8K1@ zKZ9$i3G__P_;7sGbi;nS<=Dl(O@M6U!cE9h1NNwFZoS9-3bPx<**dAWdx?(u1%!)X z0ix`?V(c_{_KKwp4*(%C^i|_eJ>g9sM?Mm;2k=-h|F$Mr>yGb@gT+`EPrd;m-Y$cu zji;ib7g-1EH#jlN=z%j_z3WmSA;eaHwXSOvD7C$q98NmjSe~e^_PmgA9oHYU(ZMb%&RPpuK66L`9C>x0ix;tGb?KgmE z=HJ5TM{Z(+E8{PfJlKGc{DnLDl~keSfv}sMOH|PuSc#6M%1OZUK(%ia4EN_Cm;~+S zvuslUtdnC19>&7XRhQ7nA7 z=E+cvBMh^e-TJ`7GPY#it{s8QNuBKg>sdr7vf?v7)jSs&v*NzV7wQ-CNZIa9TZ z>(}m^@Y?bQ?gD(A_5E=(E5i|}HVJU5TWpJR0L~%K;MpFa-%2unUgZrxaPj;RU9q_( zFElQ77680$x@Z$Kcc}Rtt#Er^3n#26nwNdTu6%w=uTRA) z7TRz%-meCTy4{L@I>5q$VouCW`AsYgCVS=jdt4`sDd@9znSuZFG>slhf|@R7+^>AA z(eoXXYe7$@8V=JAcIt{uQdJ*OgR(4ITSN>Qa|z58`@`|z;F~=l(5Rc_h4Ym4%grAKG|JM0uz<9{p}4lz8h@ly9GZz|vbGilPZJV14-juK7Id zJcpR<9_IQ;>~uhQRr&71KkY;E!UL9=~={Kkt}W zN!9e^{r*#bhuY=_KN1ELQ&}=Z93Py+i=7AP1}zXK=2q$q<-!}uaH};WfX0K0i;gts zT}=&}9r1TcjbR7U8OQ)BSOGd)aNML#d5=jM+qdzQ8lcrmtazyw*u~;N>xCqqaSE0J zzBOHuHJMF2^G<+RIznbZOZvSPSsy+r-&f@N)hFeD=)xYD>at^eP!okgG?#z#6&KXy zsoxT|R#eIkh2<((UfLM3n~YEf4jtJ2h;+dCZqeCy zMI&YJ+&}Mg+#7pa53I&d;qp_WVFCQCKAvbnoxMDc*#+U!J+*6#gW`7?6>G7!l8y&O ziw^I9j(c}TlG8wV`j!&U_$^nrre(h555iWdEAu38e&v-!h=Y$Lu(Xr@&@_%|*CKn9{D# z9&l`^POT=~!;{8l!s3UhFO&x+{1z}Bi1Jx~58r1Uw?LJg*nkqQUROlQEu3tqs&gpP z;rwAgo7zz$CgFF=pj&1OSgt>ZBs5#SCkCPQ=(cww>Env@8W!be?y^}-0wedsT%^HSKNx@|0f z30zcu6TjW0MOt)-0l7*cqs6{~ja;2)#8BQ$ctr~WE@c(E%PUXVZOt7ldgPO=`Y4jA z48Tt%Ka)wKqg%CEUOl)@Oce7q7P-{opDds}vd!x=KSn@5P?TNpU#8Qn4U&-che^Z_ zK_2#miBm#sgqZ^>Kj?+A;>p292QqViX(p5*Po~eq*}+pWf9`4l<(w4BjAz8f#Eu8v zY1Awqt*?w%z1>!M0W4)Z^20x^K^0MWij?>!PgTZlIgNU53=LK4ROwM^b+!$$U7i8| z!*LnIuXR`A|c_W`CiMdF2JeeJO~{UQR|fKselh59 z0s|p!E#p`QL&EP(YE`wbp~HKB9cGF-S1^I;xkSL!wZT}%VQJX1TPa+}vu!g0hZY#} z1&b_8y@}!MFtiBvhnHUjrprNVzb@`U>N+YY!(HwO93oIDj;q$4o<* zGpABh=W`<*=a=>mcHchb#MVT=8s;;=oh#2_mL*xhvR92GV``Mj5ECYUn&jPOAeIL0 zu=l%(%P}z{TyPxQVtVhuI4h}g-=Yg+VLhy-3-<@cX09r98SliEgDC5V)zqzeaz4Qg zHMlkxmIaGD0L};}qDz@?l`p+^)JV=Pjj_*e;4sT021HP-N`y4N z)&0bO)Z8>vF`D0M4IXr!aYH3lvn{}#eDhq`mcgx&&_f*+(dJ};FN|zD$`2d-^Xi>0 zr-h9*iiM=ULP;Z`mj6OAmrY^xA2^{u3;u1HNdZcxi^2KRsZl=V*!LJHRKs=CkZI(coOt?P}nwKe^B@a3wNV3|H-HX+2bYRAwz+g&1A* z_(U-B<$#_A)}G3L`(&f!@3CT_p>n#Kyq6mNxOQttUiFoNh|Y-a528RXigie!`rhTd zXa<~ptkQF}3&MK%>lmb57HzsLm52T+a$=b-z}7CAPJ3IXe+pgc+M*pJ;g6f4pWm~3 z%ON}mFR!=nlI~;tdypG9;lw>7aPAhOOzMv%>3dx&Jcv<$wG+cqg&S1K{o1_u5;Wq4 z=iN@h0x#ZGXg{`<{-|!a;Yvar}A_leaUhcZZ z=b20v#&@&=`MadSDKa+tD16MzNhe%s?W8atTe<_2){0Srax+-Sg95hjP0vpTag6Dy zRsuNoMe=fgxcg#CLy89xMOis&%;Y?++(-|A(feb@xQUP%)tOD@mELFEx4qA2wVfkJq-p zx94+zwYty#Ik;H?nN#FhcgHmyh89HoVA>vkmbeGz?7&R)m*^xI^H;^P)d3gu@40FP zXD=l1LZrc1ZRg(-;UZp$0hNjKl!-oosit-H58gBNK+_Ma*ZjI13PUBDd#CKi0`R%S zo>qTO$PWymyQTje7u{;C6ds~d#TN~0M?^1wdC2O_@>o@g|5$-a3kEDlU(|wEmblB1 zw9AEQ7;HL{5o=kUaO&$UpeD`6d^q~9LAY!tM}QL|^xT2Pvas#1ZjxmGZCr?EuUL5* zc5|dO%~5N5|CW~+chE?3bSUdDUM>LPcZ^e8IJ{f2qj2b|RNAE})63eT>}Xds$5I7< zprebgHeD3FCB0o18#t)1(G_iVcbzLM-he>5hbplYUM>v#I?wHN5M^Pr6pfG3LrGLi zV1mmL-GD?duuM@f14?IyJyfY`_UET>TA&>cINe3;#%lzo8OBIhJulTT6T-5Zpb&D) zKq&E3t!q{IuO$6{q|B;% zD#Q6;uMGOQ>p^>_Y$rrp)+^?6=){(IQ1bB;Qc$Z30%f=pVA~#47Q5?~F&bFwG3mDO z|F64Pmk&@3IM|jV{x#U6k`O?OpN`S!Z%F*kEOd_64jD>uc~L*}{Y~qzm*LheKGzz< z$+mmOI;T_L`sMDgI+`P%4|fEAeka<-CA&A2`)A-*i2FRKBfx+~Yktk^_IXr|S~Z!i z&P{Zjlrax7_S3PHu(P9)W)Mk4GD>HAeS~qeQ^X9!|i! zUO}3k{|Zr^lt=>qEPJHfQtST->}45Af_!#=f+3hkTa|`|xwL3k_zui1k0zp{!V(X` zO!NrSxkiV@H`iABa(}YD7d9+OpOYE83JO7}Mfvv)O&J;rbUWW#LD6#H86kDbUM`>E z91;A6CoB5e9uy_AF~Qb~ZhDuF;LQq-#I60eM@4NmH(F4edgTI= zOc(ig9(NotKp*#eb`)wMc-SH)9Ct{)3C#vR>zE3CFB<`#q~P|I^pD~PG^AEs>u*qr zG`6&p`t9d`A%!EU+EkVY$Ex>s3Ud_-W^5DvYu6cSpODZAp{PoK3yG4-I9dPXyI>kE zc6J&1`kN9*n-Z)!a=XRnfz$EE3c&({42PbY5ajG*fMFZ73yAu(7}*F3^tZj*DWkil zJaG_}!S9|i+s6O|ezQ86l(6iSse@w~Ns+TQBSc^t2N7drT_P+is=?7{i#3k?nwuj4gr>U~0{eIBYGw+CJ zs<*^ob!qK-JX#!YJkc;UkKEwGOkg04Pab(n{cA;8sLd}H6?q~8X}oVlxX5>Ryd(VY zS!lWm{bGeRlScsw!=}2oF0O6cik#ZN2uM4SW7g4dA#$95ID52(CB{m774S6R@rf#G zlGHLRC5gZJ)>EnEp0*r_J|cjK z^r!mN4MH(~O9#~sfNWuJ2pUwby_>fM6;nvF-d0V(X+@R4ot@GrXve=~+%_5Yq7$kr zt;1pD)c|vU_D>8r* zK+EUw*TJ=N1>rYWI#H7DHQ(3_TXQA1RCy^N)$MYB%3|*edQiKO*v%%zCya+g$VSr- z5Mu3CFB>kazVj$xIvktn?eUYt=@mJH(X5Wk%DTPCinr~L1Q6~}w<9s}Qy50VDXxb# z?_N9i<4`1hs%M@`sR9Kt2}@cCrsKy7Aw572rwP_ zgmZKo;AxSfV3**8jVJKX2~4L_)}fh+xLXPkNqgKY)b4ym{0*j#pFsgr>UWI4FParJ zB-l1I=s|oo`Y&&>2dK(552$Ykq6JZZKr#W;k#LT!y9JfU7z(dDwo+}j`ojU|*`|baT4@bm! z)Foq!=7s|x6t=M8VuZ)Kfu%YS*=$NtLb<4M!e2G?9=+&4Fi_v|=VcH~p#0B&VwPRm zluIAEjRr!ylCZ#tBpbm7$~w3M=NIYjOpKA8d3s9C0~AUy*4EgdBe%^*es0`9_C zKgd}BHg~;(%l*oj*qiOx4nLJigC0GBp0 zPM#Rzhp}(<8nW1nRyVpJ_wQ4GP%>b>VQ4Rkr#)tV?Tu2&aIu<>3^u0zWm%O7IjTMI zJ)=+zLW2VI8YI*1|q%;TumK%`e!IXpu^? zwWe80*k0p&kgg{amx405r&sfQQM@#IIu4jTzTEB6_n>KJpWX$7xjMvu6FV0+QBzSJ z{Xth{M?8wEz45D8>qK131G6M?d-|OS<@9(6MffYfa_wMmu5n;H@pijEq`Q7Z#Xs;T zJoM?`v4YpWk7QN{aoc!qJ4JLA|8UDu*?bSh%a|vm`!8#HK=rEfDE69ikP>DU;b%#L zHoOd2*H_*EA@?}<6ky_iYQrH=SB7bw;A4jFB4_Wq=(H+;a%w24IbZFm6vuN7%L`qq zrZ$_P5E_3boqKBQ+xo#5un(`PZ zq)yOR(@g5o?t~uL_mFR$`g$2JGY8n+7r)C#J`LNe^L+gepmw&6qFX(Ey}{AfopZ0; zgUVcO#Ta@mFQ{67vhB@{lQq*=%a~zl)0+-^uyhzJP|@bL{B9BG(i3I`bh)rLx%Urb zd^@3BTqT>IvQ$5?UvnYdCj*6G1bLe2=@_gtl5k_G2J# z+-GWtAPtVMuY6SI&j+$>93wiPzl3~O%^&1O^0Yv`i0%Y;_|1|INW2P6pt6EO&F@Aa zn#P$ij(Cs9ORqP7+^B|RQROC)lvjWYQ35`Qdjhqb$`q%wb6Jfj6M_at!s^=R#b{b(VDBf{ zFdV~`N=$OL*d1c%Z#qo2zmD;u@>Ee#NsbT})N`$rWqBS8#((x74y_;ExNdZfsvSOW zS15ZifvDKaIk}4#L2-CD1q3PZ8n1)#g_aYujcw$AJU^L~nJ+@*Qyr*sH#|k`gF*Fi z<5F)<%f%XnZEh|@7d=7p6~+-;qdcE#U#lP{w3gZwwBtC%;-fm^nSoVD7jH7VVC)M{ zmc2A;<2?%T4}w)kFTqXm?i1wG1*Wyd@ zRX(IOq?rCs0|U|lhD9%vRs~(L z`JXFHXczM@96iNj`+#K;mT%q=8E@0O_d|C~8yNAw>7kA-;iuRV+Ce)3JR|nRL#sKG za!DLSFi~dOFQb-{s9l270@PW8#Dv|Q)v23*>;A4D4HKa|#w<1ig=*)X7={uWvgolq z&z@_8Tuc!J91}b!mvBg-bRfZElNrLi#rY#5D83P8Tt7>wSd+Z`4PSl5H1w`N*3zXW zZ>J?`1|U58$8@HuK-PU9jzw_1> zLqO;S>qE zlnr2FC9jT^eNb+fD8B`ZcE2#=M~?@8;$YCyWXBI99mC#gDD%iD2G-it1G}Pa#2bB< zSAp`@?(7TR=8IyDBEcF8oxl&cXQyz4 z^Dy@D)#U4YlYpKit?>-nsK4(r>XC(pq)qOw@{;nUro1NyKiF+-P4}zcf>k0&IS*%% zctJwL=z}6N(vo)>$oOb>5VZdKk=k|mZ8D4D!l5{5U2~**J7gaUpI(WFB zO+h@A`*dx*)0uApK=o-9HXg%Z_hK^mugkdR}4;}V!5*9VS5*7Wq$VI z(*T&NC}v@40!No5zDwBt&9(>hpo)U4<_aa7m~HPWsG@QjXVF)@b)255kgLACe90E4 z-TwF0KKh#wQaiBjegeQCI`ZYleQuOc-$RMm{S|_3U+z1>k6Qm zbL7+`noFHG+|9(wV@Kns?&q)-C zX|uD;$VW;8=0;BNU5Lm#T*oNXU+3I~3Cy|=zKFC;; zBBfsTJTDl=ahzY7D`8CCn3Br%s==^$7*TS}qzQs-Z4nKluFH-yw1uv_i-3W-VuOe0 zfDqg^Gxcja29L{sT~Hb$+p4B@BGG=><}!FXQKub^IYfF zr*oEKw%GY)JJT+6j6?G1%;5y;y5V!VDb1H0X+9`5M)kE1py&XMl9;K#3wuDQwxPzn z`zC(xKsw%FoDj|?qN)yaq;uUK{~-$ z)YbQ+lkWnw&7Z4%SEhyIgLmCH!@D9oXIUaXEF`6}aZt~lm9wR2{DtOmc;)4I9amRL ziLN-I(JMn)y*)Uu{p$<$a?1tZ3d+XQBA>7nyWduS>YpJjw6^GmWc2EZc(efh7wt@L z*`odKshXK(!+3HB=-YZ6^6vO{u5(XlZ;~THZ_@&RTkU)@?kcCO?PCOSJ8=H0E1x(q-PM16Cw&TL`BN2|$B|T7?QglGRVj z>1$ViPAv*!>^@QTGPaZT)HT>9^JDbStJgh~qF)vQi$}_L${C<5r%P=mz2g=8S`<^S zt=+R$k*Q{hSpQxNZmGLu+p*Xm80GKBGysV$UTOuG$KLZ8(7rJ9Q?Uh^iZhx}?E{f9 z9${8U8j;@5xSTQwJ}L`eWuVib_cJQT0H@x6z6WlJZ^J9A;ijUgImsm!-cQn7{Cg2; z4Yo^z5gkp(G+yjM%3fxdE&EU%*QeI7N*@!XHC9x8!(#qkDxHmst`vSX)2Hjsg2aq% zu3?Ue5K1?1%-Tc+ye;NmtDS~CEA>c)c?pT670>9bQgWKd*b6sZ<{evcCw~0lu<|5- zJ!3sHS@xK)e7htU!wgv%hO7LkDrH(yRTM(iI_k&sWcWpoe}=E>nuF;2hYhZ=W8CYJ!H5@A2+}yWTgR#I1>YU=nhrg$VNwrl1cQ8OIVDeM{*+@NRFI?122W_ z@AP}_jev?izl|+v(VvY`ZJsqb&B&yGl?KOW3r+cpw_`qs%#f~|C{gh9O<8y#ViE$F zW33P~scxeJRTkFobf9f?QmTn+iE#WfZbP?sbRZa~?6@&Cs;6G|{sMPpz{$d##79D> zW}Y7CqB^Q*ubOP^CKSWc(sJ@^Dr;|~h`k_xP9dN8HL&^9$-B|`yF$C3N3zJ zoWm=#$v*+PE8mQ~4manu@)&pix(L)2$%E$$ ze3jSJqG(r1Q&#wym@}c^2tjnCFjfD6NPqx0-ji`n%4)el4ji2dWo~41baG{3Z3<;> zWN%_>3OP9-Fd%PYY6?6&3NKKXg`NWz0Wg=Go&zZdF)=bSIWjVr%$@@r2Qe`+GC49b zm+zhfO*$l313NJ=!a&vSbH90m4FHB`_XLM*FG&eXimobI`D1Xgc zTT>fJvVP}R^y4`(VY=>@h>4Bx4UauG;{m+Bg&$-PptFD&5Mz6P{mJ~YTB=qfj0}$5 z2ve%A%Fe9(@={qP%QULdP0Ed?&)}Ne81EY68fU3%8*f!(auZE#Olp!&jWtB8Y-2Tj zX18H|qmB2Cb&a+zG&VKb>)hB#41cw59MQ*U8b|brBoK*FE;o)i8XFpyNSr6S%%6F~ zlfW2#Lqk@RXm5xW@%JP$23irZFq)n{vB;_MfrjWM9~+-Yu1`&HK{uXOO>#DZY9g;A zu$s;_!8F+!->|Y#>=%91~C{)AGm&+N;cu)G?Y7rj8|O4R>7Nar)<3G!sX~C{rg{y`j02NiXIZRE`Z% z1w(JsJHaLbls-Kzn3k$Th<~;*WVDc&6%7W$t)ZEy2s1~ki^O+>*yu=>Y%))gz8k;( zy3y`^J0Cag>(SA8qkTL*n~l$AmyIQ7+u3M$#+TEpi~aE>c^(E{jSnWHN7Jv(M@0jH z))}+;v_Y?5(0e43ss8Z~Fy10&&9A>U?G~Zoc!s;=23pN9xwJGIW{)U+3wxHnVgnX(wn|5z*`CrT1M1ZE z4O^!46}wF7J2qY68Q2Bx0EzL-kQn=uF{yR0G3j9iufGPL8k1{r=wn5R%f!3jW7Pnk z^k0Tgt#6H050h(g`+reP2C;7Se+ZMFzPG^V&hcWyKzDbiM7PklmlJN0Lst2G50kn7 zFU8ax@*l+^4{(UL!ojI~Nv5kD;x@r>=cM2U0pRq{P`=&`)&-)MHLs0;zIRY*<=ibm z`A8MRrfsf?<$rOZ1QXtB=P&Gc#GV>T=``ar9UR`UvM;t`WKQT(Y* zE|!(1H=|*m$ws23x{SEgtv1BUbRS+P=;Y{iDl+*EpNVg9hBc!KJSat@LGfHPjFNMn zWO}Ws4S@wa#eaROyDbxi%r9tWP}oFf;Ug>PliTDHIY2E^cT>}6!jet)tQh*9l(g6M zZ_{cOAQrE!`|_<=mygvmwe0>(@74ZTaBLuHZ+OX&mzgp|*m(k<3e8)zhMY~8R>7G# zoGkI-@QD;1fer<(*p6y*7}$tQ6KzZ$?xk2Y&vx|Q@PCR!VkgFtg%;1RB1R}e=@0AX zUcy)cQ}QeFq68tVEFHh1&ImrkVW12jw>CLF$fwI0Pl`i}C2LF6HnBLDnW@9LH36>9 zo=9gA>Ki)7n8a=>)bvbk41sYm98eOr!q+8sf2O3fA$f0Pgp*~SXkFy6k=9y_dxQh6 zGIec^9DiD9qh++E^#-%jRy^xAde!?QXdD~`A2Dl=FtqhsbWCE@25nNjwqdIc7Fs@% zMnaL6&ba(X*5oL@u}ujwZqXL{!h0?Q5~WSRQfoX2yaH?)(q2ApdQx~H11Vu4TvxSp zpar&qLSNhsANiWMlu{kL;YjT>Js+sr3Rm*D$bZQhu^riO?$BE0u-U+Sf`aESTA?W; zmir-NTcNEYHPK-^i^u@9IWPy_L50#L&Kuq+#sGEap76dI?pLm+ImE2>hT&G88@D@MnbNW71l@=&YI;q#T%hDywiDW z=6@UlHqSztwAd1UBHki>E)JG^w`t*1zWm+(wOcSnbNy&1Z!uC4FP`gIzLwNPUno~( z5af2rrD%l$s-jdWZM8^|7Bfm1-{o`ipQz!Ppd@<{m&^rDa@e!b2H_L1BXib%AD8(KL6SVT`Tjew)*l#zBswK;vA7Jxl6*k5gMlZVbGqyNo!HQa+hE z2XT&&&EWjf{}>{DzX+{5Cwgci?vdm`?73=55w&w zc!!fp=F^ea3h5ZTB<#-FDZ)Sa0FRTAMm=TW4-Vm^QF&R1u#vh{PEU-QO%_{{$EASO zdN{~(J;;@)jyU?eQvJ}O-+xBD9k9mCX~VOo9{yO)B?=m4SEzkd%$+{jEtJ9KqRF$p0)jqUdn}8%pAp@)vz#M~iC7X^&uLs*_6?RB;Y%9hda2J9qlb@6p=3)d zH1({NlRx@0dzZHGM1Lz%>ek!57zrGgNz-Z!PP-gY4w*?)Udq^x5zWq^a!q_YmNIg5 z3b+(WY#MA^y^txM0(P))S)}b znso?04FSS3)B+emEs)l2?_I2<1~v{{x`KKM?i%5`ZnXWluAJ*RT=7qF#vPqoH2 z<68~uO2D{l!mJK}f^6MZvpo(Agv%d=Wrs5yIat4p(|?LKN!aPs!@X_=g<&h!s-1jQ zOZ#P9j;^U7-^y1zQy>vYnKk()V7V&FbsJOvF-8l?cIT4`O93-D?d zm*&!!*}JsDM_Q3mw+Cj|*L;%1WhAI9_B@Ymf!@ZcIkGR5 zdEv-zbFv|Q(!9t6^t@fs|d6~@lubW`kgsh>tk)28B}-pD&~@X`0#A|m&dQ3zSD{( zPDV$UjT4GT_$K^;am@ph1K;F(-V6B)@rRfD@`d|k;JFtJy&?U z{r3IdLvn>z&sVvEHRKBNg&eN#7M>8Yt6d=^TRDT~$=VqnXxF(zG%MZVVf(0k+&*o$ z+Gp)=?eq3k`$zk_-D!8*z4o8&yLQxmZuh4IMtjg6j8A5x_OLx_k48N5ulB5+wtv&p z@zJOSnzPC12+N2v&0;@wi{(bpDxIg z)XNv`{^(+Q*6vR(_ODJ4Pbi!0PfuvzU^*M^v;214j{mwEowVbx`zNE*_Hgp|xILSk zjoT^xRoSLWHSPJy6$Q!h#dzG#zD(P%6eAbY8rrDWf%e&>$2;$K7}~JHsed|Tb+-3{ zER(H3cA&~yneyfPH`~u1u_`O#!-mdDqPiDVVz`Bqh>2m*Ti9~|!CD#b`SY#k+b;-$ z-S;c&hTJ?r*`PHaBK!gbLgdGi1lJoYlf>x!{9^i5Kp0(IOuvZQ^U9&B3|bmE<+wPV zoDnFeS0}T{`N_8)9BZY_-G3La-#vZ|I99m?d3W}nf11Ew&gT0-W3^LE&JHJMli9bM z6kIDY{`v5aXD^=q^7PHttCjXn?DP@;1%*yAx^{Zq(~ut*8m4?3r;onYughMvjbBc_ zidWalrL|JipHKGQK7RJgtKCN{l_QlNILc7QI@@GZMYIb`5uF#xt$(b6Yd;RQ=f^!Y z)=EpS-n@GI;^i;9TaT!g&whoKOl%%l{&7m=ABNaoZt6Q?R=3JczE;M$eg*fqeS!+^ zdHa&;x9xfT_J%4r)NkEZMJ7FLsXRNJ(9V8Ld;3XyiW=^`{j0q|xpqZ+`)Ov42hlpy2sR(Em(;b_f7g{ESuXDYjPn`F;DvA6pMev7J||Ew2+R zhMz7u&p))P6l14d;lsC8%&KL}FDmyJ?eE3@T)}tte@j)}2YA8i!lt-KSLRb4Bl-L6 zV03w0Jce8b|EQ)poL*hPe~!PM0ks55`yY?bN{J}0R5AwdkJHN&etmyc;Ug!6zuLd9 zrnB+E=MxZg4?@Epc{%=@L~#BQcC%`C6<__@erx|d*lE*RnfJH1d%yqrT5M~ST4h_` z*_N80Zrdkh*}) zHAWt>Hw-4#GJ>T}ONq_WC%U-r^LwJ$oUn?$?3fIF`*d3b+1SrR^g+{B)rRiKw&FLv8T z<9@*LhKGTr^?Wbf{Q{0~59=A$@cs4VVG0Py99k7 z_8QcFOY0dVi>Owu$K1nuhDF-adItXNR{FEO4}6wxXqLQrU@fm#c(YeOAbjZtWl6ZZ zF_ieBlWkIlviaA$m;CeHE3R$lKgP}F2g|=t4yaU=-^6P9nXHjt!W#L>yp=f%Oh4Vg z+pOSi|VHl8EI00kG)FzL%f)0U&==d2nSQFIZA# zW(qG!Ze(S6AX_jXF)%S*3NKS>dSxInFfj@*S0Gz4ATuB_T?#K!Z*O!UIXECNAW{l1 zNp5CuAUQc8Fd$M2FG)loTRbpBIWj~-HZnIbLpd@yHZ?RcMmaY)IWjddI6^f=MMXX! zJTOB!GDJc)GB+?oIWi(RHZ?RcMmaY)IWjddI6^f=MMXYc3NK7$ZfA68ATl>IAeS+Q z0VsbZ(7Q5&Q5c2cwf-M*N+Qn3I40s8BF-WR8fi75Z~6x`O&%EEaXZD`i0Pq_C5eg89Lsb+TqQLN|;9W_CA|ROcZcWUK1+gp^#fsPz+af2n z#Hy$kRYWZ6Tb4v#L_`hIb>)LPQA=dbJvM)cdLn=AF)A8~;*-Z65f?FH|Hr#^F(;Zt zLNtpO(JIiML{jvN0pj4&ZwwM=AFd(d@zym=yuP_cNM5*72mk_oC9SkxxGdD2`B_%~qMhe49R$%}D diff --git a/doc/refs.bib b/doc/refs.bib index 414773483f..97960d8534 100644 --- a/doc/refs.bib +++ b/doc/refs.bib @@ -1,26 +1,52 @@ +%% This BibTeX bibliography file was created using BibDesk. +%% https://bibdesk.sourceforge.io/ + +%% Created for Varun Agrawal at 2021-09-27 17:39:09 -0400 + + +%% Saved with string encoding Unicode (UTF-8) + + + +@article{Lupton12tro, + author = {Lupton, Todd and Sukkarieh, Salah}, + date-added = {2021-09-27 17:38:56 -0400}, + date-modified = {2021-09-27 17:39:09 -0400}, + doi = {10.1109/TRO.2011.2170332}, + journal = {IEEE Transactions on Robotics}, + number = {1}, + pages = {61-76}, + title = {Visual-Inertial-Aided Navigation for High-Dynamic Motion in Built Environments Without Initial Conditions}, + volume = {28}, + year = {2012}, + Bdsk-Url-1 = {https://doi.org/10.1109/TRO.2011.2170332}} + +@inproceedings{Forster15rss, + author = {Christian Forster and Luca Carlone and Frank Dellaert and Davide Scaramuzza}, + booktitle = {Robotics: Science and Systems}, + date-added = {2021-09-26 20:44:41 -0400}, + date-modified = {2021-09-26 20:45:03 -0400}, + title = {IMU Preintegration on Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation}, + year = {2015}} + @article{Iserles00an, - title = {Lie-group methods}, - author = {Iserles, Arieh and Munthe-Kaas, Hans Z and - N{\o}rsett, Syvert P and Zanna, Antonella}, - journal = {Acta Numerica 2000}, - volume = {9}, - pages = {215--365}, - year = {2000}, - publisher = {Cambridge Univ Press} -} + author = {Iserles, Arieh and Munthe-Kaas, Hans Z and N{\o}rsett, Syvert P and Zanna, Antonella}, + journal = {Acta Numerica 2000}, + pages = {215--365}, + publisher = {Cambridge Univ Press}, + title = {Lie-group methods}, + volume = {9}, + year = {2000}} @book{Murray94book, - title = {A mathematical introduction to robotic manipulation}, - author = {Murray, Richard M and Li, Zexiang and Sastry, S - Shankar and Sastry, S Shankara}, - year = {1994}, - publisher = {CRC press} -} + author = {Murray, Richard M and Li, Zexiang and Sastry, S Shankar and Sastry, S Shankara}, + publisher = {CRC press}, + title = {A mathematical introduction to robotic manipulation}, + year = {1994}} @book{Spivak65book, - title = {Calculus on manifolds}, - author = {Spivak, Michael}, - volume = {1}, - year = {1965}, - publisher = {WA Benjamin New York} -} \ No newline at end of file + author = {Spivak, Michael}, + publisher = {WA Benjamin New York}, + title = {Calculus on manifolds}, + volume = {1}, + year = {1965}} From 0968c6005e9a74a56588ab55dec44c4c304cb834 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Sep 2021 18:26:03 -0400 Subject: [PATCH 20/36] added details about covariance discretization with references --- doc/ImuFactor.lyx | 105 +++++++++++++++++++++++++++++++++++++--------- doc/ImuFactor.pdf | Bin 243257 -> 248399 bytes doc/refs.bib | 20 +++++++++ 3 files changed, 106 insertions(+), 19 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index 4b71a29ed7..f76ede023f 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -1433,7 +1433,7 @@ Given the above solutions to the differential equations, we add noise modeling \begin_layout Standard \begin_inset Formula \begin{eqnarray} -\theta_{k+1} & = & \theta_{k}+H(\theta_{k})^{-1}\,(\omega_{k}^{b}+\epsilon_{k}^{\omega} -b_{k}^{\omega}-\epsilon_{init}^{\omega})\Delta_{t}\nonumber \\ +\theta_{k+1} & = & \theta_{k}+H(\theta_{k})^{-1}\,(\omega_{k}^{b}+\epsilon_{k}^{\omega}-b_{k}^{\omega}-\epsilon_{init}^{\omega})\Delta_{t}\nonumber \\ p_{k+1} & = & p_{k}+v_{k}\Delta_{t}+R_{k}(a_{k}^{b}+\epsilon_{k}^{a}-b_{k}^{a}-\epsilon_{init}^{a})\frac{\Delta_{t}^{2}}{2}+\epsilon_{k}^{int}\label{eq:preintegration}\\ v_{k+1} & = & v_{k}+R_{k}(a_{k}^{b}+\epsilon_{k}^{a}-b_{k}^{a}-\epsilon_{init}^{a})\Delta_{t}\nonumber \\ b_{k+1}^{a} & = & b_{k}^{a}+\epsilon_{k}^{b^{a}}\nonumber \\ @@ -1908,13 +1908,13 @@ G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} 0 & 0 & 0 & \Sigma^{b^{\omega}} & 0 & 0 & 0 \end{array}\right]\\ \left[\begin{array}{ccccc} -\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0\\ -0 & \deriv p{\epsilon^{a}} & \deriv v{\epsilon^{a}} & 0 & 0\\ +\deriv{\theta}{\epsilon^{\omega}}^{T} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{a}}^{T} & \deriv v{\epsilon^{a}}^{T} & 0 & 0\\ 0 & 0 & 0 & I_{3\times3} & 0\\ 0 & 0 & 0 & 0 & I_{3\times3}\\ -0 & \deriv p{\epsilon^{int}} & 0 & 0 & 0\\ -0 & \deriv p{\eta_{init}^{b^{a}}} & \deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & 0 & 0 & 0 +0 & \deriv p{\epsilon^{int}}^{T} & 0 & 0 & 0\\ +0 & \deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & 0 & 0 & 0 & 0 \end{array}\right] \end{multline*} @@ -1928,10 +1928,10 @@ G_{k}Q_{k}G_{k}^{T}=\left[\begin{array}{ccccccc} \begin{multline*} =\\ \left[\begin{array}{ccccc} -\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}}+\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}\\ - & +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}}^{T}+\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}^{T}+\deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}^{T}\\ + & +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}^{T}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}^{T}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}^{T}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ 0 & 0 & 0 & \Sigma^{b^{a}} & 0\\ 0 & 0 & 0 & 0 & \Sigma^{b^{\omega}} \end{array}\right] @@ -1952,23 +1952,23 @@ which we can break into 3 matrices for clarity, representing the main diagonal \begin{multline*} =\\ \left[\begin{array}{ccccc} -\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}} & 0 & 0 & 0 & 0\\ -0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}} & 0 & 0 & 0\\ -0 & 0 & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}} & 0 & 0\\ +\deriv{\theta}{\epsilon^{\omega}}\Sigma^{\omega}\deriv{\theta}{\epsilon^{\omega}}^{T} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}^{T} & 0 & 0 & 0\\ +0 & 0 & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}^{T} & 0 & 0\\ 0 & 0 & 0 & \Sigma^{b^{a}} & 0\\ 0 & 0 & 0 & 0 & \Sigma^{b^{\omega}} \end{array}\right]+\\ \left[\begin{array}{ccccc} -\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & 0 & 0 & 0\\ -0 & \deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & 0 & 0 & 0\\ -0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ +\deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{22}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & 0 & 0 & 0 & 0\\ +0 & \deriv p{\epsilon^{int}}\Sigma^{int}\deriv p{\epsilon^{int}}^{T}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}}^{T} & 0 & 0 & 0\\ +0 & 0 & \deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ 0 & 0 & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 0 \end{array}\right]+\\ \left[\begin{array}{ccccc} -0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & 0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}} & 0 & 0\\ -\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}} & 0 & 0 & 0\\ +0 & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv p{\eta_{init}^{b^{a}}}^{T} & \deriv{\theta}{\eta_{init}^{b^{\omega}}}\Sigma^{init_{21}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & 0 & \deriv p{\epsilon^{a}}\Sigma^{a}\deriv v{\epsilon^{a}}^{T}+\deriv p{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv v{\eta_{init}^{b^{a}}}^{T} & 0 & 0\\ +\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{12}}\deriv{\theta}{\eta_{init}^{b^{\omega}}}^{T} & \deriv v{\epsilon^{a}}\Sigma^{a}\deriv p{\epsilon^{a}}^{T}+\deriv v{\eta_{init}^{b^{a}}}\Sigma^{init_{11}}\deriv p{\eta_{init}^{b^{a}}}^{T} & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 0 \end{array}\right] @@ -1979,6 +1979,73 @@ which we can break into 3 matrices for clarity, representing the main diagonal \end_layout +\begin_layout Subsubsection* +Covariance Discretization +\end_layout + +\begin_layout Standard +So far, all the covariances are assumed to be continuous since the state + and measurement models are considered to be continuous-time stochastic + processes. + However, we sample measurements in a discrete-time fashion, necessitating + the need to convert the covariances to their discrete time equivalents. +\end_layout + +\begin_layout Standard +The IMU is modeled as a first order Gauss-Markov process, with a measurement + noise and a process noise. + Following +\begin_inset CommandInset citation +LatexCommand cite +after "Alg. 1 Page 57" +key "Nikolic16thesis" +literal "false" + +\end_inset + + and +\begin_inset CommandInset citation +LatexCommand cite +after "Eqns 129-130" +key "Trawny05report_IndirectKF" +literal "false" + +\end_inset + +, the measurement noises +\begin_inset Formula $[\epsilon^{a},\epsilon^{\omega},\epsilon_{init}]$ +\end_inset + + are simply scaled by +\begin_inset Formula $\frac{1}{\Delta t}$ +\end_inset + +, and the process noises +\begin_inset Formula $[\epsilon^{int},\epsilon^{b^{a}},\epsilon^{b^{\omega}}]$ +\end_inset + + are scaled by +\begin_inset Formula $\Delta t$ +\end_inset + + where +\begin_inset Formula $\Delta t$ +\end_inset + + is the time interval between 2 consecutive samples. + For a thorough explanation of the discretization process, please refer + to +\begin_inset CommandInset citation +LatexCommand cite +after "Section 8.1" +key "Simon06book" +literal "false" + +\end_inset + +. +\end_layout + \begin_layout Standard \begin_inset CommandInset bibtex LatexCommand bibtex diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index 041d8bf1a2d3e93d115dcfee3a9b001f5a6ea52d..a4ec57fb7baa660508d5c6872185270e178b1d0f 100644 GIT binary patch delta 103379 zcmV(@K-Ryx><-VA50E4RFd&yPh5;ylEso7f1TheV@ADLWk_1dlcm9vcI-uam=tVq4 zjS9}rE@5O}-^A>ty9=tns+%-j&Ex^SB(w(7Cy+*|B7w6cb%gW*FD!i*E;MSkmeV-y z9-hWAb01iK-wu_(ruzm9fGDH2)L|k@3I>E$jemyCJP@mS{b>O5Y*&^gm%4RP<=Dko z&paT@^>-ce`m1K%yr(|$(vv_Ni7iZ!X*JzIKbGTG_TBWxMVqCLe+ri)j1=Lyrvp?n zs))U(@lvz}xBuAgOrAvVw}p*-**ER>m%AUod#|(U z)_Akiv9f=K;azu+0d|>0wi_KCcq>gl`i>_xe}CFqIJ&L;X{+<7@7^MZO=6VE;n+kO zCznaoc4y-_`r(L#m-pM;$dz_!l0?-ui8>y7{D~vGdqPUT)h_zXQ-^Uw9Nlksun>A& zCc+R-ywc+XaByzJr>ePh@&z06sOehL+2!$Is7ryBkLmY58H#pm7Y%L{lfwXs5I@qJs&a@UH0}k5}WzQ2&k5!2~g=sjItY!NkJA7RWXMUR* zo?@aSa%sbkUK7uNIEKls^$V6j$^^IMgY|z@N`P2j9YfcLGp~7|dr<*Ll!rYGaFVIQ zxVgH6>u6=SZ-uX~yN0JUPcZa|AE7_Mmqg8BxIrZ|W$iohC_8+1CRM3KgV&xWNAJnD-;fd=$}ks%*Lt0#RCEQ*+gX~W2)-I znv371u>+5c_LQh15l{bAp*f^+3aZ?(Gb7c-nZA)<@_sOwIMbLP=m5ba8Vo(vIwBOO zn}kg48)uFvE7->3f{Ci{LVW;9W*L9@EaA>dgQKfJCU!9B+eAD%*CZYd;SSjo2v$!) zuuj3t1osgd}rl2q)@ddpAIxrF>K{z@Gjvq;(Tt17V9B^Lr z7ba10`py0VmW$#QKEr*{X8`JG3lm-+MyD~4oncJ~E(O=8SA~#}5aNF?3&BCuFykvm zSCCH9g=y+#U}v_-y{N26Ek*#c3TvXn&*JKT7ic=A$t0rySD(&qV^Zv{y=MvLT-w6Q)Yi zu;-ch4KF;QTd2t0Jj#C-$>|;{wkkORimoJjyA~G`SE!V*hK$14-!443MR>4_@SqF3 znb7@yjUOZ%HnCsFQ22psoH_xO$8O3FUKp=lEQ7dZHsI^5Q2uM}Vmqr+jj`oQ_myzW zqova-&$9UiZJfZLK@M)7j_F**8Su}c?iQi_p*e1;ggJ#hm+gPwQon=l@^(nJ59lVP zq{G~s3xIH`9mCV~ICR4tVzr1@wII6}+jo%QGE$=fFCwe zQN}yTBMChsh&da2R7xx0x{{_1`vPsVg#?vwySPg9HsL&o|^e9tkN7%TiP|l=qnYo^Ob;6iRLa8SC z)4&qTLEh3;$ErqD+xqj`lcW>2sB6EX6Gj)!+2F4sg4L3*p^Jq^SV{9q>?TU>|yGPEdTFNLAV64yL> zJwOk3)x%WB`&pKCjp}2I==;^)Lw8}HG^TPx<4}Xc?tN9y1a)ncOA8JpC-HOi8gLys z;5dIEOFJ)J5CK-Fh4cZzE#;X*y9+?XULLQG%{nLt+%ii7>CU{;&pL@;=mg|YH%Sin zr_XKEmCbn!?*<+2{2^sn%?0Be3c)e^{Od}(1q7IsO_~nBTdfG8EGwq1iML#e+|HvX zUk+3N!vHAGLIq$Ap*k$Oo)6atf;?Bz12unuaw^kvXY)GzzDM?D37Jsa90T=02txEj zoR2YzsIxBtsV!82`jtRRI_k@E^>T2OVCi0gC8}1rhUL5fWv?@R1^*-u&_I&Hn(O-Z}k~y9y@*GcY!nF@^ys zlMM?Fe+3f<0nn~I#ECaY#VIGA+PG@hmEuU88G0phOj5g^{Q7jG!2=XDnpv+M`$Zx_ zu+fd~{`vsFxccbR7nxb{l;vs8S64T1$(fRBrE|^FRIILct5?Zu!PE73SAYBTh0x(- zW{q8?H0#d~ZPRU=`}Ibcq+D;LRmm4s(czU$fBx94VfgJj(@D`*MZGPFqOt)+shAYm zK=Pk7N2V*oa+A6#mT93@8_ou8qG2h><|$qK32K$W1fy|+1WIxxm@qWw z<1;d*S+?4wOyzz%K3i`xrIV|>l0@5rXck4wM$z1O(RB@MhE29r(U&_Kd{^~%v^V{l zekxLp1i}oE%t91Nf4@ZizFU_t`6_<^Q?nrRLhN7GgK z`iIvvkS+EkFL|xfS@LDqR|hcON%IRskEtE3H8bY9YOmsY&p{G-qIZsZhn$< z1AXqzK!s)?3}Bjsf6HX%LF*sI8ttsQ9hkQ~`KE{Uy4bd-@N&wsT++*bFMD`H<;f9w z$Wq+K;Mb*-li)8QY`5oP~WDlRv zUCD0QC-ermj~n{Sf8A~)6y?$o{fx-}dkx5r3vdLH*Qr#szau@uMTc-t>V-RJe>U^S z1ORu{cJBv@ewfjqoe$(H+De=-{P%s;A9p2kD^iCN)}aKv2AX!m1B#3b?FT1-NgixK z0tOx+4FW}k^24zpBL?t5zHrQG2QLB($APxI0aQgr;T=Ms zn?Jlqe_*GGG0rq&=pvM07Gj}Cf0u6~=#n!FhAUZ~dF|IE3;4aOl9MYe?Ur9Km2^%!4wW!?17 zb&VZD4218HRm*avhd1hC2G+U7OdU=)tK^7c{FB0RB9L(Ty zm~n<%h|D~<6B%HxS;OY;e;%H|FGMcb@!@5_oebdT#oCI*1p?Tkt~%WBE0+pk@P;Q| zsxgR~JlVCFGUF98>0uJ?s(M##OP@W9%$&yYYtr;A0`M_r0oDTy7p)H%?U2505s4`h zl|S~;(3^%q_vJdzl5*QSp&;PCsLK7$6-22=WElKY1p!0C()AiMf5NJORrd7gO8{83 zfTzUhF$U#2sY@3Q;R=H@@IVEE&x3H>C7$rVbK3^y?l;6gbzup4e~T|R`=gI0^w>qO zfw&GKn8SpDf-^NqL(_lt?FT&SxEP&oNsnOvhIK>Ok1V4$)TvL zn`XZ|TZ@>{xxR`ze=OFNa_&TC3g@_=ItRP)d#F8d;6>9yl&;Y_+C#CQvUlKV3(D(T zmxvly@pb+c4;f%7bJr9A)tWCN!NS!cZ4W#rQ|LL8JV#SLrY{Fl$gv<$+C21&Z=)Ln z6Zptg>2%cW-?~}}9b=(xOkb-Z-*T4cueXJ-ir%#@J@L-AeWk9IqP=7$$vK{!dhX#iZgGY)ocD;RA}8O^g8qbNU!D#UL*k0W(GhqTHMc z$70To2}5YBmKi&O`HL7e%QDHI$CMAmQ5j)HZAHLd%nV>}QynZThPkkv0s}JDo=C z4sa1Jt`*aK)Yo8Y3pHgf*SUx&VvZ<^2Z$mm|3#4sx;+&4_ujE`iaimW;L@-(mkXR& zq@5|7M28$!L}h?WeE}6AgEHe*P{RVSuc&WJUtK%(f6E*kNrYfRkboQRWVF6GJ4sJd zrj%J^^dS?06JnW?i{uY6jYC9~>6n#xE)kI6oiv@BKrHPMkVTDoc$`^~PbvN=vzXWB zq2;PDkSJfisi6XN&)bU3x%W|!#$B+*7ySITK+I3RcTzk&wyy%KH~x%`MFY*mkT-%$ zbHg&bf5>%j8lM>X7KK>GaTvi!3?Ax&v2SNoL-(TEdl zgw#;~%!T~=3^ktr`hzj%EQe};Gn@9s&>eLz+pGxg!D_X6GRx$T@Acn$3D* zWrso272v@0U3umtBLnE4I(KIi@m~NofAbI&r?m52R+q{A|FpYkp4jRbOH$b3^2g!; zaoulxbwi^*^~sX1$DT*;@5cIaYz4qzv2R>b46hZwt)n<-$Arm=E4Pc$;KP%(u;1t+4e-Wd( zjP4wJiqov$ovTr%*zq#59$2$hPZL4Rm+KeJ=|Bdo?xHe;DmWn;?LvbJfk~CSzC@88uPGI z_Y%W(v9H{*flOT6e{7Y>p;gw=9i0Ox>i^4=KE7Ji|2WfS!!Wn=M{F(%wg{lJ|k={eAz1L}PM1)`)*j_zr+8rU3863Sid z3y0xLqM)k+QNwMs4-w5Gf7on~ZCjp6mclJPO^Ps_sYOtJ&uaUb=}^R`11g_I59_67 zN|McIzm;QwMFWhE1?C-sbL}rl-7kKr`(*<;KT!7z974ze&-ycEPHOa1xBC6HJkSHLLyk99qp8Y6Kr4I z)SFu<5by)uSuGsde^C>Bj1qjg8tdm+#`UyZWS8(@TYunPdM|fgWJ5|CrcEC7yIeYw z8XqWA>w~KQNce#sy3ZP2FHTM0UclTp_4rK*%tH447bNiPD+st4kln6ZH7DD=A^4|t z-PeC}4x+gOOlYE+uT++4tsec30J}C~>?2VU1O%rf2yXD4V7_;*m%0sPI*UljjcdhK~vTv#RmyI9Hw|xBvVR+8g zvLc_F^-C|rkIA%avWp>Yai!}=UtWFmKXXP1*^?0^6O;TG6#_XkmobI`D1Y5sTaVku z6@K4ep}uiZYdZJgB*;V4CP<7HL7PPoz;O$%mTM7~L{*~gxWB&V%nUC>4JGbIhTFba zq;x!&Gw1T1Z_a*wck_pDxn3|zEVXQL_qfOvp~5b-)r3;MxO-T<%08^iLwWo9?j;DT zp|D^?GO?gu?3EXhc_aeEwSNM?P|j1sC?dIRg^^#Xyp$Rt1le+jh!homv&j!1UeP6&3Ig3!;(In1T6tD_R|ImqO%Ovo7($X2-X; zJkQDx%j3uGwrmd7$_s1@c>dKtuj<30JnnCoAX)Dos@2<)n14L`%F8Mm9d=Gk4&!se!VcD{AwfzkmX-*`&+QWwYw~EHe@~Al zw3)Nd&L)0_Er{&P+a=Q`y=mA8H7eTmr9s1RKP86~-~{?fYn*u&myYzy)G&q^o-YP^ zP3xbN+}KF}KTVt_ocUAiY^MJ8=}u#F^MekotxB(t`b!PToM)?I1D`p|{)F!=s}F!sil#iK zCZ-ThDNz7V+z>zPn`&GAyJ)IHS3C!!><@V}+z-P+-22)6Sbs{4?SLS;1x4}f+uK}Zhhr>FNk?aHYYsqyzkf)hbAmE&mIr;)-SLKTd8(cQ#n<_OL>HSfew>v zRTgj#8-Mw|paWOKiQ_;?Qwx*;tN1WV0<4uxWgi?A^(%QO5s2=>TMJE)V>u9O zYF{1{UctOhxb($O13?Pj4#E3heyrJ-&QQdMLQ4Le&UP zxKN+%RLtB{F%t$GjmtTa=*pr$#w3P=_j*L)d0XzZ-g#57D-n@EE7Z32`OIVDA zJ$-PZ+l3|6#lFqr$D6<1e2rA%i24g-NdQn<@@VyA-=sXQ?J$slj3F`?7uZGiEPq=N zV_QH^lCg$|=L(<}N;%3-j3rJb8bLRvZEbsVp{n)d0mz2=a@KlowL&jidq;Z&SeXi~ zW|-%%nEE=nw<NUb(1xS$WdxlZ};z-G9>J3=fzi>`q+L4JJ}My zZw*C~ksf^oU%zum-qIe0ZT$PH4u8M^W{zyiVNa#9BIy@7b==5K#pnj6TksibmZBcD?0odj%Cm-#el99= z#)*X)CGr9?V26h$m7_R>cnYu&>dZdyG3gu{;vpa^sncJpS<)wA80{UxER`anNFo=4 zVBM$xiByM|2d?_bH9u$0aDR@B!PufzL&|5thOLfopUwkJ^E@bX$w=5Igfk~5#|^j^ z2+lA$!-$b*O-@h^8=YfulDQJ||JUL$fa;kU;(S5YW(YI$@^y9$da8NFfnRWlq|%or z751p ziM6`~o|Iq~cpSdF3JdanqOZY4zV)Z=OgHFo;!c)9}$As>F`A6~s9&?ZI_wf12 z_C~aq(!{d4tQQBUK5u$HG5wf97gUbTSx%etu}n9tFl$e5H{*e#;z3Ms8mZQev0LQI z#*|(k)mw7=m>}+b67YW!^ctt1XDaY)NIKJ=pa79~@Q=%h?koerb_tV2Au3Gdm_%lg z3EOE!rF#ezgrDV5fz5;~f#L*qVnG}@snDC2^VQ2C_mP+|hcZF3L|__GFnNz~90h~3 zU`+NzQ#)-PXn|t)Ch*GsiwldBx*;G@-r6sbMyXqVoa+Q^^FL-qbv3s@n1 zI?m7C_B*f)pN^>$IZd|%^w;P9%fA+TNVNOVMR=h*pu0yGysZu3VdK%Rp9dczU<9KF zIg=|QB7e9IY_U7Coqrfq5AaqbLoXmiVMci_PP&GeVT)Xv)4;O3*Fy4A+7j9+{AIDK z@2euIED0FOc0+xa&fr$bCw0BezXzQ-;Vy}{gel%5a8O=MsBgm!Iux@kYj5z@A==_` zh;kJos`G5Tk`JtXwObv^Z3w!~>yY5b+GUNwIDg4rQHYj95W@6C1neo=F2WD)6(e77 zD^t@KL0_a1JJ*m7pL`XbU(w0c6`UNFChZeC<_20GLx0T@?QV9mg%ZqxO^`tYj{kp8 zqo-jLtV+yaV@1?bIqCZ9Nv(-bbp5kIWX8#Vg8qY0Lb{KEH4Fg?xT4lrJd?Im7zoP9 zASD2C1AJPSxQ$G|}&{rNaS zJ_~hiqBr6P!|GZc4clhmHL$JjIS|=+nU3GS+Z6u$j`?((tNlrEsL1T-=C#8BeG3l{ zEj%W)@BsF%Ko>>d1o3eCwJ}27Q=s6a7BaU!F0JF;Jbm=M&l;eRR(^qTJfS(9+FQlKI<- zO-j>aqb29u@6~q*;RO>M_M8@>Ct-$9+act8_b|V4#@6PgCEAQ;#)c7|!N zqTsQz_1OOavSX|PB9jp%DVMRI11W#y8`+ZExbc0yLV2Sq78W-^r~I;8>%?1oB?AJ|2!ddDqwj8hdwKEAb7^Lbl9Z-wc6l|k zicpcxbgBuZe0I5-y-I%G-{e)X%r^6duq=78oeQ2c`E`{wMY;8pMfm@*gnxgQ92S3v z*E}h!Rk6*Qyq>?g{NbDDT=(BeXA4e=N`-&ji*3Cts(b|xYMs2DbCZ1X<7S=v!7kg) z7u+U!<*#2;PJb-I%|BP=e&>fj<;}WuD_1qFVe^HQDQ;=~mL_>o!yYWz0A%huZ~T+l zhRhdA>f{xF^8}`hN>66%QIt4HdfJ=!<12_CD2HyhkF&55|7-jvsUt=3uK*RK*i*0`<36}?4o7gr3 z$Q^zQZfx=_wi~m=Slcds9*0Vavw-?_zOc!k<_m^Q89fF=m{J1>C-yv?6>MjPh?5P( zL)t#VlpevFTX;fs@VX^}&J0Nn4M=k<;An{!+OMKfE|H)KU}0|^zTdPs%@z{gMYWS* z%B5fO0fhqOfu{y^!Pb8dnkoaC*w$Alwm4BV;RecR>Ldp*S3R+@UToa$PEg##TR-cR z0#1mYl9J{AUQ-tK z6{5#VTobL0<0U(UQLq^(BxAJGCPbi)V1!XK zPnRjJy5I^x*K&Ad9aG_%3%OnSu@?>C!;iZvuj|0vG`T9Ps9NESNYGWBSd-qRjycd6 zMY3D>*z}3fX0U(F6T~!4mQ@aZL7;~JLp`xjD*1Q5Y)Z7wpJFh9hoY42UddF{f)TFH zLl1V+aYAv;j$vqsWcom;b=G){c3EAchvBeWBTD7|dL6||5o`HKZ$FZxAH(Oslp`Ib z2@^-j2j(U{kT0l{xWUn&Fh)$0fxLKI1J<1Bbm%~V?md6FU{Nh9I1!Y6DNPZlt5t_Z z*{0lHkIcpjJm96X8xwzO+9}I&@p*CiT8&`<9UBX?{>R%pnO2_-Z~n=qV5WVW9*?BWijKZ1w`X~I#>bD z;SpIHY$U+Kj74d%i6FG^FtpSf69VZViQwsR7F9z!{3WWaNqV+^I*rqP`~|Y-+~vo& z1!oG>aS#4{)*SiXLJ7j~R0ODJ&`_Q4oxLl(jpct}V}0P~%xqp2@8{raLSPBA?|Tv5 zl(z#eIFsxYcZZ+i?qKH29$c(8ZbsP3w@p?=?f=3kVmP7+w4v#-yo`Ckyv*53bkcx= zTv!xe5#U-)8F^J9OwB6r+OQm;jqqd*b{#Zhy9X4#62wsk6MnQ%yTdsDM;Q4GM|Dn zlIdMC56na)yzexbhei5vMP5I)$Pb*rN$X=jgE#ytwhx4q=D>iDAb9`19^0G17gI}%uwqzQn{ep3WyCV`VA-Mjc*VC9Bz%-0899K=B3l4y;UM_eo&!2Hi}EGH zrxAO5(o5%uwcJgkeuc6JmSOQ+2j~z`kwT2Un6Wn?uvlP;73Pa2eFsLu@6w~eWgKn| z_ZPiolciO5me}08wmPK0$D&78H~@b(!4_(G0Kh;pswp7oGNW?s6te-4sh0AJHKk?T- zO$~$hPCdIajl0I$R=!z9WnDp}tL0Zxh`*JNKWym?5};C*P1d+B6f8oQBgB9Em1SIT zRb@B1s|(XE!2s(DXO%pesya-%x{xC=wy_wvlQrHrp=JkBhmdAa;b@H{*3WmlP2s@m z8O>|gw$j-|vGAFU1V9wv|ER}?9&mPtW!MaR>Vknp&1IY zNgcNUPl7WOB8gw~rpjCq>6EsspGz#m3Ti^#(vQN_z7B)(YIG<6=v%SMZNFUu@7!RM z77m=l2LA(@fos=|VGg}vho^Sn9@gQ}@V_ksMCIE}agEaQ3A1|0*bIOCJkRahSa+3s zxugML7%WQ-PRSGKWxM5Iwp?HK;+YPUsZR@p|TG9gM2TPP+)%^v0Mzh zV&DdH>rF{m_J@C{b2MjXEceG$$&e zAqqpfVbsQEy;WD!AwzhZQ}|39hix?D#FeYQ(DwX6U?!YZ<`O1hVJ!V32!(^`qtQ#h zjCh<{IU6jDXHt>RSud(VRNnVt98!o$SHutNuO}RvPWgX5i*7Q=2_C2M-6eqgHYeQX zUUMqOyd3CkT;-N8C3(JUQv&L|+2 zAS;-n9yCw-B%vI41_qC7mDkIvchLl%bIoY-?m}KJFa!%YQJTe zg(zv0hu43#KBJ57{G1O9T_7x-{dcqF&U<}j?II@`I(_jUwqECvHsW=@DMDki0N^lE zTl)(%l=;e!%YEYq?MDl4fp2-{6V5j-0q+tWScow%+r_Puhe=X55n@E=4=%Eqvh}FT7jb5+L3ey@DHEt4 z&;*{ZMD8+y^6qjq7a*tr5;I5#dspd7Qdiu%t8}FVJOR{$*xs0c=c&n9E+&whUEzHX`fNt-PCS`=(IP+mL;y;yYApA2VufL z7?*#+C>ZJ9!eD!1ID*zJ=Um?-Y2BOJy(^j4FU`E-V9rE(&DRjk_2tLE)@ zXT8kWp`q3XFt~oZ+Am}Itr4T7AW-~l2ju>$qx=XI!a+!^B6mDiJj$gW!Ppu#-dBDII^C_QK9!{Y3J!|4#2^6TUV;6S*y}%1y8{ zg=^23$rfFK#*Z_9%O!?zaP7Y=#NnoR=PQ#je;){HxqZM;eDtN>LQv*&JqSwot(8nL z;p>g6bQzaom;f8Cr0N(*W@4304LSzffY=@wP8ZRC}XD;OggP# z{_n%RQ=>icxY3@tmw|Wm2$=jmvNI(IPb=;_d|jAi6Ctai>h6%0QR+TbglLZ#7Q9>4 zdg{Le;HI7z-a_uqGc1tpROCE6$3mrkBUflF|)*pJ@=3x0WV_W9RbC5#eFElVyg z6C()~Hc?g)N_ldzNM5Jk6jgEl_TszGzs^jTmS;pulTf63Lpen%E_*$H5=D1JU!2dl zHtFkFcPt|^Q!V9Z=QE+w<}c?nrc`>{`KQyoiM=SJgk`*a{%s)XjZPA6cW)?bU`C2G zcRyKbXSe6vq{X~hS1+JR+4OzcTq8|Y)El_+w@aj3eh81RuC~j(eFUl2b=j2bRcOms z3nUE>u074XY~0@u`1bjK`sSRqPp^uVyVcah4I-IYL5xghOn`taGJkPhfJg*O8+gAX z*J*1q>=K67u?Wc=(b?ZF&VD;%&`cASa1L@1JW)~+E|U4p z+3UA7S-`#T5=t_mlJ}nS#woO$on`XV*+0*|bhbLQKM(=W5|x3m23uW(sg|@ysfeIi z!Ug=WmN}Mr?V`zlOo3j>c(a;BJ(wT?ssIzD3C%JjY$D1f2;F;+FQVcEmmp9%jN2hJWSB#h9t;!R?4h0wF^oN+=R9sLTIquhd&aGQA=YNeOi)mlpiSPPdgq5; zkb}or->j?6by?rwop#$auG2fFjg(^eGYn8!j2U>j3-CyBF=F zHUY|M_wO2iHLQtNtdCf+=*Fd^FAJa}$~Fj^Pqk$|)t2?WY*|mTINi17=0MjRv_ekn zxhKXr{IWz-b(^@JFSaDj>C@SYS)> z-+bP9;0LsMjg7(8Tms@+SD~L~jrSHsJ+I0@flc0L`OZ92TQ9dbD%Z5W?9u4-$K3IA z`%?pB!CU1D?|2lcap3O%9RKeIPTFwYMUCHsLj)?8ZXNHMrZ+gkMX|*H_+lWa_k2OK z=S#DH_BKry@*3NEBffAOgML)1Kl z0{zqX1zyJ?TvUm{H)TEe=D~)?96Ihkz?~b`O@erwy^Lp%z}~T5g7t5r9*q*w73?@u z;uuqVe}0H7G2rTUge%D(gR7`Z(uC_>KQAzU+sXt$4v4AVastrxnP5Bx7JH{QSvlz) z-HPT_qBjW0CI#i_0Bja)5iZ(%(i@=7hMoW$FRT0}T;{8}Gumr#R*TRQ%?~;CfqU?ch0mhbOU!d?oHK49JZF7pmj~>B zr}6586CVRXK&BlTt>lDi_86n}^QHr6g$YDBirj4LaDhk`?$#e}+t!5@LHJTE z;&arf&v_B+2Y{y9>E&jm57SpbJ&J1~+1XjbZ5$$7wL=IlLb`#Mt3^5YYKmfTS`Y+M z2a)7e(bD>55sw6l1-8NEbx{Q^5SAE!Zu)8fU9K=E7zC{{2lZQG{s1ux`!1W(#m-rl z@$_fE{DXN$-n>A{-R!~jHAZJ_iHHQ0k}9|20qiKz)2tzOGB$e*PaIrK1gJwMr_G6$ zS+ZCfa%Y)EcC(O^uCkmcnjVoD@8Z|Xkti=aJu(`RDrS>islJR#RcLcus)}TPkU&oq zt9T}mG6o48{-8rl@Q+vu1Q1K|SUE!KyS zb38R-f)b`>$KlAhli>1xW(_@mskrR9;&+8Mgw#gvBpc#6jAxVAHJ~*=#OAtMZ?B?& z+5#eHLm2kJV96h%0e1$oLoAo;YGhlZvx_n&IaLp!?&o2n>u;8X(J>CeH-zX_+&#M7an_}KoS5H#XAfgO%b-Et zS&JROd+C;>`wV_$=)XSzE0j)S;c#8kT4Z!c%%{p{X&h>N$*`FJ9kOP57 zyE8%E ztJrXNyyMBP;=2o-HLZz%Fz|P+R8NZ&Tcr}3Pf@CmW9|u+iVu`(=-FIq+jUp#=zeX+ z8PU>hgldSQYPesU|5~oDS`Zj2SQbT9-kt;0&D+u%BpAb6!V<~F6u`yffUD24+X~u) zyzcVO`dyQk(a=BBf>0l%6k(Phie|2Y!38r{DRmewiAP@m>dVo85^LN(w+M_a#y}=G z3M=@@G6;60J_eu-lOho|1H7OQ70B?mRA{_J#uXcJo(PkXOzZtXqv0DwA^}uAUzyCF zv7YD5fI>Z>QYJP;=0RcCkgwwomU+O@p?euOGoc=1x90WH$o5U#j_kejp=sC>b9&{a zJPE?;$q-haJ`%)#>Jyyw_~cq6`O&pTcgjFrQnjZVm7FlogBB<5T8;{VO%Vdq6NKQ( z`tWWkJ-NX zDBFKEQtayJo?(eHaCH^s3jFTA@MHRN&eQ1C(V^uLwZc;JXH~2FxrPCDg8YP4iyQ1#eLPJa0?`>wJ&yoKMDcRuCfUld_@iX)=eJjs(kBpS%+@QOYG)-3zXox z_Jvf4q+}>Obr)@|4D_@sms#Q?ZGmTvlq1VD0+5tGU0tO3_`SSdHzV~>_8Aw0?{dq# zl~+y=Mk=pBXPA1%a5!886xzS8TR>TF=T6P8+qJ)ccnvv|Zjspd`fO#gPkfhXW|@eu ztqD$)d{!Vn2yduOJ-@F|gV^ zry9j-^e_f@BzO^-)EV{XO=f^`+GR}|-;* z%vxW6lR7~`o-yV4bQR<(jteQX_Xn4Qy}|+8v9gK|+vcE~G0Yc9YW4Iv@fcQB&+Z-X z9yG!!mET{F9R3$@d29xaKQ(EN%%Ge&gMtXo9_xV5(JH5LuFBrak5b&HjK`_x3wHgMz2aKH$yW8I*SQ z*ENPOE4WV<)Ktlzp#4NBWHL^N~*7ngbXnh7wp zPy6A|f#zNA)qI zKdaT}X1=Ye@O6|vdv3{NghR$PG4?2bhyAl%(RCW|(f#72aHtCz#G-GiFf;9X0h|z} z(wic$w^eb|e&EHm>a<+V&|mJpSD@YZ3J7RQrh=xx!+AIq*7Zp4@fuU>;wI45TU@)T z@o$i#`)&?4Y^wFUWpU%wLQ9D78KhF(K zZXpYwy$(d>s>Ee4*E;s`9-s@6!(vdxQUNrcpFS)gDo( z;vY(a$A#Z&=}p}e2BN8f{Wh9y_!YH|DPE0X?B4ffPKry~BJfGIl6Tl4@5hcj&c3z! zWb98_T_v7ZAela)Y50gRK}KrDZX_J4_D zNOBq_lp}$)`}5z9lIu2QLXf07!j9zHkuVl1WE8F_1fp73bWAy_4(BdZ4Ph|VohlwgE4j}nEb zrL#ZeAqE=$C?nuvc5Ob9610CrKuZz{HmGm4pT5(uzKxMzgTC{wzH9Zo3-5|h(6&-? zcvEa>QxHAvT@5Xh292SlZ11L5YA}9_Y(ir=8ZR{@R0^bFWiP(ZKW4Lp8WV5Ui>oqU zuk4eK->(bzx@>-bgBdS2rF+OeU8N1N0b`MPQ?HUQFBe}zo1j=jYLb7CJ!w#-!%j>z zQd$o=v9e1F9ZnjU@Eu7*A_?m=goSK2pD?+V+q0#CgdrMP&@ADM#Ao?3U!(23;Ah9)RXzzj}X0{A3L#h;r->7Hu2<*5rX9`JW z0AN6$zra@*62cK*UAp3Cy>aD#zLp=0EVEx>=V?)H!h5q8)NUzm9%6@Mo$fLiGh7=N zGtzUeE>i}TrbRVr%upJC9~569q2!SG+7o{ur8Zi$SP((tK2>6 z?#U_xIN<@4#$AEJ!Cqy7g7LeHHc;@rhF}8TAjdQrqk{Q?lijp#GteW+#@_e%7C9bvmVDxD|_y0^+p7$RCfa!56aDa0YBP)GwAyud2dM={)D zW!orTb!;{6ro#JG>>_uaTh^Bi ze*NuF_vU?iQMzBD!P{)9R;Tr=x>>UQ;ni}P7GHj>6i%!of*ceHQfrbxt0^#!&j3Wu z8s06I>tdd-U;+0u&msRX$YU#;lFB><1`972t$OgMLylCzpPl-g|-<`+Cl5O z{+chdAnfJ>No+d8dfKT}?19ODLehfGrD*%=spI?^g!pKCjF6)N7iq?gy3N6k2JnKC z`x@ZGM>Y5+@xONL{W`c!TgCX8!YU>ytiEf#4U|>ToANsZsH;JE2w&}dubrt%=Vj?) zapPMX_hvsOF=APOEgLSd&fVsuG!j~86!aZNOXF!q`+O5*EMt=?oHV_lK z%IY*IbOOY{r(t^ls4?H}kK(Y_h0=#;y&EIUgo8wMgQT0#eOC%P5a3fy^t~aok>M_O zhWn^P%%31oqza#Uz*ol9qm-X^*#Sb;; zK6-Y49Ei2vVH-X8D8ggqd}&ma=zYWFj=h|k%7%9U8-dc`IJPtXcj3zrgjN&6#7-!A z?fI+*cQ1=v@sqSQ3>#@8}{aj`4cL!-%M#ZDVv zC=L#8s!rWTp@FmjRCJq#!!3xkmlDlh*UgRw(ABt@QJvZ34rIl^RxW&QZP;Jk9oQy5 zDZ#-xWaT9-do)%fo;_G~p$HLNiyLGsA!_aI0A=KU2AQ@`o!B7ZWX*6F`n?R5BLKsH z)fI;p`|w^h7H#gmHG(u;2M*-aC=jT|WF$4Ny6u$Qo@)s3OTEVtmL7y?d*J@v@i&!dW7jfkhZc1u$~%)_0(ioPmRNRYJaTvDjZytuqlJ< z#zdoFpBmL1spI$sF&?{P-Kl3&CEp%@*SL)!S>(?QdT-RigUyBjB25#tFV@wNkJ_oA z9qX0NL;d!$2A3qx=I+fPu$1jLeL)+vwQT~&G_H+srfRx4%pp#Zhin)+mq+td1Jyv(!kDY%=k?XG)w*Y^dKeCEY5s!4N38j2=I~%=;{yd%t%c9@r%lk#@uU~H#Xo}m?rKfi#F@>PU1hWE5gMS;kf=3A4bA|@RUnir<^fPq&1Fy%dMyX zE#=$~7Gh*bY^WQn2;*!tVZ<2Ye+T}j97SuRB+;A$N8Et#SjjHcSX2@r<56v*KZR){ zim7UbJWwRX?f0m6U67F13 zHajc2%WB1+Llea$R>OFI8sQ=Km$T`HMR3XCucERVM`^%vG*MuQC1or`JB(1HNo}U< z0P%(}+gR?-srrNx0kcdDsm#1YV2rkF_EVs+ClMGJ+wI@tXnVvALkLm4Q zb<5$T!}MbPdo;Z+o|)q$#W{q=pYO+@pT_a(o%zFF?fF~$8 zPN-qW3a;ULU{)GSya9}C?X<}e2#O4oqlt!?N$yi@;F=6Tk=@u|^@%_Eg{(XzriNF! z2~mW`W_!gLFUs`;f6xbn* zNs;kHOBwx~VQ$4|XCB7fL}~71sG`EpLXpOO+{_uRi$8 z^m8&T{9|*UbxJ?v+e{OSviD`0>SMXgf73jhWckdelUVdITgPrSQ&eS7uk3K>C1@Vv$a%}7a3f2`D_>GJB$J35-dmq0BzdOdn{ zLzjqHEyn<1G5YQ5A6GwO5vWPKFw|v8l;BU{1`k@G0DoYRQfWoa0>vH+)Wo6zGFZYq zLn_4?AU~W+K?5|GNu?Y#zyn%r_G@utb6+tmW}sG}7CXRLhJbM`DDlA91zC?Smh{)N z^eq)~f0fQ!fmxmvwYY7W6#4vfSmI!u@o_R}vdI!O^}2$An%gQRqxYm_fd8gXxWIdb z>n!e*lVQD+GBTW$*@L1b$=34?O81 ztTmhYi&eQJ_f}AzwtiHD|4&^nyo%RjFpO#e4cIARpERC z?8&ET`PoAgfG~NU08Q7fD%b0 z949qOuDj7R7GCPkT^iXs1nFTq?t(;USn3&xIEEQj*Ux-4FFHz7QZt}M$EQ?L+F>D= z5Ee=o7wTuIZ6D=<22u2FS4_jOOkXCVe?6FYJnVhWirp^acVvywAPr56-=X0&x5J;2 zhGSSkSr4z%b~^5P%wk$tM%bP(J3a`rbvMk86``EO0tqDB@z z3_)`pR-aJ?=c}UI5E{|8iHWtksR01kRClKYM3Gkh0qR3r^TLZ z;KTrWizanOOSH#{2DH5_tQCIsBYLXayj1FbQ z{>1z%-=23Dgkh?Yx_R7_7HCy$jcv4~zp8owgUTEeZcN|&L%Z`%4O>U=q)zF{~$8dE~6HfYCR=dPD(6U})o!ty!OD}f}aiCjj0n~jdV(fs2hnomBY{$%4 z7%R`&#s6}4e8yK<`Zl9uLF-kxOIDf|NbOyz=|AcI2=NGWU`L&thf(8M%yW4ce{>lj`ju4REyT zEfG7tC4X=9l*0|z8ewVl*I)kSZ~QclRRmbsw_zM;IC;J8H<4Cie`k`r65EClyiV5Z z%`){PHmhlt=jkFDv#7vUCA?WSis0CAdpPHcD9a9&*4a*b_|BV1L|~v>8!2C#|? z-D{mPpEgO^u2al?e@_gH9_Nci*_RJDqBs89NY9C%2prDoZz^s=_XlC z%SYBlzL^%T^CsQCO5ol~m?q^fPO#dKSU5#W>L)Dk92TN zqx(fNP1nS~{ayWJh#Q(Yj{8P2f6FNjUSP|ZS1tThdzIt{mzB{XE&Ny5Mun?X{e!{A zJYZQZHOOhu{Tg$8bKsi}UG2rc%CL{fBB(ZkeILBF7o#8a45ZGh~0a3+CTeTbf59o%kZj%U9 zDFHZ_F@^ysf9+gLbK^D=zWY~bZgOpe;QgqrRP83UlSkEVC0TFnVUhz!qHS#~$&u(d z`S;rmfD}Q26eVk%OjRyp4n={DM)%iWHyZl<=IYb8Tu&G!jyg8Ext&-=sBjbQG@+DF zZWfbw)0_KpeLWL`O{@D7FZgu5S?>H8F6 zy#2O;fBD(mXsKA;(fS3GL{S;-2Ool|%nadnKvYL4cM}ey>!`u3X8dKXna{HVa3e3O z8P}dpv1rYQHfFmVj zY^!DQ5F}fa+vP9UN==LEnoZ%7n`s$7+T3PWR}t0d>NfW>2WZ;J{Jedva>H;%B(;Zu zeOOFiI7yh;yb5=! zO^3Fu%3}8fD%h5baO3BvVvVC!%W7Hff3mA1HDRKWw8$)vA_k@+h*MG6_qhqfA__pH z)?!6+ zU_`={m8FCMs?S$f?|!6{1$+n*f0{@z`e*;>YQhbX3dzI6j@H2|#>Zt2%%x0Ef3dvAq-diN zXpQ!0t-(>27v6xNZN%zBKX!nA$oK>d)1`c=%?k=_S@SVAuPhPN4B5O8_)2}M&Aa2O z2Y+J#LM@vIowCe;kTN-z*mRXcR^U6pUwx{}h;t%3Neq*7z^`H*uHQ$R;IV6Wzd_u3 zUf1wfRN;f$%{JWHt%`?-e>|)~yfgA_OYCq36SMpH)bn*MB=-Por)@@)N;0z&V9xrf zTkZbzv)Ax5rUBX@BT-<<_|g~o84N@qE1M`-8f#zVW+{^e|Ah#Yc$r{GDQru(9nWM0 z*bKZ&*p`AjfmJHv7#lTth^s1{d*^-iSgpDHDZ?^rlmjEUzxytme~}U@jx)(t_B^=8 z*-}6&d;T$FwO)cYK($f^-6>EQ%G)s$`ElS-<$9j=ZN-5ywie@6c#{wUR4>OY?{VHF z1VFf!m$2=Rf;Q<6ZAu*yX_J|x#*%eI&zxjy<@fQiTSKDzM6^0wObH4wVwA74=uEx7 zDw*%X!09hpnYgv1WMZQ?G%}QDU6zYZWh1IsM-}&R zAq8tCA}Kqr>cfMXIkf3^h42mBMFxweBuf}^wB z2|%((s|$iHa7N>?b~My}pD!$0ae4**U6$LlBL5ymJDYUiLh5*B>i}=)g`q}wp{6S) zN0vsJKG$G7HsxSMXUEtSbHq|MXj9IGosP>J66xH1gCVJnBNOCFYUR_yKHt+F-|K2l z=!V8z)TO$1WA^WP8L{I)60|1?)bC5Dxmd$EZi{(Uf8Q#q1I8Ekn|x`WP3Q4TzBJz+ zWxJ`u_Cbzs2{0AO&cn8Y0+MOFRnI2cTMWN@R&-qP$Pw+nJA6bSDs{s5cB}Z8>f_6 zKj1_uhB+^E2|W zTTZB%2(5`5F5Y9pO*>H`5sX`~VDK2B;mLaUe}(4}95G%1zVa6r+VaIzK92YZA~-vX z_#A952$?XS+{%T@%CeLhfn(kqBhR@H+b%?Ar7u z+UzK%qnYtxGh;nO;*em=b}{eO2=*xp(b{b37@M${!Y#qD+%gdg3rO-sxFvw2;H!m% ze^i&Yamxdh3Z+Jt;MpO`0hP=&(e-XvUo=r4Y_~ikQerBvUx@CMa{UfjYUC&FzjomS z!VE>>kpS?IE>|B>wmUauvC+x8{3w$39zy}DD?}Qft88`*(4v3e*nC*@W=U*5f)+<4 zQfEli;nEt+1|po@1D(imX_c>=0GqY|f5J22U`1qe!XX}Jh@E1PMl{{613MUyscd65 zw_C0rAp^;#Z_f8z%mmO@G2B+FjvHM!<@oGazF~6thEDR0jtv@L?t!2s|1f+EX2P+3 z@&r0IumhusfC*}!0lYjbQI1&9AU6n!`ekW}<^*QU4fQR*o#?KQM|W&gH_G|qe+_5$ z;=J|LIM^{uxP+0wb-6OfT{pLtJA*9PMGgG*dS->lwoIeXjp;5t*_%$z-Z5=g635`? zD>1!!Ucrfn?KwLU5aq= zep&3o)ndE6jh}AzZG-W#YPrIeaI7#oH?6<2jDP2w)oQb@U$!gDD8+KUfBziY!?*Lm z8sOI5wpf&nrd!2MP(o}xXUGXmPbFO9*rJkiX=I#B(6$4*5O{ zbSi+@_`^0}fy?#$;b~EJOg6e8-YU1N zc-dI?qVzTVvOb?ei8h_{Dd8-W1jdaAclJplXf%e~k?;wGYb$oU;;-z$P$P{`^!^soq~LU<#(EwQv2P&i#RZx8QA7 zBFfZ-kC~qwl;7r0l8eki@-U%e@e9oo%kih|>G2cx z60WT}IAd>HXY8r+&8V1*2&s>qv1ddWam>K+m$X@vRZ(r1zXtJc169SEG$4DoGX|;g zc2@-zZnle1f1ozgr}ezt)~zo7^fSbu-@<1h*5J853??KCMJB{NIt(BxTO;hM-LZC& zu%`37Aam?^Y9zk)HG+=Bc{^qt!n0^syjb4Y?EW_(Fgz<$*Yx4_o5$Hhd0X}T+=1Sk zsmr&zIHty|zf^-io#6mx8*TT^mPp1%2G5}tnMpj3e@(fsLm9){-oU5$108h}+OAlY zDc9(1ywUcVhtqzCNDoDsPwH+sG=!(!VOLkIwX{!oHU}V@KEwYN^9`hy>-zf<#ad5b z;#nUz@m3JK$zl)Q91p+xvQhZ?fN;1q)@Fnx7OQlC6V{s6+TsSl{{bji4YmqpZe(+G za%Ev{lRIJ_0XLVip93j>?OjWABexO0>sL@Wsw#x>epD(|DZ8?Xb91b!9M(S25_gxe zUeRl7|9w7S21CveGXRG}Nm=iS4}lGIqw#&+4Gi@C`N?Snz{_4XQXmyh@B3#bvqN!y+cO)ONOWk>z~nnrgfX|>q4yF-=bt~Vq4U*$sRmm5a=yM?RnFzx zJ^FWbi|c5p@F}`OGjp>A$3%s>RaK9TdvN9(T|aooy{f$Uft)R*u=Ddz-o>6C{OGut ze-3~2@9F$vc~kv%wR~7#eW~8xT|IqV1fM~R$`SExHOW^`Rd00u;r{lz>9_vj{pxvr z`&2i0SY5z>C2IMPx7F*%b>;rmr>Ec%n2DCVR`LX!|3ZblSzh@Me15-rc)EH_&8MbB zSxlGWL|RtKc$b`2%4#<iYh>C+r8!Dqq}$LfB6tW7|-Od#QZ*uex^)V+$jm2S1-LdNy+3m`Hf zNe7$LmXNj`4eaQbW78ER(S#(%38M;~inxr>u(mjcq0kUuUCp1uG@}PsOAPLC^0)Jo z|DJdN!Suioju@e4S_onopIuy^y#JNXF7ZbgG9bj~(Dd4mRia}$yPExc^3%!po+(-* z_gYRyw399BIB z(E%gX0VDroEUT)~uZfBEBVeuR-^^}X8dMfiZqHt7>J*V`I(O0?cj}CY5^defj>rs; zND-}A$%y3fmRy@l9Y$ofNA!=>z#Uv{t20G^Q?f83DK?EbPk5~NIhI1yglo1CRk5@U zWXu110Hb9Gmg*2NC$M7LqF6!!NBl3gCnw1;3$A^r=%=xosL=FZ=}^Ur{Vno71)$q_ zu`xw^WQcjJij9`ZDKgsZf(othgbj}oyyg*w7a@x2I&XWVKyOE zEMj3NqbLL{0$OTjh?VRxiqe8e$k2#Jgxcn)KuSSZDOiiUI+%g@1vWv1p|vZD9L&*S z%nzyMD}5uu`i&Do&mza_6+)z< zhPFt+nA5KtLU)ox7E;x%z7ER~)!`!od#Tol`j(O`n!>sqW5xx29rW>%-c-V|;LNjq z4L(e~R?^WiJ0)DHZ>i#-p92bP$->hwWFn!6rTUw5e{=4yu@189-7imc?P4*1Y-F{V zX=FBrZMEwbi%p^kY!b!dOuMF7tWx_H3!x0c9bk>n2;1tWKd-OXSIhgb3n1A1L)`u8 z6x%u6uZg*SO0u=)Nw#ha>IPhYPK|Us@ckS&4g{ZnT&3$YKo041SxhaJ!$Va0fTFt- z@RxyY0Ex!z_`3j8x9jdIbRt-P4)j9?Cz0}OvP+$;U0dU}lZ(@&Jh&V48(4-YYWEYk zObV2tK@iAHR-oNUe>zFBfMbXmCzkO{uMP9vES^iK2w6jE`~wU4{~C)$kZ>@+?A{t84*RNkEBCkky-^sxB?H>o4%& zP(Fv*>#6?h*+RLd0@SX5X(G^px@;yX3?b!UO;ZrVU8knm>bjOCoDAV?t8-=&;BG^y zA3SRMH+})>9A7A6tS!(-38K(Pi9Udt5GwcTQ_C8!PpZ-gUSU`YrTQ3n9s=>aO+q6RF>=U1{f4*yeqowaWGiOa9*AJT1?%a+(SlhOR1j$A{OqmGy1(^xszc0-ZvghVA;`{`E`bSZFsedfWunEF=9v}>@ z0*FmQ7z&Qx?m6eq+6^-XXS+fA^8jNMXj9A>CmNk42ySc`5KWj{2fGBD&{Z(3jvE#EX*2vO^B-*##A&%dY z!%$%wn$3Xa0J}&NDrJ+fiv+khF%`S`I=8gDcsyEV(1!H1QKT{ryRlgc8n1E+of%fT z6BDW&xurnmVxE$e810VCQ?P_`d>6vUTB0GK0!tKsliB2!IPJ+~wVBWok);YOQOtN) z2GrRJDbEld()SMKjaE8xSzhUKUc~hC;vgdw!j z)0G!}VbKQKIcsu%ZiT%rYf6}BBx|1bv*zJOijwxS(L|)#IpzT)DKWEK zhdXm8eblR*{@FRz(>^Oj0XQNYc#Z}4!BZ`Nc!@`U-og>g+!+=F>`*d1OqSn))m6X3 znZUb;Wc(XhaCy!5Sj^q1W#=@Zl>Q7-lT*{P1*cMnS8iN*MdT1(mEg@W@wQkQdl9_5-9j44kq;LZ_6WKM)}e^M5I zI_S=+`cAdfgjCxJmfMnX9O~KdT&4q(98$&K$ntlt$OGcQjt@a?VY@!WjZG@Au(*{e zQeHx7=~$8Sxd31zixX2K{05-xr_P5ApZm z!a#pRUwuCtzPtU9zEun7H55^HnZ8)G$M z&9s=skg$>f;N0=Uj!V^|guf(JOdD64-MG^A=UKK$b*>S0`JzpM?%6_rYm_DYgL?K= z@+|H!N?tUVS+{Rw2^IAEgXCG!h5aM&YLdmke0_$!$YO{n+LL6lA`3JVpEW_b4>7+9 z!Tv}|)^vBh>Cz<2yoDs|1@+d_j!Uwt9E-h`y@qy%RbTj|t2qdpg|Wt zPHw-B3mU|0T+qNvFKF0*Z!W&w&+zSjhPQe@!?>N?Hqli8j5y0WmMhv66)rk88$}ty z8GolA1%SmQ|NpIA_m*+f|q zt|awj+vBi8E5|tKA|-!4zi!`f?t?U`L$Jn>SNm5%ElpQ`1ZG`-7FT{0T-_%NdF$p& zKT(#ygQRQS7u{n=j37-be>ond}5zEZ>UlB{kUc)62< z$g9!L2PfGFfNQw)l}4r~L0$}5jXT|*L0*1rLf{t-q9dQr2F67 z+P7xWlh1hlBTieR@N0D;Ee-n$$eLx`PjK=79r$f*yEE`6%afe-DZnT|mWsWvyGE}pt}c6fqG%67N>aLX$u&fN1=+ojk)mokhPR)KxP)H2gH`}_Hp)8>V?ZP(BK zadGzFGXp4$v@xDB8;uW6CFbVUyR%<^)6Hvqe}{)Da=!V}wtUwZr-DuR__q1a*)L~5 zi7CyW+(Y@G$ou)DP3XHynAX&CE|ce2roj5twf-(QQQ!dI8%4==tzKyDGXoDQhSbO~ zme6ca4xQXi+UfJHC2!^e+3!QgD-b#fhbLo8s|T16Ze*d4LF2Vpz( ze_E5FH(?rrSomNtGjDTG-r8uDj+i8in{IHN z{U@q$!uzH+lOtDr(X4I80Hw z{kDMU8{`{?fR=WJl2I_%DJd6UT+Oa|og@L5Pf&c#0r8bCKm|ftVSdod3d9dkf6tWn zx%8TK>9vU#wb!HFUU2exL3x@d||BBkX5b$ZQVlLwQyr4Miq?Rj=EU4ta zRmCxJKi>O%SaB*4KSDiE-j7opq_~O0=q>P)K22hGus28(^{hKDGo(3WiVmd3VQhzd zHnEkIHv}{7h4|{0qGq`wMW)Vof17QJNc*L>0GcOmK6HG{^T?V*127sgt6ljB+(NqP zTw6bAM_|Y9py$;0oCnp}sXK5~+WICC9?%cn?H3+Grce+v1%*oO#=--4Y#Z(>FW~hq z>Rzjl_(!Rke2sRCbs5+)Y&}7Z_EaTTIdH683Ju4gEW4BHGIv;zw4sW1f3L#K3>F*& zv@||WDsLJ4$LbAkeBe88w8^*L7-Cy(vG_1JFhTCcVT>%hOL-=8adK^Lw3-M6a46#o zLflEA&Isi(E;1*CI`c#iGbmg_7N%89Bs&N{WXaIRudaYmA^EK_$PudkAmggR*r-BE zyA}frNrQzL>0atJp3DcjfFH59%VWPTd=$@K+M(Oz<3xifEACRr-W4*a8J3}2(&JS*8-dk7lrB?v`I z<=HN5_9C=^{YYd112pNmrZel?$J_)d{ilNMVQS;)=#c8lwoDD? zN30smyL^y+e^3(+1cE#1M+DV6mwy~M!@^?NwhB8V)-$zBS7etOeJt5flB7?DS%diz zt2*-!l>9M56MWi9{tg~f*%EogGCr65eaOW~PJuo`DlBexQWVfZxdaB{gA!Y8(dNOn zNDqbpp)>?AQ6fZJhx#6?KKJ*}x&2gXy+r(Nfiujxf61Mm3h;7xW&ttlry+VQhd3a_ zqr&!3bQt2u&EU?Iqtb9pIX1P*MM_wsVjV7etmC+#eJ-*a3G>~O0~ySuruu!}ffCvm z6-pfgvdl&-ou5aVLH2Qlj>?85y{*cqr8?v;bGG5+DjfddvJ7FBjA6ZtX0{G&XGPE0F$tN_6@{4JgbIwq}<5QeG{ zKR`VK?`1g!1w^%GKh@10%*1Fp6&d9EF7bdBsNJ!D8mIoGf#a#Y>aA!EQg znT&gEnafHSi)wW)6zLX4^by;gkU5zzsPAq&J6w;TV0X(yGZomHqGu&Q%kXREhCzZl``-fEmX zgYPj0Yf5-o&$I?CCZ!+b4E}?sozjZxkTGDLOvc0Iol$w;y{fSmr#N}-F;(%N0qUC& zf3D>eVl7m55m>Q~XpLB3pZBs9!X%8b^q}bw_g8S#5$h3EYcYoir8z_mG6t-NQLW+} z!dFqPG48M6KO@%j)UD%E2r5k>DiA+nJsIID&mepzgOI~ua4wc}ig>7=WEo_G?LHW4 zkKqM&`q1=}6aiB_`W2zomz?bE95_)Ie>rt;GsT6@M(x7ddrd^>2?X)jH?zLW9zoP9 zGRZ%W8H=^g?*QW7!9qVP8M8%r%a|Talh=LIFK@12o!hv1bG{|Zn=kVDNl3#Qw>u$cg{B(Q$>gr?n*YEFd``^F4yoGz%u=(G4beq57S}ujn z?bV0dtB+S5&h^b79nz;aR|D4dP50^b_2nP$Z!X_Rtb=kKKW4!;l#{Y2y%9n5l+|F8v=c_SRmLF=7*wp?VVoGcq-kF;ppk zR`jyZbXSrvdXBY1>?{X$ZW~|7iLCIBiIr_`ln~QHg z{YtaVhSufW@@$MEqeN^dsA0xX=<`&6WSSzAYh`-M^n=@Zm-ah+SO zGi7rwW2?WOjkO=WW+II8*~^P(KRx5Hgjr?W`P^uk8Le{9Z8n)byL`j4D^#MhTuGCC z2u)`hm$?-lx6|zW**~6rP7ro`Zfq%+D`C5xbDPGhGL0v!p(k7}waP@^H2x%iw&^Ym zFt8cVl~0p?&6w$#x6PgPnasWR8^$u9YmLd~Qrg342rM6&8v>2i)=6mS`)G8m1~5QC z<6@hOKE$NUop!_&V-uqoI%bT~RVt(C%Du6;5=djiL3%vFP40wf9=YGW5;^BS13Hp# z&gixWOASYIE;ASn^J*`aB6rSz?!&UR#dE{-DOj4shN2HBxQcLrTk6fjf|7#*__3owVNBdBF_$$3ky4NAF&Qd|(HOyCrE8#LrX_i~Ff zku#-0F5x?~`uRSdk`p0pX3&Xe?ooKQwh%cL_fJAD7s%x{$%O_+-w#}WePAde#4uPS zQ;&wCms#ewKP>~_S%eaQxf>|l%>$b;M=VK* zMkMcrfe?)los~KQc<3XClsg3Sjj8`W^xbhpX)DJz(-U_TlYD&Plv~stU^co%@?#IX-$Gidp#`{b; ziLk96ClMN37E;0L0iE@e-=RbhkCO-jfJ=;a5a1hIg9AU1M#vn1W`YbsMIUCRbo64$ z3<6GT>krCGaTF_$PTop}(|{q6Z*Bd4Xt_UmD+jfIE_NpGEvsY2z$}b^48z3k{SMC= zggll>88|DJ@o{HX$(Gi4FJAw+g7mm` zQcC)x&J{>QDoQwq;XM4FrLl#p+lKS$UTEIEb20~anhHG7!+_D)ItdIl%v+~){Io%n zM;fxfZz1li_(z>|;Og!kof z!Qv+$%&G&(wz*e{kf{dA;}R*w%KxoA?uO3e>V!N#1o(}u!NDIWk7o#Z8Z#QxM;V7$ z=?(hV#{hFM3AMJQ3H~-@Mz$wqWY_L)#?tZ8m(_Aom#ga6VpT2XY5B~iITpTO&`s1nU!0ARtVi#P z`Z?~b7!}hg73tCHri^uy#hGyEOzWnzWvnRb)S_4}*R%2}{#YfGZ_hx1QEOvPMpjk0 ztQYHL>||NZCucmi+URn*Dprl{d9piyD~sj2E@x%5)b|o)wg`P*l~dS657O{BNNE@i zVOd?3HI0*g(>Uqcjx#md8s~Ub%~IuZ741)`?xt9-s!6Q4ty4w0T$a>z4hP2XuYsH$ zeW2#$&vZ+b1hh0R6(`HZ>~>nl0nZ4JV%#^s&G|2>M-OkNtAn?PpI4Cp<#+{uD`DVN z`mR{sfDg~<6GA(hmo&}_5Lak4zm9DJ_H;9+{t2W|x`tV-8Zjh)Br&8Q34zUFMnEBFlj)_GIYKIvO!GIM@F`5kkqia{ zEiBO@a1=E~swv{n*G#H2Cf}?XMjxx^iwZ1BUw+=rBL#-Qcj+`)kxq5E6)WQNd<2piCPrVK zIXPNPr;%&Tl2XG`kf*Yfn{2cxD*$viHktXh>(!KD4_`A<%W2KrHg6#fDJp>}zu++`W^ZZA(aQ$VB6f zW`9OXF?N?#qzNS5?SH=5wn{tslZ`@;nC3WYpB6IM58SnU(-+feYb+XkV!V@xp%r4v zN4l4z<)jGQr}DS7NFURP$S}Fqt5NkXY%d7{92z z2nqxuHvT@J6m>BRLiN{Qi=47D)K4skEpF?wp~H2ZG$m;cwzU!wAmP=hxz37t^=>hZ zZbb#}Xw~VagjzC_s!8^t?B{B^E~evZj!{=cxoF~-Dh_5gF2=WE{T75qwWzCP3vkT> zOK9}gk6xusi#FZ=f6fx&U&9jle>~Hm+uJh@u?7vk{4DKsQ>)I*&S|6*dVoM9hX`om z=KLeZGV5JmPah1crn|&90W27jK~ipX!iQiq7CaZtKMh`r#Do`hRgxHFa`b9h*6<$^ ziGq*5E=W&N`M=}kyLH6zrX2shD4J&HAMa!~wfZ4mzJDz(f2)_}YL(i>%@Jx|L@S^a zsFOM<=5r#2(Q5Q6_K z_N5ZR80$qAUHcBOeB?h9T)$>W-bOcAP{(aa|&=OHpL)pJJ=u7)1+!ye&tN6sc2wR)#x=3*Z27@cGrsybFJ@sgh^pD*ke?|N_ic22yRN3R$d-l8VccR>^Z-c{; ztM#oZ*HD65-mPj_H%0%p=Y3~yBiw7I8OI;~nc=kL)+7=L#zorOc?Zpa2Zg`;j|1Mm zKll$#VL(I*Wo~41baG{3Z3<;>WN%_>3N|nxFd%PYY6?6&3NK7$ZfA68AT=~GARr(h zARr(LmpFz2A%AU?%Wm5+5JmU?3attfh!{RZN$j#sg2V;dpcYV|X%>tuTSR2i5a|^D z`;rS!;O1NJU?DM2_txg$6)3Wgs0n|NBp zLwzjRCw~`$qub^l)Zd5Ev?B=aQq9**W_m z?n)9Nic>*9_QC8D6kc=WgAN@mJD>FA>2oZZQ}j&_JDqrQRiS&>Wb7X*3Twh~)~7zC zjCFR1z^6WqAnE;noWMbMqw$Yu2~kCR@{E^Y9DglcZ^3@-4Uv*v_UD%wx+9SK1SnU| z`geBpon0B<`5#?5qnjo*PR*cwJQ#%r*8+_?iGOYSJ%SDIV1r%_9?fOvjNhhV~C-9ZG+$tP1MPv<;R z+aKmhi|!@3XR0P8S6MElB&?dhTqaU-aoa5Z0ohRj{F5W-D6`6gMkbdj3IP?fC8`lV zmnb;_6|+m|-XWK4X#o|tJ_-TpE|>C!0T#DCIRP#(m%F9`7Po=z_;{g@7(WU`qAeXoA0Ts7P#{rfcm$CQ(7Pt1}0l*8F{aykVx6AJV=m?kng#s3r z$@l>cmmr1$7z8#lFf*4SnWrJQpN@;+{tw2S3HrVNA2AMe1nlSxzP9)}K{B`nO^&!= zPJ)XQdtRbh9Genj3wx`$(J!#{ZfpnBvwxSz{7uiJ*$J9Havr!9x2uK2O^BR^+#pU_ z@5T#=Ime;6eZ%5z;~htzAKDRZhkr-XY)C%N^}#J20YEx#Uf0``o`MW>_Cx0Y+^>A~ zO!%e0A550Vp3fuI!;l_J8fESUtGGS|ZgjU#FEndCHUz?kDjPdSSrAvk13(`g6BP<^ zoY0uL$}^gaR<^c{_>77+od1&R{XDc$uDJe&Nro-I{bn2kniYuAAv4%%7JuVWN`+t) zl(L?js9PqRWaG=)DC?m0P$mS|tVecSNUneUH~k*N;<3T&aeo%6Ha-e`e5;)n*ar#3 zYiHdXkYJKoAS(lZVM1n52x+VF1@~sc>*{d$5v*x zzaJ#pn9wL{XuU>mPU4;$=*1!YeSqejRkH;V#p#3+E5ae}q_@DLSbue+n52W9d$25H zRMlcsYLP>dB?ftNeK_Q zffT#dPbemp2n;PtFP|xHas9~nr3^?;MeZTW%YA(E`t#*OC|?<3Uc}~ zq&CIaIkSMWq-wkdha zC6HjtM^xKHFj>Twx10Ch9hCRgLYnkeOP2PdrHH$U^?%(fq5_)w2CYLl239gx_*EnA zhAj3hqngtjpIOQL39*1!uBt57a^rpeJF>Agy3apvA0baO&1>lol`Av%e6%dguD3m_ z>IwU%E6h`sa4Y>oClKqNlpsbQ2OC$BU7VL7V~rR~lLP7Iv81RBI+$pxl3m`QJ+Ola zS|dss#D9Hm2M#X$y23vqDXz&JO^2k@5L&^vsh~rV8^P5}K$r7*PCe{ro}`Mj@!0jU z5nrFhyxxri9RxLhNyc~SpYW8kTo$6+42kOM`^aHXORkJ?hMysAy?ezwXR&`1GGzs>_%csG!&CH|h;cJzsZp z&I5Vs9j^wZRkhXrq2Y;H<@A4en6XJP&>iC7ic&oc3@;|xQ5>!ap%p#+3odltUWX8r zm46s@r(1bKBA{>zpEkw2M6Y(zy#NyL@J7kQ_TB0%uLat5MI5s?sjS$jWDGSp%c7?t zaak&X8|k3HxWc~_mn$L@VeR+`!6PuOwY#e z_e%c1qnM~*`1aK*6HQfizY-tnYA&7VKYs?-g;e33EtIxP9mXymMdYW`fOpYzw)=k3 zf9BdMSWU-GaO|K=^icHh_(xx31-_Cv_KL@LGP@kl#gi!gd<|kobdiz_j_Q7JZGXY{ zaLReh=2@_($;L_}(V9bG+k=H3P1ORgd!DDBpqA0YB~N1q{_Usr|^zjT0@GIO%t*IUTi$K zvd}@id))w=WjNo^ zxFhc(-{!c5U1B9pc8H0n2Y(U1pv1%be0@<|8`!27ufjSK2+sLl$u@eY2A3-By2kka z_OX7K$-(*ksQ_-8A~r#gfy>OqM2AF6B2Yu+0uB1N%w#YCthSvm@aC-BAEG@eiJ(HY zto67LuHo|{w7=QQLTKQ5R>#B0)49^AHwcWU&-LPHtLH6YJcZ&MNq=A=h#5?AFp~!l zf3Um}0O3IC4;zNL_#Mn5l4XJbpEgPmrLkZ&^+#}5^?p2Kr1`V$SoQ36e< zEwc)TO>)BFOn)w$k;;kMzCT=v*=*vaeEh(Z8{i;qbAXT3e}TtgMsE$!!6=2~vXtbo z`i_fYkR!qyyjAFQA;0XAm&Lx0Yeq6@nL%N?^6D(!K2X;XdN;Akd(`1nJAXvHdv)S8 zKGTJ;7IJoh(Fbg@6(t@@CJ@+KpvR8t8{kc>79q^iLVx#LV4>K8Mm0hs?$3>I!H2qP ziHpGE!Es*ut=5*0Gq2_Snh-9tj42R8WP3n_TAG55aN{cH9x=(G|Jjm$kzv>sZvLC0 zLSW?=tp48BgcjElsQPKtWBeW)`cq%~1Z`QIDXd_#g2D}fQtgBmC3yvX==1Q z6Fj`T>^;PVD%uo&^u*#5JE7iH^Yq=Bx;Xo@Lh?5l(iOIPzuIx1DH^k#vYliatL1%| zijfE&{V?g-7|w9VOoYSh6-2!Iovf+xSAG0ZO zcf+Lw*OFb(D<71MAUr~Pbk|-y*(t}#J4;QUjR1Qw$pN?GA*y4+yx_v=hzTX$ zLE?FQZ6faJgGSQm0vE}9I=5Qqcep6IFN?pnkLO4^&ib#gc4O*8bE*#BD>xkTivcvg zEq})AT=>>_c~PP>I{BqyI^!D8T8D!cj3Z(_>kI=|cZ%W0SoK+Q(qHQmg^4^z!)Su| zH!%e4qJrXmKi27`-Qn*=qU91?#>;t51=F~VqrJVR);Gnkr9Lv+CUizV=t7u=+?MN9 zS%tkoiSxTu^_(x>{=XUnkDI@_Zn;qGYk#kMyr+&(u$ch7f6RvwNay3;>HQ2r`@wP% z!$7p^J>h!)Y@5)@8I`8uAQBqafH2?f^9)@Afj`UT38Vchp|S+%Z9sDu=7o)_@asu1 zU%c_WGp}#6ZHWN8Sp&=>o(Jzr4yz-OAxezVIP$R zo7;rC-=0q_X;Q0&P||2C$RXY2sDBUNkwg)V!Yur@lC|hP?m*Mu5YIn|syVZ4SgX!p zaEXyInE5H2iCvtyom3M$JH?iBm(Dci6q&HilF$S@;B?nn90mDN2`=c1rYh!nAz)zOFnt$&KoPmA|L zz>AASMgCGE(D6Ru%lKzZ0QD09q0U>iOEh7O(*x0=tny+O4&0Yr-GlLO+E_uif~f1b zwF%gr&`KpL?3`iT7e*^=Q8Ce~3DT0Abobxf&O!+|qH8^J;%IaF-o!6rZheh!xiNus ztGl`cONYmI$@k*bPrv6a%70H#ny{ps=ubwuKb`WyacR^40bhEarTU!J=J95NOvDFZzI0iEvCV4!H;E?St@4FrgN#%QmnQObR_JEv&vJbuM?rJhcPen|GL-d$ z+1lAn|jI} z_^y^5+^@IrdH{L}ZqMh+vDsS=5V&U}G_;?EboOj>gTH|bF2t6ZxBS_Zvb;WTxL<)l zYO4ln!F%G$**dc;&;Y;q`EW3e3hkril^|qL9N!(x_LkcXPJf>s%8A*c=r#-T$<=J!bM-KQg*V(i_ z*RZ#$NNywR9L?*DzM_jFW;OYXE;?3<-)1 zAEX&%vmWhjLw|4pq1>#|jJn+Kf)=uvWX!`1z_(-Vs>f%c0J-zyvx=AX6CQ;fb3i-0 z;5NFey&hKL5HN5Na6MlOV6r(JE$8zOJkw%JKZ=Pg1-;PPbqlen6CI|JHQa3ueBF{j zb<~*b;#zIMQRxEs=v1J{vMHox0*>m|2Y9USARpRuS{jb$^Yuni z>h;?GhBzE%Aek4Kw7er7apAqEi6Oy~pCMpz3 z{iN^Df~mZzb(l3h*lwFX5yqy|O#9J5kJ>C?-MSJj>e&g{D@a%IGE+2&e5*W7h2(=8 zd{jD>7=P8XSASFNuCi*y<;L|6;mx?gz7h;FYS)rPXLSlJNp|AML{1Ct{YrZ0^;;ZK znsDFK6)173;00$$J(~IGzQv@z-RK%MvD-HAbzWCyu@bPF(~t%V0<7f6X`r7)BL;*+ z;KQzY2eu&>c&a32oV=(f?C4zj;NShnWbH>1Ie&^m$X}}KKnWS9`B6H#L?FyE%y7qY z!6;$-K1G%+!OmzCh_tyqu{fn4eyt+BD-N(0 z^XsIhiZIE09L^7lhmXmfq-3vMKfKaML z@PCO2klfZ4&&(epLpq{ zh_?`sJ4mL$QV;R9fFV%6;{XC$OD9WCIsAa~_C!EuomsBA@~^@OuP*m=3V_rM%kXN% zz-(8+)ZAb+ruo`8Mgn+2E|g|v<<0UcUVl#->c*LSvAE_A7&yaXNLTjWl(J~7P7bA` z>3fuZN<9`*?6&HNqLF>=S~4g%P&eXNUTicF9w%O`q*j+q8@f3DSIt~L7cZr+>5yKy zYrq1t{IY*rpKYlC9zhYRAxm6(xq1+C;KzzM>y6n4ig7d&{pd$F?c`e>{}c$9tba)0IXMW}1#6G-%Z6(mA1z0P;xP(>+gLt*v+ zPtAh+(GDsD&4+1UABg;jU?C9$?|&P^)H8lJIu*Z``e)Y0h4j9ey&0fRooomlWt28j z3dYN3<$2&u*Y9O#P9VLo!&Ohvg|7~Fn;7YEFvp7+x!UYAI0SU#mK(0EVRqWyZRZ3^ zD85%+S{v!b#-Zp{-+>@@cI+&@ON&spK^+;W`vGi3>Q#da_`h_Ti z>93OzVVU3X)**iLnv_!g2}fL_JVLC@RIqz9ePnbjtAiv;_WX&YuIa%Mf_e`#t#JTy z|B)#MU(?q?4@M>ghmPHs#eY_YM`%TXw#ZK!1^LfkXoK>?^|{uM64UvrL*X*qyTHB; zE6}5?Ij>Rj7ozA&u2u!o6ogbMB9x}Gq%G6Z5OuV5gpAbzZY*~BeOL$_9bak)(vUVV z-RU7uw7lE(%{7~^cVNEwg=UyU)I5H^4U?t&o3k6kKZp?YN`h>}!GEGh`s09~lZ~f6 zJ@hIbV_vJ z3;8Y`KbFhha8@jryAq7~7b}mej!N9wlM;v@NftYd^ctmYnl#CCI9L)JNnw5w{r?hN zRh%y7K5`Mxxl7I^FLb(EVh`4BN7P_MqC&X9@^UX<90nN&sM9JAxM%)YV@N?6QW_)UB#cktX^k^6UpE5lJNQy^%Frou^$W-X_|!O_qexI8cy)!0ws?mXy-7e z8l{Nkx$;Pf0)H|kmlK}0w)(cY#Z%CbXqP~`5(UqkBfH4`J9oY%J?Bzp;vMghNlC12 zvFV?SrlcyZ$Et`94t6-UvCv|PFyi9(Vs-QxxAA!Yr5)`bOnV^Z1|)6sX|18f7IQ2K z1E6l3hKBu?5P>=WhLXLrbufcY@1|pyNXKtTtpLmkcYnM=$2(cKJ*j>nxOkakB+Ct4 z#x~hh?uBY?cQ)_La0irs$!fdrYc9VCx)li#TZqMpHqVqBr$KVM;NGUfIM2b*iiSh& zj~L;@&*A9M?WYiysMmkj$?@M$?=poLp2i|>15*y&AK-&P9JIE;qs8_2=P-)Q zNgRhZPJd1JxJ&H&PXP)0elI!^@^Qhdo+rY+2dA(rMJ&b;^FMrY?u>x%yaY}q1v_+$ffdmIaH-X4a zq29-;sI4c`*7zGPJMlYOf>mMwK?-G|mmV;iF=eIZvPXHY(r=gHh2Lt-wBr&^zMZ7! zeI7OQeVoY#q@U9C^EoY=4V6yDpS7wIZ(qyYx=2;+xZ!>K&tYTCrEM4*6` zu7Av2P>juz&=mZYXi3g1ly>bOLN9j9*QBtWd?O#@6)&5`U1&HFhyG%&23PJ|HoXMo z&0N?~hd5GI9qE4w2jeYn=_WU*uigb}p~{bnpYki+S45bv*2-yCW6Bt3`87eW(d9K_iog#H*D^}IgO?20FXMSr5E>QD4yM}Yx1 z5LnqN4TqeI;Y)Xz=j01}V>x*0Od8BWE;*+d%qARF!aE(X#`UA5G3s}kqQ_6AwSS-l zihSNKwx$RCG`h^93=Jk@YOINV3xV)|#`OgjeM60Yjb2(`#d-qszxZcSm;yxRoTtJj zKI+OutEYxDUT9ia?ehwhS(ah4K-BgzUfC>J$xa!z6DL zkIlrByI)@B%8A$@l>aw;*2v-6og0DFYz{GB+|cm*J)X6$LUkI59MrA>;uke{6bVaAw`s zZEV}N-LY-k$rIa7I<{?_9ox2T8y)k$-#Pc3TVK_!{byp#T4Rnicde?uHaW4ly`77y zrvreQo|%D(n@B}mS&o^Bi=Bvxffa_FT*L`rx3PD#G_fG!b#rqQbaQrPaB}5m z_@_t(03dR)01%m3+5m_|6cn|j(akBlN?&yeI{%hG7{ns-7ul3)olgGa;1{h{$B2!Bf7b0VTxuqQp z}?%fT>wr* za`vVGCp#i#ds`#BfB&G2Y%Og(|G&8Zi;!|L`bP&LJM({(WBPZ<(plWn17NCX>GF@% zW=1yuNc69`2H@ZOA_p+FbhZ6=J>VZb{@GDedpjG?|GVTrZTxFNMm1p-30WE1{|>;v z(qeWd_NJD0=0qwk|7dCCWcuI0ztW0Emj9lf|B(65G!ZfXe?MQ&$i>OhgGh&o;eW=1 z>3^R8SbF~tB`j?3;Z4uX$w@@d%ECm%%*Mt}#Kp$q`@iU#xH>rj>|FjO_&>e;$N$$L z0RSEV6PWcCdlQ~utF)HT3O});xk_-_xfw$>+7)Kt)#;vF9c0TP3sZxmYn%sFoP2jU z{Mp~ee0x{Be^L+4Bt~%nxRc4LXyS0a6`a=+(n@o`+U<9xg13fn{TncKY+Dm~u-k}x zmyC_|Kt-Aq|^IktgCVa0EUqcE+%>{M-ByG!l#e|M5(Ng?zo;M|^Iy>@6a$>C{; zByiNZ0pTWQW^^cSCvA!46H+}TD!T;MpV2}G^IcGuYa{7_rT4bjF?pNz_a?j~{@}KNw2m<0E~auc zjQNQoe^mph12q{c4%&>?+)rUDY?5|yu*#07mx{K7^O|QX0{7SV8smrawR2QXYm>hk83mUG({Xv3?kgn5&nE(-@aP z6{vr{1eqLwdF|+f@ry&vRsi`^ZG4^=PQoa>e=2P_fs~lqR}G1GL;I=A+P%#so};Ux zJDP_@g@FqgzLfcL+829ZXNM6cKGF2-be(8skE<21{`jS=Tq_srrEF_Zr4>1_o>lDA z1ZT9}fBdnz2jE}KeZg?E;0&pkC94FZqSv5L7G}rB{Y!9_88h0w%RH`puN1u`8}T|L zfA?9|WXENyyU3J?GDyOf4pv5ytZ*_<$0TO6zd{O4d1ffxv!eRwYiWP;^`A1u;?g095^nI7q=X}-s!LTPCG!ILkR4>1|>M#IaIF_1tnvaN@k zfh{G@bj!jZqm++`)FK!>8`=hTuHRrH3<;w(jSWCGi#`P6g=|^I2Vt@1q8a@m$sE5O zf;4Jjh%^vggQfb`dGJqLz^Cb{L(rW<0~elK@PqP5uXy;kRuf!byJ;n^7(o7xe=;U~ zt7PcamX%FltTMY{Z|T}>{+)J&qe$wPle?u|_m@wKO6DiS?yozkBT)BfN4>w6u;WV! zJyJm9zYCuoQ+`{A@2R9an2DSf_Md}bp2F)tWc4^NrnP9}_4(_uMW&Z?#U|dE=T=Fy zd0s9CG(_(9i@-V{M3g7u)+Ohce?+%wFH3**Xg|B$pWUpH&+RLUOC4_fnMIQrVP^4F zeRU+2-^f_zwDxh6Dz$V(uM}fOlI#PUlM(xmHYXL>zB!5V*VXJZ;{+c_+Y;*#JJ!ObTmo8v4fLsxW9YHyQ#xYerssr&98<+ zl47jNUc^kWDj2eH$AXCvpe`+zZq>rVtoz){je=(I+^k<8;3Gx%1E$Ea@*+g2pb+3M zJ&Q7b-BslrKfR)EI){!yXITRpt~ONvou+)R_Mz^f1P@Z@5mtB(;-27 zg7y>k4cL=E{4v?(ysll=J@D*w_?WWYjKVmXVz{O-;CyMpTVA?BU&0e~{B4tws#o{? zbGIdpbeezc{5eT_xx~#nDwJ;G}e>4I@NKJ<$c|F4X{WdNEi}>u@E2X~QpsApmhxz%OpXv5HX}INx zb}B0Kc??sOuIppK=&SIj1fK2;BaLzk#aBq)oKhKj=H z^Mfn+%~QVwuvF(xpKXE>lmm*{%o9H-tP zlY~_cbnY)Hf9BX4(JY~?3^ed@jRaCs;vUgE^%D~lsl<> zsL~BL9$iDL3ipE57>vu$abt8|^t1-)<+$U*9qtTIYB3d$A|^rv^@l@a zQQY036~D(|P4_`_RvRTo@{|r0LLBowkW3YHe?Q=;M#r~xEt7pn(EhJQ)s}by+l2ob zZK*u%fyQ9V`~l|4OZq2kg|SrP*Sac7DZ%ujM_~Y$|9Ch|#u!No2&%a6kABYp`dVI;w7V~0On?1C&!bZ<~xTOCV4 z^8u@>_0;4R_?Ix1zXkM;IyitJeB7L5e~dffkg30d=N=17Ha{HjSciwr?9m;Lx##Np z&U8~x8s_rT=PpuJ%q)q$C9?BH5CeQs$2_;Qx12P}nb)(fb45h5OfQ|1n%*}pz9*u} zBujbiqHy>W{V#%lV>cGXnFX(MV1_dgFOj2~7A-IM1r7Z5toN|Iz`Nr;4%d6Mf7_1L z$3f81TXMo+8a!0C)ivFaT@z^og5jcTBRWjFMiPw6p5PdL&dU2(gdNM#7R{!yk@)PU z(N@{O;r__y4;B7EhS$^pp<`%{30 zFNmeObg)K7rCu_{T}yt3LH>8aZWf?h>oP%vLoK*owd6Yfp|a=Tq7`+xbLamk0 zalx(PP(Ca9q&F3|NmbJkmVFO*BV`@$h8W?v;demt@|Lc2Id zR3f{8-`_{*@M-S!Pr6kHTtQclX0vW!q!_;UWR$~J!|tr3Bn^28G^({Bf_bbg{>SHg z9{`2Owe~Sp+~(w^2THXUe;35pf0kdr(oEEG(s_`%UBkB-A#2$#T4C24yO#H=%Q{t? znDwF1S7^WE-zXt-xH^I2!~%254^%SIv; z>H`9XX1zCH1|X>rnX8SfmPRuVFCURhT*hM8OmI&kNh#FM#_yzSf7~theR&x|gND%h zY}q6WBph}y;k&;xK3NyN=$mD!S4;12bI||*or`Pt4M1uJf8`K=DGsR?x3s^RFju7a zLF1?L``G>(G#2&rcNJp+upa2d`Ovbbss^sZ#d?brc+=4v^-d(fw@R4R-aTwCPx(3o zv~&YXjHiUz+rfLm^!>GwI|`*`Sral5HHc7e@9pG-aU zLwfY~%ojQM9}CAHqbqJ|9kEbtutE$N4Te^Rl)XfIV@*wzToTSg;pF-(bPV}I;hTCq z7Ws=aj?0qlS-IgDJ(F%^QfiLJ+IF|n1X(3PNtbep()vomf4<}9#M?(bCZM764l(sO zj=STv1svncP$&q0ni`kt<6B>DTX6ZJ>iL<=SgHVC@z0nfPPPD0H=g5+P^ohh+GGkQcNMc`}?wz5U)=Bf*RmwT-^g z9*F2nHvsqGHT40iK-IQ;dR8nfWI0ey3qaqe@8IWX* zGe(&(Q4AD~dNrxc2HMjvfQaiaoWFk3opo{+MT_d%`7<#t*PUdZI@a9$X(v1_F$vwe z(b)Qfe{fygGZF^9)XMLn&AWSLtKY0$AY7B6+<1nZFD6+c4>Y9??x5uj4nT9>|#JK<;8% z%Aycp_b)!7QgYJlE^Wg1x^irR#bcuXU4aad&O~KY@IW>JX9KJCPE#^;HoEjo7(}G@({PdNLkiM>}$icHz2>%9o#dKg%apx@i&<7b372g3PRq<-g`a0YBZRFkj)(PFOEYhBp}= z@Erv?Ch4W`$FE`Tnrvb%9f}o1u68$FGRMy<*B7 zfh}Mdy>5~W-b?aGGBz}c_RbZamW6#LhB;OKp)SlxhHO-m%L(fi^u)i&UkdHL3BG0N zGidRIGm@0@UZ zyaoAlqTG|8TnZ;=k z5R9qp&*d^xZ_`L2KSF}Aw=Sodg4x&;BfY~g>Ybun6>b?6+a6_sdQ6?3r__K5CbqTY zxd4+Y{d>cJ;JMd`F(9NeY>7S+}POt@@FVremK6}5SI zK_$5?te!?N1w6WLe$mL-tNTb7x-6+_=bEMf7=MB&7{l+IU)}~*;kMKGS?jd|jl;1J zyNSf~qW zNiNQd!HAw|`0E3223~^Q6W3mkjBPh6P?Sm#!EI+=gm+RuR&G09TmJ7-%hpsDHmfdy zG+<5{C*wmRkKl4Ge_lssFa;X#vc_tswNJQN3<5bf>!1w7lN%A;eyA{Z_|8A92O}k) zTwTnfvdxjLMr5MNh^J8Wh~4HIEI_!e-;15Gh|3!vcQwjMc4VzIe^YH=N@nHZhZ=0d z6Lg=bL$fqzwBlajKD3skfAtF1D9eKu( zsg3auXN&rsHY%e>D*%v5W0J1HP%eW!$^4!pJ?f1raW{F&c$)cAwzOME$}hMn#d zx;4>0j`(ob^kzDN&X+sVd^(C}c}5JZ0)({DBJH)Tc{9xNIXCc(V;TV|s|ZJHwX2Vb zQ2)AKbn-yPIR8AX|Mn6JGNo z{t~q`7B59zJ85#osl^H*|S++O^i|dGj34AB_W}C(5RKvA|llcU~$If34S;=d2fHTsr zTP0eattj_yPuzC}lOfLlOl~Z#QE{2Pyuv&T_CLcxAVi;;Q9rG2eQ@v~%hH5STC~fO%D>m#HJmUW?1X`AtRwEGoB0Y{Sw5#onS)P4ao|Rrbeu z?B&a)gOmPPRl*Y}PYO-<*f9xzt ztv5s$c1ash*%A2`&N;4*VDjZ*xIr)j1Agmfi*cgQdno{_3F@&>UCHEK;f)T_q}-X^nn1(W12P-R6p=D9oak25Y&)kjY}tY<$~iPX|Rz=(w|?UBxNP@ z87?H8jg3@4eA8{znRJN#dgbdDe`~kS3Hw?(I%9fX>@q)nt2OA>M+5uix9cU_lg7WB z5*>*+!JQ-_>mARi;&7gvX>@y{L6GHpUXW}QAJoJ89}KyXV+4aK4EhAI{sAbZG)PK`=Ke_T&_$527( z$k1OVO(Y!cBoP^h`OkKv9YtDX2ODxbL7472E*O2L8UScGYnlASl31I zm`YL&HICFBpPFw~h|%?ys&|!JDh2^Hb*E-1Y3$B6bt8e_YEPxw~1f(34%V z$!WsXT~wh5qeMA@*#mR3dkZ$?PPa8FP;i~!ix_d4o$*)?w)V`)j6~xr^YiL4jTrtz zdx`*C7n~yM3MBpvO4tuFd7iRat~T{n7-#P3S)h6xw#yee*rK|wZ^PR43?n8X2KpYA zl(zUcJJUsN%Syqh*zZxX4gyJ76@8ft<=Jc#!gI8;ZUeDkAEOd{=H@ljrT$;2Lm4l z%FqbNad2k(ZBF^`lDX|a4##HZ&t*n%x z>4)NHEen9{p4{ltP!aq#FyZpBL`O4C=m2E@ja)2Er4P%n ziP4FIc<5l}J_$iZw7DG_*!;c-=$jyU(pzST7arbq*!78xm*0b?+@e z)(u?p2@i0E2pcoWn(4@)=uN zptHIqnAy&lm8-GmRG#S>d>S9>3BM%hID1~09zS-GOruPz660h7N-8XpN{dWRba7KZ z=|8qAGW%*_Z&{z!!Y6ttYDO=8GQSAAOSdby{#jgOs6{cxM(GD_F=@r*eN=j-b^>HP$5!yV#)zGYY!iP zWN#o3$!R|5Du(b8QHC52iOISCq7&+Pb*o=Ly#ux32~?efZtE=?N#q+tDqEP3h-fiK zaf&&#0G3QckmjZm&Ix9WI9G4Q}8(y-+2|`Px^7a zhG1U~lT;C&kOLd;L7kFU45j#C{Y~8!U}>flz*sDg`<*f-6$AkUoRMy!WN<#=`>TF|E9&M zSo%v{cb$L9LV2n9KwE;4{wkF_2xCMuXgMitkADMBVgC84^4V@|RX|M61aEemAIqSEm%b z)|SGI7Ew=&6mCn*E9vUpUVn?)r%af+uD#zEC)zN@vP8LGLQ&WkBJ z&6NzJz{2}q8|!T;3~z-8cCtarX2z^P;(%lDXKcb{kGT6ho=lO>JhvGx3~DSNDH&BODK3ec2^&yh#YCGH`}Ibw zFB6&kTB0;pM=1S*Ll73RRi%sVg@@nP-(t>KY>KGT=?kH=)%doynug9I$KAo%-=Nu1 ze8rzTtd+(vC4W9IrQ&)j>ufb|Viev5XjNq^bjf`tl#J%iLeAQ#EIxDJ0T za964(GmpuHTkf@0vZdxK+~gqL^$-h~`v?R!EA`nWH7n4L5Of+|ON)0q7;r?B628Q1$)l?q_TIum z@HLKM`G45Og`Gf8=UNtUD!b7l^dM!u(F%%?*Bb@hnMbtyri7#4L^RBW?6V{2bq!}c z%dm|0>XOU8A|Cnmg0(w2Jh0@eC#+l~fZY#QzJv(^IU=)|YQMiyQ(TLAXxRzpfLN7j z4|UZK+Pkq5?#%ek)hgLo_4?S4a-unbj}CzN*ndzC>{<8bkpH%;WYo%{RR%FRlv?n~ z;`zqPZzJ;*!8LU2bdbX<;VtsY*t`eNX))^wBen-t(FBH8G5EuKc+OfpQwKkiXax{P z!rz*J^qUk>ut*=^OCh;0gpp1HdFMLO>tzxvXM!46(#}_cm--_M@=c!sF=O|GbUUNl zb$_iB%h5>-?){#o2-IWFVh!ac*D8|gT{)lZEkaR!A zNYDNqM|S1|*I~o%(ysb~Vu7nuti)oVw{Zh!2S)-<8yNlXBE0{Vj{4*K=00U_>?e^TOh zn?z{7(i2IWrD=sbh~U3(pO(4nJ03#0{X3qGL{7e^Pcc3fm8>Zg7NJPR?4(BHj1jVo6IXonVm>~ZAcx@%Zq3Sq;WEWnpZG3>i*ongBRG2(v(+Rqu2d$%?x<_7St66Hkfq9V zNempp^25yNzToN1(8}aXb%@zX^pRQTvoump6LZhEmRUm-Nq$b+Qt4Mo5WS<`|2!O& zByDpka!J~f)q)_>|MckOQZv`ri>G>C*U{Qw#3PJ&sk{y_KYbbEz};kgTi z0+(Kk^boMpo&6@LMuCW3Y((%lB4L@J;0iqc^XGRJOp`4O{-sxao$*B8*w+lbv$s`$ zetcPFMY5Yfu<=y(+~1;ZKE$LL0qXK!_Wt1`ZN`|}<5qUqi5dbdSAW*Bq@8xR)KFM~ zrCnid$0t(Ty%9;gw))#VDb8{~5WolM^|TV29xSDwrPd z@4#8&$y!|{?+;?OZx|P*_1fH$cEza{hdVG%JNOfb(>i$hUw`j@6avdvE5u5g@b7^` zzEmqh4OIo$9J;)gA$FXl78zIIN}-KnZg$|fgVCyn$vaS!#xYhb{Zxv1-aYSLf;8nO zN7|7V*yvD8LkVt8wD*eoeFAZQmcYCR(fqH}&r&z7LU$Ki5OH8(s>_^(Np9p%EG$ZC zXQNw6dE{%p8h_eDmPB9AJ{R#+>cVkTUlywbQ-0=Nf9Y{5r-xTdPG!_bZLhFt-=i3OAw7o@8QJdfktDw51!2@!u(0)*5d02W{A(N505L~B^Y`D}n$pd2(M6`vpdvC4kK%15 zg1RB1OnvJw-A(8j4JQZr(TWvm|CauQKb}@@PJdPJYxyU8s?35p0Eg@2z63_UqY4wx zakXQA&Jq+rLY&hf1Mm_MNmEtEXMQ0U>*AA6g<@a>igHI=5DSJT_~)!w?rKhc!Kf4cF8mE z06)WRDJ#r8CY?BC*wqK&a4ip=o(RCWWPe5nWuN-HkHM=|@o7gK((W|g0xn?k3&|&U*b6MdT z@p-ooqZPKo_r=HcVhvi%pf;6FS=j(D0LAB`M^l1DbjJOVW%U<722lR4;a91aXMeiN zImCoGKK;ly^;#-Sz@=l^%P%h=MFhHiZl?n2OE_$>$`Uw&dV(Lkpk;6na$Z0s4NGyb z&NVyGNVg-~7yg?sh;A;#27J&ko_iYOOaU9yj%f$=zdr^Dy1v(uS0FLvJm7FV2fZC~ zi9~%-Nd_choZb!L-0b2PXZ${0FMov$S{LARw2`lfUOe_tNWia8EC5*62kF8HG)&Az zaKLJOxMV2%r`L0zG!Jwo9$)NX+TIjtCip|3@IRI0Z6zgivl4OR=x@e%qGel@NVn`w zBN*tLq|!yiA~Lx~Tjf+GKJaU_NM{1c36pNgm^Zg(6;4zUQ44RCnk{9>w{+jm zTd>y4VaI)P&S{Mo=!Wn8@;+T~l@^j;zT2kz&UavLI{XEy9R%5f9wtoNq!t2LgOr0J4!Iw*Wg zjZ4E{mlUVg@T)ZB9T@NC!Kkw54RbN>3=6`$7EIUfwuMndCH(6fq<>HwZwWr5PUBC= z+$eA#kYPv%DAg+*+S$t}$pW%PE$<({Wu3%tCdzJ;c8Fh#c|>shIq7IcIjx~|-gy52 zHMW-6+hg}9yw8A*UJA}IZU|Vm7c)={hoFl#e-4kz>C`zYCiX2tF3M7m^H-!phoXmk zGjfR|FJ1~3el^JX7=MV`xO<{l%F?~M`l*N+rqhm$zo-n`3#f)ZUpA)INei?<~OyI8 zk;*#FxTd<(ALgZq*h%oR4#e^!8hd#)^KVX2fP5`IK!{vhV1L0@-AZ`H3<53XB<>Zj zGRZ+Ffp1KeI*yBledFj%5KIuwN&@Z)qWh^Vdw9$D^5^5GbWpF@izNS%c719l!I)61 z4yVlQFZMJII?`vT50-yhu? zfNr7FLJW*RKw@hhphGILMxS%#aSSs_)qsy`C$5G|Cx7ddNwsh}hv4wBwj68%yPA{_ z-gt(u4*DC?sePro#eQu3Q{;1aheZryZn2;nNp9Ck8`mx+A!SL$kjpFKzN*7b4* zGCoHhlAv^(72b5ug%`ph8b#@!NG= zwV>J)V}DqjUUF||BFclp9g|h0wZ&_Y)oiJJu>HLkP+Og~!0uCx{m76w!XW1P0DMt! zo%ptN#zoIM6XVRT~S_*@AAoxYN)rM-W=%E&P(Ch;z#UmVYH}k9)%NbK7^txgCm6Q&QYdJ+DQO z!B`Y)ZQ1>oQ;_5taCwf5xb>pBM1<5Bdbt;)w7`@7ggK2<*%7i|(LilWpyE2pxwv+x zsgv71L}A^wI25P)AH&UQEj?B(pz5cPCj)4>dd!_Ju`TdEJM)>(O8lHhkU4}a1Wm!q z(|@dARU5w^S){HjsSAJehaoB~-^E)+N|y2$s7PaLMf#2>Uh5i}ZtOgdx=e zMjxE)gQ_kS6~Pzty7JMu62es7T@$T_N?vOLgD|=W^UpR^`-Mh6a7#22B|yCtY-M;P zbNtGxx%(L`%%`g(v@xSyfSmK|Y)0B4M)`vg$%oglv()ZTb$c^7?kjcbGKWBklT7WCt2hu+hf53mRz`I9rgkC@`i@z<+lK9CXtU zasHeRnf1X0RjCX0vWc$#X_t267K_P*LGsL3B1127`8L_0PUPGv>{&jKPbju9UR)zp zD%HuZbyiZak!iMmlu0SZ&>+@k^$gtti#EFs0;8Fz@J;G?W7V&{E37(K{e&~g0iC4K zYnQFKMr;CpLgpfDL;jsMhJWzXpmH?Ri+BLXzFJwxH-S*s8&h2Ofp1P-j)URWUK4if z&JRamU30A(GF34fOQIjkjvB$8$H!>3=t73*_Kr2%k<4>K5h&aYM%v^(5Lu|R(BLUW zE&h=fH70>0zC+8Q=!{5(iF499=!LeXr&1!aZ>QTn+v<_q$@r^J+JEY}0Y75V-1!3M zluIeqR^0J(5n8@R*244S_rW-cq!nXs0%YuFVFlQK|KB4ztT8H{S|56-<#G>QJSHHr zGrjt_R(nr6@#Hi|{H=5n!IjVtd}x{pUqsraN0u$8fK)(%#$MkstShtG^Ti{*pdoU+ zmGcH9pVBJjD$K_OS$~)xV7tM5M^Cw#42>f!@O~@Fs z*KT5)>zk@=lG)G!QMXJvtyHGUQ~YO)q{Ayfvp@>~uaV>m#eV?bjBeBI6LnRMs!rU7 zNy0JrA&<$pqWPJ^=@G;8+2^sfi`@USqRB9p&&SZwAm8kxIY+YXAVYu}n{GJ*JawlF z-B%|f=}dw5ZV}(VIi>|e!k|HLVN@=L&}oYz3EE(>dr40FdlEGm0l2@XKZZ;it|(5M zqJIK*uSh^1DSyb!su21TVUghiNH-orInrM>ajE`Zvzj0r9p2D@_qR^+l(=j_(g#nptsN#w{!dGakm2FPu(KiG&B`3*~E2vtY~)h zcZN<^0(;&wW$kx&RM@EZb*&#`C<^OUwB;C3Jc@l~@_**-0)iw%-j&ykbPp^F9RY@S z&|`wmVZrb)rIAlJXiL1t=zJuB!KRKtOliOI4+iev${s~R z-NZ&({a-(kEGkh{Xa&XKtP?}#@_$Vuhwq`f zvkwc#Lw`QvuMgSjaIzDyJS#%Z!z5*7bvV=S-sJWvjHQz0#d_k#NT-F8-$!8 zq4N-t0#W5MAKst#23$Oxd)@2JpuULGyp7yN^?%PL*BO*whGbx&Zu7&!Wn!8-K01Kz zu^wcCXglOgMJV(imEE_s%-o&0Il(4=8j|Wrj`3bZm?v-s1s{S@-(I6$M%>%>&<7_w z^uAj$zHN@$OuwPw3}L1@P%eZXLwknk$gJ4hQJ;aH{zz_PP-6y zxPM%zw6#Qsc)Aeo(C(oZqm{-%4%@A1?)!w%G(=tp1*t3bq&+a~V1DE1H^v9oBg>eF zkv1CkjDt`6J8O@ja5{CRz_z2q)IW3fCj6MRjS1wG`>2p?XZ7YZl@iVFs&38Pu1R6b z6+gwEr{>P`gFply8a}V%UddM*#@$ie&42R2VLS)~3xxaMAi*{v=wCY2SGHk{tZ8Fj zv)sIOazgUZ-r%rcA7Dx2Ru3Y6k=QqI(dX4*EV}7|w3}b~A z2_8lDTO9Ll9mZYX?Jpp!Sa)pB`Oy>_`)(7cQa|n=zAqCl8p&D@Jlj~fEH2?4rhh>- zAPH=8C?fnF!MZ!exga(?s!l&<8zl1k?dXrHp-m@(7GO>%LNyuN+l89?dg3f-nJB;B zUhl2~5`1ymLmN)p?dVybV`&60X>SMUcXsy?!7XHe*3&O;#R|KZkhT>0`PB4N_zC^^ zsDZGhKFxpME+2r9+wrsRuq!kc6n~u$>r#Y1m74|jso9iURPmkLnK|=-7T*rldi@Ca z3(c{&H>zk<#|mA4CrRZ}?cgyYj-JDVGWhJr=C`g9s(FbO`|7oXZ+~SzGnwVR z)s=v<-4>dNNM=}Hb;l{4?e5`qs8wE&wmMtq(22eNxKjXIBRgazg_!8O$Xbo=WK0lU z7>$t%`+Y~wpF5lchRL#W^t3wV1n#9rQD><f@8SD{waP=e}38Bt7}%uS=K3xH8k-DXKIt z{Ks~7ZB{hJo%ripLEez{`o?Hv*b8R~@K`f8CKfOKsWOInFf?(ho$zZ_*wAAw}eMaQO^uk>hU9$XFff!2kTxnfM_@%d!L_F{0rponeG z^MDI%kMJQVnZm;kSbs|!PT-kW3wC+a{WJ()?kxmOTM`|L!UT$4Wz4d^PwnfhMGQR! zwhAi?ispx|U#)Le(75MDnLu$3hawO}U0`v76k<|NKgw#&n+#l@feTaJCEI5c23fky z7w5r)744YM5ua1?@fjYGe1URzwC9O;BO@Ea-(CXfOwJ*MngOYwL z=c2w$>edUd+xjebdkJMJgp23xW)^DU;RQj6rr5w9EnBgrYfXfkT2>qG7re!HnE;_` zvKy%#m5xTwCQh1JXU#(MxQ8F9`j-3dRP8$4s8iT0uYd>h413^Dw zJTLe&lq6eJ1@ngbFu$6zQYp|3-4~;C(xt7}D*z~yQ-2aE#cR-lIQVfKDOw=vew*SP z*u8^85)JObX%9UhB|KJ)`p(V|S6NZ=M-i;CX5tsh;50PxV^2ay#9Oia@sMfH?WKB} z$g(Am&VgUb(vomXc!-ixlvv%&1)muTa|X-;afi?jssonqi{Cx23cWGnY3Qhw+p_lcF+qlRU>> zCeoD7mU)qtpLq4O5z#$0i5-?mk~B!np}G&KV6T~Ai$-@{I(Shlg#1YM6tHCLF@Ld4 ztArsnINxL*Iuf%SKG@^pPn;*__+5cpfRdBYWq&#>fO|AfgvZ~ET?9MsEHbVY4;Dc# zXi!PLG?w{G&#_IdrKb0U&MaWga-N*!bAUk52uLFnp4vKk*o?Q&<3TN?#Wxw!&)^Ru zBoyEhA$=jQ#z`FgdG^+-x>uL2T(%ix6xpKuNUgpdorrNl){-?th;mXW(z?@M}$-4!D?J<9v|K`%AuV_`?k_ z_vD}s@BCO|HNHYlB(40sg2f8Get$<9E1wMK_VuHZr%Tkg#~@XD)N10|%#Eh4dp`iT*C8Mqxqr22 z2)Slyfnw&h`F+O8f(y^Zey3G3V-;EDyV1L{?AQMZ{3`?0tu6tG7f|YfN0e8XY#c`~ zkmwg9%?>5Nw)QzCq@3z$4!# z@^$0&cX4@IX)@JH=cohZryl=k&VSTty~nnyu%y>e{45lL7K zLG4qxRs*mc5K5F(eqE1>>uUDByxh+vHS!6v~B-d-yEz# z^U#$?TD$vS26*!4s`AJ%i{j$uQ8E52V#V<16H@`$@F^N#pG}$+NqRPq8Gr6_n#GAyig+byBQyxg97NTCxgocm|Eq+P zQX9N=sKqgKESdGl7+0v`m-IO!J{EIUUC4w*A?fw-hZyMnQQt${#y{jduYh`egb3_+Jft(92_2hId+vh*9gi2 z7oM;zQA=tulQS!&*z`!S%sRG<=w~i%s#?E;Z_9$j)^4(sI{KWIeJ`0smvXI{onGri zvA#G1X`e{8d(P*1K-b98zEstY$T%$m3<#GaXa3d|sWV}B+>H7S#Afl~V^ zSf%Y^X~Be9PpmYAQz?~d7qZrW=U7qP z9Hk`6U(xl{=)&lPf`6rY4dM{Tfb6}_@R(;49$&fZs(Guq4~%4?RFi1ntSAVfL_Zrn zVee#nQqX`v51G}`1O`AaL5qC!Mn>Nw(MmzPdAV|)aEUHdZ)Hg&X}ACAt+mv&=l|f8 zfS6H5u8P@Um(9ISiTKn`>@o8(3T#(B{J?+l2@~P<{-e%S`bWH51AAD*s@qZ>9<4hbGM$%c z_;i$}0l{MKIDgz3B}-u+s@aq}m1prc%1TW<3eMa4LOUo8DXp=xkTx^-Z!-x^1HZ6? z%}Xuk<^9wT;+84XU>9DsCtMmmFG($=`EXW0AO0=R!4@OAig<6#hPyR(r%qQMv`o1= z4?0z)Dkq}YYV99g3zm~-&#+2^(d8J%BlA!dVk_bc&3`L+4;CnH%rDxn4inzKbIz-N z3X6UQ&l8R$DUIS0c8=!&Fa^h2BxX`VnkNphAGAGQt33^%nQFRUn_dO)p7rry^VjGA zPV)PzMEm0lgCn7|2ymnJadxelri@4d4c_PEgY}zTEVP(_({yRoQ>6zyrH17*k|xoD zIQ4QKSAV=%Cwz6;J9{&XKGEvfa4w8(E_b6haq<#?v zsHWI`G~64aBolcJAmfzJ-i!jk1BA6z(b0M^QVjfc1YKZUzTj=KoP#o9923U}Z{3yn zXZD`N#LLsi1mdE!I2=20vYLXHJs;^rpEG1EG=C%|mA-k=+U-N;dpp=snqy69pr<40 zG%sT&7~}5wIL;!HKCs%y4f?Lc!J{iqsh(I0*6nlL+xgQ6DC2!$*9qD?{w}in&w44B zgwbT1vrr(kMaimUC&^_on#asTs^>Q<#8dc^!zT2q>2xdG4v(2 zz<-_{sv;njNla}y1J~XdfR4KXz~YrWbYP9XTx+7Y97jG(DFqt- z18N&%x#CZ4s&KWXNlCP1`WaP17kmsx8iokl(XFNNm(fQ=WpNp{MBXlX7dJ1eM=m-2 z0DP1FntGc9)S21w$nfh*mwGfJBsCTE@sqNN1R%73K- zZjk2pFZRQS4K>(WDs~rd{Zebxo)PluqZfz^Cg6%FK-lKn_B=13#+?8tTbO!oQ~rJ? z&HeDC|966|9YStj(YrE{N;is&BHTmzc15n(47Z>ql+9h4+ZpGdgvZ?OMSv~)4g^u* zqDP;lc=PpmS@73QPidmKtBt;hfPY92#mOyv)zIcC`Nd`FH?@^jN#HjS1FuJ4upEp| zWyq#WJ4SAnWqFq?Qpf8g!$wwp2x~XL7)o=zr#SB_W4}XDetp{>wq4oVNDd9QvKr8j zB4@QLqiUT&b_2-+d%|sJt?#o$V8}~Pr-h|dW^T3^?qRGn_Pju3*Hg5PxQ|^XKsbb>LEDZ;jJ+^ z)zyf|tooRx&8Z5cuNByVp4i8anfiDP_4Z7&AM|VM!^ep9F<5uy=}6mEUp{gzhvl-1 z0EOOvnW7s9HuFu)l-ut^+kcqz@Bwrr%F;^|rhVHfDfm=iXrV8|l02w)y|I&;McziE zx5=s5y+^(#QrLh^eok`@0M@Cpl3>SU3taEwp5VpYZ9`>rG+w-GBuO_KK+<#xm>D9H!jAkOx z#q`u(7#A9(iT=+7qVl`S`*uThxmoH`cyv%p9UvH+PZisTa}Z|$2KTa-e<_yycxL*M z{l!A6+yY9BB@7YJuz^mJyLfX1u`=tm0~G-q=EY(&phBptQHgAAjyyqni*t?5oP z7qgNdzaWO0Cj5n0B!B7!D$nu&=GgnYy3@r7CHSU>Y1xfr+Ops6goKT55Ow78z^sT% z3{ZuwKh8>8P0^1n_^EKGxiKgcmNeA_GWhB#9 zcC42!QYcn;?forIeu+KXs7NXD$u9*dczN1O;uM!B83sG%B!66xW7KKO)mswZtOC%X`^~OT0_?jFC>T33yQMIYY%S-piiJyYVP8Io<9CsN_Nu~MX7`@Jo zMpJj4$B$_RN`Lru2NY8Frf#D#kNY4Ox6te@u(Rl7ge`7LIoS(gn_SoDi?Kp8=7yQN zkwMs<0w2!wy`vb~ms^-&pAVGIl@O6D=rQ30$5fYa_=lIZ!9z&&n4|wpK}Bg>wlk7F znlq=kHHu;1rm*+I_wslf1fOxyS^x1P7xCbWV=~eW9SJ7cSROxJiRk7Vm@o zWT`tuW>8ntbi;r9!UXTXwTmGZGv8ZrXy6ux;uciynV&vlN>12sG!l@NTgBaDhtWG< z1D{t=3`~GE5LrB{^3di`oj_YUJ3-gBKD(P&Xuus1>%^-NZT~RoQ3-*0TPir`Rg6JR z>>vZq9DiyZ@J;U2Vl5HOGAb*9z@caL(Pj$fgvF=u@{D*@z$@bYAO=UDZik!mb=gh@ zK%?9EC?8b;ifr1tv1KSRxr;E?381}v?o9)I_NS!phq`?_Dl|Tim3h>Qrh->TE3@k` zm-9f}5p*QvFC?({>=D{T`a=Fj?&Xq|Lv;kd2<2bt#D~eR+S+b z3;UkcMg5Y)*P!yXrhBrjIq*A@1)`k(9KjV&W=xbcol05aQ!%g;c*7yVQ5Mb?jWM0 zLlY^XxJ-8C(%}hlxt`~itO5+NP(XtL0*t_9K;CUJich%bLYahVA?YK1qTC~jS-#X6 zvo*{iq9dJPuT-tN4cPEShTn(=x{Z2$s(1Bh&=@n&vI3?mBCgVSjO) z>>WlMqt_ff8BPUhO|T48&e##qj2f5aNrjrMW6{BB0tIQl`gzK$BTVujipIozM%^xn z0!X&e3@wqRNo0GS9Emi6klTuUY6fSmm^@c&pU@NGpfKa>KYL|3#)Rv)NoYeU@jOK;crQ)aN|6&Mupxw zJg!IXtdNyn23lu$@FZCm8rnhK>n99%n-ljMU73*PYL{!Kd19JONV{mh7k}q)u<#}z z5Df$Zze{qJG(-6l-yDWGy%3T>0D@IR(=u^qy=>jNA5=&moBa=s`IqOrRGih#;VZQH zK^%pN-tT3a0Eqf};P6ny`gWC>Fi5ozlc+DjR>bUB>cw$d&rd5t{$HE@ymSyOc*+Bz z=_mu7PFAJ(M-z&fv=v-o*nc%nQbED?mUZ&tBl#W;grWZdzl~_a%6)n;vPjq$(89;d z2i>(7W0Lb}9wjQgvbvMs?Nv_>QN#usP;jCQOVM>-lC0`)zxw#px+_634wRgvTU+2< zC>?_M@it4uTxt)HUqgq>ts#*@XQF*m2R#2HAK%s%NNu7FCsFcS#XC4~O8wO_w=)F|XFQG!{U&FZzq${p~ z^THGkj}UFm|A6Q-34e>UvsVwt-WSJXtx<`p2YE8qUS?YaJ=k~PbC&j&U4wy6&6O7Jsr8W<^q83yjs2%7703 zPJWI(+S>2D(uAwY(@H<3*pX#_nDCKPWT5bp>LEOgSx}8){*>^5_@>*Qtn48;J5Gdi zhYp|)OQvT%t_}l&R-sO9-0YVN6LTs_g#L28>%2tSJdy&OaHKR|xU~ST5>oZ3vZ9)~ zEBqie#3bKw&VTFxHkSEZM>nB$lYD0>9n_Z)0E^;?K;1Y8DoF&s?Z6ISYYk916k{yZ zYF()w$a1yf0W8i4;s<|p)gBDng#k(UKD(PQQ^s@DCd%P8frB8~zwOQ=nWk5OvNn`| zwwtXgUg#-DO0J1fvNO^C47Y2%RxvpcP4`^C+?Kt;6Mwf(`NVMx5rAm)*QYF*?dBP{ zeImr6cogY)A#IIAdJ{MyT|iSF`bW1V!JvlZoykF$ks=?}qf%hPN{o?tJIWYkg|=5} zU(T1`v(bGMSI#oYlq`YXf2$4E_0uIS(&dJT>}nA`00JDz3r3)29^XVSu={sRgPbcm z^VxmzLw`p!gO`7PqX#sT+DLtojj4a9JNV6A>WolBP;))d$JU7N$?*%C3qy8olGPs{ z;ymU~kcGH&E{y4JGlx}2?zdw#KI{S=Hs1QQ!|tQmINHMrwEOk* zhUSa=NEG|}Z`*x7Lo;i@=~FjcCty~X<|Kz^^M8r|iK2=*MFv{wkc)uQys(Z+gJ*q% zu?A!?yoJ`2q~)UB0dp;ASzpC{E=;cub>m?(*!-Lmw_0sIFn!=EM2QbFX8x8W;-rDY zzy{cn$?#YtCGD3kVo}sr~UlOw7AR*{H}5 zgMZ-4pKDVKa13ne&Um+{A64dM^tbx%sGOKP-eJy{&miss)ayM&*J z&a)kNRIGG=H%6r<$oM@U-u4P>J{U5UF}ab-fq}SS22I!Sf<)I*j2Es zMOQO zK!M?)!3Ph2Z6?=$x|7&5CXM4m7a8`)gZ5|Sb^CU1+V}{Hq?`egPhs3`k;}dN1GRg@ zVb@)JNi|CI+srx#^>y^j9AYP4g0#ChMRW3c0!75 zRvyO}pYSzqugID(4|Lha4}WOfmyS9`@)L8Bm2T`6rG?@SF~4Tg>XwhVz7ZflLveNE zL9@4Hwt!NBC;lzUTx{%5B?VIj(>}vAwk60}w@qA16@{Z;(Mrj{N?X>UniIRguHmR0 zL*mBx;=&53<=%kzihyX$NVmc~Ft=MU4lrambK>t<1>z7sj&VQ*vLcwMEYpQIN zXpT!ED}jN=NbVwiKOoB;XFAK3dQ2eeHsx5xZGS_<5mGJ)dY^kj68sWfV|)~bGx zU()gs!+Ut+@KJEShtNO=oX>~)#=G~xqqnoW>}l32F#f(v#Vh)ubf?<_B0n+vqkw{S z&e1@d(@1)X6{4L}abp_^(SmGly?&BGdW^3fQ}OQHe&q0fPk&4=`@s2W?05|?ufZuF z=3H*N&gD5K?GayB^h1ZntbP^UUi!4tc|p~u1Zc=b$!`L+fd#~ojLa~F@* zB@r!&Mh_z^?wD?vF(`vHc21iWl37affR!#`n8gY9_p--qV)oDEU+5tsZZ(La(pmv^ z80enqyvN#2tbd@JhtISj7EUp&%IP9=9vX`^0lRa&-A52aOJ1j@eQ}GKsAVR9L6AbEKBYm-=knn!0h&(2LnDFDB}-$8Ib>dN_n%8T7h zp4q4JX5_);^lW=E#gSgi(*!-dB!Qzm6$DiUag|X!RxV+k4$pmcaf4#A2!OS&PBJmb z2DtFq)_)rV5Ys2%@k;rI4X@r-II_koj)p12Ey_NCu2ueL8UX(9RUrNlr&D8yq^)35 zeR%9NyIs;CxzN@Bx-tRPMYMun_tOLI5b{5*U$0xYBEnJ7^>m2a2zktZ`01bVNDQL( zXWW*Jn6uOj2jcm}<~Nzo(xnGtK=Pn-$zm%!BY!aZeTr)ATv+K6gNfbB5(S8Iwx4%g-EXiZ7x8)#v90qm=wv^d!EB zK6C8B0>hsHJ(VW}@M8_xrC;CjPd5dEtppiU){^p*+it`4vEHq*^A9`&U5cv3Bo$Tc z$YonBu}~0JR0lgVS`;j8AFbNq}?q~^X$@bl4ulgFiu6261snPzH~hh1cxTDeGGGpfc)m#h0U2KB^`rU z>t$Qw!TbtvyTR~RfD{IS$(b{;{tnk1kl9p#vOMr=)CS*zPC0V~-aIYamW7g#ynmex z7O=!g*>`aB@?cskUI9-AVqN5F4ltCmw?~#U`$c-04aiOt_sJHW?;MBTAHDgrKZXe< zPIeUJZhq=l%RtoT9$zJx4leXwP0ae?yxS}c_YgQg)1i2U)LHWEO0#@&qixJ!daRj7=LFRqn6NvOB^9Fb=yL2K=lVY(?oa!j&V_Dm@QfdqTyFvsZxffCf^du}#>B&1xCL&fvUlc6RdA zvtP7O)2}i6PbA1BSSl5ZYfu_jolM11kzUq^Q@PIGEh^78F>+FJmmaXw^?z|&ksffN zq?wMb<(zwmG9_Wdw%!ll{PF!;DmB>>0%*tFHcO)+ZBhU74uBS|GRaIxQvr{GTs+I> zr)8SSXIznGXH@pvy-p2paHak`i7LzGX5`7o5!G(S;*clZdTKPE_ZY}F>Blr3^uf3o z7?HLP_%acPkbVbOyiT{7EPq$cUn=g=A4=)Ew1%@Bt|7x3{@kl2QhRV~)Q$Jv&{kr} zF$*1GrJRu0y^G&t*L7MEfY0Y*niG4!S+2a`&YZ;XG^RdA|2L)l3NymRI!OUq&C3Vk z^Z(}}`)h}x%vddD_6X+r1vEI(pV75+oB8s_Mxrf7P#amGC*=Hw+>lB z%6XKA95?9MQ$Khhm;^Jq8nZbNsPweTvRniN%~rgxgACtl6i}?@cSZnFK(4I5@1?`6epX4sb!FgoRJS9ib9r<@v?NpXb}D zX30-ry`UlvxdC(P&5x{CvsQnjW`iqtPxJ>>gosC+d!#&s?f23VsRVqn;ijM7$YT9* ziFAhm5B?ijZnGv&xSigB#RhE&e%xe8j41A*QD+~q`$KHo@LSAeL$?_ss(Y<(j?YW7As|Z`OJbpr?-Cl^`#KY`*60|~E9^!1z5SP4Ra%X>40e1^D_ShtN zR_iehJI2JXh5PaUc+TW~9Qb?se|=LicviFnK+s7BCf7j4GqLgu27{xrhNJ^7>+t=1 z+5->s`^30~aav%68e|a|jEMyw7dd&M!oo+OZQ*~+s zX;Fz-OE9?Rsp!=$*P(m~Q-?d@NV85^w=thb@()#lD@Dts!@JplJ5MaUMFqz-RcHX$4 zV9qJb0UN~xwr16qQl?BB*F{|KQB&uk!``3h39*^Y4_#hBvGsq#H0}&OV9NBkQ*i{@ z%_O|L=^#@>#40)&fFGJE?x+8aZ-}Q+GcH8hOBX;-`%3zIY)_ z+OdKL)=PQJWn{Bkuo~X#arnN~HEGl%V`!ez6#8|goU%wc^OTp+d2sY z2GGW?{bq`2_J~jr4#QhDz}=`K+&||_&ZZJctDCi=VbGKx0((hEVqSNm+%Fph>ACPy z8s3UzwOM~7a1=pb;C%20LaTNL5L|!Me?>xUv#Yh^K`BBm#rX>()48${J(#pBZ+e9j zZlo02HbHb=sNFE}PyZgP`TqT~wtM+H#W{Zw^WxNStLuYs;y~=~69$ZGNoc1W0kzjv?57{g$s=~yO;WPr!LBP<9$;Ptf{sR}x6g6>XAMc45F2*6bTuX&7SzhHYFI-oz5s%pQY05u*C6>$P00e9bY@uDAmm32J{5A7j0M`pJ7s7++R3_p>-Fq^Ghm1=>W_SK02Q`Xj zSPV!OPqne7yv@b&{`T~<3cyct+{W>?9j07^wE0*cUf9V~qu^H9u)(B#$H@#D9)omR z$vGTT)2b$q$I}#QVu8vXLdW5t5p2~=WHx{K)dC6Sl@zFNe$wMwoYWp2MU&h5(N z+Bp$c$X2iqun-+65Bby%4Y8=Whx1wzBP-SUfiDQVbd%-yyagZXk{U@*qBDOq{`*nR zPl0(8N={=839%US@QG_ik5ODX2B713(8#>y;EtK5;5(hU3eW!8X;8exu36rdL{NV^ z0eWABmbTMOBLY_>1A#&21?tW|Y0Y4!0M%u#^C~^4bJ1)uZxM>1zV9vU%Q+uV&^4?J z)T2NcZid6a>LPbtx6_T@Kd*Cd?>dBX}654<MJVc4BB zOSPH3l83GIgGKU7fKN&%iig&@k$m|`nWu$8@2YxQ7gJgVHd&58>)7O3##u4VQjf*( zkcVVDuYr@FQ*CR=JCCJ_7liNhUK_ZSi6q3D920rQX5IrD8jl(U+S6Fuen$dEAkeD` zOz}M1xMc`raWl9L+%Vq;HMoEM1`-Xa=;x#vMhy4;p9-$gA^45qY=Z8T6;^^P!n@1Ijp^&?Ch%c+}?X+Aa=4I>GzZT3gzJIQJh z5bwZW3IUOg(wOP(^t@rBrh&+pHX)J1Q19Yi-4y|TKrILK_4>0@KbwD==_Ia%N<^Fo zSlA8nN?hJMiXx!74srTzne(HO2?PdH4$kmFzToTmbEq?c1~4Q4va=krISphZc#11Y zfB8Al6tUqpTg?zX3lj+TSQTq13n|+BGVJw%z{}T%8YeXP#5CorlmBr_Rgb-7Cwa9! z2-r$hC}#H#PDTinc7%V~sTC0}=P$^!LHMB9Q9+&}ddog~5iP%CuPcnDkI0^Nc|G02 z5%$S*;%-)`kYoNbQbe#g%s@6_5G3o4MyfvmN4}37;$A_Q&G=f|EjP;3TJ{Vfn|WO; zoh6dz_T(+1uCkA3-1IPW9{|}4f9W`Lf%&RHGkjxo^VDt|vW}+-2 zs4Uo6r9A9uCUp;-O|ZoRfSZfHeRpJ6!OWhQp6>$o@E+G!B2D9Ej*Ho61d4`&GY@Xo z&n~8rKC*}lF4cdFimZqp>HTb0x}F8yJXIA0DAL_HLH%>1msnEE3Y9y2l&#sRg%i$b z{ypI_{KX2|8tKv8USHIxO;fwtj6Vly4jG2(p_2?q5s`GdVK3CYIBG^ltH-04B}q-C zXy<{;JAYK>>Bpt!*+p`=Oc>44Wxt1;AMDNu9AmB)Zq$E(5*SsbNgX&gF9g4|95*~e zRe6jiyqZg7*Ww(0y2yO~`2Zv8hv+G^Kr$#h3&3CO0<9#YMw-4`3PU3IbdV6SIK8jW zkgzu0mc{#S=g`d4M<^%;x}ASI!bi(|#NkWryx~8wGumu{#V^>A20XlM&RV*x{9YNl zk&;Bt=PrLdH7JERku&XX{LS&O+nzw&f%9f)Qk8w6vzT&H{dmh8z#?=SwXxraugnEB z3RGqh`*c2Jx{h$k3MKcxk&<%a1RdtZ2G*1HMX7T;sut+!W5DO$0ab@-a$WZvuDNRm zz~gOVA|J2$u&_fo;U2nP686kj+(6aSey>j2QpJDqBp6ydK$b-#<7C}*M^bKkQjoW| z>I^7j0j4H1AgP;~5)E8awx-8S8&@oZ54!Q+h)?xApc_F`(UGoj7OA4u%wt>V1v;T9 z>k3w@C*iH?V}#rqSM)AeId+q-(y2SSTMQ6!sc3!f!citFEX5X3;`C}h4)m$g(XgcV zd|rQ$3A6UcD<^wDBmaC{#a?e<886=RHk*=NZ)0Hu5;+bjHUY@v;%Bpp?Ui6-mGdu< zqaWxV6`$M)m*Rvfu~o;^|C@i) zf8|(t_Vv3DBhfS~3U`$Sf9&XzfA@NDLNG4G^A=(6H!qk_H1W{Q@V%vFj>HD z{*m(L1%o!`$LX>tUcoDgprFhj62IaO_a&mMo(mRi`FjIh}VjWiD!CB&+xEmL+k$7<@%<#0k~ zmeao2GLP;+%k1sTKBJpHWNCVu*0k?`2WelQLAhe>JO~vaYXH`hTB@H|Rmk6>&Gw$o z>a`Pn(V+H!v&l&cyvVBgWoN%(otj*Nq>!_XBpE5;`*YS80)vug_KR3kxg>wBvWd>^DEPG8q>)ySu97Pv zn?ukKu`$au&^Ros@u?yQXbXQRepG%Q$KGg|d;=n=c6^?QPCtXblP_?x=NuPPZo-aRvIG0%Bco0ekz03ZQ@U zrUL_BjoiO~=RrU0Wn_O2_tdT=5%mVtLS2G+#;;LVk2D9h?HFSBCN)VbRgxQE_1kM~ zGe%S`{E;XMZ5;l0Dd8hdATSCd6+&2-!?Q9r4CmXKOSI5Fd&xI6K^l43TyY~V#%4F* zZQ)^SwcATXVPJHDaq~4yt*!#d|DF8Gdy;?o_BYTSnY>9NNfi~6 zbbn1DOCdx1%Bhkhug{%pKKT*6AL@hiig-hXx+FGetr$xfxGSBG$pQxX4gy_QZUjql z;z$XiawPJJL}~HnOKmGP{Onmg_uc15QJ)FOE|7_;hm4OnQ!MV5CuI`#I(-8QuNOHc z&QY#-O!Mo0^#OkrX#m*d&ji&u=!R{QvJh>k-ZyEs{>Vf|XIf{%FoP>4TOXF{6TG3D zeeQyKZMc0J6$KrITsoc~4UuG&q_264*v5915I-~PEk60p?I7EQ>H4S?5gov!-Otw} zu%po~_8;_Eq<1BaQRLnJHM%^)xXA7W=isY}-^S*?Wa@vAu_O&jB8%8ibr8+a^c5n4 z6wysWIR0=c&be*U8Zc&ED>)(mb;;*jCfUkql{cpjrP2if@q}Bhe*p40Rb}XZP51X-xnXav-<*L3XUFFMtsw`*3Pn$`u3NNR=${^2?2uvp(*tY?p zNY{@EBnp>wJp(D1&nW{7x7qLl-#7v>GLsRi6SvJN1G*EJc%B0clN_oDmzzBU4g@wf zF))`<3IP-aGB+_eGnXOc0VjWKyJK)J-?lv*+jgGVwr$(mv2EMNj(2R^wrxAvv7PsK z&bjye>sGzhUnWMcHRf2ey1Q0)lM#vA+qtNEI+!xiG0`(}160ISrI;AG*Z_?5EHGqb zB2K18E|&IoqDC&J+yD(z6M%}T1AvJcz|6?V1VaW8v3KxvvNX4F0Z@M$Q~f&#P`5EM zv9z^x0;t>D*t=O8TL5_7+}s4+oL%XiT>0t$IZ4IT6yRcE3NW*@F$IVyC~8T`O8_V( zV;o!^8wIu{3r8{4zDSw1Z*zmu^yaX7&K~|Ab9k9sW1<4)`5Q>I9IpH!*dx14y|T{ZoJ0|H6!HEp0sie}Vsl z_zzsj&io(g=$KgP8Cm}mw{#Y_^e{D1v~>ALa5E#De}wvXT*LG~t0QM>V(Du8pFvFj zQRSa?HL_7dt;sutKThQ<$hv?a~0q; zb2El&G%HNNtJ6I?qo7A6KqS2*{oIC<`H__Kk(`1XG;cct!|iH+h-;Z7!}Vu&L2 zR&ZX6Nh-|!YPR2%^55zs^sm9xv2Bgz!EPe&TrxJ+gA}Q!ShI33YNQ=Y`H&@;VhqbV z`oWQQ64n+U?Ifu5C{QxBzu`;|XsVIsEJ6#ee+j(quY-i=1@FP#kYO8G6qE-#9EEE= zuu(~Li^6|W+&n0von+BT6Y$$0H}~8b;AJJ6^{hJgmA*_VrqjA_`FY$citu083Qymr zTt4q#z9v6^pJe8}>gnB`UhJ&Kf1=w_VNkwKd4Szo|61&bNM^6H+T3ql0SlPIrLxbO z_`Soj)!?~u+rgLVUchg30ioLr6w#G7v6<#ywhVu26RI|gJ0Nr3TwLAe1;=3rlj2=6 z<1~l~Ovmwh3f_dPo_JU5Qn8=H$@?A43ygdlUZ44&eS^G&)E z6C8iOAVFxSHV1P?CTAQr_)HbCrC9WP4yF_d9g=3ZsrhYcqEc4ZH-fRZpIWqFWbgIb zh#-otIc|Sl?oJ-zqd2fj>Cid+=3CJD<1y*5FWTz-IZuw5@1^_Pt3uJn#;`c9)Z^fC z(2c~wbVJ#!Gf0C|B${qQ)b}`}&FIeIjC+4ZHBoaMAI$&(0qzEV_J{pw2cuDf%rl>4|VtjdZvAfq*mE*uJWogHoKkWtj{wBmk@7Bb86?^8?= zcs?e|I~SFHV6Vr9Z(6s(IXr?ks{Tc$Kioq*dfQ1p?%FI#IK! zn3BbRkj+ikM|}kMS+T)gQ@w)UYJ6RyJ8_cqyJ$7R>rEx3=^w}Mo7D%0 zs%UBc9VBAw?RZQtgjQipg@}JN9=V^lWvtW5Q)&k+D0fS8oKA~{qBFg@jL&K=T51Tz zx*F~_W~RmWXT7Ce!V|s&wUs9>b6Z_&KUF1-P10Fcaw_wy#gA{FfCBvJCJ0r2h#V3^cmWOEK68H}D)p6>cqhn} zaMUq=Bs==gf&fX6*|=OSP{V2H*{5V4KQhO1J|$j-D&gY2sv?NPCST&$ zPh-I2ygT>jqt$&>n1V71B#rFUMcFXZj&<6o(k)t!Qfu34Zd1}~FE6=M(TAtKmKs56 zN~9jd78u7~TJoI5Q38MI20uSYR%Nmi-fXiv*c0h;3E?0LHCylbN17mz2W@k2tjrNC zxZGjq#&N*1X>x- z4G&-ApoPqz0^-=FPES5K6rFh2fx6G|NRmo{F)!rUJ$5>`I*Ic)ILPIDmn>6#A$M^b zWOn=D-^VjP0IYwKB4*GUX2{<*JLwI;OgC3kJAo@!GeQ{3OpCqeCF`#k!+W~{QNWef zSZA%a-kM^#v^xZ4%D`8_-`FtE8~h+i6NwL8gOS!(^(JS?uDe)xM3a?h$3b8xL~o71XEO1KGw6C+j;DDd^&XBg>e~MOkf}JfVAW|ADBC5{H_FaM6cw0ZP+lEB8T*H-(G~ zGz#9)+nYg3`Yi$23@_F?|INC&BPl-*QyoxbNB}!!y3n& zf6zj(j=DR)m&f#1yv5jn$2UBz)K0|Td4?VTQLX#z7jhD0- zTC|T1I&kxG+J`NEMSx@c@B0Adm|~tyu`i12fE47=7KRj^_=5{KXVff^D=b|Dl0^7| z4kV0243(cSis%3V-QjUM+C1Bij zja)QrYlopJPdHbcpblrOWIAhE>h95sSAu zw16le6kUXw$m#nH>Z5SvQtCy>nL_SBm5evw$vh)olH=Z<#3J!$d@r>e-P@}qe10jg zQ*<^61H5v1g0gX~ZwU-I2yuV79F0vNOIbXvs9YTvEjtG#SUK&pfsJy>^}4Vtx^FY2 zuo3h_W5GTzE?M`)0N1imnf@k)5*r}H+Hm4ucssirO;Ti# zo1Y|5IQ){`MeSt1@gCq5f}Cn@gpre4=9IAgq{07Ui|CQ$(w~$mc~pNBC5(%?VaGpK zC`g|M!sG!arYjh-hwKny@g}4bjvao-l9qKoAIcf$L=<*Cgjr!F$yuK?2SgX2!z+4Y zakQ6-K(6ID&SbDQRA_m`2V0{gi&BO1Mel<&=ATko4I6Ve2NwNq58S&f#>c$oQ3YEG zBt4?yD_m-qt*h&b)kc2>4i}7T23K$t&GFi6MMWOXCVs2tV)=l5QC|ZkX?l24CDl>6 zu+zM`QiWsiW=b-hmmIF5K~Qx09tg&J6%FqN=NjqR+)Z)=8p>U7>eaE%%TFq$m>1&= z_X<4RA>L;$VchD@q6BiA5%{GDlpqZ7p@|jhuMPn@MM3t6!kvFqhtu9BvdnQw34QG3 zP)Aqr`y0)PGh{_@SpEq_hNiEYg7XE7L~HN1iJ{Z2@G%Yd(YMmcR7$C_N#$lt6FVBR zF|$6}ba**-(K7S*mO;xWRt6Ce?`IJ5XL}Yp4dldZJ4#;<0?$UL>~)(BD`*WWol^+T+sT4ETNkL9OxPe$E4%sku`b=< zT9k6-U!1y&yWS#jp|Dq47?N)Ir(h|TcL$LLWxo2MurtMAvhmCt*h6FG*R9Nl0CSOY zM-G=V>cD@@BOrQv(ob36Z3JMvLOtc2DQ}(9!rBN@3Bt2T5^gP8Xm}n?8G*#W1hXEN z_K^p_h(k*mFB1^e2oHX4Iyzv?p!!ezOT1!Np`RuHK6!#z^AYSxa-g+?=W||R#>w)H z^0!?tQsxIAFt}yAPS7g!9rE0vm6M)SEVVqy^pStNfPHXoJqp@|&FGK;uZ!8h#8dX9 zl9Hxhbt8#RHK<|BfiXc&p2si^oVf-^ z-{uwi;Zc6g`6QV2GWee^Pv%NLtph))iVbZ!QiPYg_VHV2eVvs{2%HQ{S2bx_{JU2< z9U^~V`n7C_NC~ZkT~OLw*lOCsq77N)d%;k|z)BMhe}G!;7#S%l##4Er_8iSJl93r( zB(E#81gLxhDJ0);#fl^UE_e;SgOY~Qf1dokN>IQ>2IAy?$#(s@xb_JPQM`c%UbpcZ zeDLviBW7cwo(;;j`l|Dcn{D z_7|cQo^-QO8FHv<=HM{A);P#8RZ;|JRaYrDkQV088);wy?>#sT&drQz%BA#H@#e%c>0e=ncM*i4>5Zn9^VMW#xpn5j#zhxUgk&1u( zW9^t(_d0EP0*tE=Di`#1W(YVBco{~PAD4PYIxgL%ijE;Khlgfm6?N(9A@l?X$q)ly z(<(?dM>KBuu>{^1e^YKSF*q1?l2dV*SswLh!Jw22Lm z(rPSMtbTLdM~&UI;B}$CAIp5D4Y$cxtu{Q{$W}*|7V9rqA_?au`yVg7ehZ@mj&OQ+mzXfMZ@mY0e&__!4OA755zZJ$N@K!bl76WMX9K{_G7#K1>9 z3itZV$3dPI`~L8sCLbKxj0AXW5vV{=8u_{DGhR}qbjmC$akjMM*(3CB8H?%;rL17( zmVg`0K1P$u8bPZDw%?CP51I}GfWvqoNCMfZN^6>mzu>q=J&yVZi6@d^ z$kDf5n@H_aw=r8B6bp ztR$E&)=eRI(|fmeA2Eun)Iy zrfz}jwnJC`76rP~^QjGUgJvauRA_=#@^#1Puh)N|H6ssaU3co(2p#YBBP^d`WT8Qn zy%^dc@P4*hv3XB_1?S(o_xJUOqTjVfJg0xIgYctpr2=*Y)X2@ZA(}350Evr;2WyEYG#NP^eb* zJpMVOx%6A!{?+dtJVq~PC{(_1wu(;h#^&QfOKeqZLy9__2~}=CA%`}S!WbQ~La%>s z2op2?rjfp}eVoefzd^VQeO!s=uIZpr5?i_n_A)d;UL|k4y-<#11Dn9*m9IxV^S@7} zEL;x1Wt@_~*xn~W2pU;$(BK0eOeQ;O z4^FLr(?@BvKBJxF+&BMXEU6@0P_%!d?bbR##et%`<`Fp5b#T_+j~_BwD-(*@WhP0) zxOm~@Jd?DwaTn6j>qZZ7#h|Qa92bI}>e4}z20D!`89%FRErI5=Qaw~xLtk*iPyAxw zvdVX`WzLa;aq}nrofhb!@)OA;bs+Vc;PnOEWK4v(f^q5QfR1+s_xvR{VWEG>0DCdj z{9DXKrKGOBdD-c1;uy2Moe|6ca@z2{tc3wVZ?`=fNCT8W1nEd={Q#PlDJ?pUUG{0V zpV?!s{aiVcpFKJxDZAb(sN@2`LA6(9&SzZ~c?%#@b9a96oN>xz#uThQot){A5W^r> z6beBoxgH5L#;P5s(?|M*LJoh^wbmZU3!Mfg-{6J!C!kbH z%dvORwL^xaJ)WdgTb@%0**{6LjHsre4JIV;JT0GaJ3S|B!F*|c9h}{?Yx(n~BD=84 z1zbHXQ68qo!)|t*#jRTG5WbTlXYtBIB+`tWGt%FVVu;~<RD-vYAWIk?=GZR1xW z>fu4YrQ4gdvhWkD?g{R3J39uhaQtff8h++oObh$ZHS*3w_BiV3Ump}Ebfv=~>hRg~ zc_t+sQM<-2&w-^x!%2V9s9#x@H#gpd+GSPHE_?((Oo7cw1&dAN1Dh& zLyq#EpYzvH%^*-5p!oiyk)n;V^2u}aRyO8S8T~Q#^f8I=;89Vkc05g{SK=R+ zXI>0s{k78U;L&oJLoUL+DRdb1t<7ZZYPf1W!GoA$nU!B%&_jQU%CZjq37BRj60V`m z-T?ewP05QnlC846jU0LE*%dqUTkFSqjC>Q)~+%~gMAJgzhU-r#vn!H2B)5_Pmz z^B^WVW^P=z3sGz-79k|`GN!2HYjlk1bW_deU%q?OYO`t6Y5>#TAg%~Z9z)~ zd~;Tz7YvXrW39puc5<{PnzwrRhx)=7*l?Y;yZ;a1b7^03M&I&q+wQSGfy#(v5#)(+yP^|&2=+o)g8pX>nXPt&mNsS7G`!M z-h$X@?ZS|dZcj0XF!m#Jlq`JWa4Aaq#&iIFPDae2`HT}f3+1*77TNx36MQ;=i-6d4 zAB=zN9EsZ$6|TpS39rBK9dW>O^2q25Rol@@DquLSrrXvbe%xYx$q4X~f0VqnrQ_b~8785VH23&>GlGzfVB$_UCXRpY4EOsKx!5b_KU#^?xw4nN(6BxLJGPzQs61S>V-D?y>cU?P*+K>O`w3dG@ z49&{xbtc|3Jo|f%S!lSNa6*OhQ!nW{5Qf84#FeeofXk$2K6|W4tYWR54C82~>8j!AdTN?36>$ZkK6gpO zyxdZM`8F@eiE;K%MRA`6uHRkclm#$@F29+WS0MglNd|O-n zjm|8`-ND)4A_IsQOpfJ};u4!--`>_^_O@28Y=5AqHAA)QV4dDm+kU`@*23tIs!8xHEc)5IzbF ztiTkjS-~?bZ&9L|U-N&qB?p?Oc0!VUzk#J+uTo#qdoC|}M}*OBbZQ492e3FWLZG3! zpZ6Ov%{t=STp>Y?YcN9Rg~UXNl)w+x371<@bWakk5Sp4XcO*#T-LVCNeV@jj z&-%=XfKoRKP|$zMFweD?2?S3Z6TXq&H@?;6qR7@YBmi{~QqBP+DPzYekhEf?>{-&i zv=US*g53}3)(L&k6Mj%tLi+k-!3vdU=da(Rv=D!~;uKY)2)oit#VK98!XNedHBBEs zH?NUR#p^Igam8xHS@oL(G4xQH%D!pOT@{XyY7vZfTd;qt?uJ{Pt5?PS4dRY2)f{NyKFC5G$j%v>hw!R-1v)K4jVMvN2TvJwZqOu@@dW-QI{zG@ z*NGBbVTtxfmfp?Ro{|fPDsalY`cKZNy>HwREmwaUxhx+1x!2!$;XPb!rdsw-qVcDT zY$)4Sg61*|LWRl^D-g$g#<=>wJHduLmXH`<3h;XG_(Ba}TTf`9L#&jLI{jaDzKeub z=rVt*3ELY)_*Knzg*iYM(C0`T4{%Rb*_ql?RN&(q@JAUw+CI-787ZNo9;2hV=}WJM z^WSnhHL<>DwfDS#ho0V2=1_Auu1i?P0QXuWLi2{Nv`KP2HF3UFGfWJ=P{S(=65X#n z5cTtBp2J5Bjm@AP{x0FO^1UFG9JugO&!m6J4t}46aJRjEbK6H8QgR6OJc{gumobno zV$*FNFo}+@d0qIK9Tj=Z6IM3%5!Rn=L(7bnXJdnWfq?5IF~|M7+{gM6u6$1H#G*;} zNkAgq$r0rpys?pLq@W@7UWFIExXWesr027@>!G4HvKHK1Y%p(iW%$=P#!4MMeQFg_M^ zV7%#CaTvL|SOc zZ<0iF_R=Hx7fUSKWyv^xz(x0&%+nK_5MmIUF0}@k-z2>HBh1?0Z{>nyaUi7)t=07+ zxnZ_DiW7@r>M>Udrf>_*R1kmBDfwfCe$;Frxt^dldtKcS{T^*3rDOg2-R;kjZPd55 zFogvlR6qIUe=Y|&@Ua503hD%Wyi%@6-vKOm&`3|yfP_CIGWXIZ6jJ+ zg$J@aWCK|l6^+BHQu_!-Emd{Q&Fpv-VgrZ2yokl<3Lxgre;s0E zb5z6y>4JM9VR^Vij7h{-_)iqsUxt>1JS80 z!wyYA(jXbdHh!>UMQU%JJBG`HFxc8-_>gp|J^tz&^z^9UFRXv(n|%oiZ5PVMnjo`e zFRlhyeqQxb^`Go6kV>4xl?gcZsNb}7au5@`c44s6zgc$#o*N?yVlNz!hMLZ#&wkF- zFNM9NN>%EG)Z~KJ$|c*ngZo3UFFVU3K-=R0!%0cd3YS&{{`JiG^ps9svb?<)3poL> z4sE0nungU)w7-9`5T5HCNA8=a8yHO>@G~knc+``U6WJ~0!_FoHldx{0imtDY@~5$- zBO-Ldf|>Za>3mBG9~tg3(eY}L(O{$-sS?uWI#?Vbxq4`dS3P(f_R{OEvrxyJu|jIr zYz@elaJqG}*r)^q>!&BaREPxL>_p|apreQf5UE*dCAoiP1~2#j3V*s(gA{P{_PLdZ zQhNGAP4^45c@*!jm|V>xT{x~p#H*#l&W+vIo0WC>hk-9|Vh|7LmQja4pL*~38W|q| zDi-&qF!nuTsc)LHm{f?c^(2`KaZ;-{Os0_=j3wp~P0nbYOIXqD5?{|%bQ1?|S92b= zACrmGw;O+}j_uXai`xmKaE6PlS}%{6Th=e|_u!|; z6^tSbkF$;ZHitl=gj|;0q8a%(m#R%rHye>&Y;b{xsz6L)R^hX>OE@TMCdM$5km77$ zbd7&alyr`t$a7(@_&g~1Q!Uyl^oM`d)(n4nD-kpmZY$pfO^j1$EgxK4x++|a{Q>r^ zMbe9YE4$>D?_M1k`1PV^+y>h-KdOBMGzh}8d(bg}O)8@&Whu~Z4>mDDdQnUWV*(Ws z6EEivQgC<2Cax(#$V`76<9rhz@74;U>#a#S zz7&E3@n@u;aUBJ5B%-P8k^SEEjGh0yDKPVv^vZdfwZ1sA)eWY-kl!pyoSO9O-&I|m zBwK+PEb#<*^Yv%yi68#oZ6PLPtV0UkzC3@=V>NNX z&AU}8oz$@N~ z`>J9^s#gZEa`?7{_%P!wG76*Zx@-iv$jFrfPDL@^_k;_e3jyQRjd?zK_Akak((gys z2RI%99rC*TX=;|OmTn#EvGRW)6-^uBXwIYyV%vHHxJ{ezl6lV4bBB;LW8mp#-vF3b z(e_ot`OCGQL8NZ+#R<4nh6s9@Jwpg>N^0qXSIlt8HK6eI1GT388JA~i;1BDoU3&X_ ze<}TSySyCAObzD)f=gS~iB4#Jd0xJR>513{yOIVS2=ABRS7z`Fjf8*iQTmBNIJPg$ zfbf9s|NDaLvtZv$z*5kT17rzJhx%1$J?|$0Tz$9mv1T-a#tY5~t5vg;9&c_juM-Ss z(zN~LM6LFqWT`Zv>lf~ItRVI2CXIpKi!pY9w~~qIE}b%&XStig_rCV-cf0@_;@Fi$ znT(_Z*mk6@wpw)4^kRQ;vpLwlx&AoZhb;!>c3WTzr7?#|1YBznkVV(T4K8-5kCaHwpci4gg;8HCMyFsD`Gb6J`Tm4 za?9m4NKktBdGp^2a6%a2Oa;EH8v*Zbjy7^;O$yHyq9)_$)Tw_hvZiAMp-p(kb|IGA z_t6fn9I;k%b2O80XtpveCeMv>5cTNRVGfZ|;EZBkA@Bl1{Ai{Grb5duDl9|rwzbop z*zyf6JpjpJu||KfdY@eP-f%sK@DYZ=_}KCba_29$&xI-IQ|)1N0GiIodGm7K>c!;G z#Ic~^lZV6>uGB^XI<8sH7#+D2?FCgN0i1~;098P$ziB$-2W~h|Ll}LM$u)dD^z0-S z%(TUROjt^hGD&dH1uEPok=1^&IZh65*U5PUpmo!b0N&p5uEBzTbFKMV0GIkUeO6Xm zjTD51+^(5AFXJdYuoF9}zlY0^){vh7=^@h<=oauDPbzC46-m-L>d7592>Y*ZV963< zsXla(@%)gi+TQtH@HZKkdeYq_qu$fgg(@U9Ghsr%J_bTI(=|gvRmjrXQpCTHZ~i0bw<@38cGg-1AnTNgN&dV?gu2 z3W0EQs<%yf zVBC{sYL)n5Ay;M^K9MBPNY`A!A9N*-FXOi(KWCFsu;^^e2S zRuh9AiN!(WH?VR@g{XZm(^vb!b>@QNjN;~VQM^j%&$NyeTZ&hcpv{rG zhZr>+;!N*d7O19a#EbXDeeuhzZ{wigCicg2T_AQz^;7&IsBDO!Q99e1hGn5Uq#kj7 zyg5CtDjj?bQxw8!t?NcB%XEArV*G(vPEjU*iU1;~G1F9vDSyu!Y>MuRRD)aJp_HJ# z2~wHX7t`Y=u&0jVA(+1mG|;q+9I_53XL>ZM0P`q;c1j#$ha1}{>(Kg1{>2z6n_a-n z^lrttmuL1jICf#Z$qvtp$CG!$t%CbBHyM zHXn-Cx;WxAj@>|`>4*=>51zd?Ul{p+$5lG0IAoJBli{a~vWR={uMT8W?4J4a!nROT zg3DRVVS&!uH>!G@Ze0W!9?x@oTH)S$9U&T_I9R9$qH%XTg43AP8gZ7hW!S~GyMXUa z7}r_HNHvqc$9`srF?$llfiV-R_%l8g0`S1Z&M8Ct`7AW@$qI8NMlS)QRqc^~ru4X! zqX2H-LAFNQdG|D|WZVpDIE5dkwmgkrfILTGptG+i;kX4Zs1w#un!o&W`L2bpxDgjqN8BbL5eC#Vx`)tFyn*w2huYiKf2qqGR)m;@uyn zk_)0{9KHBg?rO7M#U8lcI*rkPXRFYOk|o5BaL=#(x+^vW&C9aEhh@pUqxmP@m362^ z-w|#>sQ2I8oAPA~k>0;5DS{s7W_*~6>n}{oI0mF@e_K0*K5&k|?`*GV*09CA+Xv%X zlOn?7M#3?*0F_{2ksAvSqb*?_)mm90%wJFnXkLw{MAR4Fh+V=|rb17Dt(E$57CF)9 z&WS@X3rf!hn`;hMo|c)AJfLZiVu`&OoFKxIeB9-93dC~s=c1He^pqT5G%x-M@4!(~ zuwSXx9K?X2WiZAY5gfpura<>W^)9v?j*De&2~?N5DNyQsnT#{94v_7B+Dt`K-6e>! z_+r8hPRkz9FD+rzawSB6T{O4RX?uOEpXtFGfv?KrOS|v*JY>pZX>)6~G3sugbH7`C zp0&CI4*Cl$xS0L8iNwUM^0vNp1QhcQjWcl0ab5~1g-Z2rPm zh&aVtSI(Lb)qZ+^pynDI`MjNOteN}?qoAi$EJ&57{22zJ9j(2I>*4_yhi)RzT3g@r z0g_E_-wTN$BRAM@4|;FE*1nBTcMvFfO8zkk{O3q|J<93_$O;0r2;Z?GNiGJl;pT2x&H z(DQ{2z(de~U?Cvs8Lkq?a95|*+TYY(nG8a*!WSepB{wpP{#t&zn&dfjZmc=*}FU`nzETyI-vP&<@R zOr$!LuofiXvPN_uOi^fftQ~=_W0cNwAHc;lkl(fMQL|@W=dLXgby|4?hxds85|IJt z;0xBe_57cwL_!RUo&DBQTL2LH>vmkmObf|>g7-Ye&GMm~bhF}ncmkSoTwvXt^mR5Hq(yo_7^l3`C1dxdUNI-3hp+4diXBDC;+K85LIn5y+lohh;@g&CdUd_ zd`>F_eah%F@MJ{>YqI9CzqithuE>vn5TA!{%J`>FzhuS_`A6vedy4^Cv!4tJMn|~d z2&foX6Rs*vUUl4{Z>q8b=0QCiW%g4T9BU7ScvWGIafMqL>Wrd%VDfJLjlkzakCw|n zS?aJlhHQ{S32!{aa(C&9odRM@{Nvf;q)BEc{&|_>4 z-uW7nUXG>08wTQZ2(&n@8@O$6&NZB_-UF^yosfcGFU}JYAXh5@5bb3B%MDg3z;>Rz~IX^&uvS;LNXdyBm9Xg&` z#RjM&h)tcfi|JRcMSB%qS%^0O8Vr}OW-3y(2EJVGbS?_AY+Nv2@MMUs%o_>q3`D7s z&}ts?;_{zdmLe%aqLhHuX=a}W9CAt1L(G`dIL0qLW6`Zn|1J0^%6*d;fMRw>Z;S#w zm^P$GY5r!FM&4I{3{Evn>W zd5M76ee$690x+e?dQI}0GP2Y=o#{JdCyY?0M{1*N>S7#?FEn>1liz{})m2bW3&_So6XqF4DUy zTK*PD{j>rmv*Tn!KXDn#czHH&h!-{q^At6WG2UZ1-lGC&P{)yDwgLasE38Lm!2A z06qWqE~vR`?KG?F5695s$#tYBz4M7U%*WY()%5%J`@?d&o8EyMlrb_i+~LGGI=F@R z1U{?y16KtKF_bIqq{bTF_bz*uF}F_+e52TjW-FFc9fi&Znel~gyOP&?xl)k_?5Sq3 zmL|5zE^=5PZZmfKcf8vZ+~oS*Ih@#XqI|vG(++fh zIV9}$KsgcHzJtCiKci2d<|m2CC zc^*^CiwO+fFgXf{4f~-3S&)I2xW> z{ag1@lp`9?6s!OL3w|kq)=5e7%@mkUbN#Mip$Re1(em{vjm9vEB%UY8rG6={Mv)x( z!U`o!B21uYi)@pjU?v-2I}Yn;81U4bE5b4e?Mx49xU4ps&1s){>xSHz>VMOJ)hvsf z0a0v;%#rKX!&BCg*KxlvU!$EF_ZJ3~cx|1i3>{;$Z`c<{Sk#X-WP@i!JQ^~9o_7cY$`IoU8 zS0BiLn+D*5W0eo+t(hvvSn^Kxsl)KAbqGTPUPA&_^jDwL1rOXzT`b9Ji56SBxtj*9 z1F_3_+&$*P68q2s!NgN|m3Te_102~O9F~5$zV#+_?#z(yljwJ7$Un+|-!|0~YNcvD zImnGjvB8Z7HWl!qMFXu5$UFk*K*jba-wFgFjm{ro)<$gsFcBe>gdPcsORpx|Qx;GP*amFJro?*hSH3bJ$R;N-z*pDN$rLb_Gr zv)mr94;|0@Vuwj1?&}PHlL|x6H}qAJ-@~>}RARPXegw9+g!U-bF~wQ7%#G5ISPj>T z&~3rxOx=om0)o&-_^Di-!F?w{gp4}^z(?+p?b~)LFpp&W+*dsSR8N#YP^w&iUqm%r zm}yZ5qSDDpi`DwY!R`2bz=mA47;`bRbTB7LB1^j~HBhXUO{!#DHSvS5hzz{kffKV38#rL=flkMUHux3z4zQhj-#@X33p>tyAYj zjXzj6Z4SAnCJb$HasIdIKfRlnOAWfA+U0})K<&^XOXO33eW3bv!y0vKS{m!O&|&rq zmb3FBC1=dZq=uTR9}RAf7Ke{e_xa;g6Ij8+t4Jcazl|eHvfi0GwHa=XLdp=A)J@KK z{VA3KNd*WGiO)k@g3*$tuII3;#o^K74RSvV6u@GAeQ=LL!mg8uzS3-Pb_zsPJ+6$ zN)U)#BX1#&be}M>ez}ASOI8#rFFk2ohItZT=TK@_w<>qzH_c>HQG}8kx)zccmv8vB zlU$6vIG>!tj8ty0$3td8*_aO$czp+8-KJ)yT%gu}?i(|^`uT-jePK>)6S|d3v3%xv zDL7F!EsIZQlvP)>)7-c#d*_CjIJ(7NN(I6I= zUQRl*@;frQBCPGye3+@vu3Jy)lE>N#ce(yYvo985bvV;!lVzr4={3`3B+3^~nf=lM zm&IFuuXDam{sz<&Npa5ls($X?m)m#@F5cMeVd7!D=InZu&!Z8;0q%&1wp{%faw=7! zR1A?$Dzf1_B6=2dg^+k$Ha*Vo#-PkZ*a#Dj(BCvJ>O?o_==DW)U-w(9Qvcxvp`9CD z^npU5X=w1{|Ft54n4!E1nin+`Z=mm*EcTy&)7nih$C@Drldvt{Q{2n43nb-jyLBp5 z@ohr~&Q~@_u7T=7DAGiMhYGhlV63z=qZ~FZxAfmWPx!Sf9HGQ**|d{+L{Q39HU#2k zz<>Zt(=Z~oLcMeLU&_<-{y>pL#C`oX84u6yW*V&=)+%2qM|rw$O4~DEnf1(R8$%9JksBQg zD655I9N-4-tTsRIW)aZC762+A-+@bDO8!t4{}q4J>>3ltCNNvsm17} zyjy5IQDJP+3?)wv=!Bw^A`A=`2{b^t0j&1$YP-va@)GI>zhkqm7&}`FwamZQ=yHqw><5q z7}-n@f0_~zXA_v>Roj(O2696@1lzVfGS#0c*C*NxtE-k_WZY#1(2)+gnslO#5$a08 zS2g&;=I^R3!>Ha&erfbC7zAs78Fr*hvn4$K{71p^hQBM(_Lo`Fb*&sg6@JZc2NY=G z_2$|sRe_zapQtb2f}5dUT07?e$l#c*8H((?YoxOMXkfd|de{q~u^b;wdR2yp-!rRp zpQ>)t*q-1K2Br+SQPYh6$c+cR&khwgzOTz?rs$b}cVJr_SIZqp)s&@wB|Eo8XNPh; zBkP8COUS^XD70~6A%Xo68QMT#pcqXhD$azySm2NByq*5$Djdb9{X_0B!e|eYF~Q{} zn6qqrep)KNM4jf?OT70$i2X`#ynWBfEwAYIvTZ>1#r_Z8jj`6v7D7}TIbX~r}K2(YQd7swqR zI{(C(!NBoK(cI;XiJESpV@Fz2(7q(?6z7NVO>bhkpM7SWM2o|JW-hAi|KG3Y5W)1k z+FjEK#_bDN=~us#MuK4|;I6wTH`VZbdOwqRs?M$3>}#E`&gGa!*qhV^b^(I=boWj+jrku)!HxIYRxc zB&P4&D1SXIS;_N7YWFQc9MLD2T(&w|b<&+4`=ED*6-CN_&!jf%=IdA9-+A%~RG|<> z9$QTeLB2wk5F{S@C1n^zX-m&?gp&7=u(h!6&mlw1*k%lPnQ$7dGVCKBKqWm)Kx^-z5nAV&uCLa2BPax9;h6I zW%)KzaO=%~?uTx<`XAA*8u9soWlVmVGkAcHG$-hp1k=v(8#%R@ehP-KRD01Fd)Dp5 zTaSYU=)r+j;^6zD(mcrrE`1)a$}w72Hj_qO`H%R=G~6e$a1|f!tLfp@x9fo%CF)x> zp3en@4ogVt*+}Obo-!4 zGN+s0ZMjAK1hBl5zFZgA6)ZdOY?LKwQiN!O_Y`jiX);Lz-k>LO>L>~Ibeh=7UTA72 z*yW=t#ROP(la(!*C`OKD<+0#vQiBB!TtiIjxA*8#wa_3>ux}J{`Ig8Z!e!SWz;`OV z+x!uKs-Cvhi&v{1P2rqNv1MXjxd$-df8meW{m((9)H0t4(K=#*kP+~&(L1*&U_=^D zp@pD?VACW>E`bb!HPW4z^CSABCtXyXiSb_4mZUFAsFd?T-dr<0n=1DiJpf(y%pZF6 zc!aY8U6b_+*X>86V}qpl^^QZpV9VORoxI_$fQY1qmZKKKqK3mfeOC8%}$sv8e_ z-45xz%s!3|qp^#G=tjHH$oX;`_n=N`nT`~DFiXzwX zsv$Z$IAUX%PPs`|Gql85C(+r#>o}rirc8|C%`w;K+mE`2JwphXcc$*5Oz-T7MiW$j zMOT|Gk%>dbReU}r%m#8Y*c^oxmVd*AEzf#jHzU9SKS{EZ@ zc3)M;$VH}b23f|ZEDPORXBcWw=$0Z2IKX*xBNmE?pjLQG3&V&Rl;53FFf;*CUO+RJ zX8+XkN$hk~+v*HvvpX>s6qVj-@1B@{zM#@5`C`^!5}^F-$`*?5B9} zHo+(%U;J~FO#jWP76wz@O%#5DdBtm7Q)Hj>xoV3NraXs5t}s67X?+caUI40p>xa54 zNwKNm&I9@;Q6s~jp_s6pVN!gh0`$PYV<9!PO?S@f^{0)#k>pfDg=Yiml7rWmO0cn9 zc)@1rNHPr03NT4?cm*M<;ZAIAcUXaRO$!Ujx>piR9airfxU|CFi^ZPur@5{KtH3d2 z7oCRu9~tS1p5WXxHf5o#xY-0Vxn9A3v#z?3)Lh6P+Z&LvE#hTCGLB90dCv=?S( zIfAcJhVtvPG6{0r%}dO7aaC#%Uf(x*GX?t2V~W7GNk@1rECjDerExYgDP_z|wuT)t z<9-T3fo7!bhzvvU0c}Tkz+^?_U3qi*-^7=zZoZc}GfbD6=RXi7jECrdm9tIt7?oCz zDeGb6Q@tzrjIlBZczCz2!=()DVK+$EhgdE8V`s2(F3;@|NeR}6y^fYGf@q>Vgt3_@ za*TtaKJESzEt;8AV93}_wT@3|70pJf!ed&nrFqI>i8=tGp0CrRZo~{2_ zeA;U-UnRUNu)PoG(3;SH&Kc-+$CC4Msl^~8^i__oaPB`6?Fo0>qx>n~Ih>C>;-#@sSk7RZ5zYk@r|9$Fp{See)w**OG2M5o?7} z9fTs!43}t!>ZdKISMoMm`DS@(TV)Em1lwO!0Tgh^o3U5cm@wbc%CP4BqOy%Lxv{Nx z5~A;9U9asJ8bLusp+Wu!MXeFXUB8}5UNVs9%XzB)1^)c%z#m(T)>th7=URrYFa8!XR$6gG4_{kxNwm}1#+$LsCCfY?X`a# z2&&-f2wRon)wZA!OyiFk9fn`g z-hb4c8MKxWL%Xm3)Bnm=%L4VRGH+lMj(=8utJq`TIU0(c0vSnfQWL0NI@0JU(cH3x z-Pt3=dj%o*uILqb7`4(d)M#hgd#V)7{bP0)p22UWO$n&iT2uQN|CzxWGplid0gF!! zK+m8oI3sy~cD$O)SleB}CBfJ1zvWkxsaDPiFrh@MRu+k1Q#t~3_)$=-@(Ntq*qu$$ zM?*}uLOszJ76qwq_6KEgJS)Wsm*p=8%JLEfbT(l3R>lra0-I5P+82#2^6>8RxN1E% z)y&)+VneUCDUUEf+~@&oYj-L%xm;f7jW8f1cT;bFMOV0v(kHPJEF`hJW>0R^{d!{~ zSa-s$T|}YH=lJoRW;Dizm% z_Y=l{k=rRHk83ouwc6yV3j%D!G}3G>Y@8e9;eeAp@f#QhMs}zM5c(~o@^MdlF@nCp zlxlm#k*qW{^@{_k3Re9SQwd%<%WC@e0H|*WOb7$CaoTDKI*UP19NVkmyoDPWmoCt| zZllUvv8ddACah!p_z51)eeNBdHCKm06UH2W>g9u6pqZDICbd&8Ky#*(>>ae{)}tIQ zjSIP#^-RHe)p(dpr)UVI2t&l;6}I+Cwa)_aPT)+mIl^WXXp0pF0Kz7Wcjg{rgPIA6 zE9Eel8;fLSEtGFwlkX%!plbu!Ywl4$qx6?7g`U$wg)`(WzkavZ-f90b;LVcr`cbui z#9PvzV{zA;6HCdgUMwK!GsHqF+Lp2{IUg~bRet9Ahg5$p!P-WodN<;H!*hFU;ksf_OQa$%H{mG?^?N?lZib+d8Hryl zoHY9JyJzCY^>ubx0bCk^2%e)(25JzdpbVtikOLISdYF`ewrc?EfgMx9&019~9Nr_p zml}^wdn`#-f#WIP;IQlN7W3K0Cj@0UlqY{>rKwcq1;nJTTU}QM^M19cB5`MbC~kd> zZMMO8r30(@lW#hPJsMee29@&yP`|iufr#l=K0F`>BXcaFMrozH41{>s01gSE{dU4N z8fzJO`yrP$fm4fCdIXuC*%{ynmI-q-yjz`X@TbTBqa1EUZjcA!@^UTgp~BQ2=zH#p zb}#w9FA(0jA|=gGztBt6P6$YUlc~1R6Ygi}+k*BO#0;LgX6KA-Tt>{tg3uo$PX4ac zHs?lSegE%a8cy)#6b8T$!!*)kYiwYbhLcM6fKFm(nD6=(wDfGBPB~ry>{Mm1bsiRr z+~xV>(hrdI4YWQ2vgHV&R@E!?AuTM^9^&q@_V+%j^yLEK@y=& zcJiq9(SixSZHXTp4%_QD6jriA*uQ+&g9r_@G_OCNG562csKN3C~E78%|FwzmG zVSRImdN0MPU0G>fsPmwIlNles2U)V_N?7QlMGOOlk=&qv#a~@mBHrewHwN{Mz3iYH z8f2JS?^{yLMa!T6#-hKVJRKy0&Me@@eUI*Vq03u9ipc-!e*q@Rpg-EYstm&E!2$hP zx=bCMHuv_Gmf-;IWy@j5$$mj{et_wzBvl;Lkof$sU-68fcby-9-ZjUjNpOpXB7=3w zMoJz|AI$5uqIGQRn>t38SC_`rX}_tWAr$b0b#%i8{wYU_1m#2lpL{XUKi(AxY#Vn< zQpy@)bXHK$7#CGK3g)I8lz3$Vk>kU$YZyF|}>! zRHDw0fWV{uGY~zlVEBmOj=(}dFC9wy_eQhxTTtRwryda$OT0YhNUQ(%Xk&aOHt`s1 z%Gth@Y~S`MM-0hA`oDor5~hTR-fkU)$I#^$8iD54hcFE2}E`zw5DyJ zi0Qm*ow7t2H_Ww$$C3GOf?`9eM(5<;{=#7^?;n%Fv()1HSz z7eKcc5kGr5)r%@@NFYJp35!}p)5+&O%EB{Cn9{KzX(%Ufa(C zGOD+3;)w@;jDKZAYkqW(SN)6(Lp6VNqJjpRcw*m;06di~$AEoGHNC z(TQriU)AqZT*O33(9(ZyheRABWS2W1%By7F_oim3$(+NDpIpmb)yC3bDCrveDGU@$ zfqLtI@SnW+Ic=-~(}EMQ!?nYrbxO*N{pehz8#dzZy+!HFk%=SHseM$v$tFFREQ7_@ zl5!4_{JP<&Fm>r0UFYDOm<1$UytBG1E&AWo_@%P(+3xYUuHhxp(4!OMc4WhuoOxTrDPl6TdWT&j}g(vtmaSvzlSZ0@3E z&Fzmzk6R?37h}jQTz$Vy;?&bXmp1?2knt9mj=|ez%+qgt8{fj|>`WyW67sLkznXWiR*ptMpUaSGU^fkDD zjm7FRi|D*d!B(UijR6xAf=Z&AH(h{c7n?m?XkOY;oINvsj$gLhzjS2Z!L=lr(@;z+ zR*kwGFOjVKTmDQrFz>P7p!JtZ?!6H94w)v}bms8I4I`t*vx?mM$)Fw)Aw%U8*#m}% zdP`feE2K9PA|zpgtaltWH^&VBWMnXZNvyra-QwA5u3Wv6c{P#GP`A?L81T-?D!S}4 z$RBT8(;6?zG#7pYV~JyDAvOKApuT*0ixh^xLn61s{>R@+224pQXsMN8=IEMv!xX3g zH1R((y^(%)@-&ue5|MtNps?$v0UKdR^HtxLiX(uGB2Qoi^!xHsWQopLEeVW&&jSye zdrXqeh}!wRS<4N5dbd4U9ThfwIJz4(&GySIZr(+9u~tyB{`-nvwI#ZTIS{qSI}saF zbi_ukg$rn@eQ~ruZ-$(4<$U3VjsYyq5jrj4rq71e6p{z9Uzehej~$PF;Uj>XTBV&i z_I~;#lL!4`b5REInjLSqF>ycZQ4=27^gv1Ib~a_1S@FcTWm`=>s6vvAPLI zQkVqt0d(1KHAdIM0Tey*cmJDY==h=UN?^XMIO;x@(E(EthGr}>E)V?gP>w=gM9<9Q zV+P|75(akiJV|(wjka6#70OzMc#)J!n3c2tF<3V;Ee3kmFdUT^AYt`}BnbP_(F(l- zV}qbK7hAlo>P)VA&aCx+3*Zh?=praqP~zOv5`<$z>|q^Totv?A{yXvz#ooOg5kbLR zgY~dRJp`%e1~{>Nhm$LZ^fIR(vlN!br0 zm?$%jAZU2&v={V*2i4C==J|^JhB{`}Sug(io=<1>O2k1JNOcUqE_f9tt2Ff(a&Nml zwQ-?51NT%CIV#ZUI?gf^42!+QMJU)n41+0u(g#bJ{+VggnJW<9F2Fv?!Hr?y=i97o z2IFf0fOF_A0m2M_?PmndXEwtE^)P?~#^VRb*7Yx~&M(Dm%^@=z>KyhKr4cAW8mi)q z{*cWjInD1QIHN8W~M` z{})l#!V+o+ntbVE;z%_sU!5>Rf)ai!0>~96v$>_8S-19oz3_Fk^D$MyL>q=;0K?5= zm*XXO0%PtLfq<*utR1Ya*2bbf0t*+Yt^IP9+cT1{O${X1wyZ{x28ROlrI!} zwn_(zH4m^M+_D5C>jx^`S}~Tq0A~JiqIyLi);?etckqU#R$Z?JF*+DSsWBkwS02?M zDmPAQ_fU?1vU`-~DC1Rat%S*Tu6S;!Qb0)y}3NpISFT+EM&5 zB>{d3a{k*63lDPDr&Dtkc-OyuFG{$wxOW)UY~5#AEPB+Al%nSk?uYwfr4JG)0f5SX#*NFeQn`4I5s zC?j{b?l~xebyXXst6nRh@1BMFXhMZ@LeoVG0mDvQm{!2Y zIf0Z|eTH}45@@7CDsamxgKs1i&IjHqXYlHOS#MPf+uvgD5R6ymJ=hi)EX-}UOhK*M z$nd#L$O=|cFCPXZ(&j*T?bsxJ5x!F{{#tJ&YV6>X+oGUwCNE2LY63c1mgg3WLQoK8 zM_j@rex0NRmEjJrX0a-Fqum?M>wzr`Qg~=D8VF*A%TpV2fn`m**+{ghBSBx|gf%gL z;#r>OGyibh9-qz4T_hR9UVjhOOZP`5KsENXofQptf--AaFfz+T)iqx=#CsxvhatDO zKf2~d;H_vqxm)bf0^&;qXutDp#0^~aq41cFYTSoF@d~d>zFte*=eD-N_^A#(9{a^x{c+Ln zc0GQ~Q|a2=y<2CFhc% zkB3zpX=7D&`ZP%2lBLIm_aF@w;TO*izirQ4l~yRC)w*L%V8!VBe8B+YvvD?=>b|mS zr82Y|ngu7GQ=kuX@SzDVD0rO~;AEn0F4?t4>u!|S5mIhT@_^W z!e<}IBh{;;&u6FZh6a7B6J^rg$e*4fkD)QWw<_U`xzLMi-b;K zFvTprdidf1Os5F4T>9^%(T<$k1|oiz#=#uqq$10XkkLrD_5B$um5izcppG15q1z>85oG6!JoWcp-4ZjtQpPr?!T z|5EvyTGSPOlQ8IRjm>zBfk>xP2KpwCUwlmjj6e;0{f@~T$*qM8!zOCd!7qn`cnCl% z$cz*|HnTc7-vb0-Pd0h^mvA-y`QL{t8iTri49!WI9#c4faY4#tIVNj(B_9tE+IMqg z$meT|rK1t!u%hXhb;GLrxUI-{lw-VjDaYh=wMwg$I3uKLi34ujtPhP&Ng%6WMdbnrjzAOKLI%Cxq6wFsNRU;oG~?qeS&8!w!>Gb1a*48;8@x3VJ0^K3_@;ntWF zlcP6VPK{%K$64Kyg=J6Q8N>DO_>j5VPr zKklc>?VD}Tdko*T@U@GWt+63$_~2i$31k7QUk*}#Ub+$CKeVb5o%7pwy~a0?YhhiZ zdWXqkD?B_;u`cmoiGx9Vhfs*EB@=se!1I~_**NbA4?8c#ztnRAYA6 z@Hz15UI-HJ2LjL8wI%P_O>BHtZT6s*da21B2FiJH2olTShz~sc3>>4%2qaKg^EQwP z>s|eS6gkhoz%FNcVugGYe*B0sJ6@#=uVGx!#sXTjC}FSr5#n_l0%;2@?{{QUj8_GL zoP2g3MSJ1;XR&~IeI1JKbZylW^yXaiPm|s?_B_4f;F#HQgbhd>@uhevHr!zt@vl77 zKf8ivF%b@n!F;g0s+Edi5RWmmIH!wd997eQm-yuoJ0gMIU;L49F(-E3MtdWV%O;(6 zAj~r9i8&{!#BYeH22#8mk+a2cY28Lo5t$e$UEsN{8tb{W%%LUSjO0AQ*Ld1_BihMsumsXlb_RgUq z7Qy-$Q?JB)fZk9@skvz!@{(q>kR_x8{XVu)$>qz0VV_n6f*=2xnL_#>o1+rD4&=Df zqbz`5wOv30SpH%`(5+tCVCh*;U=m?}T5UNZfU2CidkSj_6jEX9!!w?MNA2;sy@)YnuxvPEHCr za;DT_F^7mdi#bpWrzH4h~f_)N*lxJA@Yub{yFftFfMcg1#kLgZn{+ zDu=ae^onaxTvTxVk@jF{;jb*?j?NaFGh1w~{iW?Q%Z;@#OH0u^FKlkFfjyPbSA7nw z#|m$&gUt_>fWAYL5b|eI$2a=*i0=2hqTL+5{Hz~>*X}c=(vm+ERZ2>3(6`%^wCO6Yx+`*ghXEQ>2&SgA0k(GFjnSzOQAK_zuy zjyxPQuks*ZZLIOL7t7(Kc}JE@vE6+p+|xR~5Hb0GWq@r)&IY0*h;fFX zUCx<@;pOYm?{QBimzEipu1)H0?ZKW^5p%RBwysm!00Ad4+IZ6n;6+;ni0yS})z8vz za^OGkufbGb?20M{Lp_Zz{pVim^I2XZN6Ys+d3{D=)a@WN%_>3NbM_mwBE8A^|X$oSp+K1voM_ zGdP#bo&z2QI5IUeIG69915G+DGA=ePF)lPPE;2A6C{$%wAWUg?Wgs#zF*z?pWnyVz zZYdyZaA9<4b7f&5c4cyNX>V>IHZC(RF_&%*rp9$|_0ds;N{JQ>EzL+bUJsS$b90sY=_*SzYN=1%8TE zq$gu&tVxy8l~ShJGQLtqxyrao*~VAYrCd^#i9|4(f6CJMXl+GPRieSxSGq}o7*tvj zV@oWJYbqOwpVeEA777_9rM5h=@+wrGSw&w3VwIAu0+DbbR6$o>(V_#9vcxRd%EyL9rgxebXo@AKG&D9g zY!R#Ie-k~YDrwJ+gokgMDk=h`p^}6qWN00<3Z-JC387M&qy^C05;O#m(n0Gg(O}c~ zw3TSE(L{}~QO41Vh>0?h71JojmJx1fxYdq^G>o@Jjb1ib)*-!YqD7J5qy_66UJ2EL zaa)Q&CCyN;CslZ0#yawZq^2o8koJ^?)*8|Ye^rv>DU~8U@LH&%X#s|42ct=kL?>7q zw>0qyju0jhRq!kmcSTksQ4Wa~LbM|RTHNzFn40&)O+^80~7Twm5KW^3UznxF3`t9Usx>fJa&lc0O#bss4*xzl{ zfA6N3^Q()4=_Oe{8eUHiXOo@zb@gXM4W8B>lK!+s(=TWqapzJ0`WFcA5wYsWAFFzg zFtgmlRWi%A>Pb?r()jxA#r$A@x~Tr7r99cI>i5&@MfIsAb>kY9>Mt_gXOWgIufH^^ zva#hl`IKq}Vdrioacm`R-LiV}7*$D z#I1v~;wbYSJG`$g8QaIl=zqZ1N_M`k@gvg+=RR0>}jN-6M|aTI}R1>9YQA2^BC_Y!^$FBucQV>Kg@ zrWAe!&|QTec!PBhrTI+-9(DiH9d6u`?kKz)n7w^4v+v{$BS4JqA0zHi3g5Am`?`P| z}IK)-n=~A#vXvf7A_c;V1D(`d7+BdIf$#$t zaO=5%-^2xOU)-N`2;HW$DIE-gx7&2!q!>gev~8Tf9XH@XN+0w#f!DZgI%(OoopN2; zqjTG~)5~OSjN1`4N5@!We9Gmob9J8f6}zX)k#cSVv%~6dnX#0X8=& zCvUesHJFfql#mdrW2Lf!f31a`XE5AR+s3u1(L2HFL>JxatX_77C|P1-BSDmiUjAzI z9xZBEM32>35+z!6B18zHMDM-q>v`w-_|Cj@zMM02ow;Z3nR7n;=AP>+7(;r0w{EpF z*LaaRKyIy#u8CZ_JdzNw2JiW`Jnlefvo? zDl5Rrr{aTmGDCJfGN;}lj2pi=osRkR{ma#m$N4#HzQ;o@Y!=7FzAW+QIQfqUh4x7d zhQ)`!HW?DoK*t`ihvEa85CefXu|_7`AA5i5$0M4?x39;=IezkZWfyK2u07V=udT$X z9BS!#;V4}rof1bb)Fb<9di z1aE4xwNGkp()Zyy30nl;(B39z4>>QTgjw$FGK%>~>DZ)+?6re|tZ|qR(myRdG^3tJ zz)Bjk{hRYX>b+XmotZQD-SiiOz)@!5Pr0@##i?D>bf;7r46)mHI~LJC8(t$3&jqW? z22Z`_j_)-mrB!Nl--fG1zL@Dt_?$d__nS3xbMdf0S#@+kW8u(bkT{AIJAka!Sz@5M z9`p?dpDt3($nstT_r9&I(D=ja8K9kAl;c~1hEdy^da~O#P+0@eLG>MXmyU=?>7L-( zb~gx4FJ((FC^LXs*!3OnKlJJLK5fNAKNuxKLh?QC@%y)}vLy@)>y450yW2bWw^i*< zg*jx|$GxU9HyO-C|CIar(KBDtR8tTv=|tetX(w{H24ywpc?Ju zTp$F8x)+buCKw_>7BQs7y0%pyxWvT`EvdKCwV~9~o>SAmG&An- zN={U>X&+U}^M}|)*q2l;!vF|>k5xNru{Lcbxqj)u#+I;MvWsGC>wP)y6mr`dIJ80? z&G{G)0Bv)VS-)N%r8gl2U9(Vvgd4wm79exNPD@wC<`0BW&Pg)+2j6|B$(1HUB24MC zy*FOk3;mQ2NNz`5k+S$#XapD1L6)Odbvgz8x*jvhvoUQ%czTEw-VM(z8}Io193r+f zzNST+8N~z?)si2S=`Xz2^HGnp8<~+bwD*#c0HCp6MM^0wjj+<%oe0e&_n!CT$M^rZ zgt_(e3x0HZ9{T6dN_bVUUsFEkNJf{L%(9x$c+@<8Sg~^izi6O8D<{n4L(J0*YoGcj z;B0QR`f|_gXLWXh8mf9WG%Eb_p1h;Qp_dVy*YO|kJ#L2>6p{HtIF2*jmgcA4D-W%s7{>v*Dw`U*gpNyD+6{`K^laV#RF>=9Jc$c6%SCX4?b22 z1RI8UPedu42D*JD30T%5EXy`p=0!5fI_c1exl^{3Iq;2i+0e{=G9_Q;p~3k#?~^{P z*W>ZonD>?9b|=@?hjaM}g;nV)8=<@39V@9ndL zXW5+$W|%EuME*nke+g-Lv$ajvhNm`iPr6kFHj(U1B;bo>6&d7cZH!;9Ur(xSX)BCVj+JeE9qL6J~&S z8gg1q@FgK$?P*eOj_bQ-F}b)@0wu(gct2ln&c0`mo=!(4zrfQG^wW=sSg2u4eC z+trn)73uZElgEl`EEeE~wNm|udfeUJV*^mLovJaz>b?%h8gH} zW_H>4dn`Dk#~FXFtPf`=>(&b7>KYdHoXWL4s?>|h9Hp< zbnUY#%_Fi2%_I9!F|fncs1e>i!PAi7=8~~$KTqXM`5tTe#LTDvdB-}U!L7#&r9)Cs z(hT%lzA7v59yN5_QEK;AuGM-wpunU2kxwmPYd zp>|&UEoOu3E9YyP61^n={jdh7ILA(p4kfz7YeUgAs{WzwdS*I#mMNRcaw;VdLa>85 zs<(*EJN%8n#C^OUt^fNddTr1KV&Divu-VHJTAEtEfjD|ZJCQ4hNl3qG{%6;8feQ0^ zEiSntxfvcuxK2BiHV#`C_)``6Ed6wC$P$=HUpyYG~gO)%mvnBxt@;v9n>T98Sa zL8jNAxzwm%*4<^bLX-LV(;<2CNLf(T5}fp^atznd_E1Eeh=@6orm3N1vgeg6BVn1o zKS}2C3+Z3z-f|&-vIxhv$Daj0NrgExF{P%ZJ^T78qg^;^3T0od;gKXQw5Lde7p^>o z$D}5bl#X-|HHYB=tb}}U)%mbC&1T_??xL}B?`TBdr%DVs1#?>VeugIi2kGp^J1_?_DBx0xAUZ?S(Y-5vSs`^;nvdL-MU4AJdH1Q@=q~uZ#tg$(m zQYawI1Dx+uEV`p!yNzr$j~G&ORCrhT1X3i@vbs%0uB<)H%XZ9~m@B--3y(3X$b${rQC1N=2Z@a5p{%5~|+_CFu!IR2xh1nsvbbLIJBeEfA`eGc0Ern|pw z4UB=}M?K~@)_HdETzGw{WVbe**r_`W(PZjI#kL7NL0v7LDNBtDY2^n1nR(oUH5q&WwNarLe7?*^b@wf&EYKcaa&I@?n>OBRzqGtDy}<;*u}{BL0cC%F zT%BB9{=97Rg8|i)YXsVX792*#45@y8LGp@O`DK23l(w5imoK~KvDKrSzDg>&?1qlP zZJCBf6b`l>Q|tCZN8Oibo2l66dB@&?N)=d*28t9fS{_?$Yg5}9S<OVgUr9 zEK{f6neEmVg^W9`vyIa2dEZ=V_;8y95!!G|_55Nax7HG3nh#0##iLtbAKko}rCx&d z)EL#5QSvb!)m=XGa(4qfFIU461hJAyzXMMj+f;q{kp4^4I+A)0uY9Ei;QQDmb%j&1*#MXr z4R$85WXO(SiK>TU0#B|YWk zOcweKdp5q!ZI+l6us`}q-7Q0;2A>0PltW_Wa&xH#N}uq@&Rz^OQ9NM%HhshB3e3&l zd+?l3%{;*tQ`Y~dREIL8w;4J#(lIphBG$Euq!}7~y?QV@Y6HGm+K6obS#+7;e0+WY z!j3`HAT6$B+pnU#$DtEM?7^Hv}l=&SJM5 zR)OCo6=*F@OrJefs6w$C7VB%AmOSr=%gc}&xSrVpK9{$VH|=Z+v^=tf{A}gg?|@%S zQqc&7@iM2FGD{(a78r|DTh^k>4MEo8(Ix$Ah^qkQd*OZj)sUUFM8nwkm&GL_H{at< zub=-qG2S%g0oG4!PwpLJgn;d%KbzRM62AoA+#GIiT-`W?CO159tVHzoD|W!&VtF8Y z#Q5nqamCwujZmt~&vn@CANncV^IPsa75yo%0{;Ghj){$gKiBSh!Io_B2#f<3Ou!M_ z%$UUq+Rgl`J&211X=LWWlmU5pMV?fqVQ*#I+#CZ&{nS@=kij=R20k!WHaeKPY> zqGX=fQ3ct|)IrnH-wjJ6fp3^M50>B_LB3s+eG^>rF4tyQPib2NN|pR)s#l=rGkRjB z04-U9p1KQky9M#(r*mi6%@b+Xdn@a0{%vAG^vJCeX46KeG(#=zSz=Res1y9r?$$NQ zD}N3bxT9(P)aJjJ(EtWjz<8gk;6fo>^EJb_KN#S2mokLsUvi+uz3+K!LP%$j&V&ld z0Q*RX^FP}2bBSf<*y{$NbqF+Q{h%#lG(Rb4FF*0h7hSc+dh4j&T#>2O;a;)3+B}+f zOQS5xZbNvU)+GA;dV=H0M;p9$i=H2|oR;IA*9g6!qaDJdW`J{FMM*J}V`L;jhfjgS zXdv(+LmGGp#Qrh2TAhJzfUHfBEEJq+(L&ZG@T=Z2)dMhD#_B6qzC|o%bG1c79e0_U zi?)jZ@0|}(A@yQ8=E{bys&JPOrjP{{7AfQx?4VVxSRpm3phJgh3Zl2F)&IJ!Yps;m z$IF`sSyB1}e?3-irKH>?t1Cvyz;C#b?-WzN3kFR|H7{@b5McT5Ut2l4dbzheGp+1j zwKaT`i&fOVarbJL>sZ15axe0q?`;E0r~mF;V$wFm6ZO|RT}Lq9f#6a{D1cCDCHmVNf;Y%&hOe0#}1cXo>pB8J0Na{m5A9~GNO zlty-CvI6avy{TG&cYC$$nUp`S&Z#J7`Gi0Cp|}~{bCpwQ~DbE zuEoU_P;;bWG4K|%$TDzdS4V~!)O{&X>meSV37x_hewj&g=Z+$^NulmXuh*p^{0Xp~ zYAOin%3+b%c((hs-8+AB-NnW8lZ9OK4c48*^pY~qD)P<*hrCqt*6xBAi@uJTyjtDs zNgGsY0OS=>QU*aiqS_B{`JH`IIiguFUSm3eb7OB#m+&Ndb@QM|m*Q~}hxHC^cs$g5 zqs`P%(frmphWovW$$jm{v&$f3c5q5|2=7f ztijT9(o!-I$wyMsau7`oNr;4`gc?LcUR*<5R#sk4MqL^7|4Z)b{g;hCl9U2vNW8-p z0C-1r#qe>NdJoRBK5E34S2ff$i2azZj%yI9Y7kxK;Y^luJH4kl5gxk-S`McC812UA z?&jukx5~hKPlGPL7*AxCMd>V1)v6M3+1M5LKePVC@k z#IW`tC-Zu?knTNuzU_Tb-IS0 za96p3>ubf)oWTCh1PgAENum zRjY!tqm)_p@7o$LFE8-&n*B>>@mOXdLOaBDcX`}#(T&p=U`l0-6<=8_nQZ+4=?Wi1(O~DDFHB(fj}seZ~+8=+sGAu&#zG5D8OQd zGaL>Xpbwj(E_MMIy?B8IcDKct8re)FQ6;Ik`S(3HQY1}f9c0lLYk1~zX1;Sjet-Yw z?X6X-M8$TE(_7yzBmdDZnn1$abTn9d9M#lW&=*`TNt_!qH9Tk87PrUHc9>tP&HO9F9$5 zj_Ywe=XOxg__RP?akz(nY9 znihs|IA-DoCO9t(HFHDCgd5I?IFjh0@@-5kH$6|S zV`X#ZsjmTz5(7$w0tEJ+f6NqSBn|S0@dLpU2$c)Wcn;qbmRw-QufKX+_359T@50S& z<@8PPGhQrzw*nyMXj*>Q3uqieGt$%%G}^`58PUOnPk3Kc@QU7K)_Tgdhrz=C5xgtBA8^HWvgPGK63C2QF>$PT~X3uk_t z>7Qbv19EA?hF+s4Kpev8*7}MikTSt7`CvVk5+K%pRfo`a;ly(u)?HP=0p)%V1Ds@W zVcb;R!F4pU+c(13@7tP5nh6X&;z#KB@Fh{b>u*pArQG{gJjw>2@0MN4oj+E)dXM&e zk(Xn6t?}OV@!fipr4BCG`x%fg+azA3g%wO=`G=D%=^9T0{K%hpLn1%HuE68!Sc)Qm zMEstAi4(nMmz$4WZmLY2qz>dt5BWu@gqPW5ysU_EAd7zD6((D`xNxdpfPOZKGa%Ed z>cf(Y-=xZcM@D-};vx}G|6HLtq$&kfZrPcU>LR79<(Ir43`WjW@dF(om_)syr&>pZ z;&_uR6Z=NW0c8c-SX@A;x;E^0AjvEPpC#OXS!r-|5y;36dVL#-N9UTvqaoZOdq&fa zL9i}{mkXNzkQHu(ri*h|tV~>3IlmCdi_xNVBs9HnNEX{X>(^vU!f-Jv@`%k3zN{b6 z80hx!iUp0aS)3)=|4m_FXu!Hh>z?B#?qZa)W%(lF>~D#7PgaW$DCINK1!xMo|%|PfeD8|ppuM*pG4K}hI+wLi-9Um{@*x0e*!#U`yd&4i}cDRbe z{b2HTYVuZe%CX5?F?l<?!NXivVBx#|eu z`7NTBX?YpZ<<~DMzg9YSE_JM(0wLiiz8ZeE|6byk<+0I&+0vsE@)O1s6h=2j{@?BPn8+PvR&C zoU8uAB(X}r* zykc+#=_p+or(OnjX0zOj%8Jxt1R$%hCfc2kWyf}CCAb3B^XHK3!A?^sL%|8uSyDosf9(H3xomd!i24IEVMI{vE32soTF1uF#E!`UR0 z4_x+c!=7G-7ApsO{%pg^H*8Dz)k&F5cH!F&EMy`1J2g_WV=mrOkzWw(=e9aN@~7vY z_e1^as5nAIAr%?A33;@C<3SOH|N6seA5e0b)TYvo05;9JtSG<7b0xjubQxyJUR}g3 zh+M$KmC`*ZFn^wwk&A^L)qJD+PG<&i6J}VVApt!m{=(Vl&T#mEb&aPDsW_wkImiLN z-$+Fn?<9{T>k&cB+0dg>S^?LUG_7A=$x#j5us+_PeEMROCr}!Hs87{4ED6gWq4Xv- z$*?TN7K=QJNff`bzR8h|dQLDNm(jqgXG=$g<{+adA)y^%^}b$u7&MOSO+ zq22T-4$Mc5vT2X(Ydc|I0Gc#kqslvu`H5qLcTqY;8cCP_3XYolNO|# z-c*NwKvcT(T~n2zeML+fya}X( zat){EF0mrVVsaH#9WNlugdNpE)THVB@K(n)B_C9u{3AcuNyirFA-@a_%GgU`D6+&k zk6sVZgI)Wc)bf6o<$jOqV~gm!#oj}EW}h^qa(&}agTwB8wVw#;(kPb}97s;$=ioKq zIFN0xSfp4%V-td2A31A=SHGy8TIfQY?3o*kNXZ*Ma-&yqm86R-4(PSll7Kn``2 zF|feiV(`OV%(Z|$EC>K zGqFck3*vcRnXVeGq5Cm_>Un&{t@ zi3RakZd9BW`XZEE_nG}m*Fk;*8!2tuM{UY5iO5}E+{Uu8BiU^FRvXkqxt=<>UOSV% z008MW5KHO;aU{+Ry%ISgsa;QgeY(-$0SX$;tT!9`MIu44 z(T(o@`T)PW`sDK$I$Nzrxgjkt0H<_DaQ_baS!%_oF6MI?4{6syQXwpoXfzq{~U{(qy7>yGIP!cPiazk@I zJtJeL)M}HZGWXl@#d@QpPOk1s5^W2jSrko;qPg*+>l)Y$n{2D1FLyNfuIle-Z~8S$ zfA0J~-A4BA8ut!30$DY%YEfvBDwz`(ZBg%<156bxd53#j?BAp$L8#J=SJQ?wcw0V4 zrGKtbvc9}+i@s{=^+swvY0`-cLY!45lVD3H%G5DsY8ZC2s=ANzrBkiVYBmwHU>FB2 zR2}g({P(!2Qk&!me6@X1kr4RvKo54uf6`BF=>I@^+LimNzNMkEZJTzWT+@3oK@xGIcZPb0osFwrf1gvm zUic(X*wHw-q z+j~8i<5r)cNB_)I+3$fq^JbtzGvEd=O~AiRh4P^Fw_=TUR^1NFTb6v+!+Kq8+cS7M zOI0rD<-e9aydm@Ch&-qaxAAx=e`&0sp|0$YAnZNey}K)0|NN#c4rNEz9{pef$a*^v zsCSp#+Ipa%{^(S))Vro=7oJzHhxQ%dT_yiVvL`p#XEWbrBYn z-;o~SqC>bR^}?MqoB3k`fV*nD_X9;g%xKWg2XYl{B~BRr`@ZUryArwOnL`QdPy${9 zO}pU%MaG5pgA>3c4>lk{3LYQ~2DWbSfk9T4TH(WOf7h144(ECD?_)tm4B&x$;h577 zUIZ4718sQ&sEUfhJA^(re}8z7{=iNVW1MNm(1lB$T8M=nUA~W?OP*RVT#@F=YriI8 z0PqxGHaLe3lY)7A0ZVa^7+@z;%k%=?o4Z+-8V2y7Q)WHZ{?>EM!!VdCHb%jlm{2N} zYMk+pC}0YReld|U%nMFLT9P-M!P{U6H0#SXXx1d(Mpgo=jxR-0e_UG1q)f$@dKq6z zi`Y^;l{~ssu&*}FbgU2+iu%d_kB!0KmyRW zv?09IX9BDqRPrOuP5H)$SYcXZUD`e8cB-~Z?uG*G9d*;fV#_?;?^eh6fF=heQ z0}L0f4;bx`zHJeSDH4@G_0iCqg+ce_I#)@#?VV5%a9>pAe}3l*qRb;Q4E~{lfFWS% zdW{)jRlq8Hdh|5_ELy-*V)Ph;a-Gzr3x{xp!5Mg<0>S4&IPMZp_}{s019SHq;-9*( zguK7S7n}XjM-zJNqSruNhmcJZC{J|00bI;8D^=O~GuBgk_!c;f7e;V>FXL=Aehs~ zh{+W4k`XXtWFX4TsW2?&?3gfwwrW#jM=*a8qh?bj*z=h3fjBB7tf(yy*o&C~>}{rl zW%)1{f3}ljK&IMr=#&tmMpzRJLOfrJ7_P=45gVseuJ|G2mKoW@q1^ad^Z`vV0>@Uk zy3x~kixtp-#t=!+vC9E2!o{^rH5>IcI%}vV<#L^ih{ETHB3Xbag7RM!si50Kaewa} zE2r2K!3iczn&o1F6N|JnODEAGhviWj;8I^ee?`ck%(xZQumJ2U>f6#+*G~N+2S?%| zm=Gl3hC3OpFV0TV(=3(JEHe6#iNFc5Ov!ojyO_oyB8qIxN<5bcNbpXU%}pSd_Hf9e z#ymXEEXXG%dz4wsYxB@@Wf(}LFW=-)0lMdHMdsZ5C`jWj*y0O*ep?{sCqFtV9v<6Q ze~#4~d&b71fhs=ajo{MEq{=RG-J8ZIM!rSCmvJ0MFcO1@x?t?v8P(9esP-Plug7NR zg!(a##>O0c*w6v6h`; z?IZNQJQD&kzM3(APDl;)&s@lF&roCee=ko+$lSTPEF^b1(Ok%vXAHyIk07Ktr3c2# zvY}BNuV$G=_?*of5Zf$aJsbJ!nkZvg%5*F}FlPl7F**VA&*Tdjr^ftgoKed-ljX~J zWrEWhRG|c;mH|i0#d4_jH?wJvt;jAdXd?@T__z@q3I}UkUB{%E=QSIV&3d|Ue|_xy zMF$xwO<>7&TWm3fed8v&9wy9iaTNYte;A5Yg3gS95TDQDs~ebNsq4~lUq<0#_r=y< zx>x~g77k+{C*v83hmNq;IveHGBFahM=WsDj4aHJ~zBZ|tT<0p%9MY*U${i8dFgp(k zLC$H_YBuYMl^q66SAYZ0cjcLre+&iCKXvZTCgL9fQFsW7Q`&hht5YKXKkY7>C$>7q zk`#8h{HZuVT=yGa-O#8{eN@u**z@T9-B@3atpFG-_Ki!5;kClIbtD7rm@qkU<#sU| ze0Z`J_Pc$)5oS}-<19c^X5(e@$FCImNu_8nwwC3xwH%(Ob1QY5wM1jWWfKmyz|rnzekI2z;!;_ePx<|ZWl(}g?S>05z#x!j7oZQ)F=^GW2>O1e5j_!##APTF znS|7sg`K*W7_N(b<&F(R;@bXWt4s{7vX1WP96(b4U!3&u<)Z$_f0-^DhPjtpW+?mS7)f%Y6w?*k|hC3$jmPoveq z=5Ufw?qXj!3||rje_a)b8g83?h-enUW_xVg@=UT6Zs}=KgyBpsg7SM-+s{mgA~qdR z`67B)FLWve*}VGI91DoZvB11TaIXC&sQbk(b-!#N=LhP3fkSXH;8}mB%*l*?N_U9Q zqsIh~3vxl1|7lg&)3T1A*|V}w>{;0l>P0_e|HUcMNaJeRe+NKnDr{XLqat!Pq}(UB zZpwGZ`{9d5gd?t|Rti@>U~rk-dZ?`FcKR40{A?K#2+rm7HNwUnOK$KW5#ifl+_*jN z-J!k_{u}^-4q*_04*udm$9bAf)yJpN?~Ji?hhMRTU#l!LCWf7>*|h&HB!U&%(M~Bi z!S>Zny}5+~e*r(>oz=pT9W}wnD8ZMjv3`zCnVy!5>=GVq>kqt3@8!;mY)A@|YLf^3 zE|-pE#s|vG`k?AR5`LhE?z2YMi<8s07clotJ$_RHvygrN1qnR+1_CYyWVh>9&dD}! z2>xkZ_x0bLgJ|vm6Pjq|E2K@emXCf%fL$9t_K_$Fe*%J25(GDRPTxD%%iM`oEU+@0 zrxL#myIe#*BjkJp$h&X=Zp8P8QO&y=wYv&M%xmLEi>|1jFW#b3)Enok^ z;GC^xMLsp_mtKe;lWEsv=R?}!O4m=mzWU_9L8}Nr3T19&b98cLVQmU!Ze(v_Y6>$j zATS_rlMNUU0ysF6fj}sK-CJ9e+qM;c-(R7=QBw=W9YivDXxd~FPdk}5JDJQlZilPo zS{zH_R-)~=zrN=H-~|*YaX0d~?TbZ9Sm5B`T)y++`0Lx7KYYvWf>C0rWsBQ~MXm@H zcA>2%l=8*x{o+;jVN)K;PL`m!CDSs{24Gw47`z1G7xo+x%fB%IFS#I6@9MzD}sun~pR-6$7J96{=Gqu5$ zBm&NH#bI3T$Nij|&XU~9;TfeSlVB6w=`=}0CRW(NGz`vv!Q|OjVKxyRc1}zVf6WOC zJJ_VAgi&I#vP39;Zl9o7lSljfdwMpZ&76I9Ht{oTL1bSpS4^AqreP!0sA$)hCJod5 zl$=h06X++&IP)wn9qE^;X$&#&#XzrV{d1BV8|nY2iPMBLe~O*W)W1&bRGdyau(m2K zAImxTX+JD~ZM%#prV_RrZ$uHM;@Pfbl=BWenMe%brkm$?AxY>#k}ysMk|?VDpu5y! zk}!_Zr5klcxl^gji|taEK1p4p4bogK1_Q6-Y!?Hce4?*8q245g0%y{lm;8Pr@xo&} z%*e_XD zJ=EL#qyOemZmTjpuMh9mRk7WEjQ_}C7596Mf4wdrn=s%ZwJV;3QTB(t9qxzWB<}s} zek>(_#&$rEEJ0B``*xX&3~>)G4UlN}xGi4<)MU^(MU0vNL&FAy1$5{2;Srv-S&iWE zy+eox|BZ)ZF!WG2PHo4eE5R~CclrCr>Bew(g3@q>o#`6TJ!sLI6}BhRf-`^^tHH3Q_T@q0HM}pYHygC~J74V_Hh2mq^Jj7I$9CR4N*@T+ zX4^cUTfHgO<^66#{#cJbrQ-)_D}Dse>pg}EdEC@py;{n$4t zk83*&BwWD`WiBqTi|kpppvSg&XL< z4eRBs_1tQWUbOL!_5iRl6mu&ccvzTVcy_B+_gj`)3RD3Xly=qvd8twZvb_9$%Y-`8~j2C#B}gv-ZZKsrQs zfdtK=6zK*Php=XKtatU{5jF4L5uK;EFxp99f)U^ z?dv9(Rgxr3g-WpLT6+@~ffp89+!A8Kd%91VyZ=Q5GbO^Kr!=2W5nP zhMNV{okT$HI}?;8Ufbm7qB3WkSXfaaFCYVUxNlN9ibIH}0Q;cM>;oT@&Y>Y50-};S z{k57k`Xmgay+fF#QbZI<hSWw*<-HxIdg_{WDMqi7OfgmJ_|N%b$t7D z9$=d1L77WN!agCKIWakIz_noD43jgA746nEe->yo|z%e7i4XQ zFf%V-XUCwYnpYh71&2r~eQAPm*Ny%TuNvL`qY31el$ludc{QD|!0+UU@gKn#cobbe zYO~+b&tLeD`|1FHOE~TkU+V||iIvTvz$EXb*oL3OFqATNej0*>zB1(oxXyOk-xYgD zhz4!ly=%fYJV(-Q?pXWJDwY??TjQ=oFVS2r#zHlCj1|D=q1cr^PY-A`_~8!K^f68D zVQC?sXVoXTM+~hxfJdeB)}hDT6R(ia(# zlEsJlP4Y1Hyn~F$`!4{pQP%O2C|$2mlqy2K@V4G6w&Mol%sW&W5^pirFp2#xb&1`J^-7j z)xv-5ipR%)$|3s+VvR$&Yo1B0-6rs)1Y7uYyjuFq72)Q2yxMKTXAu#r=fNIyS_TlF z;srb=boa|Yk{9rpdxXD-&rh~DqP>(Rmd$0oI6(Dz%kzol#|*lla%|3K+MJJNx?zP` zo4DOHlf{FW;51UL8)LV~m5nLAKB~9m_A%Z2B;aq8Iw2YX1(Q`FDon;PiOeDsw$qAA z_Yf!uKdYevn+aC}#R=@hf;ezep*Jn(t5-wrBe7r(WrAdhz%-&@@*d$h3I%DK;FbLs7lf0`As|tn?3YNR)Ga^HAuIr*!IN)o`ydcV{HB!o}L`MKME z2bST}F?AxR>2`qr`rLo{*WwWp?PKU7ywDxc-J=WM)&}sf^=Q|xgAWlfg4x43lRP3K ze^>^#*d5v4KMbk|cq@{j7Z9Q_qdXTUT|>;UMJ~;0VAr@C@&_|ci{#didmMmH+Y*6ZSgonxegK4 zc{X0j2iCsYuMg!e1YPHKNbqCrvcX`Se`K#HM9U!vVR|A0_7rUw;RpAMk*~Lvsp*TL zFVcveYe&fW6~?T$XW=NnOO?PO@_<|)bi?ZhUf>9Ns@bME)*JB09p2@ZQsi_nuW!>8>K z^1XYQ-?(xAzcAGS)HUK1+hg5czpO%ovxCUV&KtblX`63&XuerV$+PdnbdO)y&b@{J za!7hNxE0hA@@Wu=ULcw|+G;oF_euZ3f_aEgL_)n_FG8MHf+MCx<>qW1nEQL$eyO4v zQC@e&F0fZ{RWNScht zPVypwAPAxxeSGL{etUWG&2!CWoW&_i`Rwv)W_8SDI!n?dW=za3SF=~q&-0Zak%kzOuitx`vC{@cD~BybM?iA9?CS)|ig zCK8^cCtkwRZ1jugrR@*oI!={n2fk*SN%-L*w!<1y*lIuYNocktg=HF8E{jd-rQu(p z^(}xNV__d-qpchFYiL3Xe`J{c>OzyLSf~T7O=z0I%89;(FgAJ?nvL7oSlbSM9$uA} zXD#a2`NBqjnlCsCWpEoz%(Wh@aAMBGUcq!$$}rnNJ(TSe%-9jCg@q?{w_X||<;=vX zVV-DVC2Vb+$i$6eK`BvS31DDv9KPSQG|d(Y-o+BqVJ4It@&T0sfAm4525iCBHJT~| zo!Hh_sJ7TqH2wzaXiA!cm#d!ISf@60yHgZ;cOx_shP^s|l&dgBa>~N6@m`1Q9sXk6k&(sMKnoY+Fg!19}GG$d4Lc`J%HQcgJsBq7v z+OAyNsRqd5$6b}zwHIy{U6obPtOy<}uvH?qCcVoX3*a%Te`GiAvH26?&0v}*NNE}^ zs~m8F=Z5=3JF(C@`ggu;O7za3LTdtqqP6W_$#u|!#X_G)9?X=486^^aj6xGDo*Wpp z&KgJ2E~{%q7)0F~NhmXG+wpNVn_9JQfF?tR{IkHhn%;iz`fxAf$?DOU%>~In= z7$YIcKwq4%e*tgKlXM86!1f*>SkQ_}5lhCul%)vs)#}5bY*TKpM{Z*U2zW_;Bk+n; z#i`)`6IS49aN!nK4ikZp#6s9Fr{Slf%Fn5%Ngw(DF}N0Loat47=rf5P#5##12w!Szi)$f85~c9QH5 zx5ml-h~MpWVqkp0@ZQ=Q$%Al(!#4KF42qZ`ZUNJTm_Dq4eR> zaaSame`m>i*gJbyI3Fv($GU?bx!Jrb-p>JR!od=H-}g>*Q)mYuI9L1>xFb%1I~e)0 z2Z+_4n{jRB+a@c5{(oU~Yy^@CykY6FxQuzgxXjr`bkc!>URcyl>DRTIa`0e9QYk(k zhQIj!^5VA(>}E5VG6hQno?RtiF2Lw7Z!TWFe_^u~-27q2Vg)AW0}Z{I39uCg4a#Qr z^5Sn7-%>PnL?n0)V7$_(cf2DsDCocv&D2atLaQwystrMa!BINgot!lKmc2|Qh=z%o zQe(Ca?52Vd2MK)^JhP+0R3z6n5v|Y%wI>EPz>dmx&8zS}ImSMk-%tCS*L&QBjhX{I(q0S3%8!2es2|AyGF;eMWIuF7WD|p{&IuC=A z$5r{{u~mKm0w=wX{S0XMRcIbKQksJRK7!)?_ae48UNF*u)kW?t2H5~6!eA^>F`y-& zz$LF}^mpaWE~|1pgb~Bc+615z zmdBQx2a68f2NmBAkcd%$WCQ@YMX>PWwolGxN8@thQ@m`&y=R2Ys_usn^jQP zHJo%4^_3*zZ-wIzQ<6ghQmV4ae;TSn!6bA!BD|kj#sODVc9T-?Ljt0c>aWgrgZ}9BY}-8)e+NqdZPA;G zihL;FpS8t9z@4kAya`t82#P)(p~;frIX5E~`xmmIBAb+?1!NMyj6X^Inm1KONu*QC zu6`~t4J(=Pc}v&wUHjTM%B#_x{G%(yD!2V|4ZL%MMOxS(zy|*Voq=nr#xRH4u)|Y3 zfQPkz)ct8G`1hCY-*FNeJwj=D znID){d9X?>s|#1|rrlid4+}tpuy4rn7!|$UQ~8<#0Tpd6n+6tOe=XX6nfs^LzEOk8 z@?F{Xx?3%D4D5P>;nAQCNNvmxj{7pGYtraYk6<>ySEf z11F!Z`l`BH549!ge-HY-&{BhY#DbB^y(Ryc-Rw4QliAccCgrh8l3|J9_d%DKoK_wP zPO-D^px$mR5SjA;3R{X;Bg+`odURTal&osHK$6iJbO3KVgFwP0t~ZREkY7J z-gmB({=T13GBQ;jtbz(N;ko^&J47dq6P}JGXLKM{peq=n9u!ZyAfXyp271J`%IjrS zymcQ0csP~0@tb0sXO(O3vS#h^+t&9u;93`y`z?Jhf1Hvwxqn@Y8R>NA`rNUQ4#JB3 zKlPS7hx*EzPEN{K`rxj=Pyx>`t3R9F%>$On5@ z>Pj(6Zrzo-(h{D4J%h8oF`mv<6AG`1gmOrfxDx+KhH7H;bgo*Sn5aD?Yem2!=(=Gz zuK2XiDDEz5H&XWPWbk$9-aF3{w(ebZ@DxCpf4~RhG#CRX-5cnAPl!gaT6_dMCY^yC zI)jPiembIITtjb@IOQ&!VOp)62wxSe_VcQF``uYDGIl7abq5$6zg_K@q4?HFP*PAR zaW(+Czv<{cd-y!2HwI;C|4zeu4HgHh~2SM zf55R*k(l<5o!nY%@SA#7Z`FAK4` zDc-rvWC-sAL#?n6coZLfske}fyI2n{rTf-OMHujPPE}FFXhUC5(B&$p4^KQPp0weq z9C(-j{=&RYpNIZC24x}-vJlc_U0l0%e>dymrr2Z^MoRFKKI&3FQiu)GKx|A^))^KH z{W;kt64k;xS{Z(NLaAuH@^Ky)lUxEOZ0R}>;NoT28bpGzBlBYqkP_h>27I0dPv;i> z>xrlHAvF0%@PLyh`hg8hzqDb(z-VKq4UCvJF#q?*y;Dzn@^Mdl@?H*}_~9w}D0^UL z0Z1#19lkC~vWX+BVfyYPD`$*8RfN-CY`90ax<%^00|-f-!;^n9C;~M&lYu}ef9+iB zliRit|9*dk@{KpO5Il%iJNeLL>Pa$5+B#RKGq$HgOT0TKI!Pg^bN%0UfdwU!0wvyA z_ejT|M1f0ivDn9Nfd#+5IQ#M?w-ZK*rIt-DE+<=O)Q#^{RXUP0A)8iuxL9 z%Dh^`mA_pe-Qr_-e0jB5WX&T;wW^A`SS>?awwxnrcyQ%uW<~A(e#E!We^xi=ta*Bw zFWs%WB5n|qsTIV?$&?8YkVWP%u5%EHU`Y+{cjP*$vEkNT=QHRH2I89dR$e`MQ%$7a zisRo%Bg8}#tEnfkpbQ3HOq9?_MPp($M94{t2qYVOpCSyNn{o!PMZ$TYv<&bt{oXb7j1stg4>O~41{UYHcP=5#zqN_!f9A!n0=M*4HMn$p`Hyf zjNPN>EN(4Y>4Oe?f6A>P)~1uGpr9^6o4iBy&JVpH2amJ5S(WSSqPoF5@6lU(7yH4x zU2u}fsO+i?1U%W-8SqcLF>7M9g_*K4cpDq{fsBE>X^}ZDV^Nb4YPXK$B4R#ZtXkg1 zzv+WB(fGG86FTW z1<(;?8wAbA+Oi&N%lb~XtVda#ZrgHwplc3VA;rXv}R%lkg_mv38Ma z(0#CW4tmsh{O^|MVBvLsRb~!U!LSTVitzgbfGM~;%NFiGO}@eZt8!i}vpTP0d_WB2 zlt?SE|6k6He@MWOaKKH=6*>&~qmp$QkXoM4u_ga+Hmg1G1KO;@#^7o$0dcL$&`-U> zd-J@Sl|`VyChxO+XCA4o78@LuYg%1)Xms*Z=J>h&xrVXetzwCHJc`sfaQALOdft zlmEWSc27Dq#XS)6H@(cI-%(hhv{V8de$ z9d{q#&JAlPK|Ic0%F_p6?^rLv`qxp9Mu}((c9Rn#SE z!u7VFe;1f-r2-%a#8huN0qFWnFrEU7ol_gFoODmOqIs3*3<9!AK{+}An+98iizc7+ z258g1C&0$bGP?dKL_8OekJhVjfLr(qp$EAnrKzg_b2FW=HnI=E2T$1X!k}#aC zZU*Kvb9dEq556(?S@ddwd2WSs#tnq$wCn7$e}MfoUVU`pV;~5~v?HUHoKVdkVzhqV zbO5a|fe1&Dn@tri5Xr*b>f?>Ok0E2Vh(j?5Uy4P1jve$lFJk=w&{SK!To3eNx(cWV zaV;b}TT8f&Lu9MA2*E{2H}GOPFJ@j%Q4CHCf4MUfKZKnI^_2{E>F(>0P?(z%TsClaG;eBc5@ZQj~wz; z)@H{vodJ-9ESAc~|EJw-Q~0bkM5bApV+eGM^&#XOPmP$MglXAwI5O@exV)QLe?w0y zE_<%{zR>!R+Q_YBLp+D^th1^DwC0CcUze-RRTNNLK;*0s!|oX@`F%8CZ!lZLa=9u8 zwl!M2C_|zH8?dam3l?P@U?1QlXP#VnyE)C=iZOG`hOq-1#tsiTNe-cIyBXnr?m0RU z86D#gd_#y{#@(aK9j9%&hl%-JfA%ouvlJTS-db!A-b=S6-DU6-L;u|YDCanF6J}xj z9MFmrhNt*X+yMNJ-Lysb=v3Ke zN@zYtsXmRlM^q}_S1Pfe+P2-*D!N~raz?at8=)GasOs<6X1^87s|Eyy3YK|Z7PsdB zb+e|l1__4nmas%}F$Qq)IN<8C?6!h-Ag{f=vwB}=MKttJwII|7DMgs&hoYIQU~s|A zRZ1O(OX9&7fVy(D#F`ZBe^Ug;=0hM89EBD9WEliIQXd1*hJo@4n*v_YhYDnPQz|rE zBIAmUIG+fUl2q&6K%?OsL?QuHJzbg1jY#>^PzFr5_5Xxr92A4>d_EZo<0)9>JyywfB5KHBl*d-MtfzT zE~(m44N6X!r$LJ&cP$5nz{UuH=@CM3WqtZ-&`rc;pe);-pooTkkxHUn!kGf83jXt( z)y+C9L(t#u@3?)G*5*oxx4ZgVyz!QbG+)f|rW<7HSbTvuqx&#A37EncYJ}3T)}|4b zkHCGu6BNZcoJi%ee{cvwI{oY*KRd|J4)RnElAqK;nrG!8Mbts|$7Wd9WBi{(v@fD- zq0Df29e8sjdLQ2|cEy&{7TF0EdC2y~C)xh%fnrxj_XJCnfvc-1SKxPdg&*UWa~?;p zjt(u0s1=ryKdD;X%{BC}6Xd6ya(6*Qv!L*Icc@4x?yDw+e_J3~u6(fz{80#iwv|oL z;45n2x2m&HSLIu;iz;+eTw*sL8lVK%l`o`1Bqc-Psk>-uWuT{Rxy%9|X$m|mq#RhL z5rCxh>FOfIr|;!;x*4d4vQM}eyw5FfS6(?i7^u7gonh(;!(o37P-y?Ub^&FznK?DP zZr1+dHRMdXe??;B>$8@G@6j*JZQjKCYdKiOS61<2^>XiEPCR4yT&9Wwq?@3DP zs>zfM3#G548X~aX@A#&Xy5pwNqkFE&)LLJYIzmC7e=y~Ez6x>`$Ay&HyMxQ#USW^z zSXo7jZFA7g80L#4wR-%VcnGViC-;u~M=g!py5rq)#C#V36MLfCjhC zXBzCT#NS>I< zg&aS?`kmX$FPb38vo!#Nz9tijE@BQk#5q}`c2f~uP% zsL>;Ek{G^sPE7SqPU+5M{~C8Vs*4%@S*`wy8PXECNsN zOz(C4U|`B!odiFDJpEZq>3lXL0CGdIe=X>yk2VI6QG;vV9iWEB-@+m7CEhE-@2Z?T zODgeS^JM$GI{C5+=OK-gL1--fd2VQO3t9N=bs#F11ulEJ)}fF009}Y27K0+5sx-+} ziK^L!{&EyfQ*Rn{^`y32bYmVb?Z{#SdSiM9o&B(_%T_%)BE5nsru&;i6Ic zi*PPbORrw-1*vQ{%NIGAMqcM-b3~zxe<%qa7k;ayGj)#`h{gu?+i14oSJYajcr}Ev zJKvW%DK2S>z(>_e?y=vE9a)@x8*BB+*dMdVnG&kq7PbXkACec1-lUG0} z0ysF6fk18niIea^EPv|ue~Ds9avCL+BZ0O1^WTnAkTzvPkc9tYM{?~*n2Z!M3Re^Y zQLQUFrX1CW5KE3U;Zcj~4Hh`Wks}I{)eOtfQVbd15Wp&AmKeg~pF@i=ilo@C_D4W` zjhNJtRRecK=awi+Fv6Ngi9*!U*&p%{0}X$a5pXfPHlIidT7M#-C5Z$Z)VJDC-)UIi z#>lTh-+5QxwR+x#cSR^@TPZobDK@kzh@SSYhL%Z##!ynWchf617{5g}p)nkdml_f( z1=3vm@qPX=nHbdq zdvK*8Zb?I^Yl2_J8alLWYz3pjAWs6>08!6RK?Wps2ZC3+elaj)u9_n8peB)x5N)d> zF+h{`L+AKf#Y;&Ow;vWcgX0I#9wTPgpe5+n4JQQpEfjCrI1c6%a?WL$M|KdA z3=#B{G88@R$?2w*jtY4?T;;m`Hpye`Pa_fca92Fp>|Oe?Hc#f(jP0c5jP0Ugh1@TE ztj~&EYp{l8>?>`bfSZJ^EBwn0(hjYn8vtf=S>;SzWv)lVZ~$fgJyEPmMxGRjHB=OD zY!6biP%x?yi+)q`uF9<1Md-IUbze@tA0H_Rd7L!FT@XS6DHBCek`(r2@~V>yM>ui5 z6pl;6r<+7)OaYsk&He!yAOG9ukql?v1Ltr*EX`${+}{W7=(DRD66xG}goCE-T3|DR zu_=1X!%@eG>-DKkXgmAmOyVpc6w0Z&R5y2}{@il>Ib3VfLf7xDQI)4L4#riPLb_H4 zthTJ5M-Uu^*Ur05yDr+N_ZQ^W;*aougCy~__Of&j7&r{w`Yq>w^3hNu217O)({X8Z zv^S7ztk+nhPp6a2X%|~2xVqo2>sdXJR3;C*rHcz z5&K1eW=}%pp1N$K{1+l3NNMmHMA@u&n|Roy7QPgD-j`c40~R{+8cK${@S_gHout1! z>+er7OY%X38-y2?@C+f50%=Uar@;D{N-0{Qt1)1kyszM0Z-WfTF(Ok~`K4&!l=(ox<-A9&<(T*Zm3~PP z9jjuEf6Bqv#a5$1fc6Dp>wIuL*$>T`bV-TG9d7ySwaLm#dvE9lR2sxMGyX#WyB9&k znv+!iG9+m=Z`RiNrD^QsO=6u_);m#m&eLC07Xw?BImkcLVfi1uwbGQ|=kp`+NX915 zvWJMkcKj|76P51LUERvSgPYKaM@scfQzkxEP*U2+GHSb6e;ORv3~A!^yCPv8ySu{pQ7?2p@(X9-FLGa z{5rqx=em=DMVcX{XSP`{Zp3@J{8I%l5wWMcMWP3*V&?=+L;k`(*5ZFY1O-cN7uGd* zV^Ki>ic?ny@U*Ojzf?6^yWP~HmhAI6laxya33F1BSGp`alpj6oiv=2;3&b@%l87Jj zli&r13OCp)3g1M`@hlnI(5H)pY!McQim)t`%R~QaNfiiuTB4~bryBINC0J4WFzeCU z-zy4Hz}4rb!h`%+syLA*9A%EUTO+(s6v(D~d+vY&x~AvzaUXXoLZPz}LB+GEtc_}_ zNr``}iSVz`XNSLESs*gW@XcNZwMR8C`yGbB8d+j-1x1p= zs^79jpRGV{5Z0;@^>tM}iaS20)YoWET#A9(R&qX#6Sb8;&3k8B?N5#q*kVv6$Kp`) zeBCaHPTRB_nvxNHj9bmlWVEs4V|6ACbP?v&od_Hn+xL#(Tf=P=EX-b1n^k+9%^*b# zNVB6+Do5Zi{OThT3x=INQIag??8sBl2mR9rk6oc?x9Rwk>}j>0JG!O9akeZ*l6cXA&)@5# z?FImf%6N(MhA_xYGV;$ot8`KZgKx+9jDE;h#;JZc=AdN^8_hPiWi+-(Yk3N1Qo;j5 zp{)5_GMUHpz+ofn9|jk0nHC)_FSKtT1N50Zn6``A%fYl;;vdJqIB2Ou$m&vyjnuBr zfN0vM;LIEva|};2NU{`p(_bm70ee7|N)5moMJ_|@JcRffr+&FmE5U0@fb+^RpFhw- zDk3hhtX;GrM@PZqRQH-o$VrM|qWz1kHm2|U28EJU0z&S?iT^q>=UEiYWg_1ii-&_) zDy7+18Fvj+4C?V=ukP|BJNwtum|l#GvE&*pIPaenv}#;D<#ajE;!GWgv2sglA zX8p3}FVh7kfTUoafO_Z+;O&z>Yc*%4NhmAs*Y|f5g}d~-QlJ?}Vp>p$^T(hhx3eyK z1bT-?I5K*jstb%n{9$Mm{hj%81v{iY@p&G-sIQSMnyU8q~TkScIJ!X)J$vfRt z=^;@Ilvy3!%s;++m&GMxl%n7Pz4^Za=tc**NzpRIRjVd*Zf?NB`5_VW+PlHSODbKw~a1Tc%NAqA>Q8wMD0fUTC?TW1$Pi950!}hVmapHHpyFCabqX zXqraKpoejoC!WCP{pf zXjuv{Jm{1^iZxDiB+>vzrImu3lmECG?|GO{1arlU;@?br4Y&+So=udsyag%9V}jgW zUKzl3V9|LdrS+UGrJPZE=gy7aNORf~_sD99VkVu=lJE7929jjVikgp<9}5Cy^7F)S zy~1)OUst{!zcr970P~#EXEI*rfeH6`X3?LC1R5yzXa``-y8H{^!mp4VU&0kGjvhiF zQX{ly(m|eiH(NM!kgoHi>;2y_ zCPvfcB`BEaaVM?s_V;`!rv%NGKV?5=4MSc>zI z$u$(^>Zi5tT&vq@loyhSUq)OP2`XBeuOwNViRAWEa&1#nIma+1sBQ^wY19HDJZ*SG zLRY)8pqRr44KhbmkyDo`UYNx_8|u}c?n9Fsz)kbg6SZ#;KLpCgTJIkcVtEJQdkhD` zAe=mucW&LH%j_mYS(rrz5lr*6NCxAFNh>PMpdzj@G$_eCM}`9e2+H*y7kQ0Hnm^93 z6RH})VmQm{rd<@>`BpY*yY&?i5c{G&HLxP->F>Z7<^zOv3E4w{XRv+|H%|b9e1z)` zkZo^}F!9C0BC?rAWI}E@LAUV}^r(l`;3{&3UyF$eQ3K;KA_gHnjQy-wOD$i|vp22* z>A~GMuYe@}lYikP9JUH>(H@+Zrx&(*Xuc-sF5-y?<_J&6F<`n$nDX|5`P}__t8H$P z%8_+E`C+cf)T>T;_N1`OkF-G~W~J~2Ak;@x{=sZ~5sAWaQd?RLFz1Yn6_gxhGX+e) zQk`bI;0IXdWw(D^%fP$SwaT{XE*LEf1d3R2MbL3_e9v8VqaUs$^4sJa78ef2gx#7c z4jYq-vJFAnS>8ol)@$RQ`1;MPd4FGGk@5e&uJft5%athJ7=_N1q@inrR4;=96xJ1! z9XUCy2chbiYzM}bC(qN?Bz0HhYMQf2FaI9Lk;b{p5e9ZLOW5=8?eBAmB5ty(;Emk7 zdEWKq5a!=$q!mv8Z7q1B+oGJ*fG$C*TSCZp2SU6d z*+SjKdQ3)GVW?sdz&{2M>0#-B={zdE{fk2!7cnXGd?f{r95o9jP`0jHSvan-V?K(i zeqsZth=5}}Pr?-z!~lniutxU%!(8jU{DXhbS6?hpW#H;lAV0<9qda`&D!}4adMNG7 z+m3E(^IY5ab;&v6zTPMM{>A2(Ns0%i`s0rTg(a_U2B6n9o%ruE5BzRmKV z5!1G5*b<%6WfXJ{)k!@%oKgR|uAZG`Aq1Z&kmWY>wS)VJO5*=zM2)x?HNw}F8aV~4n$uh z%csf}RDWNjWZp!Q&YQIY+UovqELscK;ABtCVm0>~`dFm^`h)CAmrm z&n=@Xmt%{Ymj1rRaw_lbd@^0`Au;x)`bj^(N2IbaZjF4!TE5ePH0*4N%nstS0yL?Y zX!EqXMBtBr`jN@g~58aZ|?}=8Gb&d0{KgMQ6 z4K;~)B|LuvQu%s$ZxxVT(ew#6Z#fW9cf(b<%+50dKN?zx2?PNqGWZ9D zoj_H8UGI3())NLSR`O*P+5O=myIN`2mD?nR=X~wx#M2bBa6qADF+^3cLq~o`!RdPP z=}8`jtM*#XZ*TF*vV(rGYx@0tG}}qgzgn9u9w65rhec%nC(Mgj9Fm7~fbbMd!73?l ziSV_?a$C+LOHs^m`XmpSn25`ACJ+6Ys*NOS%N{+btC%n-Xj&V-Sr3sl&B&W-CqWpC zFHy}UT}H9fCt1#st-4B}E6Hx5dS@6F8i_Ei$~(WojbboKJEf6bRSUU$wgvxa?pRlC z0y>+Y(5WJe*d~yXe$`GP?0W{POVJR}hp&4a8K<#-HJ(hJ>VUN;VjsuYIhAX-Jd5Es z?lVZ$l8eHwC3{*%7*DbjWUCaF;Qrx)MBtBgFf!-14ID!rY2{ZI7Z8Z`nrh&>=^eXQ z1f}HNDf~g)#59cPo#wFeDU4|W^<`m#1&o{c%m+oBez@wLz+k0l|B0t%oV@3eFd2Zf zWA}k&8L7Po$>Bvu(r+j-T$9-F{ux1~d9$B!-%X+8Ep2s%R^}co8$aBti-jE2B++5; z`h97R@WX77Cy?bVRw8=3Z*qTAeN!hm+FnTB0%rWDGI9awNFi=JOyJrn zaL_&lN_;;n)-$7ThHZ!^_QJ*l&G?shxj+=W4~)~eJl^fN`}}m-#0Dn|u@(9ss&(jl7CSVBvFs z=vN%8?f-WaX%1OH5OmSqpjZ6_64FWMft9VE0d)ysyc?yxL{Q^o+hrxVmldQiZ3@9!l=ZG1vRL`zG%<7#y>HuG>_pgvvz^_B!pP{K&$uWyu4(8cF^w-2iA5o z?NYM1MwM*nuBwF|ua)Xk+pBFS+&CR_LhC=Dn_lY?DatNe$$-7YY_L_10%S|kDKWe1 z1+6u>I=#7bE<|Wyw*&jU5R#yJN1m03o{KZCUickdKr#xLHuEUKjZ2>lOrSF(GwCLA z=w=DOqgqwMU#?6UItCri$Gl|w+ zi}J!}I1U!0OF-%;>yif*NP8`$%n{1>O3{7YmH)^I ztDQlq05>_{?Ncy9VavkewD*|Kps=-}!qGU7jfb0VWsnxFXi46rErs>+CJHwrE1D8* zqmce8x_jCHMKfJaAMOM>LM_AA21ckS3mzwP+eoP_2o&TSPyZ%#r{JOM$_1hL+0sd} z_G{Mq$4Xq-#?3>d1ij*Hf8XRg7vp4~)cg!3VMPL8-a21DzOPBeyg|iT()hewv3x## z17W5sOL4QAc@(cHEq)5^>43uMaVQ+oTfXX3VF}!2k4ExJfBk)=efd)9FA>j~t1MHW z2l%3K3?S_H9z^Dm@^?S0g@cyL zF&Ry4hw+?pUAH@OaWAH=vREvMD*R0zEFC*e(gct1uOG0re%fp0KRb(m8qC0Mx3gkv zRMu@}eDX27UGnh2Zt%k{?aGxmY9G36VLem@XaMTaL`L0C_mw_exueW)OMXAouFBw6 zp?LwhzzS(kqEe55xB(0g$(~=8FLs(51ZZQ-{8J_kMzL5fYfkTJx_U>!}{jurXpVol|$Gh8afcCHat* zAw=pM*1a;q>I9S#Mrju7m^qfFUjKa`2tXQ$ zagc1NI=S5K<=i;vi)UG6ozviZP2{_A+c9nunu^b-xI1;~h0~ZSsnFTiZ+L2BOB%Fz zB#`gFrcbCgU2Y0k_=Gi+@nqUJs2I*3q0(1wsj+dOx{o(@*~rN|42{!La|bXI=LAvW z)a$Y$n<3laxnpk&botz%P8(n_vp`5NdZI$On7w60sws*j$8s$=Hx5dry%|TFUL6rB z*m#)J%&PtrM0>4idyP6FcBkXm-Fl<<;L!nM?hrm9E{EVYxTM^d$v@UL*wOoO^sUAq zd>jP`d*u(9y<-Hj{-Wwi z@na*R*wEY>ShTl2i+y9-^#hFA0ohA|gVCkmaw3dY#>!f&+8XWpANY2!j~Bofwco$z zjUe7!t!#%GMYVY2s@8M`k4}xnj(Uv{XqJx2aMO#20Ibt2r#w+kz#Fv+V}Jj%X)UyT z*wY7JX!~*!>afAKV<5?SiiMB6wy!A$IL%(RZLY)KOtmO6?bre0faCp5pIf}W*GnEkY-8U5Rkj7Dh|xn0#A#+fyPNKGu_+Fp;yl- zld&P+9td`;tvf$Mgvo>o9_+@jNd%CuOs@39g>Rja6dFg(l9~6?tIp^? z7?whwVcV15ojcN6q)ioW<`-|;?FPvS}w^l$@*kFAK7jz&}Xop zMh*_SZm?lGIGo_B*0Ik*$7+}x(f1uWe~S~^X#EzYNQp%X$rmcIZ=E~pM)I(HOa4lK z2b_koD)~2e7-|Ysk#cG#sFey4BswWl-WL!QikV}bZ;W&NsKsFX2nSq3zz z1Z3Y(U}s9+Hx!yZqy5w@{m}^jJ-HL`oXq`b;7K=qe5U5l+dG*@bkmT2YriZK-{bJK zrgj{y!it5eN_^31C641F-~U(vhDeSC&+-2Al2mmANMB<~mFqA|(^@y1o_}rk8p%AT z1<~xpO?KcyTsq0VX#6~p_7Zq+-k`jCa`^~Cb?s!zZ+7Dc%mj-LcUrT2Lg#usmJ5c| z^Gh+Xc~toiq^B#$9mqUpeB)bqlQmQv()*z99fPZ*cx{BA9W4+#M>Y*GwcFR3M1O6_ z=dU~fu6pU6uh&)$B7LE=ziR*V3UW|Uz)MiA{oq3&q01(}Y}#)0Olt5v^$I%CzFSiE zyK;jdjCydL;>oa@pYd+&Zdm_x5-#x3ESotSyw4t87xU43`nMId6J0r(-pNxolGCRi zER?$sVu|nga+M}MB8fL!h@L59KU%hRS{SnrI5_O7{R@iggmKWSnOIu=tKU8EIXh_6 zCw3H8GezyeNdPync->G%f1(_zg~Age3OAgh9!Arr2Oy{})nE&M}1p z{tJQ{JR=_}mFlIJ6I3(PjaC2UKw&xk>_)?RJG*cH-Vp@J98yb=BrzGCn@Hp!MEBx5 z|7}Es$E)>m?winj7fqj&x64cNo%;zrcJ>|hn8@|@;mg5)UD+3E`zK1}12bBy7t6Hy zMvEWele6WDGvDr=2~*R=0ebWJyx+3`8sdyofDUv0&4rVr;6k;xqwCMk{u`%jt*4jC zi|F?c>T@d(pJ1V`x3~8o!GO9=zs@fI3Vcr0Ap(J|`fGetuh_rG$J@3(^Z)+-J2`*8 zGx2bFe^?i?f_J22W;C=YO|AFPGg6bo3@MuDzVR3(O487b#I42$fT!25rK~sL{@?yd zo#PH?z9yy^vcg03^7i|g`o-J5i9dQwSlunG)6GSjmUow5yI#InY^T>wE}|OmNO8B* z1=qq9165=wRUMk9Sm}hWR@=J(CyN&CKl@_L%pdc`fxU(!NPTkd*7N-*{7aap0nK9f zXfr4I0eWJmlNxqUvrk=?UrT;~e`8f{^oGD(SJ|)zhx#kVc42PEx~Or{z}9)^=!yVD zxun+1QG5Dt>|L#Lc*^a6m)x$6qd)O-6CRZI;~(>;XVX`ooU|rCo{mr7Kd+7t>!bJB ztyTERdTXiQ?i;UTr-gR5^?!eI33clU)H)GmL%meHwTqK~@0SI9dKh#8z~>pOH-u%; zVcqW^g%LtbSSxn78>l_g5>?I9U5T0T3EAO2=w z9VTFqqexUNO=lWhwSMJ5Y64wdd_G7btPIs!jz@_5m9>eKZk&Tw!Vp?gdj-$pU-c1- zkg(X{Aa*=N(3PiuHuCJgx3NQeNYns7|Jw~LC``5s&VZKYd1hi$lm669y`td1DNF2E zas*tI12t=32{Vnq8PiNwLV5q3?-^MotjtBD;54}hG({s~X`xVn_PR-HN6Wu+9JPWa zC(>Zt#lt(4pUK7CIzHR&i_A}1R;iELPdMVpG5W|ce@C@7J&NY6Kik(N zt+GnZ|NGw%7!li2)&8+Wu{EhCn4rW; z_l&CqrMM@M_=I=)W(2)TSVytM+({$`3-HCvC-C*Mage#Spq7G^UL528Xe9R*oo9N< zzV{qR+S#KlTPImt2=6Lu(MGwwqt!>ZD@BvMI?6JrCTCsN_t0k_e3SB0pfI*JC+Iv( zjURi3WD!9HP%m+Hkx+wt4#im-#u|M~Qz|P8>CsqDrZ2+gdMFaZ)jf*q2VKSeUnBYr zJK2j0OG~248fZt?K7aKRy(g4#r#dr0P`5huhfl7`^7&d?rOv(ERq>pk27+ld-A=)0 zN}o@#J}h_i@x7#LL$5zyYmxA+Hz%^YS|+S(_s-V=MhvZyWDN=!(d<_nrj3eMdJHA4 zFkXS23ncb-SzqnFx<*Vl15ANO5AiN9Gf`3-gMZ* zz~qBPI;~L`SdCFIL@{TvPd5{=E!W=Psov~4v} z(qhtwfQ_nbPlm+9C5F3z#DkrnkUFhRlz5178$1_sa29xN|XJ^~Wx>qgQxh(QM2ky}l1 zV3;aU)@H_uwo{jDiXNv#W*8O7vjUg3Qz(G6QJFl%KQN1^@j+FQ|H{+?CGgPj=8~gW z*YNHPWpR}r1P4e=lkPFbMg?Z9F4|R{544fN{2R7jTc=Br()n8DIh+GK-982@%6Y;f z)mwg&Ir+lhG`7@F@e;U9A~=8&d5DQSNTUpl*x+54!0FcdtIG(AAHOt!XA%SE5QS?7 zI6&>C{F#kviDWS!htNqm(kgdklw(xa+)16#YK#7CMBM+-Eut&{ zlfy_}KT7lFP8i4IF9aybGQ7}L^J>MVcYmg|wJju0-pi&xkd+x>)PI`Y zl7WHGn*YLn;Z!s4hOJqO+8CCWB2z*qU zqoJA^M`TsbEx4a{4~sBQ=N4ym8bFcEKAVVE*LDx$8m6F=s+z3QpUL_)Q+vB=p#b@C zIi7VBrt{!TE+NCeZcVmuN%#<$cpJOPvz5tzR%~?qIJ;7rcdbJU)t|WE@5ay`pJ)3= z?#KHBR-Ez4Oaq{89Im-<()16hrt%|o2Wm%v;t)uKOy@QYAKr@BZB<04ldwwI$jQoO zf>5LChPxP~Ckwx=Dz%P}^g=AAtFQQys>$Yz(WE2bW@15DDP1t@-&>r&+Btmj6%r{Srq*=2q2SklZx)=TUL_rK*&xWCJj~-%5+YR-O$#WfMp^N}&5{ zX6SU2AVh(F_JgsNTYVulF;Ml19jQO^hnD$Ml$%HnL(<)tY!=c%qq!7)Pq5k#a!e(`5c^GCj= zfOSc=Y&S6GOTw@$L+;JjYGfYldH%pf<3)ZHp%~eAEjiWJAgd9U7VE2oW7g8!lXH1o zuYTSUT+xoUOg;4IlW{5&^BT{836UiQd+e{IK1sSU8syly)DAN0g5|)p^IE%cMv3mu5UP?Wmgw3hsmrBX>LxKQ4cxP{&SgPJ+BsYoSBxxv3P(aHXsWY2+xef&$JwoI(Ao+fZ+}Hdac!cTBGiP{PrJAfuUUcGuRl zIyc>r1)nePPc5r5WV>^j+%SmEkufkjzMbwO66_ZXk0*WxiP$wgy!wILyEA*Mc>`Fj zIZ?OCxpRV$&$#BDMsZ1mMjK8`vd1}xT|b(EG-Moo_oY@#yZ!z-PDMZ(fh>9TTjYzX z-aCR4-%hR$rQcUfdgwRIC<^(fC@GRn@pU3Vv*auS71lp2?# zcE^tvDs&_Fkj|Ri0{j*zgGZ6l_*sBMC!*zFugD1fNvL?B3C(! zt7z};w2#vf@acOrK)*6TI~J(#JpF+#Fk4&}>*O-R)KO)N3A~nPVzH?6T>~b5F+Lf# zl^}>88>@|4V~3Tw=G(1Re9<)4Y4da>HcAgoc1uh&rYrV4U4?X;U;U+QNJlnyiV&}M z~1#(6F;)36u%5kCokml2L*VM1C-$>T@ zn+}NG)AuQRVsOq-2^OxW7mmr}WhsSzC>(oN&MdCWG5Y0RP&{cu!AvjnJ0Pb{rA4Xr z>hsOYY+tVbLKJ%S7X>zl1+cPSnjyCX(4ePu#Dl*x@cz4%n6Q*J-kdj?46DI+KY@ z^F8=6^J6AKJ)phg{h8X1u2^GfUY#4zoTsa;bS1zj<)5vRiq5b9Zhw2)%wN+ml&HV( z6w$e$5)?_AzhsAkR42&)nSig&3B3C7Qq!+%mv*lu!k%EZzcF!mG~Oa8@>^rRnc zCF}1hTlR7w_FkL7v52jOz@}E(t=X%1lyf4<)Ay&k+7>SXRasuEUdPA#W(zKbeg-lNMoiS zoKPE@#a_PA>NEIE(6{+_f;HhoITLH-;J2v}ZxYLSYID0*MoNO6y<((*h{4mp8=Ewy zP(7;K1v}USC#X3dV`hDXS)4p6!tdWh;X-Ag;7)3w108z-(G??t%|jr;uf!y0W(w6M zE^E&-;23{Q0JB+`J_XSOpbqXOhkG$SmUxnC9#Iabx`5}Qkvrpu#Iic9**kJOmD6w( z4WW0QAmnn9>4~R_NbT#)yP!c7>!n{I;vFQag(XwN%(^iPTd0M+Bb^7aDVd$voKMTa zmALnlpgOu@^L#j28cfC)B;v9?`2r!*V$5juD@9#j70(H9e~58`A|kn>0~A4VKTS1H zG5N(uvaY~Myo+B4rfk#1e7hIN;(XF1*Uk5{Dnfen6lhao% z-*}kr3-@z~D!tz;fq(Ij@Z$p0IK*U_GagcoqM7R~S9@lX0+*?2dQSph%b0{A{c=ot z7bn4nyp)ksUK$^PET6Md8mZr_h1-U%_tz26WLMa&7A@(qQ3rxjR{}}5Hsu5ABQMtx z2UE#e_5Yns#C$2Gi-Y}m+vysNQVV<~Iybow$T}z(id}h`|3zanNihliGnh>!zVpHS z7l&l&7zv|$D`C{SHEnA5PPPfNY7G;mb#@(1Vrk^IEiU*3@YT`^k_BzD?DnR;dvBG8J9RFS?=$nreRac zEJc~+PuBWnU_!F8e5ZENw8_zoX30eANDSL^tDW{hR)TX8Mg%V$xCBEylS3K7-clSHEpqWd|j<6=2>AlZx?g})`LSTh7x;U$?=frK=` z?m3KvKWqTub#KogH|SO|lFiB(8w5QJ4er z$k8}&`)uYCVo8`!_8tY4fA3u>hBQhj{>p2dEC7!bEZ@#Tb9dJcJ+po$f%5YcIEDg! z`aQj!#u-u6f}CjbTr>BqT>-`O&TQ`HY_)5Ii|zVi0sD#I-2m|>umU+o>@mbifAg^p z%!4BRAPOzV+AkR7iv)jZBuHQoj`!Hk+Q;Ys``*J0<9JDN>ttckeiVeUeVIL zK0{3bQbtDbsEw@td7q(Hq@`*8^Iy_X49($t`yUD@>a z$vvz{B*Zvu)haDXkHMVoMPJUy(e5+`sN8^nADD376-h1oT8hL=JeAiq|7`|UHnY^< zEYWnCze|48xDd49ohWeM-X;~7ZjGc&yRs%n5&stUn;>^QfgDT1iU0_Lnymc1#4BzR#8u`yZ-APgey z(<#3IGmM^bjybzM)H(A-4z11z7lb90UFE$X!ELT@TZ6mp4ebPWM#K3KVZ40UQKXbH z*`{XKKphfs78BmYU0|-*9cB%mLsv z`rl?Z#d&2sME@+Bd*q%popV$JciOleyP~-R-5)TnN)3=O)TuVT>pk}-agB8?2Z0@{ zs)=l|Jq6nP-;*sH4N`G?hK4{sgpw=vpbZ%7wlQ#b8E58AZP#$xF* zWKnH!XTg2S_#C|RyqW*O#Nz2P&UA`>CFK$`k78S!W1^l(b zhlb8^eZ>-Jy%7nGgNtmSmWrL^jl1$@4p*ZF@9pCb_|2Hf3v>*cPWkoxHPa3c7weW!tJRy!(I-aLn^p=elUnhd4^09!SLX?Y zxyw6(BlcJq*ca(nT{|4RNae*LXShv@sG)@@lrC?`^mX{X$!b5TAlTSA{-4$JO4q<` zvmMj_rM_UdVjT^B?|_{>*Tyqje$mmZ)lP{R?=&beBLh9sm2!RavVIr*R|#cwQ$u-FxAmUsW;|7#Mps6B&HjOMUJn&x?CxGe@JuT1q5pr7<-j5;Sx@qXYa<}$%j zk2C+Fy%~fJBI%3Z{@qFe4D}A`cBhW^I}hck9tO^z;b9}FP8p|mm7I}B@5R9m=|KhX z*WbXFQQla@rpxz}44cyvPWNm=N3~mRoefDl%V$x8E}x+xp%=7g92(U5myEq{W842wv2K#Ur0Ti)5~0d};Y4ot(52j9F~R5E zxFNJxQZoMO8&2+Oa8vLxCnmj5g@X~=d)AB%BV!pd5*s=`*h$E43%x{rn#;3=8H6QD zMH8~I2C9HM#7j^O)P`phN6XV@g4qzCMe=Dxa6awL7lpIu(Pl(k*BY2AFeuCDh6=Zc zI&pL3wj;<6B2OPoR&71{VEr~KOwi#`%t>3l=1kgXLRUFL1XCdS(nA{SRR*n%g{Kv- z1RV<}k?7)ry3egTl^{}J4a(9R3qK+YDbMgQ&voclHYiF0uwd!b_u8v@*6MA-dn3;S zuB@Yf*`Dn&IY1;$ANtn@n-PPzE`~bapOl!I=~cY*!fkpN$kKRHyS8Y;s5<(|vuKo=ys3hBfI?C>aahpoQl>{%xEj&Qhewu$hcQ;w4$s~u;{^Bg*+K_P& zC6IRb8%OaD%#pVzi%MA!(X@MY=HYwQ3>%wsH*c4r9E(GwykH$Zrh{j9FYy2M8c@HwmEt-px-u77K$r*)Vv@wl$)aDT7?_ zmP?4@`TDEALamhzF}fa~n{c7b1Z2XXaqm&jm|f+yUD0aBMPTf_8B*bToTmvdp8=x$ z?r@P9@ijHwk{9QBnq_(hGdoT{<44kPQS?rYl9sHERo#p<%a0e&Tf`wr97jNVmp#yK z4=H{F2G^t@u}Is$Pr*iT`zF)MK=Ep`8AH*a|%`i2J_=ng=|D#Zz z5H5c@7vRnGT^1(2_g~gr{}KP8j4?qFsrAQ#aARVHT1APE$yx&!WdCb2t1mg;b||qJ z56@Y>xDkuP&dhkX3XkwZZ81a&p3JjjBUu>}I0W$?3(Fp36#yv$rT(XaYIQ;?tmL=8 z57m3=tmL~MBx*c&6B{I6ZmZ8QV8`4MJB&W7OJnX*JQ@+NxQufr^4S5KM<~GC;exEU zk$X1Jhu7)i@ZUq#Jkah>gnHSp7>gBGEtWdX0zG~!h4*9;l*ie&M=gF|{N3Z@gL=&c z>KgwD2|3J?I(+{76p$kR=&o2i0|AM{3jb-4gsV8KN<;j~JU;(|w(n00=7qp=?GXz< zGAC<;fXFv6Y#5H~Bo!I>)8HHZ>@>2TlBX~fkNRf!!q;){r|;{OcO_A`WvV1=waqt8 zI{I=GNTU1q(Fu*#o0{cS?y>Hl7B5&?;5XUJQ_k`Amk2}*c(P0=x59n`mVbncbI7j? zi{ks!1F=TBDw{^ffBS8#u)j0JV=wjYkV^J`e17?A)NxxFDzFW#uA)nwx&Ge4sNM}l zP5yG`pFVWjJ*|FgqC0oNr_}O!qWyXuH5HtVUM|Z_)oQl=1lU0M5qd6@<3(@0~NtAF-vbJMS73qdE1f7LM~3{5|}{uC&rgU0@+v%xnAv`Y*x zhrXy)+Equa_q?T|HmQcVp65kpTmX(gB2Ug-)f88mvz%>9JT*O08FIs5K{;yiIb7WC za9bICKQ9=`|LYY%awo`BHtdNupD-itD{v*5gmDyYwg=GTQ+4a74nI+dtw`_IL@#%1 zi^;scEa%_b5{`bOG6OxaJciioM)%#AU9W!Fl0lX!@3e*i-DHzm7pBcNN5J`Th>@Wr zV*y6R;t!JgD&eSGq2I(4WFPIiJ39pC{Y7i~%y!t*D>bvwqpY%1_~#JFJf%BL^aAVhr-QpcJh*))QFPFHKyv&_O8TPbu_?8 z)I12Iym!Pky?6|TYG1fj&4qkLUT^F2Gv%!M^8Eb3EOgh>cMC$k8;IC*v%|xZj=N?) zIGMlQgUuWoiEfiIbjOd~1^JrY_}{Pt95+w%W|S@!C`&U}Bc)*SMigeV^UV%vGG`-Z zn;9zT8B?xlHw{Xq@mK>MhtpOId9qR$V3zu5X0T#FO_5tSzmk8?t6qoM*0S^N;Fgcge zjRF+}HZV3glOPx;wLk*U0S7OuDyuFfL$?LRo)%ryh6QqJ($G{eU8f; zXDHMXZFFgxGPcO-+zkcP}s8IaSW4Ko5$Fpeno)VK>6li)rbnLKY~Pkwli7_Mnp$L zzz)C)#;?jL5q6z>D0DGAY>a^ykjg@07H{Wp_`(Q0MLUY0X2BA!F3h8UQD<+%b>M0yCUP|eh%f`uY zNi6?;0idVw0Ds7d&6d~y@vp1J$&+&lpIqqxsx~V6tn{5eq{u zn0Yfs%xC@>-MZHosrU43xG<*PO%s}}CWq45PFk%xo`1kD2(F6$Jpy|)b|J?c+ljN< z0^^^!_U7N;XKIb=i!@0qfc6pfdi_Slf4(gTKXUlORFM`y!cMrY-WP_j3;k|lx|j~9 zfHmd%SLXlowJ=md*_Eh^I!ti_)2~I$!Vw~r$IWYo=NJv{hFAIN_W&m=lh$0W5&>i) z*2zwl`F|?#5(Tk_r$CPWUI}WV0!QI8IkiDYPz}eFw(!q+St=Zq?*fe^%b00T%A}a5 zySBmc=D$^jyMea#T8V)R@pz5-D_T3jN{ckTvi61sy3pBHF$X{GqTHiVJmhaboS+@$ zm3WcZNTG9F>a7f7t8{0T3G^DUb!o1W2+VqPo_}MK!1H0q+kdx|cK&y2yT?~YD1VO& zqlq35NP!J3p{k9zM2U~{5BH&`43C>rT8d z_ukF1{dfs(jJQ6Nd>P=D1Y%$Ev3pw{Re!X>-{ocA!M4H1WTEhm|Fg_M{l+5E0)pis zd!#v7eRL4v#9yFg4F(9G1UWzPJOo-2-%L)!6mCS~w}>Al}P zXsZf|qptg0Bg2qCb5b0}`Vs~ABrYdsL-m;A&cuS1PsC`iRC8kTE*d@uT0HJGELCpC z<1)WpMqiUpcofYg2o>Z_z%o6q1b=t}?I@LVQVMGy`4dwS(Wf|2GsdPf;Z@(UE3~)? zp=omf{&fO6=L2Yy2Ap50Mf&xb2{-Dg)S%g(J|z4H%X^z`0Su-kso9YWFRG(J*ht$)qcp8JBS z?whNe=-HWb$J`rtc7%vqpEH|u6y@pCB=tb56GK>bu zVsm@R;JJm~(xB#Z`h%^m>ObaYCxOpuxhM36(I4+5B~%HtuxTUVa{d#}x^zpjo+RTR znPn(FDGTuDc^G=HbMGGS3+YFB$eI82eDW*OE+OHuLaT*1RQpB?aP*^dlY zt~M!IcGV0bOxbyeaxz#Ges&Ob zVI#iJ0YPUtd51f9;ue5*3>(n~)kG+(p?}U_Xbv6bQzV7EE7e7Mi+{B|Dj2%&Xh-i( z9C+p-IUqUoONR&yFw|WMI!Pgslvf*WARPwsZ-mq!%g)FC1Z)0%)1&@IP{!R<4u8HY9K`sw+|6Ylq~p07c-2gFd!y+voi%D5^4i$s*q{`gEwBdS z!-f=YoTP1cPow14pxr~Ix;019mxq>Em24d}Pnx_0R|j@#^lVOxhIwzf#&(liQ>I)Z zYmE=1i7_#M-sHGjuqo`J(r*>yKSdK4n^Kxam*2|5741Y`_TGpTSLp>f=kqkkj0@X6x>K^Y%`?(#1p^RaX*$BoB1{eIt@)aZ* zQOPvB*44gCi`C?#;rD6EJdu8&#p%2HfuIUKFysTiyUxu4Dw~oVK2PS#D3CR65Bp_C+Z|-V3ZDr-m?HWb5&rtErUe1;* z&zLCm@qD)oJNe-5l~y;Q%*xMNg+pO-6|uzS?|(X-uDc4h>_H#08Rkn$htaT4f4x>s zKrX`#Lw-A;c;uMjLy6+`gTw;n5C24$Be_-2AKPk2%LNEv`_Uncw$^q|FPlqq1P`5~ z9YtNH7~YNxGn$hpnz2dD^P)hFHN}vSmq1z|9>d@#u(a7k=mW^1+{61UiHXmw>~K4> z{(oyE8RHV4lfX7Xf^ZW99b^FnmXbr>eg`u%BR&RnUrMGbB2&f`hQTu`eE6pbgc`#= z(~1!aE~p?*(iYijZnF*Lx;yK)Odhl#Z;I27jUFw3r*MRn7^I>nko=NYvS@2QI`zaE ze<47jtiBhkCG6Mu1@e@a*XbkL0soE(NPqcWIROZ8!+tfre%j6ufd;{{;dxR#4$4mQ zas<J$WN|wr?e46pH@PT1D|njlOk-G$|pTJK~-#O z=1A%s@#>0JJ|2$RLPYW7%6nx6jTu#GJYQkEotKf<+f2}>8%6|WKH@;m`oBDbbAQ)C zzbQ9)MjS`K7CCC^kXn&Jz9!nSwesG2)}hH$o&H;hx;EU?|!&u)Og0X5r88P*odkt4?0O|MnZk zyd_7Dm-5CM8LzZaySft&XWDT>wi+ILaTCw zA5J5-P;F&M`01Z)4zJ5251xO9C`5Z4zvFK@c#YDcw!q1YZ^~0SM0IE19$MNMaH#)l zaQxB&L26d4rdYZjQ}1MZNS*j1hK>XnY(U7}E8(;S_EI0-V@;kcsS z*Hwkfw@8|m^WROrh za5LJs-Eh%!xkqAjG&mV}-FUDfwqUrqkdoO{N%*~dIe-)KEvVqR4TS6;Cw>z|xMh7E zLp7eOdX`rbB*A*Ofq%oV$}?)(lfZDPFI!$;M?h%XOEYt&a+@L6p?{~eJtXifmY6^O zx?QGAVGJFPf_aKXM5~JG{UF=8k1&BTO6~5(TOS zhDQ5+$4zPy{C~$_O{Q31R59Z%ED6_9t|<+b&1jwndOEQ!%5=-9st<#P;++tOp%1So z44cL+-^tU1t+P>Y!hcFz3jQ3ge}4g#XP~QKnV%@@=n@fz+cRgd?ge1W#R*f+a}88( z1uv?_7~i0L*qMI1+HxQ#hQUzFv48ZrVJT$6%sKT{KadCy z2;BK%_!(6@0V@9&-;>$HzPx;8P(e6^Rve4$Sisa2BUvn{-D)cUW37u~>^k!=R8lO{W6*!pPHit@L)63p_TYrcG_!CIOrNK_@Y z92k$J>CPC2+kYMrnb5)LA5hczq`|M{I78(So#tR(tPDInRWc~u>0k<>mjN@@}I*@`>9gd&x z4+be?XnzE}-)JH|;B99cQ396-7mf5KU!;~USy`8QeIZ+ntJxZa2tZZZ`$202;W|9o z!mpKnZ&eQ8Cvu7EcoC;@?~6#r>y=o0{M#oiCYQbe-_Dj$r3#(YVwy(3saX*nRcdWO zkOldh+YiZX+t3w%pvem5Wjgs8i_=ZA=mu| z$0^ber{R`cTj%vZHbT|j?Gx@Y`;>3|iO>dcep;Yt!MTiR3dG~TjWy8lcVO^?y>n7$ zwSTy}(5-;`pQsRoYRtef35H`B5BN9F=2K$OJOp24`sYKS3iR+#)<9b;s9KrBRvctD z7$1=lrlzoII7jb3VNWxJ*%X_9!?uU~#FK!%IDAtU_MI7ZM&RP@8b|eC>MjeWrf<>x zYiq!;cZ6wrOpSIs8uX(7IiCruzJw*b_J3f7E3t<)p_H0Hx4dpbRg;kl%dVfSA z*b>jgf`5h>Ic;&!(*oN=Xy0D?)4hwJr?k;7UfhHh&xTN?)J&678yZASZVc02-Shlw$lse!i?W7ChnI%gackUgcq?*mnX9?U zY$h=#HW8cvY&s5y9R7_9f1@gx~AD zw=x%ouFb)ga^tZ2flC3i9xv4;Xti!6sQ;=Ozvx0U6F0G(PG4y(Khw0FOHlp+>U~g{ z$)7i{XS1gCq4rEcqPTS>-|GW=HJxI|2rlaq{d4dVG8r%CJi7#Bj7vMkf`86!=w)(G zf{LoB+Yb|E_lJbhc$UzGD1TnMAqluuG7J7lghBp6Wm^vBe-$g8O2j5#}IXUqvWnuhO*%l zj87}@>oN-|bLA0;58lL=MIt4fOgTVkG%5{@1#if~GQev_`kO>OP=5oC5SvR89@H95 z($UYr&Q^mATh5`3pzLiI$+)dRTB(5g(ezEBQ9wfa@Mu#AeKnI(1T2(x_$4G$!WO*m zIt>$A|MdX9+F*wb!Ya>CR-Bx`eagMtyJN{|>z?DfXLb(ETdssN?l?;O@|RG*FqV8D zaWs_8rTl>-X|`jOE|B*k?_$+Sq6~ct$Tyb5oHsO%{ry3_x zb2>=l{hU}Csh}K|6STj1YeC>N|CyH#3bn=w+%V@BV>#+CN1$${ zi9Og1eGJw%Z&pbySz;$ozJ4ke5D^8P_`jO`vJ)c}396IXD6);Tw@CSyd{fo>r^6UU zR9C5%f%;CpbrW$}_td)9rdz8wh47^-rKg6CzEG3>6SVCE6~kE7(!d3kR_QMv?u1<= z5F!@?sDHV+Kl0{fAmDG4XVR^F{X5^ak}3cloo*q|8Z|jg6(nK7#xA8aTCsK% zaWJSG$ppc9Oi>bwi@5hxfw z9~BXSSzjPvk#FJd!?o$=Ay|JYDo00xgz~aArs!AB5oQE&XZ!EF2D+Z;9-=rD&JP7$ zP--Lm1CiTOijl~;ByGYuq=XxIPXF&YQZeFf{3AqQuFui0SUVopO3aCt?HT;D08H_7 zvw!K&Pe&PWKHk`jKEg%834+z;0rmE-sg^^>#Pnm@MFW3S&H9Pmhare5kvbJNLu!`9 z*ihz`g0Xw2iyQ-eho%5FdYk*F-sVldQ-4)B; zZ6BJ?qp)p9Wm#^I?k((?Jg2@*b|Q&d@PBLc28UDTB^TOrn>rc|OR^Q*xLNhz4=w%= zxzJM8H90Sn?1lI~`y+?(w4w3gKV!#55-(KT;nvuHH|p=PtGn;awcw7aCt|FIarggT zI{W+%G5?D>rOHb^zxcBLz#-Ec+8_tseMf9g9p_?V=c_lB>?{=~~J&`~)2X@AD9 z@1iUMc({KbzFMWZW+60K)0b{0wm^af5r1v+C4x>8QeH2kYB*~s&9#HkvQcC6s-khyzzYksN3%%nR z(dXe$qq-_sxV1D*A2&mLh1HSQ%Z$@O(g`1f+|fDq zz8LY}PwFL!fuV3>E|0&!s!jyxWt29Q{~nDwz@@Dw)?p102Dp~$ZZCf~SHP!mbvTNd z1DbEQDdO5xZR&$(fkzW<3xD2S2ub$zxiAJ?vf9TSRF~ASmb2fFNh=?g;nHRc={I<0 zbix?TGv{i2O9W2fahV_?d%(dF^bdDVUi%GDJl&?#+d0%TQOi4w&wO^2cEeO&C}6kcCSm{5j#Gt)N$EYt-9|9`AV_Z#+u2-a-h zj7c>dt4r5pjTcgsgVdfWg6oHI>lJk4TfS)eavDDThcK`Ayz8iU;SI^WNhzi2CsCI} zNBGEehShp~xQ)%V$>ah?n`OVE#RP7jL$>%tgP+enAbQW>=(JsjngP0li1h0Ah9xAP zc6uge$@9LdfKd18Eq}Mq|CnZjoaB?ync`~)HyXV>Wa*?yjt9PmE(_>aM;L*H;#s3t zzod7agO(OEeE5W*E&Rt4|3MDUCjs+m(c#a(76MH$u+)eLH64aw- z5woM&a|PFxnFGKm60S`wQyE8^z$)H{Ch*^P4x&EN)rbZVkQ~_Ia=n*vT4b9b%_KTW zO1)5-{xa(n>$uqgqT!dy_5moD?*9P|x6Wn)-6ogX{{a@4;4=dY1u`}^G&GmdjRF<} zGB7ifAQ&fqYs|5kO63V(UO;^`8Nek*$rf`M)?hGW?r>jSIlR=^tVy4z|`rG9t=< zMCD|Em5D@z7?p*H3~Y>vq{aV9w{ddh`Ued#a;!NilCd=gIM@&=+FBcb*!&k|U~O*Y{{O}OUxb8{!9P0uu`&He zIi~-(%pFC|-2le&=1%`eZDL^ck3|3Ws{#JAE;0aPb7$-SQpJW8maq?nb1=#PF~7VEWhdUrXozp#%kO-8|`;IXH;uSy`BfnAzCai8$F;Q?vc9 zkpEU6rh5aXifwHq3w9fR@07l=9w1LM#g>_KQ6p(z%8M+<9Hn2@(GQNa6SubbXd_0g zLy3~1`3(m+pshxlGYc-bG30;UUk3@z3*3XdCCAn?D=7E3I||kK%TCqCxx3VVPJbs( zmKaQr0?y?Q)@y?%l@ykWNCHQl;}>RRVnT=Ff`Z^6M*Aud(0(&Y{Q~4OJzOR~7KU_T znq7H@i3TJKSm)Tt=zhpb%22!oxh@kyHzL(hpt6Z){TVH=Gu;Jcxi*j-SbA@Z8I!eY ze{aG||!cI!^{0GyrX_tSP-y);Z2z*qj|9hc6JzUx*B) z%DHl}Uc$BpRZ^Y}>t4w|O>jor-QbJOH30u&>J5gQ38zoJEM6%P8MOv|vM@U~?putj z$e7;lS?YG>eI@T9-iX(K8L`i@COs}y)kUU2lui=5bg(jtWPy`$Iwm%o^%Y!T%soTt zni<(gUqkE9+keUwgI7xem|lJ1G4LEk-u?w-6MuuRAR!nbQB@NCMnHF;mGFiL*f_lI z`C*$#xlEMkqqx&+muP}l3IKg1P!ODganBVwX9cxf*+Vmdd1DR zwHojI+D$8V#Q^euca$;yTPa(lml)_T$c)>&GRx5pdoUX-vpL^!NT0(w@%rAzs0(Zds+IcM*G=i8g?^B zKDVzZF15JuXBLg31(`)xbyXD%+IjaFKiSbq)IMNiVnt@QA*|yaeX#8hc|LGBV(>Zi>;>A%hlFabOxof_447%$PKU1C6 zVuikcEX1L==#C7+H4PH9CvZQ0UynWM!xxiX#^c&)-3`x1iXu$eF2x1R`-l010*KV@PR~T+p%v1djds< zFxGoil=gS`k7<5D^iU(np-wH}tjofKUIP<`6q;lY2x?ykhSWLoO$GQp_OX@M$7dsd zZ5xDQpm1rrCaf+8Mk9WfrIm$ng2V_c7>)?Cip@HnyJ{DS9saVN?|Whv#zvRluPheT z-O27vecvx1Gx$Ck8xw5w)dX#x}8bC~$Rwc^1D*SSOY+&)1~f}3D+BesoFf60l(REs4vrMyf@M~fCp;euKzSQ&t z%q}V+j%?$S=^&&(W_i`1VFcJ-6Ysas6;dobM@&gE6ETtAsr%?(y~GF*)ekzuhFsAG z8S}zAC34}vfJ7H=Rx9P|QrYb0M1Zegt#LGmEoW$sBMoFsVsNZs3DAI&Z|Q_St5~sn z#Xk1Vlu#Eqaw@j9yes~MSs}xJWBm#tvEa7ow|KmQrv&z#KHuxFgJN^^DJ~i7f{$5o z{uMj;y|WMM*9{WM={!Jlllt8f}Rz?Sa~0%lrZ6$xGTNYq_CB!q>VoN(sUAqFaF`~`Jl5f16I*nl`7WOyf(3#HRO6v+s$>Qt=WVn@Aj9dEbj5f9%G>Sd*aDUzlMG#7pF;#)ZoZK7j*& z-Rs=UFYxYoj>B|+9&NT`ba4>0be0@2m6dLu3jSiWlo`$o*Sj74^1T%p2oJqG0V?wG0@=NPeB>~PwXtsdSd3x2Aaq}# zg>m}nwJft5G-RHkg*7TXFRK}sC94f*)aIWkN`Q8HexYa^M~ftNi+P+X#Y15UMqoe& zN%&i4Ssu3XTj_x0g#F3S%p1g9RWe8|y+S96;;tnxT`%uDe>W4*t#KJI^h+hEPPzCx z?xCXR;Gz|Oc9SbcVM3*q*M7q|iEU(ek8gjQ!)>thn7Roz<0i1aCpN(OJ7d;UaW8~Z zvirg=FnV7pEN(oaDqOQDT39SApU>Cp&*9VDX+xSt2V8zvk9xCqK!gas=VYYaR{id* zy*LedFf^*AK7whCH2%ludmjLW$hqb*Mbzr#r3XrXxfd72+jo{vx57l&e$sJ}xn0e> z86k7oCQ5GC6T61zs>?D(lZz%@t(6BY8>FT13x6ahcQkW8D6OV4U_eSVkF^}df#cog zd}z35Gvirn^h#g#iqlFg1nL6@LtM&Y(@bzrB2M|I zosG|bLEErfT&ITK*Xp7k06G`j?(K)v z4F38{^ra}cO4Qu;X2MjS-V2S7%I9PIYtT^G-Pc)!1;Bcs73)RIo}wJE4j1Dol+cRHi=X)#|cZ@E-sd2?7OXE(p(HC+cGzqgQ@BnMCkk`l;YeufC6_f}$eLpze3xqts zeaM~RJo3$dYmEdmLfAU$N^>B*GffYF_=`swh;bW#zfyO5xKv4>C2o+A*FmX(;i9G4 za7%yYE#H($;x+*&>T-U%#xZ8+o<(^;7)bMNzo7QB1-0Yqefx2G4mSWcgVf8KLJ4d< z^X19n_=f*yuvgS}!)nQ3?`Inm=97%oqFQ>l1WbdpGE-QOmxzin(+GHSR!2U65=O?- z_&16Zn8IT>xI-T3CEp++*Mu6>JXPc@z5MUN-|LhN{d8?uWHJ@}k>cLj7|` z{UxtXCF2xCCynx0#HB#u(T*6Uf<)0!G^$mkQX6PbzX3wdzj6NhNOsoBm=!LnYUa&E zJ6(5@xocT+@ui+{w?xNxYe!*!>kh(oam|S7^-?Rohd?hJ!uXifapUje?azq>M>0z- zZ%R(9vLD*6PeVvgnLlnM)kG>#%PS!Mqee5N%LWWFAHVy_GkVs*lxq5 z1-L~ub-a$>oVp=nq64{#XebIpfZe}%g-FOqvOCHAlndCfzq@?aZ^^EIpIJ9ZFV*0q zz}CnL%@iPZXMW9%3*qU43d8cm)bXF{|Ewr^BhHL(C-sWr!dN?|bGj+j(@ccek-=3> z^ftExE@dHZgOD;Uk=WU+R~0D|;wuj6=)paQIV&F8FT9D4F^Q+c1D`o7e(%C{8j#s-Q`Ir#)nH zvA!Yl_SU%7n5Me7xSh-QkxbM}3q_};19k$tM+#6hNTGr#g|Ix`zj(Jba4lO+fWB7$ z+IGF2w?b~y-?`I|_y%e+x%fHA`HO%K9a!^_XFAzlO-^(31GSO6k-!!(3|==$2JgkW#To0HgnQ=-PD?{S6G9y-8mJ4hlOP*a zWU@oM1>Es3@|Hq+Z-Q=F`t(}d;S9tjJlCly6}D{o=*G6!bzJ5Vl6U$dP$BTis?D3& zwP6_zMMy*##btNTw&NW3FK?3Q0YR9GzMM`obykfOvLhr2d+Rdl$(W5j(ULn1qn^pym0{+A zG3}9NsK?Z4xeE1&U?N*f?h7y}lKzvFSjdCMl3X-w^VG(+l7umzo@jgz!+$?4FZ}!hg^9B#60jP@c_pyk`L<~52P!V9$VGd;oote2@8v9hKEo%pRj@v zvCJ~;t6p^^D-iobU@5`!AxVsI6lZk@pfAqBkNNq3PFW1$ggn^LRfA7H@{*~)e{mW6 znN?Z(G2yZyiKIremDl9r1s3P9u(}(-xR-P&H zADw+;pePj}0^5!}2=Amm ztXwuc)_mV3=B+6#Y!+SoslXgk4u*$BZb4;#8a(#QU~)8`rHxe%YoBnl7z8pdmVxQ| zCpSXc{ZOIo@SP2;2P4IwoL$Vq(#;XA24uoXh^J8Wh~1`YEI_!e-;13wh|3!vch!oC zHe{_de^abqif3ivhw81v;433Hz*s1P^HQ#sg}7ARgEsa_)!OHy4on<4Kg=w{<68; z>nHASg$?&0AWL;P177_i?h>^vfRDwZ`7B%DzHW_losl^1*}Yj;MTAa&@{vZkr+~mN zQWtsV)~c=vNg{;+E7kwYf!|5?2>cN$&Yo9PbTXbR?GGe0>|d$z3490FW~;^L6#cdM zllgeU$Ijn&nMrGNfHTsrTLoI~tw`5ycieY5qak-cOfD>qQBkSf+=5&T_J-j=5TehF z$e&i1J~()gWo%$FOjI3z)Ag#34mtn!Fhhf=(du=~3bGyNz$xmP1K z(9tuh5nI#!K9d_7NIjOS)SjGMp8&_q956i$e~KJ3B+nVkb1Mdq1N!-0kttnMObF*m z;)jywk(TU8_>s-+cad?%uR%2UtD^K)Sf!&r)orEM1GOVU#)774j+_bQhAn&{1R|9+Aq=Okd&oYo$W<@ic z-#aFhi!Cvz4@u&GF|#B!o)BHw#ce>PN90>L=eSw|NtcIVdO-{f_^q2Qh6!HpB><=< zsK)|T1*3N%e=!1|rmnE}fcjkN1zf7`d(oun1AdstR81zRe&A<1vUlzws3H4mr%tYl z1^Y$PAOoYshTkD1rN#5rW$R{tYqyT^`x@C=V>%w}Qa^pG z)##Q-1N&vS>&4rXhWs-gW4`drA- zdi4kZ)+_*pO3+1`saRV~{ruc}q>5DM3e-H%;tc$9Aff_%B~)uyIe7bq{7`p&B?}FZ zEo6D8T7^D;uDh&#h=627$Zw-2l3(p4;pvC_opA(~I7yS1-m_Z2WUFVAJ%P}f4&F{W zhn4mCV8Baf-nStB&gQa2FyfsmtRxw9d!*oe{`T%*kNF+Px1slTO)IZYb`}hd-&6IY z(uV*FGz>{x&Oo1r8xlE&8^bIUD(_2p3{twTxORAdk;y5Y(&%+#Wn)IogasdK&vW4k zhPz*lN@X0XAF?p8u8rb0m8cwI7@<8rHQy>1t?emM=Pa{S1OjU8O3h$@cBr&`N~@!l zP}-W+Wf;?p;FzZTNNUAm<{InL)Htra5~rX=b~Oh~yZ)h*rwa-o@p7-h6f?Nf&1#q; zb`dgvU&|P|yIC*SkzTUOZo<`GRH6r?L^*-k19Px>3)1IGvo^|?bDrM|A90$Uaa#|v zbkEL+K;td-@#rxQA8w#MMS!ghN)~no5`6|G><5`VPu?t3nR+XTHFbB-S3VBi<&79@ zQC`=zV(of{5fKvseUD5`UHqGs;h|fW!lh7u?A`?gt3MbTGBv@BEq1pQDrb_oa?k$z z_a8y6Z4h+mvYRJP&{t@`=s2PL)wHbB0A615fd#+}+~}r1@zZsI;$0uTr>U|_U5hj2 z92{A#_o~9I!d>deQ0~U#Gm?=uBB(ekT62r_6ZNXAt~2Ll?);xo<%^I|-|qG_SvIGC z@*x#TC`-Q!z~(yPFH=$|4zSU;QbjFt!}!VL^VN#wAVeO|9OAVJPPi|$%gjdl9gZ-0 zhem&ip8n#g)1q>+%w=lLxWCN3?Y4*D?PU-{+2}OTS_N5)0Bi_i-%kWF^Ru+P=S#5m zSD$fE@mUS1qS(TtWvOocb-6zSw8~01K|OW*pxE z$odF$V96`Y&lw`@*DyRTLzf^>@F$}ZOyEv!D+zQ(_3aaX|AnACH{GiG zclGBSF7lGs*wO->#Vx_icKWPLwJnF@OwZuc_)t&SB|*p8^TPD_v6FZzWoo4e2NO_Y zL7_xyL{fs2i|R@Lu|=WDR||W~`m6>%(L-S~ddZXNMc`eUP5$-gV$-1V@#%>wjcmW5 z{#N1+Z>x-vaX9~_^V*Pu2wyqy9+BhFJX*Cb4`X? z`GFHm4{|#3kIo{^ie9${v^(v5;GK4HYHa3ImJx_kE;f@Xj>e0fXn8hCHK4VZrQ2RI zR)TM-)OGhIu(cKSkw7h;=^l$fPzE(%O#ch|sK5Ev^QnV>G+n?ZBUUY#9QG9| zSOQN((eGyM;iEzN2J(=c=7X+$2ph;q*P#Ye9 zo*|^7ndyj-26H5bh+SJ={%&1c*XZor(4oP;h$&~#3d~F52A&*o&X*1x<74M0qnF5E zBmOjFaD}RGr&{)Zdh8Nh^TRKLYjp0Bls`H6$YxZ`)Vw2|i?8~9zN`ezIV8cDAQ?l|Q6hEx~)b+xPu`m`CaCHMcyxOCpMO0&> ztq38uD5Jw%k{m)k1h(h%@!sd%+P)5p zZ(eti-Ob{`V5Q=u)#Fvh-o0QJcPvjC%^_`of{2m4L+(Em%B3O7x!>y0cvbR>5O4n9 zdo@mh{Xl|$Dci2pyx?AHjr1AJd=y3YZOchuY0D|~v5g=NtOY>uZB6%v zihZhsFr4=QozDBEr@l)<&y@r+_Da4bnIk5U#1`ekk}{`*hFl+^|!1 zB;zH$p2zn-T_19YnW59c6P_muPqC7;JG2dp@R$t2+LHqINyyoldpGiGEvHw8~VArNmBlnr&JrX`qHNH}W1W$$htx*)- zD)hhK4JzQ(DLId|rBH)K)YC$_+hWrSx;mGC*TVKGBWBKP&-cZNHcXLBVXl`D6!rzN z`F_-b!V7w>R~LO#1^q~{u>RM^I%^93Tfu>yERfQfG0TrQO=?4Yl*3zD;3e5F3|^vn ze&xI8&ms0qH-(N@lY@bmzs3m*fC3pMKXyj52E8e)5rYo&Mjq4`h9y`_m>DNbbxt`7w$w>~v*2kLTlXt-Yvn7FWON)Y$NcHQd4Mo5yfCEZA%nHTRVn)ZCM}$Gl|N3qz?7Xe`O0Qpz^{*Skh?>FL3}G# ztCFa!K8>jb$UnqbkKk#gQ|i z14^uzXwxFU--vakB9dN<73OLQC0}p|Lc_NzwXr?$@Z0)ZOc{%e5tTZUyqzVq+cgKFyo`gstxJ|2w*v2FzYOwfhg$o+7iil;=LA-vI zsfLkzz)ak7_gIx-T%4O)E_2&bvf*n8;C(zjb|^K>y{GY8-Z160XvP?SmHy3NC@0v{ zOW6Z*62FV>@WldmrfM>A06Rd$znhG|p6j4@Y3LP@P>;u>kD|MyKI1H+#2% z0Y@|{=1sU3Kf1bM?=2_*U;8yIe;c#7uoK|!Si=HNWiwic9;m1@T22xCdLySj^N4oe z6o2GTM8jObK0AV5TYtvA49jS%D!%M3vh*6q$Q&s+;y&Eg$%82V+t(1;Yt&906Bbwv?=m3b0e+^~Bo^@{y z`EEOlN3JYdq!W`vsRW%Yo^P!98<-{wtf5<`fgD~5Zjo2SBu`l|!dZjyz;BD{bv|HynHjC2ynI@StbFOyg}5>z{rcD@q4 z)E$|TZ+Z=g7`h&$*%;iee`}nWk4~C#?e{b-_b`$#LC4R#nZl1;wa1dK$^L}zt}NJw zpI|~jF=n*&hi^-Pr1{84xcBeavojw!51Ypk5F+jRvX(?b%-ANGe3yMm>06zinX{v`>w^>a{h2wF)$eh@yUOR$!e`B^ZrU}JQqW!?* z(I3=t(63+h2yuse6BD-E#6t2Eo=Dovjmup@1pagSw9Hl4@eso0+wp85bn-oYit#D0 zU`Zjz$OE~Wg0p6U7&x8ie4<+GUVvGM{_g2+Sh3b=Be>^5u5{r`)hF<_!w?w^M zlYjhvAE+g4u=|i6OW9@Y22z~)0N1o3*Gd(gO`BA~8f8#@Kv@F6Fpxs-5#nHx9lt@| zr%gT)QwiSALoshm5Z!G!V)B%yA`yPVTA;BqVmT(8D9}<#Uc8Hze?0?OH|nQGLL(A5 zqDb-krwrC+e<#C<*)?T-GU3z2V(}__MZHc=`2GB8yPdu<6GH8`Z<=+x#R?gdx!hRd zb1ri$k&WlrFJk9h;{pQl2~(?#JYKj(#|+|KA9W*_p(hkE<}Kbxv{ccjrbyX?ST)M_ zuOdjBjfc=%HrJZFR*;$L?`s@g4zHi}oO42-8jWvje|46*b~S(6CXV_uh=elz02$*- zf?1~eK=wpkS=< zSI*V#?v2n}zDqJsPwg4yB}iZx zQV&fv59E=i6FGmcfE#BrQPqtVY*n6&>5Qc*f7XH~CD76N>TcJd3>vo8u+bm(faA?6 zGm9mYo?iOz9wSbv@=S$51rs@)QRwo9PgEXPv8}Rrk~w%RXtQec@o7*Pp*k(vU?u{a zTZiMMgkOoUL-0Q3Ob_^X;4E=utrJ8)bN1lf?MMr3bf_gE1h+<-dxia80XRQPV4j0$zE`SeDVr7{yNfM| zIIu8PrH+CmH?k*YW+k+wi-J z-nNN3&87+6gw+xvi_sEZE;?>$ijdePWQ~+lTO@Kwko|*d=q-w&FjnU>WMADUB^H-o zGf45*p>pD35!*s|l_2_6e{8Qif12v^Nh`#s|Fs)HXH04lC;yE?>xwn!-3XJoy+u%7 z6YmWxr`ACVd1YUu(uEE5ZV?2PdSsHx!`qt)VbGYru=N-p^bT6|dmB~{FzB5B2!3UA(@+7(Y69X?GRChuH~2ZCiIM&gPrVX`HG}(OMiTWyM>EGf93mH-pQUa zvp_b$?)tbdp3+{k@g<=B^_7zGd?>u|^byaYtjRGI#nSHQ`-_@q@XACQj_1J)x- z;+upz>@-@V4O=z0{H zZ)SPes($))zWAe7?1-Srm+%9U%Rn?~Wg>wwITGzkTtq+ERMFmqfObM%-)iNY&Gn%R zxz+ZT$U_2mFkaX$S>_$!XSgjzxtYhr6Nhx0xsutdh6UJ@Q|~86sfKP7laNw(?W- zO6-Zw=}Z@Nn0ua_7I+4{p6$bE1+DOXak0HvgJv_RO{G&7R=^8DaXIKwlwjeVu|H&) z{Y8&{l>XIxN>#EQn|K?^ZpL+@WtkOAw(LzK=;<1z(QQ?7p8gv1hOlC6V6SBCeLOFJJXHndq?VRfA#GaB zfvC4grHC#vfA7ghItTJCw;x0%);#b&;}m-$GP*`v{3E-3w@vq*XU9Yn|3gZ; zK{`dS!h<*TOWe=qN}}Xo2=%Hn1I*$F`XnBA65z~Te{#^dECONdL$!)KPQEFWf|EbM z(D{PT66rkkyi*5q^azxw<}D2L?zrxDVt*RAH`gUk*bh8n=CAmyuFTfXtlxK(?eeFy z&XdZg#&BYirc1)%px`YfHWhzeT$EbPr$V1+V7!|fqtccq)XA_jG!XAvAWgH|8b%(K z@UM5Ee_TzRIrxk!jV~c{Bmcc$x;`DCM5kbAXD_`t6UZ91tbhELbrQdsD637J{>k{DJb2r-f!7fL{B~pf-cJRIV>`}Q|qXR z*t-z9FjF?ulY4Q~T=br#yO?PBS9zq9Sz9 zuL}Bn*^pK%HNXt9L{{ZvZKJa|1xEh`t>k9P;;{nUqz7bnn zr^!Wv=GAv7UU!1bH~xl2BJ(u;n(9t>n1>>KC*H#{0LzDH?B&(Ow>e%8^0njuA!2QT ze+654EB+NT5VVAYxL35&C>xywzA;7OI5r0M?N?{KK)i5fB5+S2-A_g7!&{z*FE1CR zooe}B1o@Ao^HVbk#)L{$7-dF}$)aL=juoLq>Dj!QBes(4BP^nLSbJ-5Mm2cw$2Q?+ z*4Z!4o2{-~HcGOUOC)H091=L+1zAude@~H|wJr6!9qb{DIeut)L@t1Rk$uE&ZlXPr z8SveNI*EY|ByphEd2}7ZB${?sRV%zSgpv2Us|0fS@cA~sGjZ3M?d`4T;5GlgwSXh0 z=wrS~RAN_=H{d+u{n4c!=oUIPSkC|iB&Nm=I=BLB^f^ZsM?Zs91^B3D;%c~Lf3jAQ zR0Ee|2o4`>%g!pGt4Z^{ZNhYaagD8xK3fHxAZ6W^N7u<*GpNMMkzUV00429%G$=glt!=ONJyT3X(h>F4vwBw@x^Rh>#jXC+A|67I?CsFuQRo zD_r_33aD)fR8&hb2iN8_WpcZRD74!ehvHQCW4JlBrN^QLRP_|{WB?6Uhq==!rUl+> zXFlUufsf+|GMjLPpebm1f135Ha^v?Si^O#Wb%8%$D5Bi*U7SUPcnM#DQoAv`B?XZm zr_6r7pii@`P(PSjC{hhz^ufV4u<}w~9(*ykD-Vq`K2+J&Il*G6__YQw2%~*4|7=CI zUtr(`w?rdW4Ae`(R*FY5$ET>Av!Bkwe7ZV98$UJFJXe6fT6pJne`f2Iv*Gva$ARxU z{ZN12msK66MozE(6EjX?Pg#lXlKu=4>oNE@jF7f&>nQ5R3n+5S>PO4J=_K?&T)G(AgMOqNrO_oOL_OHWX2)^5Dsl5ie0-_PDK)R>@O(cK{>b zQH9^8kzeXW(KMy=scFin9YdiWRV*b`uUUrYxR^cp`onLo>H=2P!@tSv#}!+LUF!Pj zmwkSn#Yj8ED0?s>{&^RY8Eq{tuhu*A1A>O}gHkf!!GbVpf3QQJ1_!a8d~p4;_S4s} z`3En7dX`}F=}8R=65~3d=B(pNLfG}EiTg~9n7##GQSj#yvszq11jZuMm{mJc=b24j zObM7eXMs9}!B4A9th8NpaZ_uLkS!vpP1o*KR@Vmk4wGhkq+J(^>_80)Hp*~!K`r$H zXA6=R1;*F`fB5d;7v1zjtS^UMMqLm=Wy(UGbb_;Q>ZQ%N*dm8 z136bRd#2ap6N)vA2j@toQdN?3t%U?^M5?t9Wn!`+G>D~19YZ(&qSdY)|7Zp(e3L5P zSk-Iq3ai#tKjBQ0UneQ_+GQ)Q0UN*1A5$T=A>U3be|>mrP#K!(MLd9gUyU^68-IxN zjWMq4z&D5XuY=*%UL$tP&JTNFZBvbEGG!4fbD|&fj%tCO$Hyp@r~-zl_Kr2{k&JUf zAt>B*M%tu35NW8hkf14f4Ze{U6(;^8-b3@DsPqWAiF499=!LeXrxGHvZ-?7H>#C94 z$+)Xef7+_p0Uu)FocVmm)`Iin_rX}P#1%s>0%YuFK{?p}-0u+{ zRvQ&fsS7#OaJq*s8sit*nO=QdtGOqgcygE{{#G~%=Zx zW3THN)|T4r`QnybP!l@d%6UKN7UX4ue=NxJv)*97qo>?Vg2s`V%T+JV+GNqQ z-zN~Q&qKSuoq|qZ)i~5D&OO-OzGj-{3fR!9TFn?;;!UoetNTWt>Qa}qU2822C(0bf zrUv$;pxFo60)b<{CS(lWYd5ma@lMe+%Bb&vs9mOG1GV&({FJt0g)^ ze=)!}qg!=*MP5~*suH(hlKh(cki}$NQU6TlaEs>t>~q`NMehGuQD+#-<7Mcmmu>b^ zpCj3}lOjNkNi!b-p1RY9?yD6Nccj33H;e1v9MgcI;}gxF_1FXkafy?60s3n(oJDmW zQ=(?Le!jZ#wS#gG7iID1E%4RS0U}0Cf8TcJd_)${LU*eJ+OVfx;&O@F%rBBO=<^yr zZA6)cJhwp_>Ql@r*vkBg3jp2Fb9ZYRE(CPk}Pkr?1 z6RKrR)k!JUd0||sA5Z|)N76TIHk63WH_n4lHbhCQqd&_r;kVE!kCJXv{t*VPe@-qE z9=rJ~=MBP*N}_Tv!bQNcv)VUeRT6tlF^xNxWYA>~Ri8WqW2yK_7fJ(pc;@PH(R|xG zCApixm#j#l>&+2lp`eJUb7;3uFhXsRMIh9Gm~(OyPl0*h3D4|E#WRnC4Mk9Q$nskimfn`?VA>dM00RV$LJlM7wk}f2%4|UOJ?o z_vor72rKM&FY@aCdx4{)uSdEeN}n_=I$lK4C}Bjc1J9#n$vD>Vr8Lfz7ik(b=5CVa zWGAr(n{hJKkCBGd*&rTEm@mJV>L96*01G2F!CMFxQD;&FX(~lv63;p;q^8G;OH$t+uI*+4Oid^iv zrS5-=>;rTEb>lmB$3bTbS8kr7aNItzDnYVEQ`?#%$Jm}^$KQMdfA3;1O6(5;Z~cRZ z*E0qMtt}Fi8Df$&&aCSAQ3ZScJ5Z;2e^xHHHvS#}PC(m_PG4-H*{UO+KjfE`s6Yqr z(bn4Xv72*p^4och%jO+od@DN+T5o$AG`Q_NcrtlZ0EPW>ta#fJ>TPb8W-EzVvDkdg zPZFQq27$Htxct)oe{*C~odRyPe@HS~9I4MytaHLIv+kBYAsAWLV{Z@JvFn$)9XA3o z2x5pA**o;V$M@E?y>Bb@4MIm!{9VjJh>eWB(b$yNjCU(l#lt|FJ6NiNn`DK%XQ@Rp zGoGk(Quar1v#*<0_|)gOTF-; z=?+B7w#o<7&c?%5wWfp|Z?Hkv$s~zl)B#WFGVcB>;1f+-b?$8?j98x~#HaLx%Ae=IrSjE8M-g&D-aN|s zV1fCpN8EP;H6nO7W@a6>m=qrhWQvufFFnkw}`Nth%v?_cV#O%!gYBkG;}u^J;!!Q+t`QVt5;(ZHfcPl_s> z^hhb$w>EL(Kzxm6mQr@qKi3DQ_`ei5y_*wuO)N;v`bRU?1s_{yDk$-?_qdQ-n8YdD zCY)_2f6O#wRdWoRzvqxXL6+1RYp@Kd^ObwTogW94UPGr9KsDzy%7??MX))bQg{bZq zf&x=x<3F3^V=-}|KD@{fDP@IC;grC3O+{S>Q(F z?{`@C6QOx|G;w-byx?lR(0xOykuop;%OI@6e_Ffoc925kt;x0CzMIUs6}#32<@&nM0Gn8vukvD%B^tFiqvCI>IYYIFEFt^79_iX7HZj&_oLDkkMV|qL{brV zkb79v-)hLRz72%Z+i@%Oqc|5O*lEZHqS=_)_xCqo*lu>Y$B;+cmQL(_Pv!fqb01H* z5$mAH(-bEm5ePrxCEe}wC%e4&1p}PCfAUCrday4Trxs>ZJs=mRoBjKa)kcF7mH2Z> z8ER+2cVLuJ@NdZtu(^K}t2`h!?6YvsDi;PQQrWFTx4^`eW(F3MLP^7_WCE>)9P-zA zcYqgg)vU-C2NTL1S~J$>^5oaoIQFWUy`|Oq9|WC!ebpw{?mUBjp2d2h30HdMe@Jah zqsSBG2htQbH3RgPepd_T5xf*CGz}HESIW4gRz#;BQoQ4f>V>%-kGZQf?6%f1GLwy@nQ6@*~zwG`PId&je1SYs*jYPp$xNkRK<` zS?B|v9G_A&3aemBW$x=E!pg)9XoYQq3Hk{mTe-^e(7>7(+h(WAWp$c%_x3(!Ityj; z6Fusbp1fVl0ysr#;9(ii+M)pZx5Q1PUKnWhO$5li_Fx?7J~jh_6DkYwf4jl{n2y`C z{-+RjnHt8v@7nsr5g&y9lZAN18hSNImle;OrWiIBcXfE)+mI&NKNsSaYh^RSv>O2P z(2036g1yy>Hz`W222msi#|k7A>-d$ z>%y1U5!8@-_ZY$$V?6Fqm&dzpa3wVZ{yH43RQ5yv^ z%gUWMU==+S7%$AJe*z`e{PaXIAvwE&e2c#fsn(h`Y>(5y=k#*ly zgT~_``Uxl_8ODebn$1~kx6`01$JiI}vsCohr?M^f^4H_Ue*%LZs32g(8_5VynTMVzf%5s6ALX3x*!nvHjH9MBg2ei0s`gg9#d>bf6i4{ z``4uY_dXppC`Yf$W%JT`>HU;5R4*sitS=|6=h4#rFMXgdQb?8`bS|8Q+=M=!Kcv|* zUV6?cAZXI?f6HMKkEY*em}r>|WV{KVq2Ko;jrtqPl~<=Xgsl~qHmsN^v~aL1#Iu&O z$QcPVwH|})h*VLdxv%BQD$tU12Ay*o#@0B}y>P6{;d*t|i2IgnNmvfyUn{%aM?RI0 zCSBAxu1eM}mWPaY4o`|T2Nx+9ltI;3RjzON)4f~pf2My`f2jSEk29mK;f|TZJASrs zBJqDZTewm?NEZgL{3q(5xyoHu^*tisK3jsFl>Xl%L-(;OIoc|r>b6zbHzIl(mZx|4 zJI=%+PPsVFRFg}yK+iS$?ipxhfb~6Pf}qKLZ~kXhe75IXB!Ad<*HwOjY(Cq5@W9w- zyb5I9e>rYcILhF2-HNS^gTf{nX;(l!pLwta^7P|?6#clvMT&k2>$*^*LU)u{KP>_9 z^1FB~$sCB^C<-QMQ$%y<(Yc6Drcz$-vt8ZR=5kiQZhQwS1UZ&vXaI%!6b$c zWMo`quu7hl&Gf2)NeOaH!0`I=N_jAC_1QPbG;jn@1QSQgNyw`3uM?*f~$ z=S?G{Ro5eOBj$a4?wrd98JqRJlcA(ge`iYYJ)b4zqOoyS|5RExV(lP31ao>RF1@mS z@WdEHR1++XbS_`e@IlqBH1c3q6?WsxV=Wk(B z=vdK0 z-qZ8R;3TF~j}OZO(2zKDhIB`pgY{H3$Otrpp)k;elK80$!m~9UX^U71vL*J{EBp+P zjBuRP5f(5sBX1zq6^lW#+McDCf20dn0x-7wp^>idXYwG#nb_~Fwx7UFwR<>b1tn z+w+tw#{Z=2pHJHv$$XFDz0XkYKUH}h3CG~WS_RX~M6Nf78}2ohlhx?Ie+-nful8_Z zh=Y7s&*W{K5*r=1VgH1o+f!eFDI(CpY(3f3yz0=ZdV1q8TT_~9FR^LStUxCHSY9xI!=66_Q%fv zPwVRUzEUO#i?S~La`cWge=(VE;)VRPvotTcwfLmpoXl6Tx~^GsPOs`SKS(x*vzs}> zh$q9N#Y(aIeZwt{qy^FMBHs|!aXRqL_5t!%o9*EPB$f_^-hN6G z!{P(})OR^|fwtB&%HZh_HPW~}ZS7e(Zp*PwfZhy(0xlS-`tqz9f7%LdVvzFEt$T6M zhyDVa;gOl$ADP;3W47gGWrRF?u5;>|wd7ln*J%?t31P=7r?YgN;Lo-a z6I(m3TY)>^P#Tg z`ryTGX(L8RoxV($v9f692C{!BHK$^^2*}wg*aod`CU>WQ}oL zg$OEXRwQ}K+YGz4!}WeJeDVHQtcfLbNE2fQCgX)=_xYl00kPXf(v)?DFPN-^gAM(3 zD`QHygfaVO02NNVK2({V%`s;?BSqWH%(IjufneZTe+vON>lxJ9HWNwMYlUeLsi!jf zlRL!A7zvAGYGC2|Y`5e7qGw_E73RRkZz=*XpgRyjRW!{Sa7yjvh5(_B!?NeyVE9(2 z3VOMDD3TB6x^i9Sgv=OcKa`Mi9f}m?eccYZ-&Dc5F=8oplk7prfq0J25uoXtY;tTl z`2!>tfBQt8*92Ax4{TERJN`o8U}n3!2L~U-vxz5wEmMgFcmg$gO<;3K#xD@Bst(u# z-k7Pa@xeU(sobg!XdjB`$=#!d6^WT7=EL#i0SSl0Z#iqjd)W=vEn~N}R-|k*#PW%# zOMOgpoy$1yjy>(>cpKt6;FUE9|8(cqOVCB?f1*!|Rwp--eEfeORQaKU_w~i{`k zLep*(SdlHarA=l-45gM7GQBlR7Wk&n)r8l~>cFdR!LE~?*4o(X+bewh1Q>~nL0xV3 zFO9B*lk5%#Uw1@rSJD6<^Ef{9yOPQikjL4Fv&*~19kJ=i)(t^Xn4!f5)ow=u)vbLH ze;9cb`KO8d2~8H>d{0r9NeJT_v)Q#1NI|rGWIbc(2u%|6f?i86Cu%9(GnnYN3Wma~ z+QB_^spv|=XC}o0FQu?2Nf+3idRapn+=9zTzSb8jGjx9?bXkoadOrIJY72>l@XGzE zc2X8iJpijpIpaPT$az-sdXaWA@+5n{e-4u~3c`(tbNnej&>5o&Dq`sjJUe@JJ&aeR z2{|v<{_Qc|Qw~8#S>_4M$d7Ed-ufMBw) zSA{mDC#RSA%!|EV4pGbQ<1N@#s%We_yH-C&dRg*ZsFBy0Fn&YJMrhZW(swlFe?Hg` zhY`IRz<+D?EB_;i)cUII@|XnI;1TsdPg)a2rXt;_86CN&4x`7xMd`%$OqHH`cOMB9 z9xaCRz%hL7vwc8n5ghZb7THozwdVFo8}!$Y#9ZqACP)+_dED!<6-^rti+a8uF{=4Z zxeb8jQ{Y5WYU$1p!Ea2QtkccEe`utFPUlo{AZJcS<^nZ<4E%ub0TR?4tF&OJ@BiXH z6G2<{I2-`q)rdz&GX_v5P+fBDXp&$*@yQl{*H>T00fAK8_&wF=1HTR&e=dfk!_NWCW~nN71t-}BFO2u5+_he**|`2MnsUT< zm$!k>Gv}JKu^#6{jv@#;pV(7G&6%!Q*y2^Nfqv;Vkw%Z1i|Y#Aw;%+ncM?r$J^a{2 zG9-050Wj}`cM~xlQ07+0e-t`GA}Gu;UbeUwWI)DOD7&{#+IM{u=6Avyo1W#f4;4G4 zMl;>hPfy81PXVs$*CC|yR_~r?w;L3+O9|IR*b>Q9VYHzF1xUs^t@c|k%0^mbccs+c zi3J_*r-T%{5K6X>->5B4Le;m*bw!bi+0?YO; zeufYEs<83T?s#)6jK?{WeD#Irj4B9_TAc` zy<*gN!W}uBpb%hkNq;)E{>q_4f{ntP;@ed#c~P!ZZFkqm7Uo0zmb^TsH+*D>Zf2g$2JioE_?WzrUikdX#(x!NiIqk2DpQWb2?u!zy-J)8{7@%0e z!oP6~@V{uLtgpL7Dgr!zn>KXG^3@m?0C+Ct(-0xO$7uqT9FSEL+rMhjp#Oc8YgU$K zj1W$YK2h0_)k#HEu^47td^2r(>u4B4yN9V{`h_u1 zfl#&ZKWezJg4J&}ooG9NO|hhzbJ&q-`!6Z8OPd)D-QmYooQW5N+xI((+FssmZFd;8 zRNQ$~ELrR5PN50u0D*h#67zUm5tsBqy(y(6$B9f2=#j(nnbLT@u@jW{Zz4XA$iqoO zv7E54Udmu7f21C@BAE_|4sM#j74;EtvmW#VF zhe}h$YuY|mFJZqUiY7*kabC=uQaZj-D#~u3J(0-#EWa$|iQw99nE;2EwRZb?NGYDY zx=(tiS;84y{Ow_(HVCMnOpn+xA?)zGI>wsSatSFtf9vjv6eznorhIMnt=}S*q2PD5f;Wf zA!ewH9#KfV@RcM8AR4kh)=EBmVuojfK{-Zt1?-+*J7#uEkz~E+d3KJX#dz>Z>3hLD z_s@j=f6>3Ff6GVEjj#R6(AT-j_A@EM^-HBECd#*Ux&#Uf#~SMJ9;I2TgN^-MCWV0o zl;wl_M=9at(|H5^@Gz!eC1sK&LL ze{}W@pNushOj_BItncH-!e*S3$q&HS!(AA%G%f_6lqZ=hf09^RR7CWDSEZ0OK;l?F z&N0ck;O4E-4`mkphY_jykrT0CrS8yj(1UPnjTE7rYs#6xB39an;q?$f_Pu4)BQ#;!r!-m_rI8k?dHtFshkZnlI0dar;Ll}C zC$0Mlms2v^+)yH2FSHYQgyq{#_q3{7-Rll0aqQI5Koi9X7E4O$9N3$@E#Yp2f9rs< zm?ATgR|MDUQctcsywp?*qmkc_k)!rOrC=|%N_%I=1lzd_ChG54-4xfh5cFzHn~;D#TWe*9nq_&mTi(c^)Y?$Y&9)d zHfVArUIPQg@0DGd8T>mqfB1%?kymR(Qo>bZsdw8$p_K+)Iee+CUr6NCIh58E`3yN2-76f661uND}#{-+M>)-R3MXTzmi-?e8fVv_?E$xVfN1J=Ls?X|{6_ zS=u6Q1?6HukDSR+&kN`9ow>DKMH>?ZbeB|RFo{=kxf$55By@M2*>q}Dh8whMavj&% zZ=gquY*1X$<-PD1>YhhRbweo@oh>L3t30jF{&yN$+tfUtfBTsLB}@BAp;umpIuF#7 z$4KJVWF2%Ag_L8%YWnx7im?s_Wrp3KhxU;Ds~{n|e;dM;z~J>X6@CXW#eQ#3Y0s6J zH~b|pZhz>6#w~jc2@QFFomS|9Kva@`uJiUzhVHnB+PaO^zI+qR5H_b~*l;DA)tj&Q z0SO3?)aD{!e-|#h>#PP9qYCshcD7&(|J=}RXLY{3e$U%=`zY~xiL>(#w%2nGDV$0K zAI0LU<@PZlp3F8{VU%OG%TvQYS`%-^=|o==kR(p{Rpvlnu2|g&^2se9C@~+uw~iz z44}f0JRlTHJ5tXB##rL6<8YEtB=nFqqoYh#lzO5kO@#7GlnK{O3wj|fM7?}HJeSZW z+!F~I(VLnZjg=t=H}PtOiyJ#uLF7hm=MI<+e>?P+cXx7Zn+nTj()q1%ER+%PIDa;| z!|&mKt3i{D9JAhk!dOl5iA_!yJ_07r7*Vr^>YV!2K0e4LwYRhO>RYKTW5M zy-{6ha{kDqWPX4Y<{5)*`!(X#;*r1N2%O;d@g~B6m3+P>qcx`6t<|6ywM{~{>gndO z@Gej|7I0f3kD`4Rs&#P7Xr}>`&Z1W*e|r;5L6YC(q!A7&eIuz5M_SJY_8(xbf}2DA zT3QSsg~9`g6wF3s5n7p!Ybh6zx%K8+v!#7gP1`VU3P+P#fGdbd$ttq=aJU}Xg2I>H zz~6gas;IE~cf4+F6`AB+tkTE(Nfmha3YEE!>FJOV>q+)ee#XsIPOjd)3PyY8e~6Q( zR@6#Yr43)k8@7EqnDyd`fU!`t-V{%|AI-D*k!olr5pCX9a)ajItDCVaPlmTIlI1l2 z>_I3jh_8*Q{!_Z8#Jo+XJM254wwQA2NOxjuMiyZcoFO7+p7y=rCQM384d zu)X3Q$J0`bqjBUL@QdR^?xh^@f57}T5jcj1Y$9YstKrjAx>r!M=&&f8P|<2EEMCq# zGD}O#+iklN3--moBNNW}+0S|@t1g*I!HcjA^98MsQCrkxSU}@`UeiD+M%9K;cQ9ZW zXBcP*xepgT)%0sOq`r#;_p1~=rPj|)j#Hrdz2FVFCgExkU3z1V&ged^e<7Fleo;#; zVyAJp%g!}6w6E=e#r9p0vbA&C8?A?zeg)p+yfu9|RRbIStH`Qd95tu+@`1974Do^) z4jRcHtaYao&%`wTdzcd(FQx55>2K-2>W79)rBv(V22tbmWjc2gG3|L%3T=a-kupDW zMv}OPvkg#bpzrT(!0C`~i37h94z>=V&`Y`70+mrGuQ%}=WFPL2xY)*5d zbGD}h8Ien9MB&7se4>92mH9V&*creTJGH|-2xTVZ?#9=(j7_{eLUu_TAN5GshIeE01F6ftPg(Jt7BG$T5eRgveg3U ztpgCk7p)~$B_BL$UT-&DgL+wfk!8ahw%c{L6kRg}z#^L>e_NCeV_R*cDwDvvQ(zrx zlJ-o)`G#NtnOwsEvP@6q$Pj_2URNrc>GW;-y6D|u)w%%}tn7v>Se9r+KyaSW)WAxo zg$fk=b2MKIJyrHqBSQSMA>1Y;jy3t__)cezPMUZ~5r*J74@o8u>69J~gU&zL`1uOx z#}ralM6Q3)f0-LE$Y}%1dhJO>j}7>a=+jCxR1UY2MJg;afS7tpi4r~_*CY|7TXU$h zbgR(ZaX8A@NF<$maYqMVY=u0RQEWZhQC>d+^Sr0#+8;d1j#$$2ZMs{sm}3bX_Ckwe z?e%G3P?vNxTufV5Rk4-6>8g=sZ}2GJlo~FKrjiFiBi@)^9xL-}Wyi_L9;5;1P(cF^ zdWFKAe`#qh{DVB2lQy)O?Im&#zsqm)rDwzT>vtM6{m)*^J+oCiDTIo;Jumg^MAkYT z?8ARQL~ZGPb$(4YeoS7G`zD0mjOUlZ)}QHjW7NcuF(66z+CQoafK{?9q)!jw z8f=utIB>UXrX69qn<^);UgrwIt+Fg7`Lyovoak0XMmuSG-837lp!UPK@3fxae`^F~ z!=reYqGD|4xRAKjC~peM&E4ygb>?8Up}yH6`9SYb`mz!V>2CPN7t@do$Ey5`erzMT z9s~cNIkR)}CdC=mR4WzN;va~$tGO6zhD(oy*7HN%TYKF#UJ_Nv0lt`dB(R^$ST8TQ zGzWqZbV!@~jlWxEVRbGRr^cWqe>O0gvz3WP2`DSGE%fs{@HR>CrFB>z=PZ0*;cn=D zK*ltm(tSi;sQZKoSpDf^DJlJ@j}>S0HxFC<b2p+qc;tT>63=M@5!qpoH z`dI_ZJJgl-yUe+CmUn&4p2NC9G(aG0dUG0C&b$j$5N=IiLh9JOb(rGY%q zHvO?T?O?vt!@5XiuP6<5FcFXgt7?V|)$Q^b9O;HUiI0Bfqi(?++Efoi_ojDoPU_@e z{paU0d~Gi?mijbli-RI^J7r+j?-vYE;3k6Fqy`r6=z9-%9y8DJ4> z9MxF314pty z-k{jCY3K0N&PqqAmzPgAMVcQ)czcmFv3z@!Sn-cB)N=AqJ?NjsGT%6Xly9TCBdOL8 zY%IrMIC(PzTWX?b+DCh&QyYSF_Eal>vEw*vpX{K?e@$NBA@WGyU%Vdn!dK;D6+(j9 zq?a#GvqFuLUmjqHHUTmw`&4EDN9o+7)!mzu@1hAAp*ffGmL1?H$EfXEJ^$PXh)a)2 zlEy&4g<_De#5LDB3EvmdN5Jdp{;m7Z&5SuYbX6vi!GO?LY##oL=3;=c(qjrp)S*oCnHMVnr4i!tX*GLfGyQW+Y z*uzdr0e3IVeAUcOF7$Gf1K#-e0!C{8agMc>a{OH~8Kb{(6*RTqYdCdUkq6mDY!)tR zE^QTFs>Y6o@YrHI_>Gif5cAVCDZip8T@+Fe2b9mejZiBcv4*$ z^=yaO0S)0W(#|!1_&n+Oo0YOwb60jw&$qojaZLU3X!A$~^%($M+2FH}O{UwM_ zf4T!K4!Fgdc?Pa+>8eGk=1HA-rpfZYfSrm~zcpD|ZVNR?=V;GdQI-aimiQ3 z2{14CZTkVSl${RGU`$R05{R&vT4*b{6&40(B{Z!j%xp4TP{vfnRHACEoA=0=+nMy= zp7{HHR*NaG;`xFg;t`q))|nht!5>HLjqGofXa=E*WCWVZy%KuQQns+4MNZ8^xLW=gxZ{fR47eP0kuu*zns zrXW#2A`cYvjt~!7j5;q%hpUC#d49fm92aoAv;CH}%-3Ha)m;9CY2@``boiU8BzdRU56+~r+)>S)9?n$%pQP)=*tRrG=s{@4o=jI#NvhH zwXxYh@)?s;7lgF6OyMELaR@y|@2AI>2Gai@e@Q|Fd06=Q-oR)qzPBFYi^DEWSgkC? z*$T7|FxY#K1+Th+K*cqt$J7Iq5@?BnSWxBVy(0ZSqxEt+;D3^^qCDDW-LV)t-+vK= z!+4%Qb)_Hi(9e{K4)Tgt5fKa<_xST0cGlaaT-v>^(%9MSQ&^Y~4M6f-vDi^&rfo_x z$4_j33R4W{k9c(Hq_(z$#ulbqbgz<=XV+cvs)<3rGZv7Hexu7PAU4?xseGkf(8XdQnz6omw#;wm{K=h;*RSBP5VZ_p%AGSwIn@jb~%yq4V9^5 z9e5%bBB>y^v&vt|Av$zpZA=hQ&866lqAThcR!FLnr^FRK* zdud43d+=2WweJmmttGEkXB{rM63>OZXiOnVpqslJyWC)dv6d(-X{TyB;(tk{OS=OM zn_v!ny4sK-K-^yR40BOYCn6<^lJXSD7#Bt=M8>j{)-op%1ZBi?2*N4AKLOa|`XtKj zL)cmvOtkT}Iuao$6fHJ4?{gzMs_}b!@d-cYC_%FHj`^)+;bKXIXmpBoX$AVbToZrt zgR$K2YbK?IXz`ht(lbVk%YWDPD8kH!D>6E8N-6a#FV}e(zk_6mL@FL~x~~Io10UO+7P0`@aHC%siNUf6dGK@)grVZ|iBOt$VZMF?;#od$grGN$1TxCBztN?0 zxjxuIbu9}&^b?iJ9CUxX2fU~rJWEqB#n;A^p&Rx;cPKxT5t}86-hU3~RUO=1G*hrR z2#LVZ>Ctz35i`yXQhBXtx8sDHh3@5_)+hS(-R3M!uFiqCWR2It^=(;r1`fof+RHGE zng0AG6YuF`WYgfCl#d!iF`7}bIaq|2{7y@3!D?TQ)!Pz{`G_#@amJMyhG=Heu}6YZ zMCW`?6;>C#oU)N^Yk#RTypN!O)9c*Sp)`ZDdWb_N>_$Az`{t+!k;w+BzI7@)MAXeY z)Nv_?x9>)*ri30;^2jWqys6fuFMd>B3 zSg7P(l4AIiR@w>?%RJqLD-C8_g=*fH>kjfU{H z!?3#2?-}JJ34eWp)D0sylN_`ni9@arGkGmPZx%!ZVSYcOTW2+QQi7DACalME)jO%5 zNpug2zHR!k0=IK22}W>XuhqElY4xRODS zi!&^$VJ5+m5zl0aF^rX1abmZ?NfDd1Pk{Jt43tN68eT2zG_+a{eW3{k0>}%XN2I3# zywsmOyBE-vf?FRe>bD4ZFsusTQeWwAzt{i~440W^0xFl_GXo2^>iPoTIG3u80wTBT zGXt#?m&y797MHF^0}KN+F*KLaW&#xjGBh?hHsy$cLrXZ2Dw{ubVbO5q2urM<7 z0@NhcWmuSbH~`FyY;Y75VopF~7b|-^abp)CFF*@u22cY!09aT7tjx?Ta1;PBdk0S^ zD+@~(0DrY9&A);GO&en~D_bikfTq2Ty_=P(C4k?}%}v){j$(iwA1nk^^PA>ltGk3DL1t>_Ui%2Rds(%9{#F*5@0LFG^0D0+uUbk~`=KTi^ zGV@e-ZzNi`ZHGBOL<^J0mmuzvEWUl2#r-Gi586e*`x-w)sb>f5o+c z|2`cBpqZ7c?Y|cR{-er2=W1qeXXE*Q_x-1sf9=YoE+Qr+sYv&qHuzUs!p_v*%*xIJ zpyu+AqQ*{U{|Wpnt!!-d?;Zj$|Ic#&@_$+W$5$|RakBCN=rS|@SCcUR*Yn?&{{Nsv zMeRMj8F<(M3~a2-02cOt06c75zWh;TYJ9ZeFhzl!%-LRM+vSG)7BQt;LgZg2ykiEC@B2yq*6?~<{(5u{8z&7PHe zQ7h|MCV(o%5^Yr8IRJ^W8^6BvXeULZPlcAL^A`blNLPb0Zy8c}VSy&P1a2%%nhl56{M;xB&_J5Bu#%UIVERmoMYD@3EAwgDxdGDHYf7#2layq^H zwx7p?vY6mao#@P6^40Uf)oar8-_y+eSAG5avy0uexKB(w8Z7G9X%C3IpC(J4;Ypm; z)>{W{s}KRx_%!xelWDtb+l`*9cbx*6?uCNJ7f^aFAmQDqlUu3&2Pwsi#`a#XO-SOHKPK#ND%>fKNl#G3%vB6 z`_!n~Ihd9vRC*m;4tr3zSZ=9Xbcg8hipA5-NctaVb(r0`obk_TCVy*B;-Z+Kpdj5K z&+|Bscd=Thln+NGxY)kE@>6{^V%sfQS)R@HfxIW(q1D#>0U2$f3}GsaHfqfpEzNtNizY&pi&Q z7cCf5m-J31eh$Ah^M9t-vYvxEtES7=@lrV9{P~atcrQaPwJ9n4P04H+d^+Br5(s#1>zWpP203@iJk8c)4}K(kDd6- z8~(l%UE(m+3g^`Et4ig3WV{`S4n3gBVK&+c%Ut(H$*Sbe-hVH9E+�(B&#Avb)fX z%|bY+(1$ycyW*Ul%0TB^qwYq@&-G`c-@!XfLq8oaAx4|Cx8UJ}{p!(Ez|7XxU@Agv zr~s>uTOP@mz)Y}dlqb@ENFC&hI~9t&YU+eBuTghXQNW{H!f*exHNkMf-PN=hiU=b81oT6V8?}YP4NnTQ>+RJ14nh4X8s0yPa`08I*T8? zs&c619{x1~)`R$EWN2%Ejv2(IroYuw`3aIPH1(C0uWHM^@XQ`y()7B_aOx!OchP1> z(3e6?H!wliKW6|5Q`y>*79?it?Rdf{f>CKogN!l}aet7%ZK~VFS7rw)tZ+wml1`6< zraQB>Ldb3*USUuJ)Qa0>L+kO zL}M|jNX`#pk;b!-^H1q~K~%1l0&0Rv zb>gK5b!9MzErEou@1}sq1$W-hN9%{kP$g9|Xgc}ni}Dec-JhvrDt8z;DsAm+xy^}d zef*S8#UGyb+8RV<$r1Wc+Yns)sY&ye$MNKwf`5WwSyf3+1amE#5KrVQrNl#Mv>biE zKT?H3Jm_2cV&snDAr+3gHctXJzB@;f?1@lBW*%A-iwLs^4b0(D;ud>b8v5Ita;0&& zg4q?OQV-RZ+QTF_vYYs-%Wesj;$FLOByah-#JwYCd!TOBq4p%rilAg(8sa6Ud+M$E!vWo{_dh9<15Qlt)S&Kdl! z!TPPk@66KrD1}kZcgrWxG-N54S4bMu+~p~NfTkPgI#~Z17C}}eH135Ov(L%kRxkDY z4FP)P!6gf5AmT1*gUV?ioOUwn1HdUQW`6~*Wra?&*-dW*Wx2hc-VI!}o)y7TWm)R` zUApm#HL|}K5D8lK6X(3m*87J9KK(9Hxhm*&@LycG=S@Md#L0v|JVOybuN%zHQC;_N z2uP-?FiwIXPD$Rzvgb*ro&#O{7tN>8JZ1{Wk-&K`5aZjke(Q3Rn9F{FR!TmSa-HF_AATCf4jWZhh3Xeo5A-VzCDaCLA|cB z=?`~F&xKm+JY)Em2#~k+hNjdsm49q9m6Y-RQ2V82`u@7MDAty;65EGL9lf(38_Y*- z)d;f za$N#DESZsdA=%Wa=>bTt7T`~r+1(@b$N6>&onrx9P#E5U&<47k*WeFHIW-o!2J33N3wn9Xe8pLg4|@DXgxCHP;{DP5#F?#)*;a%erNh(n z!MNvZEMbs}LiqVD9N^tuJ;BTZ3c{aMD%{xmlUC|RKxnOM@))X^BY)Yf42KqtG}VBq zB>$U{R%x->in!KGRsti+#|9I$Lwr=HKdg(SvT(R z!p#{y3+x(4&yXwuv9J>bt1_D&U07n^A>Qy{-*bmn{Q%gA5=*|gMXJaNkA!IpDU4eh z5B2505HyzxdGSi==70P$e8?h$G2l$AF8O2&6+^a(DSJU7yyir)mvD+q{8yU5r^4yn zB8R({D3v+ADjVh(4eFLO|I8#vVPPYJg7e}$JfgrINsBVe;njf^Z0-H-&pkZr39(kT z=aV|Siqp#F2L5m#u8aCa}TrlgF09y zWpHitL$(SWFMlD^?iXULLyPc*a_Uef5Cl}j$O*Uh`Ey~9cYpW20dA4B};SMI}+KX z@+S6EDlomhO2ZbG1G~iMg0LW~Rwk*N*87(sK!cD+Dt|CIgtAm6Q;RD!@iDS<(1KM{ zKN~rymtAj)x}*BHeib!=e`qb*=f@`Lof_g>6{#}bCR5`Ajv3{h6gL?&uLPaAl+1<2G7Mt$@PQOr7ER3;oQp%m;cb>EaUu=;*5?uxo zGo_DfBY#Elu{Z4m$BTp+Q^8m~ASCpJf9<0>{IYx#(G9~5yJt(y`n?ds9qU9AdNYh& zX)Vp&kT?&*5SPO*ertKWpNT}N?Kr_=xISEDbu0j1t0Iq9jrPUpgEH=)TvY=feLoKo z^==Q^w<00Hy6#a8Uj-sNs^%+NW|ys}=Ze!#1AmDSjBk!mcpSy`+GkBe8O0%ar{QAt z2lt|(7DgI)bXqObS+%&^vb9=`XZQvro5@cKQ_~_UzIqRY;J=PS^g?ir@NDTJy9E#7 zZ2)?8Ztx3|%P8kZJ0rY;j&w@)TS%Fc5!K9D*0VTapMhJ6CG82f>2->s3+rn!K2XIyKQ0V_9%VKAbj+% zcCnOEYi-fEnbO6K{o0(}7;8Sd8oy|ry}V=6_KA^02E_Rp{>s~#gG~iHHQ$Le(1#+h z(Jg=7;lK%6he_vF0lT8dG`uK{eZQ;}cV5bv@0sYU2vqII{_ClxH z6McRw56vHoYTAI~F+FatD^D8NH&kIWC%AmvB^0s53S!FQdt9`B@HDpCz%qJDu6m`a zikB(A!-$0kb0QPg^P!JPEOseMKiNT(1oAExhTSE*UF{Yh>`}cce_I9m*QGTXlYg)j zHX&>m#j290OdYi1Qr{X2e->8so+UqTe!B5b?+;du{hj6BWbGM<`}2f8<}g)rk3rVd zZL2B(6&K=eCMj0gC7tzXccV?s9<6&x-ll@pMUAKH-bq1|aU-Q~cf|AYC|ww>#dG*b#$NlSfKt4DajjPb2@nY7`*52PEB+Yz~vs)$$*2 zB}`(GY`=yMmox!EkY*VolHr#OcLOg&iwEiY17-b0yo^wW<72RV?gUJUrlgp)X1Y=L6T$O`E8OQMjuUmLqY4+B}JSp>Qip7Q)Vi zJPG5Q*qw!qR`syLj+e9D0WD$RmEK`o#@57d9s+s?7ZzHxjHuVmWu2@kep#91-p#g8 zBth6BWS6GQi7ZxVTdlED)ygUfx8*_0T?KpV1zdc_eo&~07sP&*?0?2r8PSiYhQ8(S zD}!66C5WvkEAV2o@?~*hOP)v|@|izv-tYaewHl=-Hh)TW6z`7KI5!myJ$qjfQ(t)# zv^>JB#`Ad{{k_iGu8|rHs&P^W7u8+I^jHTY$k`YMMD6BCxatL8UWG84+ZV#oC1;61 zkHfOXAu%#_L6ZN45q~A6q?FF+r2ldbn!!;z7Knk5AwoobRCDet?zsu4Fgi4sd8tQ% z)qnF6a`m$!c;zqHb0Ff^m;HJ1D#ov{b%VPkgfV>`_rlwZz|8oSZp-mDWhtS4LN~sx z?W9tv5KTqkMV*1Ni(NQ zr66wJ4w%X~>!N(6cr9{>E1oXIF21(=q#`q+{o0sY&%G4E`y4srV9$j`^&xEe>_~wt zhg+>aHu@soA21IXd_1JqSM|#rPwx-GJ8oX;tYo$JaMGj*eS;*;6%YM&ps0iWZQO$5 zUFU4Vf~J$Irhhbp(m_Ytf#zNNaHAC_>n!1*>(JxQB%S-oWY@SDUuFoZqAaHPkc6Vt z)s+6tmrz*eifJ5qrMVpGIt69ydb!sf&Dh{YYwx}10nTP;HH8zkMvPT?!RjI< z!!H}F`uKq&Gc=(D%GAXYcguMnf?&rIz?1*@6^fED5|IDtyVUsGZ8Es># zQR=(2aDSRa1+SDrFDOkKjLh#H&@;I^e;Q@`-W+Ee5LrZ(mXE?;(qwOxFDoYai}z&N z0zG;I^<^Aqk4RuD&wBiU%Eo>*AtltPP`o(1M6r$OhlW)>5rqSOZAG<#FFC9V|9iT} z;wM7ku?01_Y6`z7_>$On9%z;$MNQ91M{g`>Dz8=>`rU@Wnl+PMvd0v? z-T+;WwRi7PA^^2Q?N621L4$1oIfZ}Ci$54@@Tna<$RrQEB-brd5jDE=31KO(osS39 znb^x~Dig*f{*A}bxOx2nxItoKa|dnI60a&zC1;UwhY!3TP@Y?%0pvJrd4`R{^datR zzkdM|x%24+Q7FJ{RsKM)t7$h#DH+(EP?&8EdW}o46EB1YG2frXz{w9wXMc{PP+|)V zOn0cVzKzQ*iq_A@8Z4zsoI^wxy>aXd40+RDe$G!|!T!t^FXA$beCM#%d(ag`YVP-% z1#Q5%|44w5;pOAi=4IkrF}R=cA-m}M@_)y}zHF`mFR>H26lt~x7V4#vHhWZyu-x(r zLqOVj%U}M8-L8=8Dd-JHk&?6qw}~BI%kY^-?rz9f1PiG|UgEQa?k|<37J^Agg1xRf2o38FdfpPev%%pxuC&L_B zF5GPM$baFcC$ZLbWV4k2`!~xkP^Wn+EeNI~K4~kJqs`tdl-D3-g4vL>5}^Hn<+<2dbW$ zqo#~mTQA$mI4L25?;Vj;x_{TCQXwOdt#mM&b~5S%Z2V0!hO?{ixkb!Zc}%!T6PZ8C z^qYZnhmnIqcYGrKzg&isALXVJ4b)lsnr2TlqQ5yt05m?7+y+0P73dv~)0qIPEtT|P(Ckfn zVv3v3?F%?{?eoakaet!*N2>%A-th_`xZ8~(ogly}BKxw}`zBVek|_SC$~q zKsxP+lO+9B>o~n*QYpZnQI3B!3oQKW@C!&5R@Ta+7hP zpWG&>Veb2Fb9LmUeDPryL?NkM3u=ii45ql3PKcwtAEX@D2t!9=e0ulAlXCHGWL{b5PK4&G23-l|+ng}3|j$xO55r+CUtId5YeEin1o}+!$$`DH}vTzG+-e2G=CuH;p?7r_mnzFSORKD;@K(+d4h}Z zUYFiua!tCu;ZKZ}U~z~<(i~pESs8jG&76m4PUM$v-cB&5rr-S;@z`s3z8{N|Lldr8@v9sLC1aO7)jBzScca|9nSA}bYnuN857`W6 z&|M~O&K<7Jcdh+f4M>EH1RwO-_v)gL0)J-PMFfH2RqZfG{f=5T^fzHPL_>pA>q=+` z=dh&9*XBV*GcNR$Fkfu>kc`}rCMd>t;s=U9V?qjnT)}LS;b&oACMMoPc@_VQBI}2O zTIt%58d>s}Ese=k!oU%YbsdM8 zb|agdEhv^#{ZrQ9t;R=M<(AJ|8@awT=MusVniuL2WhGo)c)@c^hJ%`J_SdTjtu(vr3!hcY*SUt19 zv@2ZYYceiPguJ-k!Cj|%Pbhzq@5fS)k<)a)t>*f%`Eam`Ta4L zn-hqo%&}I0cOQMEOnQdX?0>6?aO~U7l*TXJ5b5>pS#19!QaS1WlhqNXT~{n7H2Zw) zwcdSj>mDs0s+g*!`s9Mw0Z;>osd}h4G}2lU#S2GjXF1U zknbl4X3B3#_OZO6;+4r+eb#t*BK^~!YD-YDeMxIt{lS?hXPtmBIe$K0=nMfty%amK z(V^ICgBMj_h~^nMaK|xmDie`smDxjE_<~}E#+ds0QoJ7Elkxi1BpjolKH39`Zw^;< z|E8W#RMHVxJFoWmPM-tYxx8QT0dugL)mQm`(C=0M9zwyrSJn?zRUssc#9_RqK}Rk_ zvh`UX)x-vAWMAg%4}a^=ckd*f=DUwg{3qg)d1z|Jt~5E^n7|(;R^kt(&km}8IV{qN zDeGivfXM6i2mPYzizBS* zDH{a$VS1yh2!BX_%BSOJ^r_yD%Gox!>8iQzg2@~=o#=HWRnElpfI54wkCwmlE!k6@ ze~T9C#FW&BWw9|Vy>mGTt3X%I`{@3N`L3iFbXxN^{&OGPM+1mE598$ z5~^9kz?ZX?Q<#>=NAre4Ub@wYR7-z92hs#63wU|jI-0yQb!!A4uug%JexK;bFl|K| zJqK<>pXr0GPqwe%ZTI))Yj&*fAn_T<7%)5h-F50JHx_tIsSo?k<)hani7tDeb0RTj1Dkvc|2pX z;+PilbToCf%HQu}su`L#F#{NAa7(ii^OtYdOU^Bl3qNV> zx7sxfs(nqc3%Q4E-n??w`AYfTc5wKo-hT~Il{dMf#Kngx@LqHlo{8of!uiBSoRKzu z9=Bo6-k*uOt(p@=+l&3RsX++pFPF+`l3jNMvkRtSV1X;6K55a%%u z@^x6(Tv~lwKq7D%r>Hw`q4t?t6iW=i$1;uti*72rusPox4iOSjSb#hirhWIy{(n5A zabC(1(mzj$e_fN#h6aU`eTeR_Qi!vh=NbfNJc z!wK^%yHg8I%wg(Q-5JPPpG@6t27gXd!l5nOFm&oQwJnRE$EcNFpiyU%BFp}2x8ppA za-|eeZ)Edk$y$(prHaq9HAclmDAf)E#+;yQu5EB|Kw+X+P{V z-jcQSJm6S?G$)bieG&8Pf8SG4!K+)!IvCL{1=7h>aFXI?wE-l{VTsWl>wooso(0`{ z)6=@COZ%KoOh9*_Vd=}F(q(r-Mp<~A<{ev&T=0dHuj7~E21?oW?YPa^?`hl&$U{1n zp-DkCYGPlSCZI;1Oj_!E?yf=PkZ~>@Ux(TLz-upP?8L_Ab%&(nW7;YG_7Rl?XeD1RY+XJdu{OCRpw zZ-@#0Dgw*M!{ZU`8w+vGV;vgQXMaQEI%ATaw-_AaLoln?-%h0kCWiv!{%~8c-Vua; zqHcFw&&77_2ftQKDxERf&kJi+^55{>fqRZ|&U=NutqzJzD!kx&8OF3Hn*mar7GwBQ z;sr-=RGplCMS~d^@zv6VPA{tBuYN$M}*VaBx>;1Y4`dS$g2)ESu!az=JFHHD;WJt3g-uTMu50$%LauCFoArV%sO`P|G!E|%I&OeYd)TQ zRn8i%l!9arn90p_6npZ9zULcdr+hQdHtm=X%Bx9?RXk~BjBJ*X-HmlG%Njj&X5FQ7 z^^}THNFTZhPf*)JWr?O(LXTssjF1q^X z3q{}8Oa?7py;Xal1!nz5idCVC)f+j)bAw#Yfbi?*n}ZZr@^(Qs7i}6FWw_jN0I|$( zFRh!({(q0{D;%_j`B$b_mMnh{%rM{I%}WQ7kY_mao*zipMK>=<&3j0R3&o#Q5NA_) zkBg1wy4&}s*BybX_4fB|g~*D@sxjN%ZN4(s;Z|7!z3r-!-~oT0{T@2|VH&}K93^#I zcv7YUg9(n+2whI9(Ms>sLty(bj4a; z1ao#~>9`(lKQg(9FUzeXeQ^^aeEoFYN##*^VEaj!TcAFq*nHDfTdG5TWLVJoZLsP^ z^<0Rozo)uZlW@@*144Fiu2ynqTME6-5uTFf6&V`r^AVvMozwTUfA`6B&@dPpp-hD$<{N zKia(UbelO6*qs>I1j{`O%;2x0JN{UGEY?aKlC54WBW1#@i>}2l7G0>2rjZ& zo=lo1^vTVm$8dCdB#nZ98DKKT%mSsAB6D@{HPUDo5EWy#JCxx{O>Eu?>0|PkO#WPy zq3rb59$yMYYlBTN=lAsc`N?Y9jjaaJ+;ec2bL3&d>57U|< zDKQ%R^SN^AJ*_loOHTF}!Tabce*{n_1wuJCJ7Uy09#tkfaWD53A}aubIgEH}J95$C z9MaNl!IVnXI}TD5O57PcQL~cj)1!KFg-V#HY8V5GK@_juSQsFd`G2C#+VxyAJiw;p zGU6=CZJ7wmv=d}T42c_fheWQvhAq%*hWmrz3W7~!(bc1r;;85*9mD4F`)vQWh4Ah1*HGmQH!op z1UE$>#>lS1!?d$YJAVW-nd`iJ@#w@d1-js>G%gR{Wr=Y%+9%Ha6+$cwFO#cLoJV7$ z5BaOM>xy4C%&vP>R-hl{^&$q0W6V^vq6|GB(#7cG2tt{m2A)K|K%Pn{hox3n`skR( zSqod+mX1lZhW;2*FvKS)e~sWJ*@i2bg! z8j{732x{Vm?O}i6F?$Lq+nlW6&|kyRv^tAShmu^VY%nxQE02`nq1u4kOg{kn|NQAg z2yWqv?%>z?w0}R>Ur0P^fpYzar@7UeGg&@WBHokT1NuoDCy)eMjJPTxB9vCExT!;> zX=*w5F?Oc*Jk>1tflx)&d!5kGCzl48Z9OZ_l?_fH#4=L%MXW@5V4`nRU-VP5p}2BT zSfAKNSJ#Rki}O*_mA*)&U291-KXHy5ekh1xTV$VXHGdmH@-QPqIgA)Egm*+7ty*iO zgPh7c#=-`A$Se<#B02ZGv<+D>!(pr^P$OnO7I%+_kYWKnu>h+Nh|)oc#ENJZcykPVG;-Nd2$`5pdw7zJiE-o4Od=ju9K$c62TD+d}+r_ zWEe#!K7UG?k2rmij(}{@gK;eX`zCEj zwu)YR^-)@uj)4EyUR424YW9_n?)EgzW2W?Q(Xa&OXfQK-Xy4CD2XL|+hX~Fbdzn51+Cm^KAH!;1k$DK0Q4sXg}Q{QCqDuSVZw2)`)))|FL zG2bkRH*X=J{aQBHU0k7V^Bn#8mcnN@a-Q_(tzotoXB4qIUm*3N^Yak&#}_JviGLhL zubGyjdMY9sa)75FHjFK=yWHuuxCCqvg|l0P^eVZ^T6sj zD;&+H8`TM07a*1grhQKoKIcNu&{Ux7C1(iF$$z|F(7ht- zB_D#N$D(7x=GM_4{lUYS<2k~8qq$Uhss};D7L|?WCr1RYlV2@pFX9&E}zbcr&nDyyqa zgm%1rXBePHuohEZ;OjY4Uua(zrggF~8QB|#X0)a$?!9G&`mOVsOOVL9q8Ta1OW+v# z)Je7N8h7OEjF13T&kH!`k6kLJ_8z*=;dPuvph%*Lkf00{z4^NwFMpfUNU~aJ9~=}4 zUM7Ojyyx#QQrTm2c22Ufzlygi&3jdA-&>(v!QwZvmgMbB=gyD3Mw^aU_t?Mn9Uz^K zVXwihQ7T$swOL;>vmFYuX{5s=CFV>RV7PA&6NRcxO==Em)xT4M<|u2SRVQp|H;}67 zg^G|ZVY|jmQK>~4NPlfE8;4G5Mlw(Zz!&>gy{WKQe07!W9d<;ZOd3#7xTV|hS4@gZ zf;l~}XM;Gy+A++Z_eD9uHEbCp3Ve0u2oO{>Y!d`P2On+?tP#2yd&68^AfjY4w zB)pDo7TdUL)$6+@=)d`g41W};tkO9}U#cy4fDuX~9o076m;Yf zS7$VP{wAjvWPbx{>JgcxNME^K{Qhl&XKA8)#N{DsVQwE$fE_=yX#Ye)OEQVV_hw-z zPn<4^iHQge@%kb?xJq5SXQ__fT-i^F*`z?$&ps{-tm?J|7lPkNbF;V~dWv29E8>if zcs4}!E(8|!1#~YVb9X_d??)||Vo~iJrkjg^BkduBdw-%22MnLu2dt7Jm83w}fx9-0 zE-cutBy2z~yO}d=NF~nLbFLzuQ6`xN=y7RRf5+Jl;oro0_|amY`W0eXih{Le-=C1H(_v~MyCC;%WY%jBxaNIC_*=_7M|NCOnfrIZ9 z8npP_N`DxfM|Q<0xVWUg{?mNxpF9r{P@_Ml=Zw_6v>UBVIE zPimu1ZRdjACN$Kjw}K!l&S8=6Kkoq7eSc;WFnjUtbx?;0vU~A97#?NQLRw@8*+3a%fo2vdHXkm2|emn=fUNNY*S9E-)_l zM0OsR2oD@P48zhV?Il^#PfO-7jPAmEP0?Paa?@I}gMOeOIxqAo$gPjZ&&MbIs~v(v zw|`?%ac7`?tplxbm7UtMf$(L@USzK`c{lB%+lfve;C^ipB5!1XU2(9hz{^O;bwc9& zqGwXBwpV-d2O*ndM+#QhcBNN_{YFi83Fy61;`{2yf&~*5rUfIpJCiFz#Q`=v)9ofB zJv@;IxFfIAhAyVwgH_LL*;?g2E|U1mP} z(#HE8SIQq+8_h`h++#xc9h3}naQS*0UNFT|7RE^_&DJt=A=TC=ufP()M}X$sHr_}m zuV2@#*f)RrZC~X}Eu0BfQY*J~M_D$@exrHj_*ib5Ea(Sn=ww29uY)aQZhuxaSxp}v z$H!DEy<(}iSx0{d2ieBG!aRod7ygZQBXv1Myxxc2o!@|{_2wi`5G3sCu9*oaJb`rK zzP6wgoz@bUl73IzXkZ3785ZB()9m@@+w4$Uaq}*$Af`OQCcW@&;sG4==NoZ2%v7aR z+u_%b;)sLkSCp=`+o<611y-z?1MO_r5ihfEG%i8f!`yZ5}WsHzR3vGZcZ&0@u1M3FYQQ76u+_#mh=&=kv!nZ= zhhmanQ(^1=N`^omi7RP`Y3gCNSj=Gn$Tmn=nRzL)X71F}=m7 zM`xbVbMHC7pJ!|WeScXCG?j=(pV~9v`O1H2HK16elAQeNm695hMxpl}{8UT*dvMu@ zX$n)HiYk%YXKbn3Cp;VKROG#Wml5M4X5Q#K5!>~oj9R0GV#Mh(1-t14^`l0&Blo0v zeAx-zZT1}PoIp6HS(#n-?`Rw++h)T*V?ftXOuFU;6>+?PKYxXBhY#-J5i5M1#UznF`#Qh13ti za0Xf!sbziuu)ET<@9iVlsTI_Z2_E~}_RS=5E%)|`a$jZfBc=qDYu0DD6U`{5)QA1c zqdfrlM(annN~yoq6p_+jq+h~sXQ`)(k#bweFLHNfAf|EJ&M;Z|)j)&g#`Ot;wHgWe zpinzMtE0`zF|UwQ2P8aM}Q1HrG$K*3V0C(B)oz_L{?{Pn_#Ud+s4@@3NnF@ zJ;%J599WTaRg(-P>*S*VJ;mc`Vz_jm#?5Xd{G*srHbe#L!+MC<&1UMIIf4HD$gUV#}yF40p_K{`iLDd=xTV*b1l`&Pv zDVx#{dq(CJdXOZ^8Y`@%;|E`~ARyA5o2_}$3Z1$4_IEBE)*C{q*OgM;emlUBs?LZB zkUUdma}_?km%SFZY*Vemhj1OiHUVW|s%rA04HPv3O%u_T3TJ++=7`Xh_ylgoExC{c z0A7qlPS;pZ@eb>`rahuaPp*(}=*CVIYk^Y6ADjt%?M=?8|5P<}mddk9v4O*L-e-?M zbCsL_9*#b)wYkpSm&o9W5RtzStW)`UvCtg;Krj=56ed0}U^49sLhI9})JXTP+=Ke! z=V==d)fq^x?TdfU2140uyzcUT6JkE%9{|()>Glx@iF=*aVBk_ zMQi911&4cm)?%k(pe&4~8E@CVZ&-h+RG#n68%V3*W$na#vEkObe&TktVWi*#@PPtE znBaDld|-vy;bhQm3*&q6!*>6S>-SKD3p;4D>cd%f8VEGVJ$dnXFlJeB(!Gx7h+pbj-QwCPah!~DH$j(#OOYeKx9B>3A|G#85Wjc>ql}UwQ+c3qskP%0-QX zE{P+L1s{3fttN_`*7=J7fN*s)7|aY<8~dAW)dD6ityq=B6IQ&TfY?qFsu)fukCUcO z4<~sYS{wYCpk>{`Smp#4&Suo)nhyTxxJ#BYlMAyQLUb4yfs!@OkImoW=k-@Xuyxi% zL(c+1SiSe1Xc1-R_o@g-0-LDH3j>h{svdII*5O~Lh9eE>%4|evm&X42 z)`h2;Ov5w1cJuiOV1vQe;`K1C2k+NpowGcYeZw!%-xgDg-3e^6afW;k4-84`E0^j; zy6ZsXQ;B*TDj-%ppd=k%#Q zbk~u2)*_nOzTe7yEzCV2TU~>3Gw)3|En=*IbzRpeBmFo7Z1(_9e8?0#(7xX!q~?6B z243EhDd&0^3lGZjODZN_p<%!Y#RJv-9j^G0%D0RmoNMBw(;Cs4y__*}(V~1C&%2bI zd}2Unz0J1ojF$W-i7(~)Cx~ByOJ5~Zxt0efM+$wW>?S0qtz(mZX!pRB+~sLlcNR6h z2JYez0Y`@vFa#miQ4hkf&<&#HTU|GscKyL;Jj@)EhH)nOa)A4Jt6?;o7Pfg_t65wk z#lWmN6CvAr%sqNQO`KgBy@~Z4nt^VL+&}tLDx2Zq`>?zqKkE+cw{UUN`3t2e{oXg_A zD3@6Da{9DenAj6nvZutR`bpCoCuH9xH+|@7>ykz`Vfn`l7uW7n@rX6CH}1<|=UzoS zlNkuF_aO~dbaas~(Yj+|#C0p2to2YjN2#~JLMS%_PZn}EW7-8iR`PN%t5~UTQs*7wyk#!E&Eca!t@)Yc*u_a zSuFtGyVUTc()F;JF~(`XI=aOGIPPrDfr3&Rxasp>CC-gKPkv7D)H=MQM6b1cHJNs@r`_kbQ^FM;0XUDZcuP^(~uujEntW0dJ}QT3@>z_ zv!;{Vj@tz}O|fb%4w_t|HW2`O+Jq`|Jnnbc*~))DZM(LN5JM(`+cr`Z3h$PM5IKJA z-mVjowUe{V0J1~g9&`U;hT_^{T_22%xS>&H>%4M4J14PodlX#C4(&nMtw@-1ZJp8u zXx>45fBdqBe_b#MqBs=el`w=z>`Hz<PQB$Im$~jz#-}{?~%RkM?2l*RevF=%bV+1#YLWv=G!W4G~@kslsf)Z)*rRv_F@tL>nsb10Nu0fM(4cxi1wf`&{BsMU+e z%cMp2u5~tIM$t-9R+vI+rzLhvk9d!wC2i{$2 zu3W5i_(JfZQwJ`DZFs?o&~QNkuvpU>Qbm>3d{G<9iG`_xXd1jV( z&29cg+}_N$a;Vb~wM}|Uth9i6GEb1*?*OEiGc!7ohn2F^AQPuC;JKGT%1yv5)i^>- zp`2_E2xGut&>dd!dt&WV|8Nlr-iyRe+xRlD{k}$UjgXD%Z4jU0r-wlVNa;3SO*<2B zRj*)%Neq0~kSx{TkrDpbvTE2OIX51%Duj#!$j5L6X5r`IuKL6w!0{p0ztt#k?K@vH zq%d_45e0D-Ex+zW8Ic(6>_k3VbUTYWwo@sSJ$KCIy?S%vniN~IeN#7F#A-1*Dr8I&( z{P89+a&YiOeCc}L3fb;3Q5y0gLPhJ5Drlr&O+_h#yQPx9TAe zenKH-J7RVq%xM8~g;i1#`Uc$Ypk6mZ$Nu|Q&(d0GG<>Gb#@4p%5A0tB=cK7;L84m! zEKB7=_j7%xCrwWQkg9w^E=6zhk^8e4$rlC)C2pCQU$AXcVf&aN>$8aI(}cn_q{k3>_sr1yL>l zi3iH`)W{;mF;iyi*HzTtcp#c%xc@Bu_!*(S7LpZdP3D*Ydk($5!@~v8!+&Hx6M%B4 zEY^Jpd>Co*Kf*dtvC}AQU{aq#B23mHDDyTaI7$ndK)St9_4M&`VUSTlLpD>>m6FW#l_7 z^nl3$#QX)U7}8mDfy1M#IdMUgM;nU4fCj{@wpI+ZRjcN4W?nxaoT3E`a}-1N!6ak} zUpj#txwn{J`8@r=tK86KqZ<8GImR?e!$=s$%^N;BH(=C~Y2)GS`s+4WyurN8i#e|j zO^tP07GnNfp&pWdwPG+&3~c`DLV>0DrfiY`RE1d{;oSV)k*(nO!m$+W6w0ccB~^#e zgtCCh6|bld+s-9V4(7zao2T0-9JEKsw|u3#h;a)$VT<#QYM$l`jZ94SuYwLbwgA^R zfKgjsIEZbgQXHWvf|gr)om=<^XLg9os;8v50e@ovN}lZe^re>PEYm%han%l5;QMq3 zU_Q9WHSK;|ueZ-4PF6dpRhz}f3%ox*qAF%CNbvn52y-}sgCn2!X(E<68lxGo*rBHe zZO-g7!^mtBqtS*@Q6k^Dzg8s|1-5n}L^2t^TSKkgem|sz^B6mWyDZpTRoMQH$FKn> zO(TNX1U@mz{M+rM{CMeB!_4yt?}T~7p2BLNkV}<%A;fI~S@qBDU3db?NE6V7Nnaul3{e(?3IMPXf$1N| zSE=FxZQ$wfW2SV0_bL?PVUw8C>1ftLLYaOti-1AG(wvh*GZl|4%w1_u%nY&^_Te_m zILsW29+w2%R54!=pzBxb)FFkr_fPM_KYMXaXvxz*eEke)${(MvNo|==a zlwiG;pE}*=&+{&kM&ZG@$k`yr@@&wE^{IKyhyHpZLw?M)<|(=q@M6DKXI}AokAcC0 zd`d?xzt^~QsuD&OLZtia7JlrrTSjK6;_kjBp&t=}eL>GV@bVeFEC69~vRl{T3llLN zBMI&68iFmm;F0SNJRnL5P!gW{EKX1}3jKFs@OtNOP7Yr=qo4gV3vM&Z&wZ`D=T~K4|Hm6PjDCBfcqBC z{DnDz1S^@gk+&AKKm=WNcs61SG9BxcBAlaJMn)~Pd=dvaxsFwWZ{2O@{Dh-Y1uLAO zOdlzOjwr!NrLs^RPoAn|%G!hbm7mJ|FL&z+gnz`3!|PK3LP+#)jp%%ARhb5cFLL1N z8tDfre<}D7I}F||;4KhTeVhuAgVv?BNuAHB*YbV#qjLSiXNSgtu@LM#@kHS0tvNA` z2=?13bpOK=vq$!qLtBfz(A^!@`{j>Hq&=7U@RNw_uZcfeGvQ6N=%f~8dQD5Ls+Z&AzoR54R|T31agq9yxWz!QOp0Np-QhT{^hqD{O5H)wU> ze!$9B`wU_vHiD!ME?eAo<;S<&_Y*xvT+4FFauPPnk)i#6q&mzDX}XeD(=o?I*6T<9 zNs1>pIQ@p7i7E-Rb7?plcxsj|q=I~#@M<30Ux4SOHRp>3s*#z+C=$=)i8w{>&z9hL zH+zO=vUYBf19akjIiZ5O={wg&NOg7hV5hh21lXtS09^egZ#w%j&mUiaT;q?Yaej4K2KkIQeb}_!BX8Hcar7P1$=kOnEr~ShM~-f?b<_YAE6?d zb9J(t+4f}#GXCR+z4bx#@?vHozb~3L;C4#jGYN-|`*J8cKx-P5(-uxHht|Juq=m{i zuZGjhC95&k>hW&daF*_8%?LZj&!kSmpN+)zYOoxbSWg4#5_BG^!HW=>NF5YZEeE;( z$(OSF2*^_U^zLg^rgPiPYAP`y}0ms$L>&G->8srq}{2bBuny6Sjgmh7uJ#)&Wtc>8b*3QfT#T@muY0oC=F zmMKXB-Qc2@K`G}IzJ50j!|p=LC_c)x|Jim416;jy+5)8jJhQ*%R^ zjR{3!kG*sJi`X-~%<4Zq=PY~q2mAD#+=)umWfrxPJ{VZnZA*!ag=h1@wxDamL_NMw zH2c)Wd;NZTXSQ=S$KJ6gJkcI<1j1S>jsQ=qp}N;#)%>31oYt=`>D@wPA}{g-M1m9Q z`TQJ}f{n%F#oV?K{4!Gy6$0|DxZ#J$#q13KR%%;BUeX04lfTPLupi>^D&3gi`?J(6 zxpiY4EmG8-bEZOkU6+#hP38M~{yBI@1uBu7Y3We$5Cgq;_(7Hh9|)uc1+H@vk$@b_ z-`PCR2p?n?Amsmjl3jPs*>a5YGxJnS;WdePkPY7op3YK5J`1`I7fx}g3^CIBAdolW z@YREDBjJD2)d7m4+39Dp(v;yC>y?bZxbLRG_kh8ls<#6mKhQxt4oG3U%Bu!OI0O0Tn;w@Z*C2y{Y`TgI37jWzvHo+)LyMICWTB~{( z$G5boP8*58L?r9_Y})8Ev-j=Ro_r)0JIh`-GF%bJhGPz@7ujlUoUK&?4?0ZI`wIXQ zt&LpC?4_}W=m>dj${8HLx?K|K*}zb0>mP>AhdwElEVpL$G__9bg=R`<0Wa>)1#HTa zol~C?CGSQU@O>_feB}tVBTjgY3hS{))pZ5sa-|!n$s}dM-@G1w*uF$v6jG)19-s*Fu<21fYb?V6aXoj*?qngBX?ZUtXGq}hl)*Yt{ax$ zBItthx&E8%7K#i-W(*TUW0<_JK`m|vP|zNooN&(cnd{f>UL+&dQ@Mig4x|J-fXfO#754-T058h2C{1Pr_oFb( zyVt~ux>_X!cn|j~ZyXs|K_Q;8_|6r=00({Y_%qR3lc9%#$8VxRHK~jOI{0|7H){U5 zQ-V)vPo4-wV)vhfOJu{VPl!=23?QkKR0)sYf>?;eb0u?7mX0@6HVpl z598lu=aWICBM9KH7R$%CF3U8?`x@`{i@|>`mdiBa#+MgYYr{F2x>lvM!`G#Xzx!HO zv86}vATX^M2??$+zD8JbIZe|)>~|bdFd$OD_{14DT|6nJ00Qo>g5&38T&}IZ;dG3D zj904y1s;wAKv~d?n*(n^f7)K&*uFgN8G23RhKqXAWF&iZsiEHDWDTCmkzLF18MBD# zP_3N8l9!3946r60R7*x+N)k^~yH@EG1C>DgW{|kw9LHvW4b-z87m6wySB?iy9y2%F z?HydW#xH*Oo2ukM1z@w2Dn81meMn2rnJI?j)h5*!FP#p0xp?nr_f0eOq9wd)h##?c zRBGAEFhVm@q5L^i?1ADI#-IGWj~WXzIUF?E3Xd$-Hb;=_c1qx5^dy|JAP z_1#+Dz`q=BI(FC};tqiIXf-LAu?jGPSVuNox2CkwZE-^W6iH=K$)jqP!wt;IU%cM@q$ zbLOA_A0yTketo<;A?cd5h2B8Pbv_M9e7QVm4ldh;iG{^Jztq@E_)OLj!**UVv%dDt z!@}uUb_G(zWJ(nSLQd&luIKdm)J_GLYt7VsO@h$Y`&wA?!v#}bDEI98n0cP%lQeIP zo=}gfmi?B2&&ycju^I|1?C_td&RsYgK#kTP08Dplq=|b4l_GDi@#%q3Sl^$nzcRMdJ%ZCb`v;bc|*s&(d!g|-Qj_I^4Z?%oeC*#~bdWux&vhW0K8JeYL z+SEL|Q(hHu?yRt2l9M}+VC!j#lY9qx`hLfpQc)o_vu1!|L zDj$E=PjAg6x_24;11zA`Kg>5SPqgClhGxrP5h6S4gQcl^KI$(7vePxPjVPT!5+r86 zkIKiu<~QLcdxvyY1Y(b?%ia;s2FHL zge_&qdr0%N+phRK|5qulDD3PFvkZ=NaGLlEsTw9ey`J|TuUges!J0+M;M3ltiRj7U z!rTB)Xftj}l(k>T*YEEm7z7thC}6jy59VtCd_9u?e6>!{@nQdHmCVR6E}2CZntc=6 zw>*<|GEo4VWfS#cq2^lE4GgRcRs1e{e_Z53N9U2OgXV6uD{2yc9Ih6oET8~^zR^b^ zZ1idQ6{QV!vm?y9pvio4$RoVAXdPUV5bwOV@mH13=myvBq&~}I#jOv(fgO>2|I?4LXbdS*LW0#HZVN*#QGI9mV?snP1#a>x(NW)IG3YE!5APB%bW zDg;Nna8u^&MJ7D5=jyU47EtZENwt2U;>>`7tH##Q_4)@7`Et&=&w0Q~W)-}=Nlv-v zhRm&fo_U4J?U-KtpZcOV$YLej47kY-7bv)0Ds;%c20E;NuCh+A108nnWgO}mU$G+- zmcu=RPJ^A?aXL+(e()Kz)G-%!bFB~34<<|Az?q4{VCO4rx}H}Y79d00b@Sw5ViipT zVR?Il!S9E*#}((e;P%nQX)i9D!`2IGC!=(B3;);EZzl;5P@xZZUKVyaTA_ozrQ*<9 z%P7y8y5a7%9=P_K9?#R;Vp$V5iU<}NMG7yt@^)pd6SCDNnqBY062zqE)i!ZV80F&L z#dbiBj`g8-nC^>D8vq{I+Sz3GFQmZf&za!pr}IHl)=f6NJbsfNMF_{&YNp$*8lOtS zLTRf1ip9&_=Y{1H!ZzyPe$OtYjAt4Td@I(`ZCL)@&cPfL@Z#QddoFwwUM#XC#&${J zeu%Fxe4j@#jMOVr^0v8s^A&fh)_%9~nGi(P0F3a>8t|T;TdKJNp%obM_4hiy4EI~~h+zd05Ep3={ z;Y**RKzC~S7yt@&rs$it4PF3Byc%6OU!f5 zaxz>7>=p%QObctLUxC4P^q7Jg9SSl(dnWnDd87#@XWt!IVfw)ZGqG|6X?oK@KF1@h z7-IVt8u2-7HmCljaIK*fO`{3)>XgluzugB-RoGEiR$iyYmm_Wi{Z~t+K3}Pd;L+i8{kUcoHq?UItJpGKuD{UuJaOt1# zvG|d0NX$H1*kBvT)FAx^;UiOemoqLWbo;d;7oaKXoNbiBg>q#}a9>(#>_W~F?<#l+=BN>93^yNx32@#?T)^Z=v zh5I`j3(~oJs+i+Yaa}jNxkmTPCBy?n;K39r%mOow?0}cJ?Ie!~Ar;I0tujw0BMPfv z4)7D9-Gplmgq_038Z2r)uLiZm>uR(`s6N^7YU#is3M9nIO^{aj?_zW`|JK@5*(0#<617H%1R=_fTkrZw`wR;x{mtgSnsoiO zD3<_Ae>Y7yebMzBoz@pl1ChI03y*_&I3_L6oBaT%BTk~r2ZCCRjc`Kh6p)m4r;NEU zGWiNh7sVx1CFmMCZ(kNvhfy^m{FGbXPnD-5?NrzY57_4K(^4Foy49(P)$ZV=MDh5} zluvae8~b%ngPbcXN}a|+d+*2o^cM@)q;M|x#lN&WRWN{|!xdoR z<>F?+{CHE^OFR@1FZA1Ng6_jgm%mFm!o{Ct0WjtGaDEt3kB<=h42YsdHy1elXf3@A zmlC1{9NU)xL}|zoQz?h=lv&oWQhQ2W&|jMh;vXL|u*P6P+@)JA#6`U+{j0n9>v7Rq z9>NIE?79egiqbeV^mXzhr$*Bjpbn>QC(=7+FR?xALt&DUtb}l#-j!cN;gQ?>H*DVM z&{@Z@T5-U&d4z2@03@Ucz^UDa#vA`w3zRAJF5`?=d2_R4}5(T>(7_=|#nbtYZN^2nUd>zWuz#mG{}&qP`0+B z5#`$^vLb6n3m4b^$$pPh_(&^T*^&%_4_SRzW5QOR5<|)?2jmY7QiG8vlOIlZJ@Da> z6zV}gSghvu8bV1CHoE09E(0Ir z?z|*tcZRn(nj+o~R8|eMMG=0i&uNSNs}8Kiq=r*6o=F+KSM{{JTKwjRo;c)`TY@-Q z82*ZiH83w|b~W+XhQ<9D3lvO-1COlf zF^j6~oOgxzHMcgaF&UQ{ED1`K`l|sH6PP8{xB--wikXd#nVX)8jgpCpk{X6l&fY}K z(8ZL9N{okviG`Von}v({|4LF@8bIaPSm{|9IOv%f*q9htScs@pOf`sPE!|9s{##2; zWbI(+V&QCRNaSYf=TLiCg20K+J2YG>|ZLB!6? zmgp};4d~L@P{M0(@I9eDzs*WxQvLf28I`wxc-T1h)+3718CtL@AKsT^7LLuhv&YZ8 zM#Z(Vf@%|fGMvdOxoBLarjtr}c3D-qoTfx(uJlI?)71E&tXWE9OKa|0tc?CbtrnjX zmETOEDxofuZZ`2EgMCDEKx2xlKbPbrtxAE?2e6>|^{=oQy{iI+zNLF!4rVZKJ_1YI z$WljnP3og++i7qXmH!wkLy=nxGrQJ9I~;@CXiH4}HKYZ}g+8mje8(89k zHXz{8)SHzSTob2hE`HZBU*7NTe;w{7$0Ib$Sq*a`vEbW{T2YKow@N?Wt}K0BJXyvcKMQjm zCx4b)&SY(+ATG|07z^2_Wu#tD-g6jr?b}L^kVk5ms^FK#Qb%y(5%v{Lg2dn8Cdt(0 z6?=wb$oB>DM@rkHGdtCuOg+X51^RN_=Q0&Q;+a4u*+OA*SM_hs28`nCRX;7^ykoxU zH@o+$PB-{}<@gF!Et@MQv*AQm*gp(J%=6f1n%x->BZKBjZBT85QKM(w^rB z(MK}rt;_b#x;8BbrPYF#S#22f(Z2&^Xp5SgXtTAAndEs7m1t*U08W`8Q!=TlRVZ@>t#NqGb}Qd4w`DW4X;<7|8)3nL`-#TU>g)ig zVMV+2&%ch3#xHAYBys0^iwS#nB|1I+RO091;*2b1wHPojd6B#LP&G9nl@|rONI96+ zxLx&W(!+Yl(B5w9Jw_@H%GA|=1rP_JNeARCEH(I&Y64)c+lJvLB~@v)wp?Pk*+|b1 z34xLtGqh(nd(N$JLZ(f)Pb-$Hpk)(WO3w>ZB0kmDAtbrfRfZewUN{ATErX^g0cLDYRp)pzqk4`>VA0Og#2Sh`!~(W! z*4(=C9_SMC&4`}{JDZVMkwh}3?MFb!tRf${RLODNPJ#Ql(WC*iM6XTMd(dCgS&lyG zqZc+t1sDes-eg!d#qtMGFyTZ8r{tAq*xg$YgK?EO`PRmPJ9m0?M{uJs+)a1!;%lIq zfEoye4-$At%fM_%iNttTZo<4IWKYW28>`wE+n5*_X*lx|7;flJky*D<4HS{OlQP4x z4escqviwxEsKaMz#HzA)W?2M+Cq=@0HArc)!tew*o|s7HyaX7Z3x~-@CS)E>q;EQt zls6`dSW);fY6v=+FbE;YfngeP+aRZ9Km^Dt+KWo$=>Z%BrdL3vf{F9rGcw_MH^)Ym zR9;3$M9%_qis^nml#McF_S<}%On-&5=zyGRi;9- zxTbpsZsL>$u)SafyeC)mxTkeIed;}SV0-TiX2&Ksy7D0YW18jwv9aT&Byd(&z?(_e z4c0G;HClOFvX$*yx?FWxY`tW(hoP9sYus>nDJ*YkcpTj#x0=!9<=43#Y1nMT*c7X5 z)T}&*Jz#AZihd$E7|htR0*95jIDvYB!ol^??d08+dgd@#r-XZ3#2N5V*91Drtcu@^ z*T_X=reb(i%f`#**K`}`G#EcTZBZfM~k>5&Eh*Ag>6j3 zC1g|Nxv;vLVIu8>`)uQu#|ulF^rA)}-8&fp=iiYhD$JVUyGqY)Kdl8Qg%PK%VY+J@Ey9>G$H0ZVjTM@`(SNvYK;ucHbSCv~!wG};z-b!9quKtreA=na#L z5=Vpvfv_ap0C8VXhKH`2G%;m6e$7M!j0xPe*|}3XcrWYck!iACgS%~gJxbFKEfG-t z-Iv(gpC_jExpKX^up_xmr{*fAHhR{&s;W364sDd@*C#}ESc2cbwYtk@+mE=01dxzc z(1ulOXT%dkJCoOY57m~F0F4q(zz?QR0=6aLYHdl?td{KiuTfzUZiSABBXe8(Nh-l6 zAURx`RT6e6uPG!Hhp@=cEOLiTWRV5N*8Q#wk0dd;Au))$U|dCV{VLQtct`ko$v7oq z!fz~k`$rC_bVb|~v9^Ti(e=>r;`D3gVocMN3X#pH)IHi&sq9I_0LMsP&N&_Ki7;tI zdd(=|Zk3j-$o0*ArvMuA644qAemag7uCPT2T2Z?~`B78F^j%#|df%AqEk7u;c8RiI zwAMV0tJ>0+0@bteKkKK@{qDxkf5_-ZlAc%|D#fCd8)f@lfA=S+ikacqCIl3hY59is z531U!e+lC&Mp{r1ph`57S9t+@Ke!b(=)trTOxCOs$9BzlDY@~FNV6`D2AWESFb7=K z*tiUn?!$y8hM3np%St}?Xb$@Km^Lx7(5WcBKk_1o<(k{}ki3k+KyMLjnYTkKR4V;9 z3}w@~Zow)u4Xq%-neMxaj17t(yorq)mUmEQGD2KD{f1EsK-BP$!xwR@jpLJ(`_&s) zbkpz6nD2}F-Yy&PKZdmHG|@g)#hdgGUDieD;I!l`6xMC**PUVopVV7jaFqCj?b!`r zAx||+w2Dfj@mz~C)`dxfLv-U7XA>8`TKS~a4%FI_pwzK9wV-E6AfxcvrW~WXlzuaP zm?mvr12jRbfSEmwyw>=q8~v0JK1Q_HEm>UEqQ*4ql*-uzx2-#2t(tZhNRYD$59pLh z7(;7COHAKvhYB=n7CbC>sTUKn0-mXBjDMzbl}xecgsx7^zd-g{%P4keNuCA_NXjh1 z&^NQhYNSc$6*N&5f8F~2v3!T-M9l!z1aqwt%~Z@!0+2H7szY=OgU>YAJecZGr8LT} zRK#&hDU2vij$1{MxBBpk1??Q4CmKvQfX{*H?ZzDyQB=yr!in+m2+9{_f5~;VSeLsGUWpNN;&1WZg9*?N zaiFdS04w*mB@Zu;p2|b7tj9ibvW50zSEYFp#itv~+f6!kn3lKg}?sK(TY)Q@Rp) zwzhW^74W4$w{;c8gqSV3@t#Bd(eQk)aP2mR_M{h;9yn+6qm=?F>rzV*I&!gu5y>?w>LJ5+~4px1u~`Z+y5PXmq59o~g+F*Xmt z03*rfIGSiZSF*#AZF91Jn~d#w+%}Po3+tMm{jLut)CDiD1@a?^+L7tc6!}>` z;JfprQ5M4GbVX&SwCcx_`!zPEK;6$vM?v)$YpGy;hgL+3`>H z&0O{g7t#Srxg?LgwciztaYwp)fTU|I=Imiy>bKWM_xBlaV(XC$jiIPGcb~@7FX`ZI z6cD;s?1|N6n?j%m!|UhNo=&o{?W^d2dg3Xv2ln##;Qj>!c(jn2u3{`xOs@c~qHo53 zxs7k_a28A7@eMtK24ID+Qzw;)iDyQZWVR_%n$cpnjRRvxjxD$>cprsufRl-ja}YI` zkIN4auM|`%<}y6am!vHHoST2fmT^g#fF*$L6z0Of45h}bz$i}3#KhUoU|?ZfoHm+y zmBxkZXZ6?2ZfCKKO(Ceex%8Ua2iT2xIuT z$=etx%|j;|YL@2aP&}o%0gPBgLidjlQXH@wwLAQP_fR2}htc-RKvVl;MxIrnxFP^b zg6`s9n{CvWM`jYN$d6{)6A8!9t%K~7j#}wycgA5~-Ziy*_-|y%w#qbdKgY@|^0J=k zJs+&`b{lKZwqX0Yx1}{=&GEhuBbn}7TMLl$5dW`>3j;qcUfu#Jeci)BM5KnY{1LB42+Dr3SSO@7b(HjvO5mgu@ z(LPYdc*nK4WW`w|YJv#a(GePXB$V{{CD<5EJIErt@zPCfE>;r}=h=*7+@m?{>+=MlDzm?Df@> zLToGUsO_)qznWvdkh9+EwEWwKy+2amwJg`?^ZXG{1IrdR0DJ5HMJ6xQRy*;jll(bH zy078BJ5sxT>azyoWEJ(E-DE`TPL_Ku)K$G(YkiC55chUpH)OIxD)+ZO9sd=N3!LpA zuTlMS8&JY;b2?mm3k{10PPSRGMf_0r3HbI0AY7bf$WM6qLVre%B3tCoO;8()w3#PP zHYoTKZ;UEg0L4qF;u=xrg}nt5vj}TT{>{%BCB9wo)UMW0w9)H=gCTG3Li~_~rxWGK zkxyp`liu!Z{Ksc%?)#x?>{H*d_i6LqH;XVk&jbKb{89an?n8S&eMgX<4}w;u*Kdy( zPd6#)G@lV27PBwJ-Wy{5ZjQTTThN&o7tDPLC{1EPlcV=7HHd5nw=3_(WV^93_uZq& z(=JXo3KhU)Y|G)&k$}Y%0Jz@4<{ZY<&cxZp$<)yHzen~)Rxr%W?5PN&pu_-X4qX^V zWlJwpB4%a|7)Es>ZDt}?BIch-C3}09pGj6CCL$#mMrk`U`=1fp|3+d&+I%dWVjRq( z;vC#!?83ratm5n<>}<@e>>@0}ESyYC!Xg4h|9=U>&yD`q+hqN@cw&GM6@YwBno-mc zYv|VbO1#{Yj=j>#IwvBdJpY*3hW=u3d|2cn!w%`9Q zRZ!u|cjr(KXq3l476eQtUkja{tMkXxD-Km|5^eK=- zEdpkr$&6#IeF&!ORElv> S0$3IfE>0M7a&ZL-nEwFqjx=5X diff --git a/doc/refs.bib b/doc/refs.bib index 97960d8534..ec42fb0328 100644 --- a/doc/refs.bib +++ b/doc/refs.bib @@ -50,3 +50,23 @@ @book{Spivak65book title = {Calculus on manifolds}, volume = {1}, year = {1965}} + +@phdthesis{Nikolic16thesis, + title={Characterisation, calibration, and design of visual-inertial sensor systems for robot navigation}, + author={Nikolic, Janosch}, + year={2016}, + school={ETH Zurich} +} + +@book{Simon06book, + title={Optimal state estimation: Kalman, H infinity, and nonlinear approaches}, + author={Simon, Dan}, + year={2006}, + publisher={John Wiley \& Sons} +} + +@inproceedings{Trawny05report_IndirectKF, + title={Indirect Kalman Filter for 3 D Attitude Estimation}, + author={Nikolas Trawny and Stergios I. Roumeliotis}, + year={2005} +} From 6bc9b50a46ac7cfdae0d1ec82c61779d25c3a6cf Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 30 Sep 2021 09:05:02 -0400 Subject: [PATCH 21/36] add test for MC based covariance estimation --- .../tests/testCombinedImuFactor.cpp | 465 +++++++++--------- 1 file changed, 236 insertions(+), 229 deletions(-) diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index a8c0391449..2f12983c37 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -16,6 +16,7 @@ * @author Frank Dellaert * @author Richard Roberts * @author Stephen Williams + * @author Varun Agrawal */ #include @@ -40,237 +41,218 @@ static boost::shared_ptr Params() { p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3; p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3; p->integrationCovariance = 0.0001 * I_3x3; + p->biasAccCovariance = Z_3x3; + p->biasOmegaCovariance = Z_3x3; + p->biasAccOmegaInit = Z_6x6; return p; } +} // namespace testing + +/* ************************************************************************* */ +TEST(CombinedImuFactor, PreintegratedMeasurements ) { + // Linearization point + Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases + + // Measurements + Vector3 measuredAcc(0.1, 0.0, 0.0); + Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0); + double deltaT = 0.5; + double tol = 1e-6; + + auto p = testing::Params(); + + // Actual preintegrated values + PreintegratedImuMeasurements expected1(p, bias); + expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + PreintegratedCombinedMeasurements actual1(p, bias); + + actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol)); + EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol)); + EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol)); + DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol); } -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, PreintegratedMeasurements ) { -// // Linearization point -// Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases - -// // Measurements -// Vector3 measuredAcc(0.1, 0.0, 0.0); -// Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0); -// double deltaT = 0.5; -// double tol = 1e-6; - -// auto p = testing::Params(); - -// // Actual preintegrated values -// PreintegratedImuMeasurements expected1(p, bias); -// expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - -// PreintegratedCombinedMeasurements actual1(p, bias); - -// actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - -// EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol)); -// EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol)); -// EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol)); -// DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol); -// } - -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, Accelerating) { -// const double a = 0.2, v = 50; - -// // Set up body pointing towards y axis, and start at 10,20,0 with velocity -// // going in X The body itself has Z axis pointing down -// const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); -// const Point3 initial_position(10, 20, 0); -// const Vector3 initial_velocity(v, 0, 0); - -// const AcceleratingScenario scenario(nRb, initial_position, initial_velocity, -// Vector3(a, 0, 0)); - -// const double T = 3.0; // seconds -// CombinedScenarioRunner runner(scenario, testing::Params(), T / 10); - -// PreintegratedCombinedMeasurements pim = runner.integrate(T); -// EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); - -// auto estimatedCov = runner.estimateCovariance(T, 100); -// Eigen::Matrix expected = pim.preintMeasCov(); -// EXPECT(assert_equal(estimatedCov, expected, 0.1)); -// } - -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, ErrorWithBiases ) { -// Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) -// Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) -// Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); -// Vector3 v1(0.5, 0.0, 0.0); -// Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), -// Point3(5.5, 1.0, -50.0)); -// Vector3 v2(0.5, 0.0, 0.0); - -// auto p = testing::Params(); -// p->omegaCoriolis = Vector3(0,0.1,0.1); -// PreintegratedImuMeasurements pim( -// p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); - -// // Measurements -// Vector3 measuredOmega; -// measuredOmega << 0, 0, M_PI / 10.0 + 0.3; -// Vector3 measuredAcc = -// x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0); -// double deltaT = 1.0; -// double tol = 1e-6; - -// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - -// PreintegratedCombinedMeasurements combined_pim(p, -// Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); - -// combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - -// // Create factor -// ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim); - -// noiseModel::Gaussian::shared_ptr Combinedmodel = -// noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov()); -// CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), -// combined_pim); - -// Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias); -// Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias, -// bias2); -// EXPECT(assert_equal(errorExpected, errorActual.head(9), tol)); - -// // Expected Jacobians -// Matrix H1e, H2e, H3e, H4e, H5e; -// (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); - -// // Actual Jacobians -// Matrix H1a, H2a, H3a, H4a, H5a, H6a; -// (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, -// H3a, H4a, H5a, H6a); - -// EXPECT(assert_equal(H1e, H1a.topRows(9))); -// EXPECT(assert_equal(H2e, H2a.topRows(9))); -// EXPECT(assert_equal(H3e, H3a.topRows(9))); -// EXPECT(assert_equal(H4e, H4a.topRows(9))); -// EXPECT(assert_equal(H5e, H5a.topRows(9))); -// } - -// /* ************************************************************************* */ -// #ifdef GTSAM_TANGENT_PREINTEGRATION -// TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { -// auto p = testing::Params(); -// testing::SomeMeasurements measurements; - -// auto preintegrated = [=](const Vector3& a, const Vector3& w) { -// PreintegratedImuMeasurements pim(p, Bias(a, w)); -// testing::integrateMeasurements(measurements, &pim); -// return pim.preintegrated(); -// }; - -// // Actual pre-integrated values -// PreintegratedCombinedMeasurements pim(p); -// testing::integrateMeasurements(measurements, &pim); - -// EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), -// pim.preintegrated_H_biasAcc())); -// EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), -// pim.preintegrated_H_biasOmega(), 1e-3)); -// } -// #endif - -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, PredictPositionAndVelocity) { -// const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) - -// auto p = testing::Params(); - -// // Measurements -// const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3; -// const Vector3 measuredAcc(0, 1.1, -kGravity); -// const double deltaT = 0.01; - -// PreintegratedCombinedMeasurements pim(p, bias); - -// for (int i = 0; i < 100; ++i) -// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - -// // Create factor -// const noiseModel::Gaussian::shared_ptr combinedmodel = -// noiseModel::Gaussian::Covariance(pim.preintMeasCov()); -// const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); - -// // Predict -// const NavState actual = pim.predict(NavState(), bias); -// const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); -// const Vector3 expectedVelocity(0, 1, 0); -// EXPECT(assert_equal(expectedPose, actual.pose())); -// EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); -// } - -// /* ************************************************************************* */ -// TEST(CombinedImuFactor, PredictRotation) { -// const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) -// auto p = testing::Params(); -// PreintegratedCombinedMeasurements pim(p, bias); -// const Vector3 measuredAcc = - kGravityAlongNavZDown; -// const Vector3 measuredOmega(0, 0, M_PI / 10.0); -// const double deltaT = 0.01; -// const double tol = 1e-4; -// for (int i = 0; i < 100; ++i) -// pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); -// const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); - -// // Predict -// const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; -// const Vector3 v(0, 0, 0), v2; -// const NavState actual = pim.predict(NavState(x, v), bias); -// const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); -// EXPECT(assert_equal(expectedPose, actual.pose(), tol)); -// } - -// /* ************************************************************************* */ -// // Testing covariance to check if all the jacobians are accounted for. -// TEST(CombinedImuFactor, CheckCovariance) { -// auto params = PreintegrationCombinedParams::MakeSharedU(9.81); - -// params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); -// params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); -// params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); -// params->setOmegaCoriolis(Vector3::Zero()); - -// imuBias::ConstantBias currentBias; - -// PreintegratedCombinedMeasurements actual(params, currentBias); - -// // Measurements -// Vector3 measuredAcc(0.1577, -0.8251, 9.6111); -// Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); -// double deltaT = 0.01; - -// actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - -// Eigen::Matrix expected; -// expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // -// 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; - -// // regression -// EXPECT(assert_equal(expected, actual.preintMeasCov())); -// } -// Test that the covariance values for the ImuFactor and the CombinedImuFactor (top-left 9x9) are the same -TEST(CombinedImuFactor, SameCovariance) { +/* ************************************************************************* */ +TEST(CombinedImuFactor, ErrorWithBiases ) { + Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) + Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) + Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); + Vector3 v1(0.5, 0.0, 0.0); + Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), + Point3(5.5, 1.0, -50.0)); + Vector3 v2(0.5, 0.0, 0.0); + + auto p = testing::Params(); + p->omegaCoriolis = Vector3(0,0.1,0.1); + PreintegratedImuMeasurements pim( + p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); + + // Measurements + Vector3 measuredOmega; + measuredOmega << 0, 0, M_PI / 10.0 + 0.3; + Vector3 measuredAcc = + x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0); + double deltaT = 1.0; + double tol = 1e-6; + + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + PreintegratedCombinedMeasurements combined_pim(p, + Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); + + combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + // Create factor + ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim); + + noiseModel::Gaussian::shared_ptr Combinedmodel = + noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov()); + CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), + combined_pim); + + Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias); + Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias, + bias2); + EXPECT(assert_equal(errorExpected, errorActual.head(9), tol)); + + // Expected Jacobians + Matrix H1e, H2e, H3e, H4e, H5e; + (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); + + // Actual Jacobians + Matrix H1a, H2a, H3a, H4a, H5a, H6a; + (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, + H3a, H4a, H5a, H6a); + + EXPECT(assert_equal(H1e, H1a.topRows(9))); + EXPECT(assert_equal(H2e, H2a.topRows(9))); + EXPECT(assert_equal(H3e, H3a.topRows(9))); + EXPECT(assert_equal(H4e, H4a.topRows(9))); + EXPECT(assert_equal(H5e, H5a.topRows(9))); +} + +/* ************************************************************************* */ +#ifdef GTSAM_TANGENT_PREINTEGRATION +TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { + auto p = testing::Params(); + testing::SomeMeasurements measurements; + + auto preintegrated = [=](const Vector3& a, const Vector3& w) { + PreintegratedImuMeasurements pim(p, Bias(a, w)); + testing::integrateMeasurements(measurements, &pim); + return pim.preintegrated(); + }; + + // Actual pre-integrated values + PreintegratedCombinedMeasurements pim(p); + testing::integrateMeasurements(measurements, &pim); + + EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), + pim.preintegrated_H_biasAcc())); + EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), + pim.preintegrated_H_biasOmega(), 1e-3)); +} +#endif + +/* ************************************************************************* */ +TEST(CombinedImuFactor, PredictPositionAndVelocity) { + const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) + + auto p = testing::Params(); + + // Measurements + const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3; + const Vector3 measuredAcc(0, 1.1, -kGravity); + const double deltaT = 0.01; + + PreintegratedCombinedMeasurements pim(p, bias); + + for (int i = 0; i < 100; ++i) + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + // Create factor + const noiseModel::Gaussian::shared_ptr combinedmodel = + noiseModel::Gaussian::Covariance(pim.preintMeasCov()); + const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); + + // Predict + const NavState actual = pim.predict(NavState(), bias); + const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); + const Vector3 expectedVelocity(0, 1, 0); + EXPECT(assert_equal(expectedPose, actual.pose())); + EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); +} + +/* ************************************************************************* */ +TEST(CombinedImuFactor, PredictRotation) { + const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) + auto p = testing::Params(); + PreintegratedCombinedMeasurements pim(p, bias); + const Vector3 measuredAcc = - kGravityAlongNavZDown; + const Vector3 measuredOmega(0, 0, M_PI / 10.0); + const double deltaT = 0.01; + const double tol = 1e-4; + for (int i = 0; i < 100; ++i) + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); + + // Predict + const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; + const Vector3 v(0, 0, 0), v2; + const NavState actual = pim.predict(NavState(x, v), bias); + const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); + EXPECT(assert_equal(expectedPose, actual.pose(), tol)); +} + +/* ************************************************************************* */ +// Testing covariance to check if all the jacobians are accounted for. +TEST(CombinedImuFactor, CheckCovariance) { + auto params = PreintegrationCombinedParams::MakeSharedU(9.81); + + params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); + params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); + params->setIntegrationCovariance(pow(0.0, 2) * I_3x3); + params->setOmegaCoriolis(Vector3::Zero()); + + imuBias::ConstantBias currentBias; + + PreintegratedCombinedMeasurements actual(params, currentBias); + + // Measurements + Vector3 measuredAcc(0.1577, -0.8251, 9.6111); + Vector3 measuredOmega(-0.0210, 0.0311, 0.0145); + double deltaT = 0.01; + + actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + Eigen::Matrix expected; + expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; + + // regression + EXPECT(assert_equal(expected, actual.preintMeasCov())); +} + +// Test that the covariance values for the ImuFactor and the CombinedImuFactor +// (top-left 9x9) are the same +TEST(CombinedImuFactor, SameCovariance) { // IMU measurements and time delta Vector3 accMeas(0.1577, -0.8251, 9.6111); Vector3 omegaMeas(-0.0210, 0.0311, 0.0145); @@ -278,7 +260,7 @@ TEST(CombinedImuFactor, SameCovariance) { // Assume zero bias imuBias::ConstantBias currentBias; - + // Define params for ImuFactor auto params = PreintegrationParams::MakeSharedU(); params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); @@ -303,10 +285,35 @@ TEST(CombinedImuFactor, SameCovariance) { PreintegratedCombinedMeasurements cpim(combined_params, currentBias); cpim.integrateMeasurement(accMeas, omegaMeas, deltaT); - // Assert if the noise covariance - EXPECT(assert_equal(pim.preintMeasCov(), cpim.preintMeasCov().block(0, 0, 9, 9))); + // Assert if the noise covariance + EXPECT(assert_equal(pim.preintMeasCov(), + cpim.preintMeasCov().block(0, 0, 9, 9))); } +/* ************************************************************************* */ +TEST(CombinedImuFactor, Accelerating) { + const double a = 0.2, v = 50; + + // Set up body pointing towards y axis, and start at 10,20,0 with velocity + // going in X The body itself has Z axis pointing down + const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); + const Point3 initial_position(10, 20, 0); + const Vector3 initial_velocity(v, 0, 0); + + const AcceleratingScenario scenario(nRb, initial_position, initial_velocity, + Vector3(a, 0, 0)); + + const double T = 3.0; // seconds + + CombinedScenarioRunner runner(scenario, testing::Params(), T / 10); + + PreintegratedCombinedMeasurements pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + auto estimatedCov = runner.estimateCovariance(T, 100); + Eigen::Matrix expected = pim.preintMeasCov(); + EXPECT(assert_equal(estimatedCov, expected, 0.1)); +} /* ************************************************************************* */ int main() { From af714cdb5a756a744dd0000a89782a55fb14d66c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Sep 2021 13:43:04 -0400 Subject: [PATCH 22/36] undo name change from 984a90 --- examples/CombinedImuFactorsExample.cpp | 4 ++-- examples/ImuFactorsExample.cpp | 4 ++-- gtsam/navigation/CombinedImuFactor.cpp | 10 +++++----- gtsam/navigation/CombinedImuFactor.h | 12 ++++++------ .../examples/ISAM2_SmartFactorStereo_IMU.cpp | 2 +- tests/testImuPreintegration.cpp | 4 ++-- 6 files changed, 18 insertions(+), 18 deletions(-) diff --git a/examples/CombinedImuFactorsExample.cpp b/examples/CombinedImuFactorsExample.cpp index 49cdb68354..35ed387c40 100644 --- a/examples/CombinedImuFactorsExample.cpp +++ b/examples/CombinedImuFactorsExample.cpp @@ -107,7 +107,7 @@ boost::shared_ptr imuParams() { I_3x3 * 1e-8; // error committed in integrating position from velocities Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2); Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2); - Matrix66 bias_acc_omega_int = + Matrix66 bias_acc_omega_init = I_6x6 * 1e-5; // error in the bias used for preintegration auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0); @@ -123,7 +123,7 @@ boost::shared_ptr imuParams() { // PreintegrationCombinedMeasurements params: p->biasAccCovariance = bias_acc_cov; // acc bias in continuous p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous - p->biasAccOmegaInt = bias_acc_omega_int; + p->biasAccOmegaInit = bias_acc_omega_init; return p; } diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index 38ee4c7c76..12167a19d1 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -94,7 +94,7 @@ boost::shared_ptr imuParams() { I_3x3 * 1e-8; // error committed in integrating position from velocities Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2); Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2); - Matrix66 bias_acc_omega_int = + Matrix66 bias_acc_omega_init = I_6x6 * 1e-5; // error in the bias used for preintegration auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0); @@ -110,7 +110,7 @@ boost::shared_ptr imuParams() { // PreintegrationCombinedMeasurements params: p->biasAccCovariance = bias_acc_cov; // acc bias in continuous p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous - p->biasAccOmegaInt = bias_acc_omega_int; + p->biasAccOmegaInit = bias_acc_omega_init; return p; } diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index de4d3f66db..5d49e4c0b9 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -39,7 +39,7 @@ void PreintegrationCombinedParams::print(const string& s) const { << endl; cout << "biasOmegaCovariance:\n[\n" << biasOmegaCovariance << "\n]" << endl; - cout << "biasAccOmegaInt:\n[\n" << biasAccOmegaInt << "\n]" + cout << "biasAccOmegaInit:\n[\n" << biasAccOmegaInit << "\n]" << endl; } @@ -52,7 +52,7 @@ bool PreintegrationCombinedParams::equals(const PreintegratedRotationParams& oth tol) && equal_with_abs_tol(biasOmegaCovariance, e->biasOmegaCovariance, tol) && - equal_with_abs_tol(biasAccOmegaInt, e->biasAccOmegaInt, tol); + equal_with_abs_tol(biasAccOmegaInit, e->biasAccOmegaInit, tol); } //------------------------------------------------------------------------------ @@ -137,8 +137,8 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); - Matrix3 aCov_updated = aCov + p().biasAccOmegaInt.block<3, 3>(0, 0); - Matrix3 wCov_updated = wCov + p().biasAccOmegaInt.block<3, 3>(3, 3); + Matrix3 aCov_updated = aCov + p().biasAccOmegaInit.block<3, 3>(0, 0); + Matrix3 wCov_updated = wCov + p().biasAccOmegaInit.block<3, 3>(3, 3); // BLOCK DIAGONAL TERMS D_t_t(&G_measCov_Gt) = (pos_H_biasAcc // @@ -156,7 +156,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance; // OFF BLOCK DIAGONAL TERMS - Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInt.block<3, 3>(3, 0) + Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInit.block<3, 3>(3, 0) * theta_H_biasOmega.transpose(); D_v_R(&G_measCov_Gt) = temp; D_v_t(&G_measCov_Gt) = vel_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose(); diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index ce169c1d0b..5849f6f247 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -62,19 +62,19 @@ typedef ManifoldPreintegration PreintegrationType; struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { Matrix3 biasAccCovariance; ///< continuous-time "Covariance" describing accelerometer bias random walk Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing gyroscope bias random walk - Matrix6 biasAccOmegaInt; ///< covariance of bias used for pre-integration + Matrix6 biasAccOmegaInit; ///< covariance of bias used as initial estimate. /// Default constructor makes uninitialized params struct. /// Used for serialization. PreintegrationCombinedParams() : biasAccCovariance(I_3x3), biasOmegaCovariance(I_3x3), - biasAccOmegaInt(I_6x6) {} + biasAccOmegaInit(I_6x6) {} /// See two named constructors below for good values of n_gravity in body frame PreintegrationCombinedParams(const Vector3& n_gravity) : PreintegrationParams(n_gravity), biasAccCovariance(I_3x3), - biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) { + biasOmegaCovariance(I_3x3), biasAccOmegaInit(I_6x6) { } @@ -93,11 +93,11 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; } void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; } - void setBiasAccOmegaInt(const Matrix6& cov) { biasAccOmegaInt=cov; } + void setBiasAccOmegaInt(const Matrix6& cov) { biasAccOmegaInit=cov; } const Matrix3& getBiasAccCovariance() const { return biasAccCovariance; } const Matrix3& getBiasOmegaCovariance() const { return biasOmegaCovariance; } - const Matrix6& getBiasAccOmegaInt() const { return biasAccOmegaInt; } + const Matrix6& getBiasAccOmegaInt() const { return biasAccOmegaInit; } private: @@ -109,7 +109,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationParams); ar & BOOST_SERIALIZATION_NVP(biasAccCovariance); ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance); - ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt); + ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInit); } public: diff --git a/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp b/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp index c0a102d111..27d87d217f 100644 --- a/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp +++ b/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp @@ -57,7 +57,7 @@ struct IMUHelper { p->biasAccCovariance = I_3x3 * pow(0.00002, 2.0); // acc bias in continuous p->biasOmegaCovariance = I_3x3 * pow(0.001, 2.0); // gyro bias in continuous - p->biasAccOmegaInt = Matrix::Identity(6, 6) * 1e-5; + p->biasAccOmegaInit = Matrix::Identity(6, 6) * 1e-5; // body to IMU rotation Rot3 iRb(0.036129, -0.998727, 0.035207, diff --git a/tests/testImuPreintegration.cpp b/tests/testImuPreintegration.cpp index 1f584be0ed..94e6fb89f2 100644 --- a/tests/testImuPreintegration.cpp +++ b/tests/testImuPreintegration.cpp @@ -43,7 +43,7 @@ TEST(TestImuPreintegration, LoadedSimulationData) { double gyrNoiseSigma = 0.000208; double gyrBiasRwSigma = 0.000004; double integrationCovariance = 1e-8; - double biasAccOmegaInt = 1e-5; + double biasAccOmegaInit = 1e-5; double gravity = 9.81; double rate = 400.0; // Hz @@ -76,7 +76,7 @@ TEST(TestImuPreintegration, LoadedSimulationData) { imuPreintegratedParams->gyroscopeCovariance = I_3x3 * pow(gyrNoiseSigma, 2); imuPreintegratedParams->biasOmegaCovariance = I_3x3 * pow(gyrBiasRwSigma, 2); imuPreintegratedParams->integrationCovariance = I_3x3 * integrationCovariance; - imuPreintegratedParams->biasAccOmegaInt = I_6x6 * biasAccOmegaInt; + imuPreintegratedParams->biasAccOmegaInit = I_6x6 * biasAccOmegaInit; // Initial state Pose3 priorPose; From e38ea502d7df488fdbec8072284715c977547e32 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 28 Sep 2021 18:22:15 -0400 Subject: [PATCH 23/36] detailed implementation of CombinedImuFactor noise propagation --- gtsam/navigation/CombinedImuFactor.cpp | 70 +++++++++++++++++--------- 1 file changed, 45 insertions(+), 25 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 5d49e4c0b9..2dfaae2fd9 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -110,17 +110,22 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // and preintegrated measurements // Single Jacobians to propagate covariance - Matrix3 theta_H_biasOmega = C.topRows<3>(); - Matrix3 pos_H_biasAcc = B.middleRows<3>(3); - Matrix3 vel_H_biasAcc = B.bottomRows<3>(); + Matrix3 theta_H_omega = C.topRows<3>(); + Matrix3 pos_H_acc = B.middleRows<3>(3); + Matrix3 vel_H_acc = B.bottomRows<3>(); + + Matrix3 theta_H_biasOmegaInit = -theta_H_omega; + Matrix3 pos_H_biasAccInit = -pos_H_acc; + Matrix3 vel_H_biasAcc = -vel_H_acc; + Matrix3 vel_H_biasAccInit = -vel_H_acc; // overall Jacobian wrt preintegrated measurements (df/dx) Eigen::Matrix F; F.setZero(); F.block<9, 9>(0, 0) = A; - F.block<3, 3>(0, 12) = theta_H_biasOmega; - F.block<3, 3>(3, 9) = pos_H_biasAcc; - F.block<3, 3>(6, 9) = vel_H_biasAcc; + F.block<3, 3>(0, 12) = theta_H_omega; + F.block<3, 3>(3, 9) = pos_H_acc; + F.block<3, 3>(6, 9) = vel_H_acc; F.block<6, 6>(9, 9) = I_6x6; // Update the uncertainty on the state (matrix F in [4]). @@ -131,37 +136,52 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( const Matrix3& aCov = p().accelerometerCovariance; const Matrix3& wCov = p().gyroscopeCovariance; const Matrix3& iCov = p().integrationCovariance; + const Matrix6& bInitCov = p().biasAccOmegaInit; // first order uncertainty propagation // Optimized matrix mult: (1/dt) * G * measurementCovariance * G.transpose() Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); - Matrix3 aCov_updated = aCov + p().biasAccOmegaInit.block<3, 3>(0, 0); - Matrix3 wCov_updated = wCov + p().biasAccOmegaInit.block<3, 3>(3, 3); - // BLOCK DIAGONAL TERMS - D_t_t(&G_measCov_Gt) = (pos_H_biasAcc // - * (aCov_updated / dt) // - * pos_H_biasAcc.transpose()) + (dt * iCov); - D_v_v(&G_measCov_Gt) = vel_H_biasAcc // - * (aCov_updated / dt) // - * (vel_H_biasAcc.transpose()); - - D_R_R(&G_measCov_Gt) = theta_H_biasOmega // - * (wCov_updated / dt) // - * (theta_H_biasOmega.transpose()); + D_R_R(&G_measCov_Gt) = + (theta_H_omega * (wCov / dt) * theta_H_omega.transpose()) + // + (theta_H_biasOmegaInit * (bInitCov.block<3, 3>(3, 3) / dt) * + theta_H_biasOmegaInit.transpose()); + + D_t_t(&G_measCov_Gt) = + (pos_H_acc * (aCov / dt) * pos_H_acc.transpose()) // + + (pos_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * + pos_H_biasAccInit.transpose()) // + + (dt * iCov); + + D_v_v(&G_measCov_Gt) = + (vel_H_acc * (aCov / dt) * vel_H_acc.transpose()) // + + (vel_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * + vel_H_biasAccInit.transpose()); D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance; // OFF BLOCK DIAGONAL TERMS - Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInit.block<3, 3>(3, 0) - * theta_H_biasOmega.transpose(); - D_v_R(&G_measCov_Gt) = temp; - D_v_t(&G_measCov_Gt) = vel_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose(); - D_R_v(&G_measCov_Gt) = temp.transpose(); - D_t_v(&G_measCov_Gt) = pos_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose(); + D_R_t(&G_measCov_Gt) = theta_H_biasOmegaInit * + (bInitCov.block<3, 3>(3, 0) / dt) * + pos_H_biasAccInit.transpose(); + D_R_v(&G_measCov_Gt) = theta_H_biasOmegaInit * + (bInitCov.block<3, 3>(3, 0) / dt) * + vel_H_biasAccInit.transpose(); + D_t_R(&G_measCov_Gt) = pos_H_biasAccInit * (bInitCov.block<3, 3>(0, 3) / dt) * + theta_H_biasOmegaInit.transpose(); + D_t_v(&G_measCov_Gt) = + (pos_H_acc * (aCov / dt) * vel_H_acc.transpose()) + + (pos_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * + vel_H_biasAccInit.transpose()); + D_v_R(&G_measCov_Gt) = vel_H_biasAccInit * (bInitCov.block<3, 3>(0, 3) / dt) * + theta_H_biasOmegaInit.transpose(); + D_v_t(&G_measCov_Gt) = + (vel_H_acc * (aCov / dt) * pos_H_acc.transpose()) + + (vel_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * + pos_H_biasAccInit.transpose()); preintMeasCov_.noalias() += G_measCov_Gt; } From 3cee1b71ec55d157e7a4654c984fb9d40ae15550 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 30 Sep 2021 09:01:23 -0400 Subject: [PATCH 24/36] test passes --- gtsam/navigation/CombinedImuFactor.cpp | 6 +++--- gtsam/navigation/ScenarioRunner.cpp | 3 ++- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 2dfaae2fd9..64d555e2e6 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -145,9 +145,9 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // BLOCK DIAGONAL TERMS D_R_R(&G_measCov_Gt) = - (theta_H_omega * (wCov / dt) * theta_H_omega.transpose()) + // - (theta_H_biasOmegaInit * (bInitCov.block<3, 3>(3, 3) / dt) * - theta_H_biasOmegaInit.transpose()); + (theta_H_omega * (wCov / dt) * theta_H_omega.transpose()) // + + (theta_H_biasOmegaInit * (bInitCov.block<3, 3>(3, 3) / dt) * + theta_H_biasOmegaInit.transpose()); D_t_t(&G_measCov_Gt) = (pos_H_acc * (aCov / dt) * pos_H_acc.transpose()) // diff --git a/gtsam/navigation/ScenarioRunner.cpp b/gtsam/navigation/ScenarioRunner.cpp index 3a447dcab6..9d3e258de9 100644 --- a/gtsam/navigation/ScenarioRunner.cpp +++ b/gtsam/navigation/ScenarioRunner.cpp @@ -145,7 +145,8 @@ Eigen::Matrix CombinedScenarioRunner::estimateCovariance( auto pim = integrate(T, estimatedBias, true); NavState sampled = predict(pim); Vector15 xi = Vector15::Zero(); - xi << sampled.localCoordinates(prediction), estimatedBias_.vector(); + xi << sampled.localCoordinates(prediction), + (estimatedBias_.vector() - estimatedBias.vector()); samples.col(i) = xi; sum += xi; } From dfa32e50207a3b69be71ad3b17df9093ae98d8c9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 9 Oct 2021 22:51:48 -0400 Subject: [PATCH 25/36] lyx update --- doc/ImuFactor.lyx | 80 ++++++++++++++++++++++++++++++++++++++--------- 1 file changed, 66 insertions(+), 14 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index f76ede023f..80c160e6ee 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -227,16 +227,62 @@ preintegrated_ \begin_layout Standard The main function of a factor is to calculate an error. - The easiest case to look at is the NavState variant in ImuFactor2, which - is given as: + This is done exactly the same in both variants: \begin_inset Formula \begin{equation} -\Delta X_{ij}=X_{j}-\hat{X_{ij}}\label{eq:imu-factor-error} +e(X_{i},X_{j})=X_{j}\ominus\widehat{X_{j}}\label{eq:imu-factor-error} \end{equation} \end_inset +where the predicted NavState +\begin_inset Formula $\widehat{X_{j}}$ +\end_inset + + at time +\begin_inset Formula $t_{j}$ +\end_inset + + is a function of the NavState +\begin_inset Formula $X_{i}$ +\end_inset + + at time +\begin_inset Formula $t_{i}$ +\end_inset + + and the preintegrated measurements +\begin_inset Formula $PIM$ +\end_inset + +: +\begin_inset Formula +\[ +\widehat{X_{j}}=f(X_{i},PIM) +\] + +\end_inset + +The noise model associated with this factor is assumed to be zero-mean Gaussian + with a +\begin_inset Formula $9\times9$ +\end_inset + + covariance matrix +\begin_inset Formula $\Sigma_{ij}$ +\end_inset +, which is defined in the tangent space +\begin_inset Formula $T_{X_{j}}\mathcal{N}$ +\end_inset + + of the NavState manifold at the NavState +\begin_inset Formula $X_{j}$ +\end_inset + +. + This covariance matrix is computed in the preintegrated measurement class, + of which there are two variants as discussed above. \end_layout \begin_layout Subsubsection* @@ -282,6 +328,14 @@ Gyroscope Covariance : Measurement uncertainty of the gyroscope. \end_layout +\begin_layout Itemize +Gyroscope Bias Covariance +\begin_inset Formula $Q_{\Delta b^{\omega}}$ +\end_inset + + : The covariance associated with the gyroscope bias random walk. +\end_layout + \begin_layout Itemize Accelerometer Covariance \begin_inset Formula $Q_{acc}$ @@ -298,14 +352,6 @@ Accelerometer Bias Covariance : The covariance associated with the accelerometer bias random walk. \end_layout -\begin_layout Itemize -Gyroscope Bias Covariance -\begin_inset Formula $Q_{\Delta b^{\omega}}$ -\end_inset - - : The covariance associated with the gyroscope bias random walk. -\end_layout - \begin_layout Itemize Integration Covariance \begin_inset Formula $Q_{int}$ @@ -1469,7 +1515,12 @@ Noise Propagation in IMU Factor \end_layout \begin_layout Standard -Even when we assume uncorrelated noise on +We wish to compute the ImuFactor covariance matrix +\begin_inset Formula $\Sigma_{ij}$ +\end_inset + +. + Even when we assume uncorrelated noise on \begin_inset Formula $\omega^{b}$ \end_inset @@ -1487,11 +1538,12 @@ Even when we assume uncorrelated noise on \end_inset appear in multiple places. - To model the noise propagation, let us define + To model the noise propagation, let us define the preintegrated navigation + state \begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k}]$ \end_inset - and rewrite Eqns. +, as a 9D vector on tangent space at and rewrite Eqns. ( \begin_inset CommandInset ref LatexCommand ref From 40e6d8be9b146a0caf43ea231610239bf716ed42 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 9 Oct 2021 22:52:01 -0400 Subject: [PATCH 26/36] formatting --- doc/ImuFactor.lyx | 2 +- gtsam/navigation/PreintegrationBase.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index 80c160e6ee..7b176f484e 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -82,7 +82,7 @@ \begin_body \begin_layout Title -The new IMU Factor +The New IMU Factor \end_layout \begin_layout Author diff --git a/gtsam/navigation/PreintegrationBase.cpp b/gtsam/navigation/PreintegrationBase.cpp index 8840c34e9d..f6e9fccb8d 100644 --- a/gtsam/navigation/PreintegrationBase.cpp +++ b/gtsam/navigation/PreintegrationBase.cpp @@ -157,9 +157,9 @@ Vector9 PreintegrationBase::computeError(const NavState& state_i, state_j.localCoordinates(predictedState_j, H2 ? &D_error_state_j : 0, H1 || H3 ? &D_error_predict : 0); - if (H1) *H1 << D_error_predict* D_predict_state_i; + if (H1) *H1 << D_error_predict * D_predict_state_i; if (H2) *H2 << D_error_state_j; - if (H3) *H3 << D_error_predict* D_predict_bias_i; + if (H3) *H3 << D_error_predict * D_predict_bias_i; return error; } From 995710f8fdf0e91f29ec15158c8a376ee4a8883f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 5 May 2022 11:38:18 -0400 Subject: [PATCH 27/36] update PDF doc --- doc/ImuFactor.pdf | Bin 248399 -> 249424 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index a4ec57fb7baa660508d5c6872185270e178b1d0f..9d7026d0978944949f5f6d4932c85dbe112a2a10 100644 GIT binary patch delta 100260 zcmV)GK)%1vln>CH50E1RFft&Mfj}sKEsxDg1TheV@ADLWk_1eguKXVr9Z*>zM=PIr0w2Xrt&T$3IFCj&JzGn0WpD1WsXYmeNv@wRRGg7yj&NP>Xg)%oP?N?S?mM}K|iL29Wz-q{zYpF|CZoZ-xHUVM4;?7LUmtz;qU zqL!!J1CMpf%+e1Q~JvJ_$=yqOEtlw_7FwsmnO^8j? z@yvt=z`sX+ z8Z`!x78MBOJ%7rjm=QGV8^&)*EDcHJB4*r&IR%u9nDOsNk60i6Ir*u1eucR_6MuYC zL!iuOE8|hh^%1EI z&6ZA6EG2Pl61LR?cY(|a*yNp6s(&XC+0-7JacWLH=K=3Q6P(2y*RX`86?N&DF*Ey) zAuRSoAnOlf&mhGB7Cp+3q#wm6*Zpl|pbe1S!H>bEY>|pvsx$hOH@<6c`vYF+i@qG| zYlCd}-HXlEY6lEPM+5rhONoq(fWa`nI)$q9Oc7MSTKq3CX zz=dJ6&o!yf)kP^Jc<_P`@=H-jM$=V_Rtp>iq<=F;S+1O@T@ew`(Mn-K6NJ^i&-wVR zE*!XIyiiiqG6aZ^EnWv*XfWlGy&0J#y(`?oposQpdZH(0V^Rjb-R;a!PO-Tz{X+DnXJGipQ1UAZV2H zDP~uolVl;yyh>PUuTn2AE3||)RN*|g?* zPdJ3cyrNqFB`cW4hl)DKxx1T#>x;ZGULCHbGHQ>JSVls(IfJPtSw z3jPQnkCO^GiQ$yu=ZsdDpey}{uHbbhSVBnpKMU$BDTlfnEKv)s?E{tf>0WKsgsL%= ztCz|&Cx1C(ge~SIBLl4Eei1k0X~}Oze)A`D}E96jEKxx6TD3s4-J@#&mDF5e%ii z-sietFRjpa*YTowo}YZaqgNN@2aRHHH9`67bFThG1XPW z7)4RVv>K}8MNOFzO;tcS`G*pyZlPJTa%YQX+L))ZOq~? z?a27jv2Vv6wtL4h#yZap*PdHo=wC$8jk|tWsYE41RQhXw+)#_Ui${Ip1C2^6DSxBG za)X5uuor42RL?#37=LK~b8ZJ}JsT`}$kYI}ITkpaw^J#HlGjp2xO($G@IG zFX#6ON3CxZDA?HiT2!rXc~E23cYiz`8Vq3Av((|a3CIj*h&zX{Z)jg}Hxy>ywcIT3 z_?KmenBjG(j+xQrl_1}@ze%d2NEUT67=v$SL- zUtL|V3Y9Whu5_tW#>DDsxB6T1RkxNR`MB0HsrsfmZ0q$#7Cd=djeWDNhxOmDet-Ys zwa{}qY_$FZ95YyS{D?Yf&U)ebZNC(;c1@WtKFf-Ovp7 zM6(%hpLg|GH7z}J#|s`lu9YJF zb;rT(+IDorFGDV{;|T1%X3fdtQ19$Iq?i*Gq(K~W!Z{^k;b7kmV||xe>!`rWT&J>B zFp)?V*H)hQg0q+<@mS;qq&K^M`>F4SZD-BlnD}ZT2&6D{vLd8Yq?&V2=zmXkkCdxC zEpuj_FV!N0mQyVqQ@@CD1lNQSX1jj1-ej3b-qzJ{?CX6!xd@np3qT?8f~5=K9jWTt zK2B!3ISB}RMzsew$WpF_)1Uf}^jBobmyK~eLvZP{at zM^v7t48l1|AKZp)rLZB_w0}W@l3a;Y3BC8${yHF5Wletk=Y=1HtDOwuG?F~-jiyp_WLs? zwO0BO7JW%_ZMSt>_ual8>)r(g828pRB2yMRXHWrsD{*0HI73w1ZGV(GkaE$HUl1LX zEVi-e0Qbw#sOD0hQKRN*#^jI5EHOPQ;e$i*OM^o(s7hZL9QjWa9J+kUC<^vn#79;L z7avN*<3sUCd|=VVhw{czGvjPrIG~c_g0N9szY z^vMX}S(-`pdBvkSjDJzSbgFf}s2@2eTM*tLzWlGzZl-ewBr1niT#(R<-LZCCJNvu0 z*4ou=bGWffb>DZrr+l#Ih_bblEYlne26k$e$|6Hu_mooh_K!37^x9z|gVPLn=}eZ~ z0!iV=MKmn!V1q?dLqo@Z>V){_0J3l*Bd-nLOsnM8FgAMw(SN+vN{pi^v3pon5!V>1kLamq<2QSet6AkI8-y((Nfk-!sLA z#-{3rX!E;~W^DEySpi?raD?>|a^B z6FBT%m?i_yZ8g{u!je5I9|-#5hv0KWDo+{xgSBKmSgcJi$0+LW_D-GGRnxZ)NVdkC z?|niw-r)LzI=xAs+Y<;Lv-G=v8D&!@FC!ZRcRreu;XoCgB>Bt8vp;ZDN-@SaW64EiA}s(IU2^$0l3dEPfagkpGsp443WI#7kg^dRMF$CJe>hWL^;BMW z^`RS0=;np5FsR-ks|A{X2?HOhS+*_<0ulrm_jT;9yiCh7pNT0;W@0`TL8uA^UjXEg z9Dmgf>35vr7KNFY#fglf&I!uheY${OR4!=TAEt>7($DKPptT)0AzwE8yS6b%h-x?9 zIH{&0nwQD0r@oS&h)I_w@vk}T{D=$Qr1Dc4_ZItLEj=p%d@5Qr9Q-}An(k6H*Gckr}@ z@y34Y(+yxXM_kH4e>o3LfmE&eq7p1Z9jHBs9F@%mwb}wQ{d6G($U>nk$}ldzjVcBk zPBXyT*r;ninpVk9#7H(Sq?r~t8Xu_x^2r#5gyOpP z*i*#mUS z(k#mtfIeg*2tw*oN|C&bSsVpXvI&$pE-4@33}bT_h@l<<5H-Q@IJ1y1%lM@{SQ(%()(F`H4CR&YKC0p;N1zIi2T;}E+rpPJZEJZHRc`8q_a}^m5=~M#0(-(pwMy5J02ZsZGpHEHDmT{2IINQgLjlumSMyKhXUE+RZ-i(n z`Y{XHlo#=U`1w1<@=V?LT%^%WS zR(DP##nY}|p6gLgwc}mnJ~*?^E)zk_uNxP$=|BeR?xHe;CU`(JI)vUJlb~)Xj=0Qb z<>uL|t7rcPgk+@Pll2!VlYl@ef9+dabL+Mde)q3X->B&kiu)y_m^LTOsX#vW0pA0CNmDtlnFxp zGqjYp-*P62kl2tIWkb6kay>d?ot)6n;zz1zt}{uvh2XQ@>5P@g>QGouwrEPO_jev;u7kxIR=4p?52fxPeYv$E24{h*d8rFpaAf>@BT zXE(IJ?4fU$d|`>Ss{7(PH#}-%H_z`f^R$FpF>Y~k3;x&qf?IXoe}bQ5MDD1ZH&N9I z4$TCW#4+?`K@5|j>GxABigH;m04|&;9;VzB9zVi8V3Mqsi*2~`DCA^OhTFfC2vrYn z+p?{~i&eR<0h_LybpT?aS$kW;nr-;`}zxA%+g zZXNr4z)`DZgGN%!f9n=S{)96IO=;qUfnPxs=*Z7-QElpnDc~Z&X!sOo!(=fpadak% zs~}oDuC-=$?&x9#DtLn+Us?-@ROurdMcu56L9{@e`_Pg5{MaI%P~MSgHSWS z-*jOnJUFP)q4hGYAsp;{>-(HbTVkwzg-DPw>7a=pxiCQ^8l*GB*Hy=ku!vEN&uFuEQ;2 zS5SaSgaE(heCJ75*tkHrW5oi|+hEwZxnGu>aPu%le{@8kLl^|0gP%OmaSm*KXBEH6 zuqi{BwejKE z+Y`LJf8LarJx?@4kV6ivihd-O7Hq&4&R0VcfDE zNRXut(4ff@Um-2gdPsc-e#-!-Sl1+QAn0(mJrJSHW{@*x9g$3pNgILPF=^upQzEmi7KWq7s zQl51~t__hAjR@e@MB{k8tu|G5bOsi;6ELeXL1-_V9IPO7DPsb`el*-L5MoR{_QCC4;D6# z{+m~(|N00Pt7j7JUl9H0C+WZamC%2lf2IEe0WtI>Gq+iS zcbKUoA6>`0GOmiH5FuE?XqO@JpQ9bd3jM0Q%R0FOPO;Y@quB^#F}DWUe{9OY*BLfCY_(_ z*N;SAaE7IbUbAk~qYN5eSM|*;ntP~oG@IL|U)u?7^FQ%Rg=Ux<0 zCQuEQk|cZ9s+cjWqF!-T`Uacy%Q=zg%3|-!SrP~MsHKNV%n$lyj>L;0WGNfhId=CU zdssyC9oT(N4*(*P7+7aKps*M0;>*j6pDr*mgM1TMGC~=EJd;EMx0tUk-o2-j1-$$k zgpn|(N8fZcafEv8e_Kx8Ui|Ii3p{K!sQ-0+Q9uPH6X}P(NqL&vA&@{DL!^}_N{s9* z4;4dO=<)XtnRNwD3#lAs$BU>;Bk9JSNA33JLe(&PB}`#e-ZQ1I8=~!o;nlz`r>d?j}n_McPu|c#@Dn}cV6;R@@%=7JP=e&ZdYkLXUzf{tZ(^a;L~I{#RWe`@^%htb{vXQ`A)ktA^;K#@g9-#o^X~}AubFm zs(*k9C|YdmRqYRzap{U}__qZikJNJbBo!IeM~*S}nuRs=T|aJ+nVhS>wbilU7tl^U2E$pOjz= z&nc{_XBF1+Ypw`4=M~m2Gd_!qSe-|E&}kV^c#6C5s4f5IAK6`aj6I^;j2}*KQ1?X4+AbJct8DjokT-p<7tx z(wg2L)w}9;{!eLCz_&8qWQ$K@!U-;w@F3hoxE(&=AZWzGGsiVy^Os2o%82tgpcKe}F52 z;shSZf>r4@dv_W7?(Zpj)~|hJ2DFeSNR|PnK?%n08BRD?4x=C@he}g7Z2SXFTdr?1 ze~LLM1d|qU!Mp&NDOehXwZJY0oMH1%X1*^z<%=DHaDATar;0|Q^yY}t7}^}MUBr@I z#`hn@BAX%#Wo~41baG{3Z3<;>lP@J212i@=lYu}ef885hbK|!0-M>P4lcy&H-yiAR zOVV6>nS8VtKXm4D)1f8WW=|4Tk-p3Q`|biDMN*(8IXXMZ6G0FJ7W<9e#n)FCU%rxN z!YFanvB}lV#419Cn`oyArF?R=n7p0-E#DR&F146uH9Q5M=9e>J*|fX~&#OD%L8srB z@Z{5Zf3^%Cz6tN;c2TUeI{x)Twz*`}O|ibce0TNTm#?_)u1_a3PKk0NEdA=z3iuzV zG1J%i=B+$!62)=}Mcm}W#W2J88CexZzpVM0s{afbR)hFIe! zGe)#^Vc?rMicJ)ZG8#u|B8&XT0#d^NYSNR%AS$naAkMm0)-Cef6%~N~iRDtw#Sd{71 z1}qF}FzfHA z4_Jw7w$DmKVdAF4l!7INi4n!rpGj>3Q;BK*>*jLCwDFU_P0cO@(Lx^-eRYiJ^GAyQ zgG%HG%D;dO{&=a0i!aS@-4WSk~x&sk=+}P>M@aS*@?W_QjsDXkrPWZkcf65+1 zFs2a}=pE%61^mZxkZF8`)S8lLU~b`6zb|B#09&fDyU| zN4Ma1gUQPylCIGTN2Fu{R@lc1d+(Q7=&y=ZvCNvym4Of(ynAPZQ=l4`A=>{{R&R@6 zgNgOp5N+%lEj~Ej1)!p_zu;8AND@LzA~=$nfgw@P#NkmN?dv&UJ}Efje;L)d{~;1W z(Vpi31Ejw^T zAMc7eiuPS}e}hYo@>oT0`PvI>-nhrB&3&CO!k{Ah?{g5~Wm$!8f9}-2#q;!K=fzFVp`9E||BnOisueNi(PRb9ueO>oNB+v`|BIN!tus0L1pEVC2 z0znQ@+;&T4bwEws97V3tHYE0;&~s_#ev??-5^nom7EM6_y9L(jj3RNhUWjHU;RSs$ z(C5G|QD^*kzsk2oe;axMvf?=^zujhaQLaO05uZLz!$#vY)e(W2*XwFiY&}0|jTXsx ziv;a}Eof}AXv??Z9VCo?U&N1p-S@#AF_3TWSDINOI#PZnlcf55bbKlyGOQwK;v6+-)G z=lp;74I%+^X;(x!BD6TxFW`^z3sMIp2VjCNf-d8tfAyafd|=ZQp19yF)hL%YY2^y2 zImtfPscCwUAJ7C~1dVOO0I$+eDRB}|Z!Twc`d2*G=`?`MfDu=3g>vC7vKjA;H?2H~GK@2O}m{#tFad5%^~(CL+r3r9%G zuE0hsT$L|^sJ3bVecW9DtgqOsa(Ta#?j{Q5Q3&fde_;YX&8jr>Qld>i*7PibH9Uoj z#3>wuGWItIWy1LygEHzfggefKmocR};|f66vVSCPSqdpGK`^CI)1_=DxS-MjK7R6X@T4&3Fk&v5?nTV~jy73Up?~3bcZXXl?{Du$j{ny3 zf!2N^K|i#gmMMp4a~}yifIcubu0>zeCTVk{L0=4*Bm;Q~mIiD&##)A{ht>g0>QKRn zpzOI6#YkpF?IK3Ya(z268Vm4$=iX|h&O(wnf6o3CTHvcB;1(c;8S)eC}ToU#-77govcJhe+?+eg+=id5w69Ufd?((1pj<4d_OP29B3l2 z?BFjF1%Ew|mjLHP`|6TTUShaOupEGR@O*pwO!7HkL{T~6KvTL)Wy>b~puOHrcB`XC z@2N|S=FAMCQVy{;h>}yO4`i8Sh;CD2n*;C5k#aD@kf5RgZZVSXHufpahCGMae*o=t zZo6^5dJmPf8}^TLgm|Rk;7P;L7kLg=!-3=-A@U%{&eu$hiaanAkyxy8jL0ia^wUbb zerk#Dxqzd#$9@K1IGL2~m7zUHoz)-4UrUv91?>5Rfj*FJ7FrVUl`!p0WK*#5O}W}+ z+hP~&D4IgiGW6{73ckDN4uO9be>|cPEDt{{`uR0XxHY9D{iNE6JI5^}mYK7Kh92V+ z??*@YAUZNEKefmfKHXv@`<-j=V`C`KQ?545^aJWU)fT%dnDJ~sOGi3Dhk%L{do_te zXFy=0z!EFWvqgM+Mk378!NFA;ZVd)=))_XMRb?lM&7;$*ef)=AbkGU}e;BE(l&Vhv zU?7>)6maA+gG}uhv*8s5sYjEwKH`>QEDR_BuvxBH} z-cN5dMiNu!o6WLl>Z}^0d7IZgnj)7%aF!PIOOZ$~xVN#!PShrUn*mR3ohh~9T zC6f{c4XoqT?@o7P&7nJ4cc&_~W}T^geUDG|XHDG@mbq=qRkBbAe>8mbaHtk<{r>=^>#^<_>5S7=<;ufXl6UOwAu^ISzP5E-7u*xqkX;Xkr zVbuU<{%ajN{FdMue`?2|af`KM6;^_1GyUnN&f^qC{2`Q0(^v}WJo?u+ng_o zh>*B`8J+=?(CBQ`gO|mD*)~rWh-Fm~D&16=3!VS~DunymYaSz~*Z011O#*}Rri@Ji z3a||AexAp_?_#3@l@+`2l2r>WboBJP#^7jD2RPfg*mjkae>GuLs=jEb0}R$q??!!< z*3y)-4;>v!ME_e=@ZxtOZ)_E5IkECZ40*g3{ABK6?b zz_;nEsmETjf3!ROUizz)0E@Q~_sd0i3*4+lWAg&8VMpBb?*Z&^kjf~5Ye4y4p<2J7 zoJ-ZKF1ku&Atg9Zhl`60Owz3_ip-{X-@m1L01#;FVf3+MB6RxBo8q=-Nxn$>Mm@j$ zF|_M13(keFrcP9heKxFOYS%uZWJ}PIIK5G)oFdJUe`-kg)sP#W+1R8r>Sp}F5LY{V zv5zaCd7%yYL0m>$Rp!Gb2kz3bvEa+zWjZOoLnb(1o#&AtrqSKaRgW zct7N2a*|#|@Gy=K-vYH~yalRGa959}<|*j^XM%xYHmi7wgNJlyN_XjgM7hXVU9e0F z%!u8NAEO>%9Y-{CL(b8IOVxOz29uSJ*oLU83D^H0t8+d>lYcTN12!`?lYu}ef9+h~ zbK|xVe)nIYd!wf(g!m1#lb2+YNjquU<~*0o++907iMH6tq9e(6{NHyM040(FMas6U zyUsm{0zq&AEWZ7AvEVlsXJ38K)QG0Urk0K_E=NX^l-rTAiliwUT}(&sl8affIv;aE zll3w?A4{41H=nG_}ZubbumiOXen9mou7ZW z_}eHQjVUKmSl_K#J})NO9G!ND#I=dm~W5Fy8U#Ps!7FSqJCu?7Dhu3Z>{eO@F-fay`K)+Ae0ox{<~{hvvBeRI361^|XQBGi~# zNfZp_m@#6F@a;`QRa>tLfAzGfr2jcc&uh|K!h~|t8{6z7g@>)y3Tp{sIaZ=+tBbP! zGDU>aBSy4UzSjFxrm+qPcqy->dY|%WYmzW6wv{BsN@w3)oc(@Ap*S7U5#xq15J^cv z3{|7a_1U`*>1YZ!LF0(vYIN_aUXMgdQiIRUM{mylb@mOezNS!2e{y&NmY)zrrJ)DY zpcOK0RD}g91iYSb97Qi66_uhZ&~q6tR)cD{=7>9`8Ef}aS8*NDLrzk;nd+~jLrMkV zUO$Wq`0_O>pGn@urU|N}Xf5rjzY~Vv@Tl&~=6q}DP_0(aqX{*vs_`L+ zqnbm|l;%C)XzW!mf0Rbn1^UbRm?|CZBfu7g#SrOaTd7-}yo+nK(zexyCQtyRDPk$E zZcR81^90B|L6Acj=PYqXfzzaz22ev3cYum_9scqP!=V5mGSpv8Zymg1X+YJOqF4YH zwq1NQji{w22D;*)!#ou_gu^q04tW&la7zAlRLKp|#tZ~_f3+9=q*tj>3C$BOacTih z5EgN?+?{{NL7h;>VA8ksYTZ-q?roMOaW5G&X#l-w)5-?x$CIBjoa(zbXuc~GxhO8n zd9X96PRxpAfm~qiuQPw^$09s&wJdLM{N=p(4cp6O{a`SlhHVD)4R98dd>2(RRhy!e zR}kOsEp*88f6bCX?vc{uW5o>ay&z8F2}tjasz~x|Rm|c4ga13tVKBuabR~3cnIqX) z7r=h}7%EA0Dw<=so@Mwdp_9O}kg8<3=I+h|>B5_<;<}h;%lU)#KKf4(pC(ovBKe~`keUz-lB91Fy&d+dBxF)}E~ zLfs9ggdxIFUHv&mNyY}2IV{gHqp)JcA=Kp82)+PTDtQRN4B#d;_|-Q6|6l~agUZ#B6`s_TWhxlv}vQf!Q%ciW^pMolJ_Gn z@Byjne~|m9=*n`J16hn3WZ+e0;N5tHp1h5;%z$ZC+~HI1$;SCwn+(;Onk=fb;1W>5_Hr@lR!FGfjHL9| zLyE+XJ!ql}>EP8S_XWDySZA59JQ~97B7o~de|UUxbqkgvJW}(+%S9;57E@ofhROy} zxx!p{JNk*<>#n@tRbT>^!|I9f07nSxUN9B}FBkzE9bsgJaYq>N1Tb$i7QaT64>W#`nLkcfQgYz ze}So5+vDHz^kw~9bt?Z>Jqk~E{aaSo=}!Na_Byz<&%te)lYJhpsEgF+;j&?7gY6o? zeJz78KH#j3n6mp8Lwb?xs2ZtoD*yA=5% ztPIvv83}6G))_E-ZK4M3TZT1e<0wcee*jLc8cG@Ur%1YW#V;buXX~F#eC2zK9~@HHfwpkr)dUSA)i1l zn*)U8Qte&L^^qpwO}fcGg$CXCtDRT2=dX)%41wiW%gnjpX;FH>fIlj^Sq7q(yYM}f#&(V`@(wsQ=D1opzxBPsqVlp)N4MiVaI0AOJC$qiwn*^8 z|KD_+#CByCQ>omFce?6S$bN}DJ7%Hr`azU|^OVjFhnoNuLDd*r81nvnF z;sk*@`R}*c_DSSZta7NSA2a+7uWN0AMK^2|=$}56di9gIs1gG|r7Hm2tM zEy00ufK6?z9OntfU0|N_gS9i=QLdjJ@x z39i~1pw%>#L|sIdatwhF^APuKm2Pd5uFxMwIZb{l(NA?!$to`EI#z|Rcecn~B-nY; z<=nfvs}SlnV4p*zw_=HbfBS7?n;2-mT$b0d&Pqm7O`pLX-Z8{(+H@eTFn?8q8>P8j zg$vJQ;qL0;8t;3PQO@I349u6J5zJAYnDaUwzT;}6mNy-3n5O>ePF@Sn&SoLp#VN8? z8;0Pvv{JW$RZN_g`e8sN2m`VTLy|4?s;&!+I40osyr2v&XZbQHe*w2{tD+t6UwEIO zWweS6v@dM1fz1jj2N)?w^%N}m#YKO-pOLL!`gFnQRrhL%)E8ir!KgVv_hMs7wn z*mI5sAOXhdIrwk&V2qI}u{Bd2W|_DEyN9-{#}o!Ky!f3A&wRo_SH8ah}5mbNy* zqJjhM1D=G-6I=_-dU>9?>WmA)Gfg=d&O`c3*PbWz?qzJ}le*<&oG?T=m9+nz*LX#`gCoMcuXv z*4`Sgf!I}iW1$w#`YagW6P4;^DPpBmT(coc^)%sLP^nl;soJ=PUTqDn%IHq50G6vI zZh=aowQld!X1}@IL{I-h_R2J07I)`Ba`Wtw*BcF#;P1s3+BEI%FqdPD<37o>EXoRG&+IEpo9Ki!qxCa!aIgChUJn$*; z1t7lwR>MAM~;O;i%V|X;@W%R1IYgt6Cd=mLd)#@;4XmKY4 zHNoc`b1 zskwPNuQsPtqgZ;LH^Q|MjD6~2oVueXV<0)z!M`-VB`Mt}EtCz^=574D89vo-Ka<~{ zeb$3%#*0JOXl$)ZM;)LbC-gZ!T?M&{6T_6+!`WqPudpR{ET^I-w%H3ahPwPntzO){jB5Ie?N!Iz8N(21CyOIDE$o5-YMjSGj^=QJ-r!D-K(qC z$$hI!5o6e%)umhn2tU!pd)zMbG8`25%vj?)36^d@)aO1M=#O|ou{#`AzwN(&7fzNv z_?w&KCsq6x3&Teh+-Lj3SN+N;%>|9qR`+EXh)0}6!7nt}>I)5))jmJeO-k=~CAauR z#F&ZTk`v8TllZ=kPog$QJgC;I%Uy<@4>RogK*N5}N9MZnfqTBcW?m>6w1Mvad?jVz zIYJ?52Q2Ymid40={XapSC{B}CKqmt>G&qxiKq-G)-E-Tx5r6kzp|&sdG{WJ7__|IX zdNa-BZraSXac?@4^K=-AiFuVog`(o-{`%VmK#8OwiIQd6eX&Ry1Qz@G+g>4pZsOHoE4L-F3QEX*JDXda&wnokA-2$+x(g( z_x^wS`@jFoU%bAyGRY=&SzX`W{P4|duG%Zm(U?;rt?-k7zkru0O=>qKT=;3=;-j15 z72YUVgX<)WSmgOMyj1$%Wd%=IQcUXJ0GB{$zhrMSeDBM)U2 ziLvQ%S?a^sn%#PKw3& z!}S&NqRoC*V6f`N=!7IYaE6Nuo} zIL+kNCVu0&fB4^p@Js{CE^=A@i2J!=;$R1f!XiQ~$ppR}5N_49r# zn|JTRO2wk6i)`kfdXCRZ_tvCvlKSfZmBD;}s0esnm8gbOKf$NUTTU|?HH3Cm!%vGg z>cmZxH~C_cJK6A{^D0e>X`cD3@}vL#+j?1-i}&Kz-#VSiR{q8rH2ki>J z6vTjpXhVyak!+8VM44v5&s5T=Mi8EE^r4Q;B8UZtxSfW@)WHzWR5PgXCK9&db}xZ{ zp}^`6Pshb#x}G>!2E&$F6*lZG(_MJOx)Mtg%)e$=Pfnkg~BqSmN=xYH{D(9LJx>%lBCI1P>lpPr)H>Zf5&ugnZy0c$pN!O6mvQc%!9+ z8ZcQ+IF4(@k?sNzL?GnCDpv2={8%aA5(6$NA|X5-;J1F^`gm4;7kz#Q_I!wc?}~BY zw$@MJBo0lJMTMc2YVT$z)gb)VuqSs80E=Pfj(y+U1rV|-XKPFb;^4!=v?8rmwZF+f zud`+_KpqH!t1wG3U(UWpV>>kf!iG9kJ;-V3XNzgOlvv}G(!`wxW$7NL0bm~H7lg`< z#{|Hzp}QkX0K8(8-vCfc0VuqGE9S*4L-=S!;u0*mNwAz~KuR8fb>!+{XSpg6VWUW6 zdzUE@cC+9zjxtg+2$+e-12fpKcA&l_l6QQT^x1U z9S&8xWz=R;V>^z&h%X8`{8Ksp{WwYGqgyK%zFT7@{lc9V-XPUvb4qhQ2B4aqSE8S^tcyYs5e<5Q$_U>Po8CM@K%VfmZ9 z3c$tJ+`wBm0Da}3JB03kK~6JrQ>-ohgAHWIVF9uuI9dhw-z>2kv@^p1wRS_nrTqNS zCb?fX#4wYTyG)WFgzl$0`W~@;9@U-{4au9+52VMR3=IZkm0~+awjle#L1vCUe04za`CiAO*_qTL3g@67qq9g?= z-MgXl5kzLL5H8L}@2>uF^&R%%dYlru9l6J}H(> z6C&;ne2)j7_>P-@Sgbaq7O%pikSk$&xSr3m>g%_T;S3cKmIoxsgYGkI2~e860}$Et zd)iBu)wEc^1paP+TKKjP_Lg)~7uc1Ub$roc2mZv4RqDVi*N5;YwzfDi+BWLP`HtL; zr%#f*4OI0vvFR+R-f>htdVj|S+-=YTJ#X7+YUHR>xuP^;V1PNyCVyga&nacM2==>( zPtf4<_@IK?;Ck8#ksI5B#x>B-g{JH7P^^`{Lg5Xj^-9 zE24J-7jw10X8C`!LQi%_gMjr{Vyo=} zf%=qk%#P@`mvZcDNYG28hC?)S5Td1fAew-QfG{D!Nw7yEv=m~m0{6#3Cnb9{LW_f7 zZU%@B2x&8WSiAH9*3)OhdU_bv)5l|fy`SR7#hEy#acxC32=?hg$&tQ{UNGBPZrEw$ z1Kj|9zLfh^)p&>?AB4bN2WsI4y&-@|L``n=+tL;JI93I*tXDTT;psAfOP09ro%jG? zsj$Cb&hllZu^r={=FNw7__ZDq6FIt?|0Z<7bmoh*6ZCt;BeS_D9Fvyo$$5%7&i#)q^^p`eHj1ot^pb zL6M5~IdlAyFJ29%_W$t!nkL&G{WP2$Ta>kL9WV_Uk-%n`CB_7dp&J148;)W>FbZXE zWOH-!C7D3jDs8p@L5qJ0uIn&X@AzNnwBufBiBRYEW_ z*pTGDB>laZ-_LUQ{B|?TOFujrF`C}x^L+H-`cL1# zqkpowA5O*;BVm}^>UyMEx`c(WWVM__%A;TH-BbvBq;@qR1>}<9$lh!C`XK&q_NSDVc3u$ zqTXsKQ0*fX5}Y?r{Laow2tyc-phzp@#{Ut5WK0pk(td2`J%Q6cNFYx66U+jK_Tz|h zR!>?7ZpDxR{ycaqd->+2;5>4JF$wGlH)SvYTS}%{2X|=00O^)C+i79iXvAUUjDNJ* zIk9@IPy9KwkwHcb!~OFB524@hCR-9gIZdp5@p>M{0m+d_fFydzNC)rHshwl##5r>VJbsAI0rsPIOrDw3&V{9whSwdkCG%;YlTpSua#I z$vD*{qgB&sDRq!U55ePT%yGLIJ0y5=pWt!87N%X26WlL(M1UmFw&)GI&pAa;oB+ci z(PN6lh~C~)w;0ZPM9;|oMbYcSnL3VAl!9yg<$eVGsVW@44}riWl2V<=zJGrR7oMNPR8vQz)%|98-n3 z@L|^D9RxfETe_q<$ip$PCjHpWUvZA3#*Hwm z_-u|HDwp@!r#ii3v`^{4FSjt+CVDFENf}V7vMtO;ebu?s<-%up=6}nwPXA0Mn=)JH zv#&Pm^xFM=YoYmCCyI*2C-<0t$tG*JtZ+%E{8PD2G?8@q(Pydd{4xK|%jI}kPF*&M zq<72NbbD+*%k5&|R#+b*5yqfd#9>ngq!Q+!DU&;71Lp;-K{e@zaN0(Kg0Nh0$?R4Y zz>>pW?Muy|46|St&VQhYlVwmuOa?{tWl+e)+$_RD2P?DVXwlw4jwtyQ{a?SD&veB5(rhr9Dt3f)S*#On)ZxtM?ypGKC)jTF~?| zd90?+ZNRFj^$%vr?^l1h`pMRS+ORW)s|1Mv<`qV^!0JdK1BIY0q+GLx1hPF6D3P`T z2wP)yflNvzfHY13)p;^02L6|hCug(W-`7dN~T7Z+Df)??*L zy60(rgBf4s(|?X*RxZ~Kzipna%i>Fz;vk$RmInLKq>&Z%r%69r&sNtN8M!AT1Nc`l z{sN8i*1bB@`%^M)O6|+ZbZZlbgJ|S$soF9xG*A-|Nj1p6_YZzs7As#&{?!(QDG(I= zYc;Z7iYdUog3x6Z{eZH*DpXM_kVAN+x8yze+3%h>p20kv!S{!XW!@U{U^7F$; zh%_sUww*=OG@{F4hG?fN-i4#R2Eg z$%n<`kbhccQEHjIv_fjzOW6|#u*gcP?8E_G&qaWe9=EoNh;~k2Z*`WmVSXYk=?x|- z00>7Mj_Ov2gBH+MU7D($E8a1I_%Il^K^P=BK9_^x7*t@doQp-V?kP)gNdOjUp3_&+ z^$Ee+Ynw}}{7v)RZ0j%uq@xwkAc*>$LVc=w>3^`y-9W!B9F?8Sp&giYJgj_98oHfR z?_`lOzXQYb^bWls49B1%O7C>lPPN`?d{=C~@BqmtXCOz)4Nu8pt(ygBKH+2(W zkeLmlN+sPIZ`?sx3_EAn-RKn>8YeV_A7d4Rr3lFo7p$4bBeK6{WmwhZbHdL1i+@Xq z>{PqE;-QB3;SQ>sM~OzrF}EdDrj97*ZaFk4!v>ztD#BT;WOa*dv66K-nm^YuyWVMs zEqCNFRx8DXsG{2d4{O^YYFLVi(lD2wvWfrON%0BaWQpzmum!C*;U-zGI#FtLr6zvU z=ccyw-dDK>GU$sCx_IN)l>{a$qkr3ygj2_Pak3E=BMkHb`+N;c2`bH=7F*%U;}~&6 z2V|d5&6>|)nR7&#-PlSB7Nv2kFjRp$I!_e(4LD3kaF}X2vt0($pw(g-jGZVp-tpx5 zb9CRn%O8$^X#|HEK#%C*uuf+QRe;g{&XPa38p>gyYK+i0{pHucxq){hBY#qelU)+dgvGno5~I7OOk=WIH?Tr;WHbYyWfAd0`)ZncH3u+p+O(q^Up3&$l6b-QJNc zCNQU3q|$i?&rgj@9mW>6fxpoktIga$Z+{k(Wm)F4%>I=_KK0G|(jZ(V6&uYhzEy?_-rFFL#8aO| ze{VszKfZfAFm$%W*_f6s!Y`0u5V#{6@^{;zs@y3?Hs)zM~~ zj_j!Cr>Xn)d6W63q;+9Cf9%*}G4pfpGRI3UCuB#m`n1Iu80n#KyMMBZ>y+m@+eTy= z&%alpAq*6zO{vwo+)UP+GOs$HaOxVX@=50ZWCPbdMmV*vJGjQCyqxFL!m)w-tpk0C z09IeCLqS)61lO9wj12i%-lYu}ef9+gb zZ`;Tfe)q3X-X!d5GWQFL0ByD#>@Lt^o4V*jk_SenZ6Y@1NOau&_dRnVHA4<1O16^* z=#yz`G;`+6xqRm`dVPNO@(ql*}HjjT`rc);Ca2S zw&C$^v%V{?il$mG$h`h>vE*3He{aghe|o?5e=o}SnDIJ%r<><)Q&#nY>UmRMZHlJ6 z2-6q#-IvNuTl;t020mYWIREYC8?IwQ87D{(HN&39_n2ZojIo(QMqxLKBc<4EN#Kw6 z13&puRK$}RMCmLV^a>VNa{ey2FcC-+8Ldk*>k33D$*r5tWrxM<{%Nr!e^SlwGBd)r z7*i)t`6WLkVe&9{`cr-ggA&1EAU7>jf;bdG3JN=Zw&cJ$Vwu8_;Kq+Me}y580(o%q z<*He4?Ehr$jvwAPMSWFzQSl#a?}}CFKP$qkqQ3AiHs!;nYD)k1=g;*P0Ueye83|12 zl5lt+;XB(f|8*E%uj}Pae^r-7AmH-8UO6euiJs9&!>h2{OTRrz6=E=8NhK1-OchI& zFrMLLlmsCPtNcK6M?*Mbz{_Z&S6P|0x*`*TU%nAIQG5_DHX{@fJfJ}>ns6O@h9bsiMLZ+MEkL0QiV#XHHZlYdy+=& zBUsZ6$3VFSR}fwkuFXIX{kfM3ITUO2|dwf7)c@|7WnCaoV+~naOMw-z>I!m%FP602Xe~iRDuE2^>Eu8($90>&` z=nmk_*rg=fqhV*9X6DDM5llO)-fqyWh+LwcAz60geR z^5EAWs^+>y+HRA|LiPZp*FDs7TNc}UV8Nyg==}42;emYBROL2%I$XMdBv4vp<0=JP zv9QTR(5$~ zmk=Dxz*ry-TNV&nSY2G*p1u2kXBY4xIB3K{=pWqB+ZjZWTv+UIGyCV+Kh9p;6irWP z8JGo#8w92Rc;wV==)-|N;AI69LO3DGWW4-qf0iN2xWs~FDlts3(RdVPd}!X1nIPEI zs&Cyys_aDAaHLx*56Nt_Dqyfs3CDiP@<9S)>5ejyje~)FPABAn=%fq_F>#8eMMXo7 zaTZ%6;2Iv`T4zT|o_Ga>#ujVL`jLV4OCn(sZ7UUeh5;>0Iz{M(MhvTcLeH38Qywey zf95dnLE#8kp-AX~sU$NYgiMAcLfz!Udc)v2EsnLMhM~U(Ke<}igq45(7;u75Y+bLd z;d*EjU)ODV>(b}M=zM!y+}z~t8aO<~r;Fl#WTVpP{$bG)Nu7n&^BB^klq@v|JEz^& zMH@+c--@Q6PSNxfMbi^fPN|*|3APPFe-duB$e73J8BByADw}a`<0tbdJxj4HC@}b- zM9mnnph8E??Wra~fM;MWrXvpbTq_sI5He}^;8{hw`QCc%T=C}Jp5dUSC4}pcr^}WG z;vD!mn4F$i%p?P%`1wOdZXE@&iHf2I*-KF?Ac_r)ux(&)G7K(4k;}8-%!{k1D0vnrmZh=8R&Uq!=@G>bj7TZ z2%gSuvGy{bu>{AxOWWLKJuKJef5{36VoJ8gM(3SD{gS1LYJFlI?Lbi@hCOvzUi8u% zfyFYgcnl8-ffVO1rO9c6hu-Fl4N#iTS?;e4OwW|Gm4R{8PO-OSpq+?<^WCGN;L)Yt zizcX5cRgbo?1Fw=z&!+x%30gV#`bMKy{OsoY4~?pd=okUogM8}>OhCYf8qSrr1Iut zY>n*Onm(D-A~j6psS?|hDFZVaJw>L7K^l|2G6j>^a>p|W6+F`aOVx8pm2$@w4g4ja z&Nf0kRYXWmDY1!swVr`!5@BOofE#gjYLJJ#-qBj^t;5jSQaOz~j3)5l z?P96hqaOfM5<^9ii=m{=e+Pqp3hsc&ew(kE*sGrke4T{gnFFMtISZ0XIG}b+li11y zh6lS?-sU;SWQSs&RH6D(qju{YsTKWn5nu%AFakuoTK0mm4scu+tEPQbGy}jFYECXa zPv&illuOUYvuxH)G1k@u5d|WgoMzbuIV2S;)kv*EKrkjxR^$Cke^%Sx){C1>SzP?# z->%lTclXVRn!5T#$A{;)Qqww1h?!!heBufxMJSF9QoSPI@Apj;iY;Vr^NK;BI<~E^ zN?Xdwlv!L$Cw%3PAY&h!!j@&SM{GFKw(`J$rHr4@V3R5@3==6AT1%1kUT;G^lUzD7R5>_+<3XSfWC$2&UAgnc z5cxwKYm6KX)~TilD*#*&96=nm54FL+xaSoT!l(ub291GmZHGc=-hx{j&%nOYM`zmd zg$p_j_AtaKInBWL>kEu0xF>gVJ~#PP(j@m*%&3jq%-5x8e<0s!oD8yoz_!4HpKyu? zI;Lg$d9k$`X6`3pYcT0n%IJP6BP02tA-d*qF7KtoI#D!24xjp^gemKrr%jMz3d z&^v(H^l@g30YtG&Q)OGzVzcG!l<fg3dFWmy z*VV{UAwQ}Df7`bv5(Bb?zt;cL?=DauOWHkw$0Cy>b^cvM>LY>zNY~zGi1*rLgJUo) z^4q%RVal5%uK9qqI6#p&fubIimLN9Z;PlSWu^f~Z`J@SeX>GWTK|mvEcgG=IX9&$= z5Jhwiu6ybi5U6ZIFt@F4?;rrlMsLQURU2~1R*lA5e@n$-57vboI>`x+#~bQ!ywMXv z<HIf1A=^_#DbK=<~C8pS|M5lpUv|TqiIg^qzyf7Y zf3`Yrub{g}zkzT~8U8P}`F>0dn2DWwA#+gCz$(4MxTJ=T+)al`F+0^_O}dqP=x+K6 zQy#jTe!`R=vxZJ2rnMMrh{&!HC2EdX^j zZSVp39+m~97Dj)&|~Ni^pZS`7FDD@HUYWs(T#CN)BTE`~|l7{-WVDw2Airp!=RT>i_Id% ztzbkLd7OhaI718>QI~tUy_^Z5rjMT%DGPH)v^H^Krb^~qLs~(EvT+PtmUsAy1IH~& zZM_ktt1&l=&GPwDspPkfoTgI7A3aSyov&_E1Ucdu8SR+37{RJG!>T6Bs+D7M)@jws zEcf%r&GNT`z1#Jshz8*V(S|`%L6nM93c1-n78+b{;0^w*nLe$q7n{fVa&^h=^wIzG zx%lE?vwoO=oWp*P%k_#RGm#O5s!HWufBB;fB-5{Qys3@4S$Kw5i*3QM*L z^w*@5Fw2KoszAon(gED_lXrxtZSmJjmDkvGy}J8c@c3!&{p8vIQ*vE;6r28Me!c!> zIbX%!mr1NP0^e>IrQpE}ifPxyC-duTC}aIpx?}hbkw}VA)EecLEg}(45%~UYy(+l@ zr>o_n2tBZBMUaWwa&9U-cb1Y3J4{ZuLlye;0|AK*Nbhsa`G-+e?`Z)Nmt}1 zD_=?QRU6fXNs!l7@_v^LN8`+KzE2%WoaNo3()j1%U1>WxUEY+wrcp*5#5DN?Fsqm5Xp6cZ+*C9h=@2p1k#0Q&?n8Kj+idv&h9RAUU00&sW87 z7xV2h#3tT9+&z7q1;4?Ff5I8LuTQ+8@1Ba;==658zOUvjf4EsZFV|1yfbHVi164U@ zUA%r=Rxyvip0=^#tN~*c<^gc#cSTfh7Tc%0$7J1tD&4|j3Ypd(Q9(AL0jWSH#(^RnF+xq0LMiJe*Y_76ex{Qfd@sRnA_R6T_vD|WqKlr(WUA?BpV#0&8V<+Of7A+eo^V<3bL^NUAH~u- zkc|N7NEi)0B-gZ%=FnWsnxt4l07v{U>c&aJ%Z#IBq|}?SFjN@&uXL$mMY3{GeU-z9 zR06FhjGZc)oT28iRev&1n#gFgpH=AK!WUR%E+iC|l~8oscUuhyp|;2;dcZSPj%V_G z&pgBqHP39tf3UElAry)g0V$OfM6(kiN(&+-nU53(U8=!RS1ida6EfGd;b8?|EBkm# zZ>rgtaps}E%s#QlfBlA|rFKfVQeWG|UOz`FusMOJUr9wmg*~~q>)ayCx%DeLw|=b> zB-^?5f0rtXI@dt-m$F)GnQiCYdW??d7@%t|6GKNVlYdr{>LTbBi8y~V_bVbp;fKjL;-+1 ze;pblMoV+B^m)T#VPFQS6+he5$u)(U_F2M)O>#-uxhCgdPVU$Rw-S{I3lbK7=sk#fYez%JV-W~2p$2zrp1x?TG;3Bya!rD$*{GDPwx zqHUIga^Fn$S}xM^e4G@#NN5PQyBXh39WV8$$He{z3f3^}mD$U_f`P#sFGF;Ij%M>I3zp$K!{sU?>~ z!o;+nAxtiW94|~4gb0@>Ow9Qi!sOxycNTTBI6r;}8x9tT0U4`=pCMx|c#JM%7kDs{ zCu7X^88YS~hj&WO#i+>P^B>}uxgmLCsvnjo8#cVnWOk692{!!ZG)LJ!e`L^@=tq#h zBz2hh=fVt|K#b>Z#NgJV(;TPo;FzApXYCI2=Pt3%0VPgyhRHP1(U!~<2 zdrsScjX~UyMEkLO$ni^(4He8#?Fr0#;Ki^|;*0_>e(S8grgl8M_~mYC_Y?BbA_F(1 z$BitJY1on-#GvCvPNiptNOxjHkt4Wdh@1^n5c#;(lml=IicpU4f2Z(c6;T0Dh9a`T zY-~lm>*!>)8Bq}tq%std4R}z55N<@kGlYlsy#;tj3muVcSm=CI)I|pPa;S*1z)_Jv z#bebJ@ooeyMN$VT=}ge62zByU=zN!kPUGPY7+@?Pz!Ar74s=SmyyGLSyBCU?!ZmIuxJBr@=;`tST`(lK5jy0njQCN zScBxA4_?6LD4r3qZUiMoQU~d1oQ2BPVGkFskFz>Fmy>ngf9H*y?P*`W1C@qD&vC)M z_iPJZv^@SAhVve;Y@cE=O8c8s_A+U516CLF3V&F{@sry9iWWv%Dh`O`cDuiKqEJeI z4oSM|`2LJjslzKbF1!jZ!>ba!Iw;;$j3iF_)j!_e9!@DnNg0kDXDEjAaOY3AVk%mU z6Wvw}Pd!wLe<(w9H{2Rj;R}u0rq<#M-VZye3h#Q*}ULmxV$r4@~3z{rT_#ya@w7l?Q+}%ax zY}W3gqAp-shB(7+U((_Z$*671liYrOpxX-x>vOQCe;ZG?75i>dif~+6O5Pt1ERj5( zyTgH78G4UV!od^|{=P;y_*ANrN^t(f4zo+Yc;~MUfak?0J^t-)AS_Rm7gx1G z@`rGF;9_&T-rUCv7t1lf_{-nQ%LV;m^j~K$%WeF9xGFGSA6k5tzOs^|8>LDdbws}Z zX|E9<9P8$)_V7gag~sjc9gHKC+HfvkM3_0~e_Z|^x6Mb=4|*PLfL1qO{w`;g5WVk~ z2Zz{d+;QFAXX%6bEOqwY%SFLD`z)2+XECLU`?G)))X3AeRU<8I>o%u+){e4{0AV$8V!G67@;p-(0UoUAGYa_RbbVUY6rDYw<`LC!lmM>bD zKv18#0F~D6x*A4fG4?;%izsW8xp5~0HZ?bsfj}sK?OaWB8#flb>sL%}Qe}w%58sEa z+DcWjwR=mgZgCE>t;DL>vLn0Jwf}zm%?CI`&JZ98idtq*q$scl=y_ zG@(&aL>X0c`zzjBp-DB)C_$mQecSwe{r8(+ZvXk+k6JfgL@(QRL0Ipbl@cB=ZL8nA zR#P~CD-<=OMnBC$IWqf0E%(X@D^1tvmK!y)S@|@Y9-QnLJPN06LqK<3tG{-wtelXe zgjKcyHP-bPpy2{43hF*`!$(e7<7PgyRolhTU)RhKqO9=NHWrlle*AyCS=o5~N>bbP zs~>K!{cNEO^9$iMng_N=i2~axa39 zjTX^{9bn{zcGRp!?c~jhj8puoq6_@0WsrECp;zOs8w4Chn`c*Bgt|8+>=J>qu!G%y zgyqnKO?FAmup5POo>iAhEq2k(`A||y&527ogGT@f)l$wO4){D)4Ts}O`hp!Sr zM$j2T*f)Gzz=k698*zY^I!DQ%n0ZRd)fbeg&G0%(0q$O)`lh)fKjeEhfb!CFI{EEuibhEcv#el+}-38D*n&?BvQ>AA} zEe$|P$gI?3LYGFM$0L|6I1xo`A+#f))E)HP^gXwO?rc~O5CBQ8@dg*@hpxB12S4K# z_!&>3Qo9)XuGl%pCJIjOP+<>fOO{P2vuvj5DbksKV0YxI4D^ao4s^Z~R)gYL8O3KC87@;=9>(5g;7Ft!kTvp(H zfVxoH4=}1skx}JxM%5sf8sjp)j`Sk6N@Z=C^!g&@rBf?!&Z#m*oFDe(<7S24aZ0Yc)AJ3*AN zJjbCu!j_r9wg-rUP%eyYx0x9bTcg)oKD1s7;mt6Gd8>h^jOsRsmQx)k z$mpWVNP8~`<1@~GfqXhD)k#=3wif!~RpzwLYd7TrYNLsViCPEw2QL~@x$GJkgfp?q zC=*uwQHE^DP!JxOej77x?az^qLyRcyUhH+=#I3l(YbvKVj%A|$B*Q~*zw?j2lX5(E zT;1_9>9iXuFIu@tD~n2u(!cZF3{!8MHJ~HmuuB z=S7SZiv@BX&m*!z1y?k&v!`=B7lmjG9xbWkPUj3*ifb8v)ajgQLeV)Mab3R73#CHZ zsW>y#YMmi$~Jt@Re~IUvw^I#Pdi{H#aQyR14?EsJ(e&J zZjXH0Az|SzI9qcI*&n=v45_ddqZL}a0y;DrLMy7!k+6=XW3zO_zjKK=Qc#K$f%J16p)jZ{DdWWgV$EfG}e-jIH!^SrsZ7uv2cjRa$Hjtb`sWwhNUhFONl;~oPM@oiHBK(`Gi%S z`4iQC7MTg&ZB!?V=Tuh4IHWReuJ-#hmm+C@0s8ou2?cvx63{~h`d>Jvn6x?#7S z0{GGtKn2basSfu8R(0|#)!dEal)v>j{d5y~?f{in?L04FCVwI#Vae8HJ;!0R?dK+O z5sA53a&(Gf#4;7?kdd(VA;XmJCQSEC7K)gWt@`c!9ExaP9oi(^0u&R?^tLn5^6GPlyi|3BvJFF_CN{GqVSqV!*ZTuOF&NyFm=F?<<8(!55Y83;1_nR)7^_U50qV~oUAyZCA9Dpn09dG_TM6q7%$L;=DhjJhkDCsO ze}%ca#yX#H)u|$Ckdd%XB3$_`|DrOYRJc;=Utt0ztP7Q{6V(wFm`_+QN4heH>oSD| z9|$v`k`F85s&drEkf-jAGVM`+Ja4sJy1#}^z!*w?m1n=_oz&zwxG|j#yZQ4w+no(k z``jZ=#-JyW4*emXjbn%s5n-BWk?V%bIE0x0eIAt3W6RhQa$NpBCEO+_`yqdQ_weS1 z!u7kGl_7immEYgvu_0#>`@7-q)kKEwP$L=4x`|!ivm#2q+H}{{rzkdDr z)PMi|-4mt<`Ro7O1bzJ%d}{pl)BUHX`_K0s&cowx9nzO~_XF0$WB2au!`*KmAMf6G zf89O4?OJ|(CAD7l&mXV{?x&9*tiPtUy1svZ|DnIu=k8RsvdA9V@9-~~(pbe25CWR0qI;iq#J4J5EfWqsfA_9rCYkYOFC3Uq+3BLNofS6Lt5%XpXYs_ zc)xSL@9a6d|2w~#xifQT?*A+kz1A}>8EdE|SP|+B=K^x`iUH)*6%2vA0A5~xZeCtK z9401R2;33;A2|+_J{aZ(fjW!*O+$YU1_r_JW%3~Sy`nnQ8KCO!2mtZ}fI?zGVKH7_ z03R=}=zkQUFfo8U$OB>xQ0E4yLY={GI81U-7jGEE)((EZ&wm~PtX6CQps1)Y=Wla> zj1w3Ju>v^*)Io4Nu+#mHRv<^fGpH2=4EO$r3)UxgaJY*Y509s(CpXB+jT?Uovz27y z1b9N=b^sl)8yMyRwg&u48K41j0{@vBHx3g(*AC+L2Y3dxfqQ~rV8Fe=5n=^)cDpxm zceVz@0Qb8Co~ft-G+n^Xe<-W{p}-0Fvp4`CH}Jpi{_ z7q}a@8^rNfjy%8I+?QFw*;)?jQ|DfU^OwvP3ZZ2G|c`1HS*kLAZfDzyLVR9qfnrJNV}c2M7dML#*HcORz1(8RswW z_hPWkAM5+`he5mmCcO9U2L$l``uz9F?7qXSq0Wxpf2sdIVjdL@898-hjz3fWFO-#q zdI1nzd;$P2K2afF08oEGPyiq-%m?uMrz0&84b0ee1fz@5ewLdOr-#|5h~s|1rDjU~7oG)4!<-9CUv_4l>TRj{hwr#7z<6 z1-90Lz^&~5=$Jp`dcS7P5#kKig1SL|-7WwwATRH~*!_T6Io#hMZuf2Z8-efV=bu|D zI9oxje+?R+pb!8AgMqwp?vMF?B?v$O?XmvwxGnkm%pZKiu&O z{DB<6@P7x#|3Bz2#>e{)X8Cs}$oEeM|BL+7<9*fsOaAE(?((+?1^3V{}$!Hoc=w`f4TfyoTB$NwgbUEA-}Ho{|0|A1mJPGe*-xGyS6~#Kf(W` zByxZ9ZthM_zu$(|5H}Y`koR9^_oej!d%^Ep)D7}`0)CNyG^>?6?A|T>_l0t=_Mi3d zR|FXB1-8POoq}44huXgiZM~?Mq4MNfAC~ySv~G~W#)X)LwYmQ!z)WSU%L!hBoynwr z>?WN5roexCD*cu22C>up1~cM)vUbar@3ncN0AoO$zs}ft3(m|adH+bsj?C*m8fcyA_ zy_{eww9K8PV8DQL(O|I?A9_8QI6eD9oIi3$r<%xtAv%5y2nd}<2DwqhjWcb$Os+*N~H4;Tw6-k9a zQIiMV!I(`BrOY8H*{3R#UAWZH-NQ4h7eD6ZZ1{yO^Hg-T-t|5yhkT8JOljZp(!^`p zJ({(FNv&Kj@nR-3ST2!t$uctLU0gmIMT_jK0zRvd|qti zB1ON+kO9=i@!NCOy#sNwanInDCk8i~hVz8j<>W4bMp=MRj5%`8!hz`(>10%^^a>Ug zva!8?l%E~MMcz$84Sj5j7Vav=L^7#kn6}VeCd^akwDovKrfUi|HLbc@KJv(SmM_hB zDa_KH^*JYgo|90AwAq_XkSV{Kc%o@8$+QuupNUw?QMFSA|i>K4nh)3m6l`Q^WL zrLJEspR@FumOMYBaVPL=OQ>bu5*yx;a5S5w-OU_>iZwO8iP$btNRF<7%)Q(*iI;hQ zo;GrGh95a#lFsvBT|wuw_=h8%tyu9C0)~De*1n3@PpPEj=s!z}+uE_UPvR+onh&r= zowY0I7CN5P z-K)2oJ?n~RV3jMb$Y-z7X!2(9Lg}1;*S>%9MU-06McR0K#0v1%UUl!7d1yvR9W6u~ z6OX(Y)L>NEuVq0t6`l9|c-0f8Rg3Bpe|(Gn-eS8AQnQQ3y2dx8fli6+V^do6qb^3K zbuiIHDly=4@Xjwi;ES-v99th3{FJTad6j|+>+|^}b(056fbq6>JGwUICha?a9aKX; z3tNbSd0ZHw+!SAJhtaXss$5^m0D5U(HEj*brOo=y!%L4L=NjF8TU}Y(+2=OzLp4cD z461R%2;2FeF4%s54RJr*oJj^tQk`9DG>0Wjr(O_Om(iWOmIG&=aSu%uam2Uses~e^ zWaa#&+1pPZd9_ncn8xS(r3D{<@v`gat|ZzF^zDouFzehRYUud_=H^>BS#~sFLNp&6 z;w@tf97@bXD85#VeZ$(Sza`Iq*je%D^U4lOr*tGGu%B#&zY#%jsQz>zA<+En%6zt0 z3ACWwA%kj(JQ($v*SK63u~t%uZ#}i%hQX(LmR7qac?A&G`GWOg_-VC&aLfu?#&moF z*4WI$E?q+L5A~b7H5?`a39`rRNYtqvSgr#8;=%>5c(GcPJr|94ByHck?ES2aQA(~2 zq|=BNrC%2p!Il2HlqnWCQq8>070)Uk!pqxqSbk{ZAV-5qY7&%xUz;}XMH#ceBH5NRwU<*a@&GY9vS9v)Q*g9*Vmklhqb?G?-H|lSY=40-Zj5VP#DZg{L&we z;qMjGyLn<&&QWQhY?Zj?LCTQBF^WpRVf!r(mBx{fLY&EeVRN_{pD{Ql%VU=TJNO;b zoO(q!noN?=RJaBrAnXIv`&6@73i+#77UCO{Dm$&OH;Vh$ZQs)86v{n=Y|iv#Ky5|` zY#&BBQn-sj`3t<$X!H&jilz@uLHX$9UE=7wEXm6+Y^tPJvNJtqR;#0Kjc@AgaW!OL znT3>+9&&qszk{3_@b_F{3nC(8K0IbXA`z$Bnl`#NtBSKIpoajD5ZA97j6>_4ANU?4 zRfp<7ln8Fl%juxRFD#R#%7Lguan`P$teKGGeTTZ4jFO|jK ztWe_W>Zw2^`U%axf=rJ@NyD(%kh(RAae zdb7cjme$A+-#QE0!4WA^@@Tlnk>X~N=gcsSkF9@{hVBLJ6weyhH&jiJ20_$5qAqFg zfQsmUU{QeCd&bc_Eaoljr0a=^(j}EopF8k*V zb{Ew%jaTbL`kLa&LY}f~Fdh2u&=6E1%*UB6XY*`ePpH>mD8Y}ZKsGuF$pgJVUwy@i z!YIt^5C!1iGSbDpYd(REIvVT*lDED$;H5-=zY!0tzsh?pr5vmAunDm|u(yF~N0r~N zl0MJq2zhg`>HRwS;VjnUI~d8*lQ(e6>?nvKGN`9uZ-f+sFaOES>$D{Bz+6^v;O7_d zDr;e5_!Z03WHB-8W*9VIDeAj8Q5BER#p;y{XOgBIjqnxIl%ECclR>CIBtDAjq!dek zRU$R|c5)N?{)f_QWS>2x7YGAmq-Q{rwcfYbh79FIp}JoO$r^u(S$Di^pa(ar=LJvi z)eY8psG;fNmQfO?c9;^a1tw5>^B`@_A8+fsPC*TPjICDv1^wtZGj++|H^0_s#Kuxc zs*Ib&)pyBE*co;@KH*x!UKuJ#jfkaxT6?Gv@n#~XMl@lPyg{4yTO2L1A16-{LrR0e z{HUX4D_%)Hv5gL;NbaBrrGAVQnXbC2xSn~}x>|Zb-!87b8FV(xmZqo|hOs{~&R*hs z(a~y;on@PX7bKn!;b8T)Sti-HGnPlfLprn$YEFC4d&sc2(Sqk*oNLXQ=%)35wcLiy zc3(Oo7)43*sn2ODPT<-`XEXM*qUVPxr{hVSbUKqZ3A=A^6}nBcYwrpn$n^{!6?*AI z;$rIuCfY|jU)Duus2z~3+ruwCJ5vYEzC%1orYKj1sexK;Hw}!|85-7K8;3fjs)d7# z>t%h@ueZ|e~?6f==RB*3BSMF`FLo(vWrN*tic+m{AK_r`w^n4`55UEObqw`;N_ z%#4JI*>mEiU?JMK0D1%M`7fcczSGJxTjXVHby3>RFV2tHTeMyQ-n3JH$D!mbM_DfM zhgNOLzV||V04BsclLqS8Y1*S-gpp%~U7DU}e3tdL@+8RcAaz7oA(;BX=2{sUceO*nfJ$=hvXy}Clc}wihih}P+wU)pcT77_ zWXWi&!UXMtb7618A5bcP6c>b&SwAP~^Q`QSLYaj$HaP)`#4%6#@F*Ch`nGY*EX*6o zD~tgYm?B!V$fjGvC!QHOY(dl^qD-O%L=TU%twWy)1x!#H#!C5x$8dbhQ~PLCt~&DE zTN-#dxJf_<*kQFp=)HP$JqmtB=~T7HsmNo!mO&FWLBpUd{79;Q+a51R-!J$qjSpwT z5l8clqa~}Nk;rEyqMu6*djj>`efZ#K1XxI~%*vlMyh679|D%m$ z47Br1t+>BXD4l2Fdq+x7ABm=NEm&ryBm!;VWSEgq%zl3z=Z!FKX{S)*18SqS&e7*O z9yG8wTT(Uqs#>I6StKN~_g!fgo`){CC~Ih8xDvle zAX2p*#Sj<|*xOnzMqDz)d`Hp1I>KB~J@`7qy>)bqj(W0xJW8hoH97Mp@n}foR>^(V z%8@W2N=RlutoKIEnj^9?*~UGkb*Qx0-$}c$!G^ZSP3cH|*m9I@TgQlRrB|}no6q`% z1lqfhVagW02dPJBh2XuNnd=|TNFw3V>`&OG8rL@HPvaA~cfIq?wCv&@YD|q*jR8qM zxd!$eY`~0vNNo3C)vL$7(HU6fi6$W4?!q}SH~cs=yw=jb19NAQS#og)lW+_@vM|Dw zbPWd>{4i8%6|z2vJa0E9Ov3LtBCjF<*_HZT~!) zYh#SX#JR-Tn@rQVSWI*6c0x)oE~PTyWkNf@kGLX#475^7i1yMifyW#_n`?PgKA#2p zik@0?O`9cput9D3OgaOvVuqVu&ujFD{{yg&y@Z~`aH+iOM#Iyxr6lG&chRjYw9l^D z!}3qWmH>@)(L^h1mTlbptw(nOp;l|R=uBU|%&Mkeh@;ikboHX*9X@PZ2kpJh(D4q> z$DcEQ{wg*Z+vAuR*M9aq=+b%Ghme4NhzEA97gL5ZS++00)@P^Ll%$TSZr%Htuz4dX z;C2dc2Pkm*hR5*gMUxw-o`RQQA5Erer@C?A6b#E;d7I=IhbpV_AgTbCFOoa9P;d0z zALcC@Z5Q1qwQXfLo0mraGnCE>htvq|drX*rW(;B5+)t|#;?sFQ*9Yx_==tesrf+|y zvA*}7q$iKRDSN&;yMxNA_VO(*P>_Gt-Xp^2#4c)_dU8v2t0|>6Y9pOWc#6dMRLe_>r!!)daJaa~?1$DI-nH5>d5E5}z{xQe^k`*COW%}g_oXt2{8YSi>6<8>o8S~Nh+f}Ge|xs0 z*gT?`AC!^Y$)#PQV9+`$ukgxeOwcWVkC9s!Lmo(|!yCE~Rox(V^?1RLBLv32Rb!A6 zke7Xi9=KSmXW5ZsYNk-`;fCqkBcP2J{GrgmdsNevjWUj@Csk((Sg|xJ z`O>x%ajp_l;xw3k%1u0A;YIm_V}>L+na|Z&49)&qL)jMGK%Jtk{%NInzertwnM@9z z+b*-~wJFrK{C%9hJ-Rl42~x{{?+}!P^w|0I_>_W$v_~RFfswrj$3R~nudP63SxZ}F zha&Lg+YPGZ#Bu-xZ&HB5(h0kpsKg0!6|kN)*gnRsW%0^@_wyJF-*Gta#?(C0u*a3B zBexki+A(u9IAD+Fa)G9gzSbx`-6wmBVdy4AamhjFbLQL0;dRcMEDMK!6{hG66?aR} zwX^B1&esTc3Tw(mbo|d^@Oi1G`dy>4XK_ET3V93+9mzGf;t6Wax)9~|2{@e%HtDI6 z<}X})Q`Wa7j5V_dSPwWVZ!C6{v2orD;`?XijL}92TiaoMK0X)PbDU9sf>q{tBjrn;0czSR`rD}6es{%@-O6v>$j1*}1(?u%?qkDMi5-!R=R%QT zwv0o_x^;4Iq0cWGMD%nclyeuo`TPl6C--00jC9R&PhGksw78-%C!zexGzmQJ^B@VxON{#}Sp#m-!98)xBM!bp6kA$m(&K-wv zkqoWwxb~&GtSB9b30Aa(GFt;gEa>h=1i;!zOnD#PT^6oc%#5}S^yy1+KhxelI($nP zL4s7iky5XJXqENEHhf!kaHdGkQ1c#%IInQOhW z4gcab9dFyrV8o)ZK&#rV`a$|KC6HZ`JxE@uQ7}-M&~Ti&-|bx@h35zMql@&yr0$_L zajNY#H`bb1MlIRdc7PpJ6V4Q+8sE}`-9zC%hIB@Mu*fZTeRPr*ITsRwf5!~|w(dsj zR;N(Xzs?W(l**oYtF@i&k-}c;V1^}lh9rL_v=J*+?X|(bjF@9;8m&_}E^mbB-*pz; z+4p}buWNppqE#G1tKnsmb%uK|TH$;WK%_PO6-dKqfH~?>nk^%;*dbJC?UVd2S8eYI zuC#A|DX4Xw>&eNT+ZNAg+k#OQ7IQnQC^p-uk4i7t_Tz z^OZ2b8Q?mn%%Gdy+*!9}glXR{_7){1I2hBvw0yJ$8a*$+b<{1rOz+wog~v3MhkPg;`#Gi$WC zYG;HgES{&#(3*`b+a$O`IXg`v)LwkYaRBy8oQmq<%FA`Bb`z&B`?p$-gJ0Wq5Y~Es zT~V0R>G*@cT_@= zehxlZcO4U!hsAOMndLbjy_%PQ-OxD~i5gaJ|5It|rh4-nBmeN}OQ8N}?AX#=QaaRN zbt+qW@w7FH5hKfa*xcE(SW$?4C^ck%T3hIVR2oOT82fFI;eKfthuayUz6izFLTr8x z(q7XmG@D0bWAA8UN%Z=6R{8QOesDFO;Kt4M)@6(DcPODyQq>=0wRWxmg_%CotF&EK zyZT`SSKq|mY7pH2Tj)@@eWx>%X>Z1ZH@e0#c+h98$!d(Wmg{6;1Rs=V7O2I4+MiyX zwH7sMgHn_xpA(ppB97^}#QDBb>lov%x@=%!hu_cLvHXCnb z$^bLc5Ctt--jx$WZ zjFOth`6QL9tB`JRbEBK_SX?sC(vRd)D+oy?#Xm%iC2q-v4C`HFz#Ym+i7o+Iysa$G ziF)+a+oiHcnoV;Q9}Q;KRCA%zsULMCoGLl=CpCDo(tWO_pfHDL@?fAOM<2tHsa~Lj zwyK($IbLb02IEazr!8`SW%1`7^W-%39|y)29cD{FB>Gcb617k&0kZ^QN{_yuE0$*c z+^JbEXt^(C=51yUUqEHwxa`L8CCccY5Bjdg>c7EzQ-&qg{#?L~(klr_ktlr*ag)OG8m3)$Uz z$0ln#&@__%UQC_QcL-m})gpDx=&ri(6*>=l|LoBV2&&fy)lxB0>hA9`E^Xx29@1(M z<)MkL&?n0SLMLW_h_iO2c_Ew31o9%H-W@IOA073M<)k&qWmvc0Ix~bR#S#D?Rbz{U zvQmU%InG)J%3P5YM2*oH*28}US3IM~sxLPebw18GHE4V>mVSOIIkr~`g1*U}wmrJ* zeM?@+b-jH_iW{EjD)?Sx*Fk#w$454pXA`jnGvBAxbs2(xS;I1wy6O#CMFNhaW*pX^ zI-aca)6q*|2^*@8^lf0)$xA){ukuEnnfUFz+HQnQ zBrH0!>BDO0V(^w%ue*ED=gWzySRMxCRkXIP zeu7+jM_&PK@z7EEWTDO|bV$=MDPR;r$^KaE;_?w#)OPdQa=@0TLl^6)0oaA+hE>k6 z#H0j&8@2h6m_jCTu{ge$shh`rzW;eXq-kJsFfx!~V^^{F82+8>r73s*GLLvf;#WWZ zFB~G=BztA23JbhP4NvHQ>ym7#c|T2dD+=dX4ae^{QS!@K8zmUO z02=49JXm{5nUxv-0cEDL<1(H{-VG%Mj4oGnbKSQ7Ax4PD;hF0|St65j{ri_l~J#Kk-+%aCa#pmoY zQO~@35rdFG4qvwxaF0ylUO$|3S|`Ds)|y^U?7+o`mLbP>x-7r zIisrpBn;a_tq$FqrQ{42xrssVxHJQBhH;#ksS9!=!DdFmdy&qJw!aqf&l4^JY_n6k7}D& zv^EITMRd@%+Qz=dB|-FEscw;}V8|GdmQR^o=O|R#6d>~qB4h~#w0M>Ub2m$13zRnN z#t2c2!E02IJf94{P6(I^%;70{W$uH*+wmB+>!|((@($0FzKgP{AQv;)b|#6k5rZ*5%JNWu+H+UP2XFoY zh6q5R8kQ1674IfVG~{7y=)grz{Psxsi&x%2h-r@mx=C%%`0DLu z8ELY^0%`|*_X%SZUq!+-M2~1K->s?;tzuqWh*rzngEOwowr1yIrc|uCOLz zq9rNO-u!|GE0P}%Q>htwn=*X(G47fFM@?;tIvkwG;!iMlhA_Mn{ZYA9ynrrORx(?1 z`4o1`14~sw6pST8C_7G%Tp6;>^|WV*-9DCGmm_iJ5fa|ACHN0o#M0vk>ZCp@K4T0D z_uKC)K0%hCAn8+oWo}9SW+rd1xcju^;3rpn5_7EXLn%uex^(Kdp*~S<7{^UN)nr60 zjNWDDup?Be+}RFilr%fe-5mV|GOUEc>F02%dHLhMhtUuB`j8$*j6OM_mLneVq?8J@ zKWd~el-yDWNlepJ>T>bwhFX$erQ+LVKw`(yckA zzmsZ~n?dY`r|CB4*fF}(fbDz%9+B)pl3fmm@TuyV-tR#R_ziy1JlKpUa| zhB3`EEbfDx_(#hEhPfUg{kawE7DMVcV(3t!`6AZJ(g=?%4hjS@^QWydBh7{wZy;13 z>pAIm+6C3YQrG|${o$p5QW2X0;4~pCxQO)s014;+M6)c^CP2&g6%F((07@VOQ=q-e|AZjtHnF$2=A@%@ za&n^8v$UfH*&6dwPy?Jy?SD-Gia*Af1|&Pfkyx2_w%zbxKc*TMdM3}is>!(jD)P1S(^ zoLw29p{axA|9{m=*z3KIgMgLsdrQ+WFw@dA|5I*iCu-^pG?X{BH!%5U+x%0m@@L>I zOs#VR3Obvm~|LAT29jz6}{(s#C@LsbAzzAdu|L34tSpakb ze?Dw0G-Hxh>adVC;FEd0CZx1i4j02{+E~lbP|8*J*LcGdXFjh zA7X!xDgT$=V=DZm_n3-*={=^>Ut$K(DgUMS8dU!hJAh98Kg99Ay53)U*XjRVN;751rv(d|$>8Xkq`~2Jbln|Kj^z0%XLw)E`tKpW*I=z@Yj3J&VQ6af zHw~8et+0L{QqX^u`==bc|HAiuwf~Fn4)3%4-+zVu5jp+`8Q)iOHvOx8_jdia`TumV zfrG8>dyD_$>UnSPfAc@SOn^XVpaJ~i9LRvn->k~N<-S4y$BAZlj2r4a`CgroW-MPD z*1lI{N@p`xDIn=00<6{>p8qnxMvo`Id%2^uU-vKYH%%_QOn^ z+kYJ{(Hv3(SdLnvAU@8WRNW8C-{cW=I`&f&R zJidd?L^s|joZ-av0T0D`1zj-NHal-G)Nna7hybF#pEvH#PPIG5RJ?2L*A||+WKe*V z%hF8u3F2o|>QYc+NmKSYwb<87}1NWVw0kUhcf9CEafcD)9K_+G5Fax-pLu z84ltE5M=&5Y7g~~z@lvmA^Nqv-G38&gI@|BZ3y;5HoN5U+6QB_57Yw21n>C6C;ai) z_2n2m6(9?5UE>N>EdQBHb*kN%wLiBP0i1V{`t6dpDM`*-lG###e&j`wscx>35`Dm} zjVc$TX$O@9Wi!CkVRu|6en*ZU$;5*OZJ9jsqc6I`fZt(kRCtTP#&u&>7=OidCC@*G$GZU#`-5J`sFx(;;}%e*@`!z7WJ!&0l})^Bsn%`>jSqaEcAS zQ5Tqe$Cl^EEAD>TpZpiq%(J5TE`PZ~K?~Sm>%?0doMojOwgikG}HI)oz z8fAXQKR!XXGw8Q9rb`ycee*jv_)bP|7JpHt4#wtkZw!x?Y=W&+ zACOB1<>i5D{Yo=+WHhG@(0iKGf$zn!V0KkKygIN_yxM5T(}@7`mseAQySgXFB&eCv z)^m(dME0ko2?i=fuG=wj*+`AAg}ip{_jjjXg4) zQ%x?ROn*Q+QLC+D9I^(b3qPfogg~@8^9~u!i&sB>C(u$Bx$QJdRU8QQq@#L5*xA82 z0;DD*uUfG0xT>$jT320XrDcc{s@|>m7}gQid2<;u=jJIFAT6?RQg1&xq7xfPMNzKI zaZ$OBe}+*HFGqF#XnzjC%vYFRck1QUv+2`k-DQZ7cx)V#LM98~15V7|#qb0l88y~% zUzkZfM^2NNH(1=Rk?LGql4v2PaBS1`_+{^6n(Ijqdwp4XNLC(~XKXKt?SCQ@zbw=BqcJbG%X8lx9bl<#H2k%1&{q#Y%V0>xFM2PH44XWRCNg zs3~iELLFH=Xp0Lt3Nb6Ph*R7#rO8YH`Nv6uYK=#Jwf{Eux|i(%BKU70ttYN0f#njVMhYoshiN)m&IX zQQw}cy8qLmS$;!LhB?BHEcPw)uW4xJhm`B}>XkP$0m?L8s#G^1^+tVV??x zk17QILe}~Rqx@X=-9lg-z(X?8@8n_dxz7O)(SHwxd}CMFaxYwhIt| zTz^Rq1qCn>jJazO0LryecJ^>w8+}$~%g7SG#EZ?UF!0v~($aB&bM;S3d^j2xb&V$} zZ1YxGppycJu$VVub+*~a#)ET#uX6IJ^c5GUtEMD5ZB+ZzMsv`rQbd z2V4dfgK3(AwB_<=8FHLWaao-lIaIqQjRs*jHh$)@WH-Dx1+J~aZFDW30?Tclmok>V zvhaT3DzBtf>W;CD;oyOb1*RuXTm&nu8IzZv^-x-ZT}FatWepWlFaR_>3{j` z$0go`Pbhukcfq@eyO&Iq^Jc_q-5J71><3{azo*@QXA;(nhOQ5dgf_f>Ib4#CkNK)!&5VX0_yfOeNB`5i0P(`XJEf`dA-gtdALQ-|R(Z`#udfY5yW z6IY2EijN_R&kq*iYEEFLciqK;+<$jl`a|QmeRDPe#JNf|>e2>Ne}A?uCM7HGxSSV@%@dP-JMNT+QeJkwrc!*?%lhF~(^BYEv9}B?fcWdJ*~Ig<#bS4S$MxOLJppU!r-z z=Jivv6n>dy*ed^;PQJj`z4;D}rs)n;SZWeQAe`ll@OOw`5gifMp2HVq7a<7H>ML;q zFYJ~Au8TMO>5ztPvRp(vDV|u+ld(VAtk+v^lRh_K3yBqe@{W_8$f}6!S$F3GNWq-3 zB6kR^-_7*v>h83eaevYwfMbGbR7ZKgy{Z(FQa-ZcXf9mU3GQviEyZvT9qr18lUPHT z{qpYUJ9O%{51=yrv1VG9FIha3S^qo(XjLib9lo$T_|}wR7T}Q!ui0fUE_4KQKJf^#zk_G}}jK$LRll;gA=jlZ~e(YhrWR0LVv(|T`PsiNz+i7FoJBz*1#stD5 z9b?Je1*U3*oqw5?Z;PTUue3~jq$bfj_xqx_T=8gU6kn5!JbD!fpI;vIR0^Fp?)(#<{HCPu) zay0JMJglX0L`=kFhU|dvvtIxp4{f6iM>ip3o1Y_$Fd3xDFCC|+oTQ~_k8pzI+Ft(k z3uWh>3V&B1jmYGe-GDeyv$FoyYCFqLd42nHD`R{cZ^?<2vkg;s!N#DDeG%TTw8Q8L z_er&R(qQ_$5uQDf82<96c-nJD?G4-N0?sUQJaOJq;K7po$ZGWrSNYvS|9p0>t_gv#dCNyM_6(5=bYJNDWAwQL z6My1XUd*59cHP#Y4=3Y6X=B-F{!ycS5ZfmO>|&%SA=YCpgU5aKGMAjw36EAUT_grd z-p4pBgvGI$P4o$&TTA=_go$;YJHl|&#Oz#%UOB&O-mdH*@v^j!DtL^AE^=dPd{+4$ z4vyztVYni6wBlN9J%L65@woC3I{RmY?tiNTR-vD4V#bk;$q$1#oJbFXJRBr9Fqi$u zSR`qb^{g>Bj{_#QNH>Ija0I|ou7lxE-cxG5v_A|z@5El|MUpqi;K1_N_!)NU3L>0M zD?(L^Z4hHd8p=!Je<9CV?;GdKesFTpTA$NQU$JAfu{?X_%cNZ>kg9vU<#M~ZQGae^ z_C*ft$m)tJlFdDzLEeCFGe6$wG2C$OlrRzD>GvxNF3^hAvIQu|c6fYjI+O5yI!$9- z#V#ZMSP%r6@_N+!9j+n?em2&?;l-s=>a7yLKmskWHE_?HtHJY@HBW66(qM|w|(H{@z zDcFejtEW|8K0pY_Ws#Q!+6@|2l9I1HS&s=XixV-DK_$~zhayOwdsc+#Z(lPJ@;HcG zDICTp!IB>fb8}UjRrCziKdvuI>^?Bsq2uM&tv?CW7zc{Qjmj$ZhZ^)T&VM{N&D)~V z2CivQuDqwx8v&2h>KmWP!=4mQS{hk3)m2EIttJU09Le|ja60EXYo<1^ zlcy4kjXpMQ4(2*2V~*!%i>LD7`fc8ItSA4LjoEzFDb`K=VFu12^N zW5TU6V?!8S#skYS{1@vy@S6{$4i}_UmHmiI*uQLsXC_#SaJD%OWn@lbh!~(E#AS7t zcJoNw9EKE0_Um2@#;a2(I-jq_9!5j-IK#0_(k_|&Ack!c7RNryT7RS;05_=h>}I`ky@>J73Jdo_Lemf@a);`{=1}p9c~5%?OK`6w*94$p!{5* zNB^j$Kd{b3raAFy)^#ku zQud>}Bm%|TwYVlE4u3Sd2X*|EqY9reH--0b;<;9S+DrafLi0sz>DJnz*hD`{XB-q* zeX26afrQNMrb`%DDmw-F2fs;B3! z*JsyCLo1n~Y)!;8Aiz(y=fdB5im^5AO9u@d0N#-ZqPvZb#Gk?F{%M9s!(NYdh@%)x!p8kd-{rDx2ZKmLt7?noHaF$?r<$7rQ5l;gwCE19NGFu6|r&mxkaq`qg zU%N#@7dye{I)bX+)&>*Fr~1OqY}{OOvxqnSU4Kdp9(Vh29BPB9IC|7xdW-t=ikeY7 zZq+6yu+n~psrb7b0!o4?QEb28Ni;vYm#ZI8yj(#negg$7CDn$d5Xd54aZf{J-RQmx z(0xVu_g>PCw0!h6t2DFQOG>&zh+w{KHbCXne2gM){Q?AQYx}DDwW$hwWi>h7K-{Sd zW`9~aXAX!EBIb}$v{hxL=LCU3VCcdn;OGm$@O*q{INWjf?YZr44z*LxRAiVA4MF zKQYZ}o+-(4vghPsd^LtVEL?|G;aj8FnSW8#C!Ks+0)^LmCm-;JvVPp|>Gz~ahLekh zFZtQ8?!+=mM>M?YZl3ak9EeRqhqWeI(k6z`un~vff76+XOD}T+A~vy}R6Zo_`Mvvr zMlqY5w}5i&5pL?o$p9luuu03od6T;YEsH~^u7Z5t-JCCl?&Z%U1%>{)L-J>sJAdXl z7OaG7?IOQ5e_wQ&^>R=!9xRI(r7qv7qNvP|j~m_Iud^e@+mT1s9Y#y*;8qZ?U~MdY z3`mBh`HeBBQa#70-=*PQ8f@Td1Uu?Ty7|9i2M@6x5~>|h^gihQo?lW06=y{CSX zQ0^oNig+D!Nm~p$i~As+Xl>fK_kX5pV3MhYWkI&Qo+H}5%Gub3ESG;sLOc)(ODN3w z11t;$EP#{(90pwvYdcNGIqqekpGZeK>5&h&%Mg|FkuzwH{+v;Z&6)h9iP;*VOrE`k z5|NH`Vs-B-0NK3N>DxQuycoo7f!+%DCOw8%? zwirS_@0-;0#8#yGOybxLN)#?gSuze>hkbSNc{s{G(8I-Jv#aW(z%aNt`)tnei7GFj zw)5o@f1vee+I<8uMn6A>L7sF8qA8A92bXMx-@%5EpgVbP$6)zZy+p&bH1n@Y`u@kh z7P1wbsJvHn{k<#U&X#Hv)PFFqbLC8?_S%Lo&q9ZJVB9>2!ZpV29+&*Bd?jKt?E!Cv z#Cy{<W+5v`6|Nz|RuX=s4V$311+>ndc_O zCFZ=i4#~dppvV~?jS5)=9HHh5>E|F}CT!dk2ECbJy2Mz5za);aU4Q$VPb|&9F)AZK z9o?c^=KpYLPiP4?vs-c#OLCsYpD<&LfB<3beqto3doiw49{Y9Mz;nRk5_SS(p$< zChgN&WglV`^b*>u^@wc(Gc^b|Rz6av$glD3PvG1?g1p$o6(r}SkpqLBc{Ryn05_4%^pfG1c2x3=t2 z@N{9u=Sh`52@ZR(S6!sa!G`)|R*CMe&d?k8GbK1RL*G4m_p6Kk7LBsr?K}(mLbjzC z?fNz<>YUDKgn#UQ@Z(Z9Gjigad-_Ev@`Y#>nh)k1EX9oPP%^yP?nx5=m*Mvpx|xxk#T?SNxpe5GBc(NHfct>3``RAh%R7)}Ir>wR!d6 zt-f%6cmW=&ciGP?8W8hw@-1b;Z;gYgg;hdp=JQk%09HV$zqkZNix)iiwmhST$|=6U zckm97ckys5`IJ*FPdjfQbKdBikPost?~&P0tgl+y4?BO|Er*r?nT!+Sx^4(K{j*Ok zN3#|vMsc`02p=s)n6bEXFA=R?g=40n^+`%pdC=I6VR~p)0Ud&8c-#eMDbv5a{ddn@ z<5JJNA-IC8IX?@@r2sCSQ&^97$8I&L=Dtu?s9svp)uH$;)=Ztz`+AO?)oziHO8 zqlz+m6CpHmO*wBrXUb9|Q&Eo%_T5o}h))-|X$*<6%@V^e1vqk@f(?V0pK2!xHy-N; z@);nEkq(tc`IGd?^^+^pUUnSTe^2Wq|Kxn5FZO>Ym>KsKCWihd_GZL<;2z%k#69~4 z>^ShuNW7lJL9zR0()tNni~*|${CR(8OuRZRMZgO)`Ux0mhnKVMn)uas(t^~xqV{(8 z0=%eZIoyNWh0!@y_jusjfQ{R&kx;npm|3y4nu&=H@p0r66?V93Acw|6xsJn@@LhM_ zWHx_&o_`a5hRaqSDO*{n5W9i~st`M%up(SpcUJ(q@|Iw`3Ri#XLvPP09|j65I0ldW zCvN`QrsXzPI!&q)eB0?=KRw|l&HytlDZ)BeA@-nXi}y}*|5v0 z+r(+^HTk1X{LfS-7{tuLihDDcjx*L5)un#{_wV?VDh91_up(`kU91|O`qO6+3pWX* zrb&dYslT1M^qaYhL?@4i%XcB&4L?<+Q9>~k5mM{=BgNn1plGNnXJGU;@36mRl;*O2 zCvpL53e6P5+SG%jQd}RW@o?4j1ft#gqQ%C~XDi+&h`N4NtGgbl!AuOwsts*4)%kxg zbD|njBBdC9sBcav*K|g`Ih^rN7flujC>UmrR(5RPv!vQ7^&B%GaO<6@PYL$M^ECK$ z6&_Fywv#)JdP*rIXW7EHXPB~sN9P|w5ZbTnXXm?poI_F1J9>=l= zFG}B~>oai7Hd91+qvS=2IytKRT%mtWPgrv}SQl_}Du$Ut63+6e*V3Tt7HoWczxfI6 zH(^R~PE!8nfSI{P+}AB!UZbOyi32fZBkj!jMSu0uN7YDS4DYAb2r1-at6!N{%CyiY z!jRgic~EM~b7M%$LQmhPqMsmiIxywz2QVsgGoI_S3aGKJ1%4)VeER_d&$E9#wsc*T z?%O=CZ{SBjg(gc<-?=>8EKpLhqjv9Xfh>(sn)ZEM*YxwmGze<*Vlk#LHFxaB{N7I=TP_!_} zU<&Z5oT#`*Oy?5~iEW{5 zogEcqZND;($1_lpZ!gOYbQCS3bA_)HpO_4-)_phU-=gc~2z^bt@JWC5TR<86^K;da zA%P{6eQx9!?V#fJpoWhIO>$HkVys=-tMk)yTr7*7mD6VZ01xE6>3poh_3hAu6Mez5 z#E&m4nDR6wmz%<58NUgY@_g{u2+>% z(Ri6`Yk4^6=hKCnkU@E)gdhc}Y_ESvI64$IO6Gik>^|g3 zI8V-<>o>i60~n|jZhs7igyXxws_%70B&y!ZqF-9+X1cPF(CKjs-5hZ|c%2YLA6>r+ zx!I{X2?TvR_^EA;O^nXIn5eNWKGsw^7rv57ul`oJ$m+x$wxbaGlPxJ5vrH6Q@yUaDYVY>C?csN1UjoO3H*|Rtr6YZi#nL}XEYnH=4?QFqAeiTmO z71}_uylHbN-PEg1(Kd0ZPSCzbe>A}y%JFn8lehB-&T*nxSpjWW$>;=HUMZufzjPCK zSAYN)30QkS>FK8MbJ-RpZitDO77epT_>oJaB)jk>3iW?@eD*wIq8|X}YAqus5P5bc z5C*{{S{V%ncOE!@fr!Is74EmykeY5!+^=HX z*8ES+A69|zY;c}K{>dt&=U>}gxxX)%Sh`hAR*cQ1-FNA!X%C&O%vY(u4a~RG@z7_e zX(2JxAdr8AzU})0>KhFaC}Y0w^V?8BFrIcN;veaCM)vStHtWY^hE~^B(b+U5iiD1X zFY%1)EH5Voh-VV~1UVZmWLym9-g3vUjuIR=(^Fkbav^078B@(Qccru35J+ZY%r5+X zop{yVyztvZJkD|rE|eDCx>LV>ARG#j$1H++E4_bhsLt`X<9N*A)GFJO__|;}Fv~oX zFT=J^jqcrvZ3=KUHn9Av>zR_{Fvlk5g>(bxbv!xNs=v@@NmMHyA$OV!ayf$C@;F_w zG9|_ftz3jp^}2q*|It9@YWcZ?f-6eE1MjLRI}$V6yBkMBLPxV;-6KuJc!j}cQAYWY z?InL6N0t{2Q^uwD(A&SYK*~MxO8S}x-_7H9*v3|cnCqM0RqtSH&bZf=iKdCgoPnCa zDsl=5Ju>y$P!Gp9i-Ud)iyp};%}FaTotv1a&qr*dBc?;$V_32waI$4Hq*vc1Q>0{$ z8?h6OhrlEj8If9jZAu3gMo59Qm<|}lz=eMnfsn>z{3J50iexVJkDOt|Bz=?ROo5mW zHzel^#n0OWQR5Yp4D_|ZvP}dZq7syE=RoKbx>MWiBTdQ-zO&F0T8TaL-w`AzG&{w@ z=uHQJy|Jgb%^%HT1xibGIfb0`&lz<_%{gvfp~lf~p=%(dszAE;D*Y&gulrEk2`YcJ z*KSPVpb_)WyM?Y-!d)#r$>`XE1c(U6ttOeqn?pz|l-BY^$Krk?8oP7U)ud6=DI_^s zv{{lJkzSs_xeQ?pS4*cYB#0G+OH7VE%$7a@&8U@VpAE{r(OwvfV!8${Qi0N)H6!Z_ z^^UxRE5*A6agosr1_7Ca@iYiWPDv&<6(2vhW$?5`iH+2c~vr{82y+g6hKuGYfL zcBL%dD)Low-b4(@3ke?Bc+nn+V36Qm`fntJM(`C80$p(vf@K?3#U3o9M4Xidc1X3> zeZToz?~>6h%;SI2y1ISCp`;Iz@F^=*u(67zuxo3-i{P zb{?|~I-mK{GDE?y!}9=u-qdK6s6|rj5tr_W>$8@GJVAJp zEkt6_Pza9ts8Hahpp>q2*J1BlicQHrl)gMenrt)v6UN!*z#=)1-R0y;M&zTYPPdMc7@B{HYlOoeZ%x8e zTrnXHijZjbB*`a3&5+8r#922^SyajTY4S`5snFBRfr7E7n{i9$bcRLH`r75<$*Ix` zgrUndX!LcAdtHgCt${tHCAW0rFD4v>)N>f9zrp9aB7VY*BS1m)z2Gg~SmZ&&iJzeW ze5C6MBbroFc+q$*B~5=n<$oP2;@y4v7Cl6!77B$>08UzCL2`QJZqwkYSQYcEq^*J0 z%Zr-TDe^hYqR3BN>y?QGnXnV5YW;oHPU@y1JXp)ei2~t)I)-X zHO?6tsjnXOQ`wXnt|}OR*x{Ov9bDx4f;FPivn;_}`as0ufa-rhct8zw?r}IlfvPq? z`|h{!Q3gHB`MImWQn{Zw13R*iI4V>b^qSW`!b}%l(7|iipQsH*4U&~x?=on&VG~=6 zzFQM#HY}+kdy4|IT51}#RK8Zofw^t_APLH?RIn(*^=55DFeW4FB4X}>BGloYKrn>m zv)6ROi83uXBM^ULBli6wr)J;9SRVr?Exo6Od*#YoTn3RR_X|M9fIB2C0b6IGU(*&z ztkpJ4#K1&@88QKUd_pxR|MuXT=2zTQ38nAPQm-r@5Vm{Ftd*So0YmEZ%})I)O}hqge9oZ@X*jyA|g72RO}B%$$6PTB#R z0HejG1bSwi0-wq;4Mx~`C(xuHv$jZVm9#^3F^M^B3O?CXpcX2!KZ}3AKq1y;UJ}9N zCNs|W+=74Zn$EjIn*md*>N*0&+Z+xmvhIog#l7L73v);$4cr7lW7i&`xF}vf4X*Ri z*mk0h@b$U)ag8rCCaGl+DA78FLTrFkiumwY`VlHvH#@M!8HilnfDA1=wJ8J}?^5U0 zNHW+#;aY~@i$=4~HDBBJ*VO{YZkQ$6p;&(@M-P7?H}GG$My<)G4gNw4zmJ4E0JMog z_Mo*Dl7CR{bW;opuKlV8QDUp3fa4Sxt^#abmev77dCS7ZrhuIYBf=h+5haLsm=nI0 zky_YW=SjzeT`JaG2SpfsyED1A(pUD!Le=)<^X#RZ0d`Nw!@4ZgW2`fISqx!28aFxZ3v$hEh;Fjk8JVcBbAEG0HB z(O=u6us$Pd>3Du+nGURGZ^-HPYmj>M;&*>c^W9Sq>serYh%I(Zng$V9%0M;37`}>4 zURtcdgJ*uUDI@cGio=l^nOzB)-pcBOgbnDVE7=Cxv67D3W2f-QO(zJIb#V6Lhq$!G zZw7g9uqBrqp~S6*P_25I^d477#ob2|pM+}$4i3>M1UZlAh%!+&)cG|FIfG)6wyS7*RnMK?Nn|7pJZ?^7-Uc>V>x;}s zisEuu%>J(x4*h}1Pb$xjgvAy1$Yg&|NAVuql^x;G4rJiBx0)~{+?f!g!nL^jH{DB& zC_SD%x@ArUoyG{3KH!ihH)E^>tiHCRJ_1X0GWcXu-HKzRY*B-jacM^w8AL^ z2s#+E4U$Mj(i3`)Tik-MllaO${lEG?^G9<1%m!PoB-K1!E|hw#!9tTLiKc(RRoI%CHZOIX6sA$NPv-Z8x}J&6u2B(}JME&z9hb!CLAfV$6%%WM0< zkKaDBHYnO~%As&O!7pXa^_)eX|Dj3aJC4MaA-Y<&-0Ar`Nv(I=YxqXC5E|8WqV_^{ zUZI2e8FL~D(lk`-G;Bf^Fu{KXD>$0VQHD)$v5wY70(^9u`?6dE6NAA-#t{+xtLw<{ zi@~TNc$9*Uil*dYU>MQ@7$Lg7*(Ps|qBv03E@MzyzNX%@zmy|VS%F~x*NmxZ2al?= z@kHp4Bs}Tm0j?D9&J{9KxkZsog5EO2!c+2rvzzqq*WZ5w9X>JZsL059y{$tpsThVHwEfC+BRoevG-H2+-T4V29?I}F2>YY7Z|4pSR!$)DEa!a$3+%IQ8HWfXQn-PV@HXqroFmQ3nDb%c=ev>ho*vVq zg_Xs+SvEv`Ss;JHElrQ~CtboLQZNuzyhFhGFc%-=)a_aj&t>4DMWWoJAJdnc-X{;C z&6+JPI%ZT3&(+A}e@LafNE<`V+|#ebhn51m_|X-;m{vc9LK6Bx=nvcS?x)cG(=!gd)dS2I7vlxzBG>-MW8!%Ha1F=AWn3JO3>fUZ3wF zHLjjcx(M5Zv~#BTo#h#iL#ayBpAM`obneh&mhxU;qrGJLtjrfw&QR#mIKcs&nk^apgaZ)*xsl@5$OrPwyo$-!x zH8768tCd*l+p^1U{jx8lLP%8vvioQb_Ct5U>P|iy3mMSR`y?OHLy%Cs-#fHTf=Z^G zNB`#bJg5_{Vbb>9HOf%hBjad zKInfGVa~>n!Kp6|7iyy&zn?~}(wgWqB*j+HIxl|<@d0a+G*;E3Heb|(KxxnQ$j-hN)cRvk zTk>TnsKPE)p|_JG*8Vle%Vdr1B_RxNdLv@fAt`OXl(X$JVf%Spa`MBKcAU%1M3kEadyPLIH6?jp(}nA{s1fsg`9YolMxsLfA99zJc|?lGh{5yH@Uin z6_qa1>(j+mG`OjI)NxBzWg^L6xx?l3ED7zO=;xRN-#Yp_B@p;m5SUF?15|Pbwc;MQ zgPABZ@&Z1Rl7?k6s^a?=b9;>!X($M}bM{+V3eRWRp)RPoxHk>idExf%({Fzi7vvo4 zSB=={?hDj$VcU|QtS;$M!+pC{U=RRK4#wHIxtFiP`qH3DCe5Cl&m-sLi+j}c1n-8z zSdcd$Wz+KSk^xStl z|FvttEqAjK+`!ocNJ3U_ObCD5gcZNa00^k536tB3DZ1I*{3>cc;6SIy|BO4&hf`$i z{<{9COQ%sk=;f_k*g%TqSM)(4wptnIx{Q!nRGdtEt!E{QPia2Tc< zRXcibJwM(%RBB%4N@X#TzP}rd#6|Q|=GpAjTbyce%+G_)WiCiV(;0pS!D3D#g%hX2 z?WqrPtMKuYW$jav)Ohz=5!xx^L87*TKjVfieiFgiSBv~Cc~nupCmOj8J}?uvMjSLC1b z+63_J6fE@dhX?k6J@8X`%V5@(RSZ8CzUg|N@0HQmU4KGG!^H_~-v>4$$bl7V?b^^Q z?T>>iyeL}uDU~>C)N(ugG+J1T3hsAfRwCXl-g!fSuZ$!Z^DTdoi}dhDD4Z#6_fW4W zgj;|CaGwu;91WN~=2n!@PDv*SBQugglT>RuDmhc8-ye&V&R(0{W>m}HAO9I6%Cdo~ zbJ7`wz{p)IdN+x6BXUW>`w^MzD5)XsY;K)1z@9TJtMe??YNYi<+q@#a1}WG;)sut? zH??d4(cAMpMCE_GbA4x#zcb3X;l^E9$9U$&Vol+G{FL9&h=Fr1H-dId`^K`Z$#`(i zF!iz57Wy^D15$c!Hv^PdCm5T^ry;ZL#U}HqEl8act%YdY+d^v`Bxp6tCj6(zmDyt( zJERl08Wk#fb1Y_q+$he_D|bjj4hfx;^z2v84x7Y-tgL_2*10uOi_~t>mRYjCk384j z;Hl!gNRG+U-P@=iu^)j7<;9U1znlzEzh;h&{mM7_oIc^a7L9^)*}cB2o-`&Sf*vhu z_Zf96fL0(8f)hG0Yw7);&BJKr^V8<5G~hJ02>A#<-0))S42#2n6a0RCuDf5sBtgs@ zos)rFxVC@IetEV}U(nZL<@ICikX-F;o2KlHC9Mhpsnsh20fWBX0vwu4N@G6CPzku?pbKpp1)aTUPOx6tS=7dFw0S51m42gM zh+Yzuc{spy##1P<3PRChkk&xX5!z4`@_o!(b8Yi%C(YvjI1m`ph=E1}(Y3f=`w761 z690tUCD|lt7=wlK(naO!bv7hUY0rQDrCX_F&&j+wl$ZA^W_SGI&@k2+eg+ds5zAnXi8v_*8b4q!tkkrlf%N*SgNNERnhZ{`-?nzo zIUT+RKkUV~b5jU;+npmgi&jn3(TsaJpe;>f~Rxw7%Kb@`KOwHOi9$|lpVuW6@ z!~w}|%)>D-$Y7J69~^|ITXsGPe&#U5Xq*fU*+tp=MaHIM8P+&-zeGPol4bE?;jY;= ztL|tOu}^)V^F&I8?_k8#{38}&cOV5MC!2wn++_ceH^;o9Pj3pe2BjMzPzhd*D8CbWvax$ITS$L}KHr#|zV<@RRGruG3W~3PhpokaBw0fcCpF|nVfryI zGH_!QA+qAmU|SCF7PYE-Yo-%(XKTp|!|8XrS~Q!Z%bl~oGfr=X#fDaW8|)Vk%h6_@ z=>c+auQpw)9s{2F-JlM+{bsp~nTiaBi_XhwV;o8yb(87knLGQQ66b#t=cU=NYYAV@ zH0GAJDBn~fyDnBN(voDjKolNV{eu1D6L0|Wb|4Pf*Wqdd5?|`efrC>OGiTb1;Pcxo z=7khNM}rM-luj>(BtLfQ-n=eVPeMO0{SuhVE8b?hK6Gl_R8x_gEJBlg=?4_q@u<`` z{I`9X-};*g;TBwU=i7hrj(R$X={~MYfjaYYBeauu)!%q@>X*BDD~9l}z1zgNrL4V= z+nr8N1HiydwvxqJgJ`Cyp?u5@C^GPR^wl9FbPlJxPDbMNSC`>WcD1-+x|~+Bx+z^# zdaoHUGrmUcxrr4^AwfVp>GyG^m~g9F1r7-&&1F=@5IJCCNdJH4io?OZI^`HNZ3sm> z9CM6etFSD(t2AD}w-ckOecNj7@nnPi){;5?6*u6Un~qPl%rDnt+5=H<_GHVd?oaJs z0<~q`YhH*f&o2ziWtOq0b&e+)ev^IQk|~^N2zA~6tcB9l!l3J0zk|~_H{MI)rE1dB zgG+(1n5lS|G08flGu>CFao6pTNHFtLUv9QFnyC)gl3>3lKZ0TgyS%A(c=Sb|_2cEe z6%Kx*+{F}RHs1FC1Ai7-Sd&QaC=oRbY2!eEe zqwjmpd(Qd)wZ3o7TF>n3u6V2v;8@%-#Wo-sWFR00)>8z%MQ?%KaxD zAnyW2!oVOnKpTW|fV!Y}1cRIbh6peWit_od5*$(vD3q%NAD@?(7ca=gofmRJF@S1A0iV6DFbxB-8k4S=7Q|KH{Q&i-8p2LF=`0)r7Qt{}J%3~mpw zgE>P1x++?{C~p)u00f8p4g@)WyCcx~AWsm?8DxtN_|rKEpdzmi0HF!~P0t;Sgt?;J zdEH^ozbW$lE`vU0WjI6;;o<^?qulX-_ooCyLc!=`_u>2NW}V;&FSy^|zzzn7*!?B} z@o?ochQr)Epz2D0hoDXP|JdxID1b0fOjJ;e9{_a&K)t~Ze80;Z`M5%V|2Y4c(F_9o zToJASJ2VMs0L%`G{=@fk2YEsPD5M88!0$gD|BdkZ`2i3Z7zMC}+QZ=Z|5Qhtp>}^^ z^yMRA-T(_AT6_Ee;P2nRS5MLMf*|0|KL3ROxnDjFbwvfmCtQCq{HK^oRfdS?YgM{{IyIyUPDfD)B zIQ@4Y%5X3O@_X(Cghc=#BogF_N5SnZ`^)EFe&6dD>wSby zcobIF%6m;SyyQ>DMX4?UyHQ^&F_MBCh*x+wbmJumB>5nv}I?nME zys929_YV$#EE4z9cSQzjcm}QgWC=qND@zX0DGA|LnJnf%xXLN^+({?#vsEQkq%hRZ zV=|z^A5hFsY~H7`ykf>RbIgozc#Xe9Mbw_3zES9ac#(20DBK+^mXb5|=%xKDKZw+l ziouJH=Fcw&Cn!(n?ko>}cP4m0*2-s1ZB8j;GnoO5o_-!-OBgq8!LbWC^gfTrZO0Bw zn-)w#nY4W@ecmyH2P(X#eh}hu*u>z(fGtNUSy6Oo{Yx;J@a_e<+h`7f#n>j6mjy}p z^RLK%opvS8;F6fZ$5>nXhoh|vc#AB`2UL57ONDQvU%VRuo^}dX$l;e}ETqCU2*I{r zGPUnu}w27%UHq&@RPzOv)kp!ig|H%yVn{v%aUi zGNWNLe?RrCq90rG*PrF{p9VrK=Ofwp@a5HiK2|8$;XT#mFD;QXd7VEvw~F9LNet6e zw%aJxo_~+tXC(?hzuDifJB$!X9pH#ASsX`bLYb{k# z*s@eWSU~_tRZhND07)f(rD{CmXpR_)a(~+6M~BklTmrl~So?gPF!4p39YVXfD_tOe z5zXsGz!GZ3`JRI)#W$RjoU0`fI~GrUq@IvD{f?==oWRE~!js@@Fh0l6>&%KW!AG zhOgDk@Z!k7?2p;(?Q4N|#>(!gv|n6*^F%O8Y(gvpN}@&vs)TCx#8cFinCTd&BV}Xa zaPLLezK(u5Jw#KfLD!Wfbn@a@dxUy#V&7d!dOkU!!Vr4GZY`aRZnP=JTr!km|05?0 z52-+akEA$d@2+d_ojcJPqF#}CU7WsjV-^p%_({51NT6=p;6*i>sl6!1KkJWaOz=;?dgzK2mO< z>eoW0>rdcTCpsSx?%KUyBUu)w^b_Otn;wZt6h&E|d3KVeO9l=x0NqxQxHj9074 z-|@+B;XB-hd+T{=<@s(#g>~J3^s=Om=x$%FV98kp@ywD|?c%rznADyfk&l5Ly+Vff z@`Et-%*|wl_oHwgZAVa!2A4EYJB5$XL}92#hd15IGTlmy2swuiP1F zDm{@k+)-Pbq)(@)QNy5);!N8Rl58n0izGLB(vAwVX(qvknFW8c)Xz{#(30rd*T6sHtTW;sD|R#4y(+ZpQ`>|Zul=Y;#kySu6F8wBz@(fTYx6LNc+4K z%ByN?8nm;6|Jh1xI=LI&WBd){pmQY zZx}$?F+|iwY6xowmv!2;_ZB(ughJJfkjnupWCrMhD8 z@Z_QU46R?&$b3hCN(u9UAg{2fX<-cnW@8fBXa*gg|lgnbv)oM*}#5MChGe(S1CI>{L;kKQMkhq$SKsd*PrQ;z%jE>(QV+ZTd-F zXm)M>9-{-Z$#RQjhM>z=3pbsm2T~$HrrWGf0%bDK>=-SAunu@EW-~hVccZ+VmR(ca z#oy&kD{85K7#@fAwyd4H4H)(m5p^-gRU(TX*y9lUF=sN^<=Qr_FHlbvKQoI`Qcq$n zm$0FCS?)$^^UbO+JC5{YKR~>X`Op@bI9TFyp>^mou0Ga)6US$^r8cx7&_3C=%y!LG z^|OJRv-jEpTFmpzWTLKRtC&Uh^9l>1i<#Wyhob#|g&}pUZmQ~$gT6mC&1F1}K~0{h z2ie|+M-*XYf>NK`E{}JV6s_Umg^|n8HN8WTGxfcQ08o!;{DR1ITj-u8 zVYitwo+)0x?viI#D4ifFHRfs>6jHG4&!fk|GHy=n;hDC?uv(irFj$ir>L;|ANjLoz zzj604N8^hBYB-+WmC__|ozVwev(%rBr+ECz_k5$4a-N1}a_UFnJH{7$ve}Sho-3h$ z#wcHp?AigA4Xq*7eeOF_ar;~m#&6$F;?1(A3LCn-I2a6&>V8SCOMrZF^)m6CF`KjZ zK6`tIX-)m|4`^+X8^!f(Dum?RyQf>{xJpEGirS8PU-cfd_Ac~UQc3HRa)K>|i7s-d zu_uG&_Y$3QWSzXWlaMo!y}h{8WS0Yfm5xP^L@1XviBw=@tgydM3ORF(Mw+xL)iR)xIW*(#_40ku#p}BSLXI!P8E}p9oQV7ivm0FJPLx6H&5~Wf z63WK=$FD;~-Cq581sx}DoOjaDw!bJKPd?(C?-8AtQ-o51aZBsK0Ua!FL%&sjsCXxb z$3v{U;~`w^qc1?~@BI|D&xsD!yjOm_=lneC$Nc7OQa__7E+F1*^1QsWW5+Yqw~1*n zBAq!tdt|tSlI79)O>U3;<~V6lhUpO3U6hKwxRZO%9G^~6vWtREc?_q~wm&pXJYf!u zl@QKm+Zj_xW164t7hh;h%bI_GYV7)ay+kpC(Dqu@H%Mxo508^d1!BfES#WQiJb}^% zdKk;SIb8NK$h%PyNzF(G*|?{-E$1m5F{*4!(06WwTR-nn09l3=GVC%xG`};Mdpw@~ ziakvO%j`Uo6F6p4Vx#}%ZYfI7wfEK4VxpY0!=T4(51;@ONd8>ojz0!}!$L`RbO?8& zb(WS9Sl}XK|0$*puuVDcUhih7I_hL!MjV_ zyzF-yp?;x7pFaIoWFTQRemKPw2L08=({s$Ix_U->i#Xj~m6&9Cd3qM!DAg}b z@jl(mpn1MBtojH&6+FFvIARi*c@Jc?*|7U_Y;|C@ic?`7aGW%d%)n-pm^WB`M)`11 zzx>Re7Z={sswijARPy}Spy%+dhBBFZ_v_k7h7}dnY?N8h$T*kSWPT1&SlCW!(#Kk% zkCeET_~lj~o6)_;#YsrqJ>0yZUxtg#ddi zQ^DtyJ0q$-g{RhklBLT7T(Gx%tFm}<VysU1B%z)TQa*Z$>`<8jdie#LU)xUrbodQ%P~p)kx*St!ygh+e%wko5+iIFCHaK zAva%W;*acRToWbR8E0@8$na5EMo~SxJAgmH>)Dgtj3akGbdsb)Yb=eu;r)Uo%lia& zgF*h>VR}b@nd()24}fm5G`aqs=>1;Cv9{EXY#*#xay0Y3LWg~`(VoKW4c88V(^3oC z=E-)aXD^dBYMwj}8o66R(Drj~LL00wiZr=BW*E&LxSP+M;4OPt{nI=sTBd@#2;w78 zbT-xHzlG0;G9`#?hA4i8%{E`|e!yZv=dru~uwGIEU9n!)8B!IUsit zvbN=ceJR*NDAn_segC3cX}*-6H4iWpRZIf zw;}-HsnGwvw2iZivCl3;pZdH;oPl@KlZj$@M0BMleCF{fi4U9K=I3{&#Nz3{Xnb~( z&T_TWhA^bWPHtJjM=T5XFCz=TQJIf*q)1?Y9i2D&jxji8!CghVO=t{XKV0jR90g~2--r~4 zpVxh@m!xcipmY;r^R;%gppfT3elR^i7 ztj7{gX^Sb!7BN&p^b3o;R`6S?%kZQ=sI#KbEO4oNb38crQDX*8hPO9ppda`7r~AHA zSc8I zlwqb`UryX<>+A2*YAxK52wF{ZiUhQOKQ?io`(~J_xi{PQS}-T*{2cyHrAH;kW_MM{ zbw{SPeTU-dAt#+xOq>3ad_=)p|B~E;`HZQHrhW$%{2*2CJxlA>u9ATTYRWptViE4% zA%x-I@XPe44YJ0W4f3zlv$)T0RLuI>a|%=>2|ga;cZ+Nvyta#}UA1@ik!+0Z zS&mYd9f+XNj&P4g&GUkfNVr4=i-j?g)O}qGW;qv=s6*yHiQWmcb?6wfApA^Er}BZT z`Gkc1w5sjN)7SCsB>Kn3<^3Xm5pnj5ja^4wXP6nuy?1O4u;1mW-UOr!K?y9=<*D!U zk4@Y1=fXbSXILFd^bFLLzsW7G_A9oxWAGq4Y3hwWFS00sI|hI|#+RzE$3zTdPuj-m z&7F+#T9>g`BGQIutgjPu{45S<2g}cnqvtRz^Js=7WVFrkJ(s#uW8Wly)z1xM$*ZV- zZ~H`OjLB6iZUFfEy~q`Iv#h-7c(G7g0wcV=BXN0 zlx<8Jn7Cf*J~nD7WW=(6oyb=RHBrsz8?gU1iyC?oGRW?36U{>qz9nz2rF5tBDe10| zg-BK54_`d8^ge^b=X(CFVh)@hHW`;igg7vfHKS++-<9<&eG|fZk7qxRtlz6$C42I9 z*SntAu2it%kPP6q%y&-e#t<1LTc}vx^Q4MNP#0$P?8#VpNX@l>e-aGNin}UE6~2w< zG%QAF3W|k$n#}+ENopp^RIjKW8&p}?A*ZgD()`)2=0eijk0;f?^ZvY#M{eHDkKJhjZ13nrY}Q`U z<}nT{VY;$9K|{ji?5;WA4Qby~qGmOmx*1<=j{(tS3whvcnD~~Dz!D8@z=>m-M^D7z zGty~i&)1WG;}!T?FtLp|iy!3_4!xW_*j`a5P+dgx~nht(wV_EivOk2}@=TRWDW^U|9X=Qn$UkbW` zrGiM^54%|T9Yf|aDxSGQiz_3a?7VuV%tG7EU_MCRmq?r+NQI%!^vIn;|7BU)cP_?e zRYuT%9JT;!=IC!q5gXGo3ik7F3bME46?1iTgxUi5TO{!uR3&i+8*xVJ<=sf$U>Ewf zPTN0=;=Ko6eZ# zk}eW%^KXg2B!zn5^W1X#uZa8Q1vuh*rUI#d;s@}4;xd(LO%WE5*UVe$+6TJ4kFM$m z6=J5`Cw=N|Cj7%q8-q%IsX4`P20$ptw}VkxHVay{G?j~+z<*PS&z*rCfGcFQ7j`Do zl>7S2IjuXT(qSi#l0}o3uVZF(E>=*&;jeb+19e{Ad#|v#1#y~%aZboQ9$aOAhneMn zhqRV0u1IHyjkZ4h`1P)mIWQJ?;#8#0@5$MF@#zQU;+zUp9M-G3;={+Ai!jSFpc-eD=R$cS?&nN|TWF*-4NcwI7T;s9{&y+9F_E zWKhTEUp#qIAB#^vT}!_|O1!#2&yrxWi7B#QeAHx#Guv9@{wt5;>0TD>!6TDL2gQ|$ ziJzn6XR1NXaeYeFVQgjrZ8R;{We;6nrG+?K`z}z>Ie*ciO^!Q-AfrkSs21LTH0YrC zCVuLh+b(c7w!DY{oYIAvOZm|*PIl)LkzLcgg^kHp2eL|+`=ua#6-JZeV_xl!&jnsv z2dnS~yo+JTHX)wYZrbt*A)o|N^pE$M+*kij?QW?TOK_1w{*&#%**N!8-vk?T$@h0z zYU=w~m+Kq#D<+`Ho0iO{H>g{GbJ7L#{%O{z9OuHNcJBgG)xNx`$8FQLB2VuM1hV$6 zJr@JqO8?Z%M!3WX1P@!GJTQy3Dr}g{fgbY=MI_HO{kT|V6kP}qiFGvJe{3=z7F)Vg zJIX~hRYwjiX#>fqluVt}LYbbE0`FJOhsfi+jkPl9rch11a#cFCB(U~yJyDOZ*cJoPQauQDf z1Rlb~JG^*tERH^=)F**|aUny4<AxOE*gR*z_zF&Flj$v6~;L(7Fs8vgujORdLYp z7dGa6X<*h>c-O@_HKPZSwrpNDbZOp1v0*nJ+arOLispP*!OS;fT#RO;`4TiB;#>0nBCMS~gI}-#Zw`$!# zG8RxdmjBIUnE9fAwF$m=lx8wdh#YWeDw-iO0JJBpK6^~ehM_Id?|iRjgORU?Q4c3I z$`o!9!#4R4QzB>hf$56=jp!;NoFaPOdR7-)3_XTO7!ux!!##m6jhSOuyTR*l)( zU)sueXZgT9Fl*~tNjm`gXj2>O)k*o&v@f%mFPXxB0EOFo?lYU*68M6XS(guGT`C!7 zzi8+?tNHtx4kReqFFxMd&ohR}bvyQ2d3vVT`e^nGd=6O>4m7W*75F|Tok?3mLK6!? z^t{!J)v9~?mBPNKHu76JB4)0n!6~Z}j)!13;5Y$y7{ZHuiZEoDPGAmKLke9=K+E$L zrKDzm!+9NMRI>IZz)<$xbi(SZm%(B|=1wR29EFWu`n)X!8eBhT0o`0Cj|`WZ+iN4?{6s+?~l>0Tea#U9`_EE z1k%0KZWWvM>^P4m^HqOhm3V>O(HjT2cS+tZ0Za|=e=J~i)X*zGLiQz3e(dxiCY^h2 z(}EkE4&*605r$7$A1%M6IHmlaqbw7ViR-B250%t0sGY4CrFj>ZEw7vYGc00`AFBo(5D+=_lkE_?59Y~EKbLbDl-#a#UoP&&ZGoC!kY~`3u#CX#}P{+_Jcl%(?JLa;d4!_09 zQ$?RY-*P0U%Yq$e;faMz!hQ1(51!D|;WN@lOO%Ij$9W6%{InW73F~*qAae8$!x%e@ ze~$v-{G8TtYuNwnUcaF!N~;T_snOY`Fc>kvC9t&4?#SyYb?FekBP6zct?)jY za_nJio@V&)4solL?>VWHEH+EI=k&ICagR7xg>i8<>C2ci%GmkKF;;rrFA`(pBadee zm)M{1i53dr@-!M~;QMCVH~~l+w~yLPe-?Zh{GkgE@iwSxa{V^$>)cW=XU-9?x1X9g zHJyB^xoYaMZNoRejImP72wojZ1~6tDz9++K&8yye&4~*cEEWCyfc}l?1Zdd^GS!&D zzJT4c>{DeVnSuA-a-I(ZzNL_>8v)|RkzEkFP@a^2hrGuv!K20km+t&O=MDlaw>uF5 zyqpj=Gzu?FWo~D5Xfhx-HZwMpf$tRqHaIzxfj}sKjkpIi+*=nmu8ZEIGeobW_h`|g zcOuAOFpL>x^d7xL?}QM&1W}@k9wmAWA$ky95GB4zZti{G`~LrHeczh3W`6tG&)(2= z0ci389>ZZ^H(XXlxU;t_#LgapT<7mc0EaavKtMu5jOTYaK;8-L3b6*k0Gc3#J=h7k zqBRH#(1%+?zzFYurQndZMV+09cBY|1t3=k=&NY}w4K4Q zzsMSY5qJQ9ngbBv6Zj|HpXgtSAh6%TAZu&5lQRhB4T0GKY#~rEKwDXZ58;L20f1nC zHou4#(pZeUaT_Mg0H$FEA^jD4iztSMvtOT=B zggZHbVF)+eU;BFmaRpl=`|i#E=Wrcia8H=;-$Z6enS|<#T~5n=nn@8 z;r<7+10w(;KnYP%5di?$1pxN4w&(wUwSa-QGx)djH;k;o-`5%L46sF(0rrR3f{`D% zzHT57FaY7|4)*u`Z^yqaTmb=q4a6D&umambV7ULuj)cLsf7!_McZGNX%z#Mw2>^h< zUjICqBNb)?he5snL;rom{AxzV>MAPSe@gzxsh|M&0{HR@N&t8zM1cSS0Rd5efS8yF z!2jQQbU=_l`}nU|HJB|NAo16Bk$w7m%N~C;!0~55I0668r3FVS7YyL|kInqV7{|+U>h9>!rJ~X)%=AU{+c%^ z1P0cDyFq^4Fvut%@PB;BA+vTw-Xd;DY5sPBku&t~b(LV&aGPJlCMY5b0J*w?ym66d zjkH7nz5>Xpv;lkl7BhgK4+cjdLjcGc{QbMX7IH;fObX@W*MF9hkuePGdJFmL9cEa+s(~ zPxQDV-GFHl!;{(F=YCb zIF8iSEW_PE&2a1%Ed~;Iq0kmf{lk0REG~2C^XCsa{e9^|Ck5&~)uL75WYpw7kC}3Z zlLn|M5_2BEb3sY+goPw8> zUYKg2eQJ!w4hRvl*czw0eD)$MQ9#f0QkllH8=-rdA^Y9i;;Bt~3H zqKI1cIe4cfXMAq_RG?m7E{0BPhlr`!Dl(;~sj^@v~ao`rf|#}oT! zC0gu{5yA<7kjA})o39F{lfg$~v&(r3KMeyd$w~vB=Gnfuj{ClS)^M0-B3~Ez1R9mn zIT^Ta`Fe!D{YifuUB>(IZ$0hosoP$v4OizFM`Tt*Dv|@tp+(S&#(0qy#n1f|QHEyy zAdR-OrhBg4BesoaKkx<2E~JDvf}JhCHfS9>UzfXoC_Dm?60y&RNeHc1X$G-L_+sEk z8U;Qg_%2RL02*(2E;tM0L$SAQ#NB|(s(-p)uxG{+(-ciocctQdblyYvnXILjj{ot1 zkM#w5(Q{?-YY!cvr7!#@+M*x4<>8&R2LXHA=Eg3xkDhBbV?~+@uaumIH<1*W#?Oot znCK{f9ckPOu3HK=<5e}6!BtazaRn&7CaK8>ciB7J+^PLq;RKiGSH@b5^ml(li`^XeLg_qg zXW${+wqsN|ntS_o?_~J5k`*gBYRwG!YMgRp4@@^!#PClj->Zr zSlL3i<<%~AEYQm9GCdcv$ck;$2336=Ijk>)LcFdM7@`M*zv&Md>ZsM(`l^qXeRQJ< z!$0_FTHThv&;QM%D}Kx@zxjHep-F>(RXbm9FH~k zW_!aDP1&=$J=xV{XRg^$F%QByN|{9+0XP436{2LhLaihbizA`bD1*&9aod(~0FAe9 zaYRV7HfLx(K_yUZYHN~}FbpSD1;6krNzdms+3Bh6j&H=c1<51(r8DV`0^iJk%r%A7 z;oVvPtM~m2xo(2C?24z}%WE~318=6@$eCL+h$q*=XvAFDL#Ve<)gy0&9kpdB_kUK% z%^CudN|&HKpLO6$G0T)&j%d@FT!doxT+q!vF=2hXxOz7_|8?pqy!E-o9Lqbl*v-=u za}sfAYW&7Kw`R7`&@TRjwKWTW&MYQ_&E6mo!718m<-x*u-Rk||c75i2srav{H|`cF z`cb&@A}5)m3Nj>%1s<@)OoR1%RhjX%V{Ob~6BlJ<=KNS6c?11@BPaR?(N!nV)@?o#DYp+dr{F1%D;N6{Cac;NMp(DB z>}NS+wd3by2>sH*LLwX4&$T8L7-SqFrXgXy7mixS4W{q+mFK0uD)`r>?Ksvg_F%8* z?Q?vZ8M6?aXC(%r$=}?5a|&%mi5(@{f%-Xxz^6WZD-)*H-E5(#3eER^N#>Uv|H*@q z^pHCsp)il3H$|y`!8&gG?E-p|X8+zCf7Lnt{XN8d82XJWI4gWXN3nj#L+fChSw++z zzxW%$0d`)ld4oW{JY~ZB*c5KR?HZ1aW}}(om1vdHN~qX#bz53va-U__Jj;EVYZYc+ z_HyCja1%{HF-Ip=Pik%WA+-R*AuW%0$f z#T_V~j-Mi^7%o)>IK}Rj#zUB2jQ1QqX93dB{|v6L=rNLobdr)r`J8Tx_xJgA7Cp4N zbMQ9EdJ)`z(_rK@u$8__?NTygr#M8Nc$#=P|Gp&)Rl*0eb<-eHaXFB`7ZK2s*q0HG zSpui$+E15=?ROoUQH#lkJ5(F)tDlp3IpnwS;qYL6yyUhLsF{6xjNhY{4Sl3>sQUz6 zDEOjLhZhDvYddLYmmW85U%>+NeiPuoB#g}y3y$S~QWANPZWD1_2#-tiHCHTu$nq0i z8OO(tX*`naHM|973ezEanpf*Oc>iP3$13=VczmC_r>@=S7tT3c0v2S1&-rGfBVUeo z@73aK7)1q~eYm^1bRr;!f<_6B&r3)EHeMe7tvfvSaZGQhIAvd?e{6{c@>Eu$$?aeAzJK$}bxw?E%&g5u?z5 zJ=+Px=v^0`VE>DoNk5sp*evAlnQjqnKb;<|uWnfq$0ZDL{u`UgT)6bycFyuaJT*LB zGJXyff+8e}gU`jXzt7+&9i~+`q|eh42lDOkE0@yJ4mJ-13(^pJIjb$vXnf3co?v`? z8tP6$ouF6Xjaet>lY_?*@OrtL+O@QQ;5*BsUHQpCp^`OSik(gc2BWh8mLmzJf|mOU z4l=kg=CXi_uP=Q)F{>?!M1(Giln?BtI_rdADrA1$$o?i@T0y$n?(%l*Xqbp`<^A%6 za07NULquW1_<_J19b2ktoXS(4S^d5|(X;h7OuARDg(YT*pSwJseZg;QsJ(uFL3!30 z=yjpOa+gONTC_XH=bzs^iZ_z-u9R|VtV8)@W{P!9ZC2uQ8LFx-TP8|WMy}!Zay~5n zZBMM;C_V8O4!MPem@FRx>!x;DeZlkqvcKjO2OWLEh=sA<16kzL_=uR7xhL$1>X`kIm)YKAO?nWink8fc!sz{1LmpJ6NIvWTM}NMygUmO~+0qq<>xH|Qt5GTK*|e$l}&L9<^& zdbhh!&YfaSSQXSLogd)M?)1$~I@53`Si+gfvIDI|x9!vS4fbNKY?bq2Q|%JGnSL7eMrOvm6y$5L;h zOZZy!CCU;Y=rl@oy_+EZk>^_TrFmfxemiXf#h%S8U!^39p`xA`&)@~>)l3pT77C-) zZF?F-&bf~xi=!ipx$s_pH3i0zwQW=WRW)&|B8G9A+{y6iwb0A+bZ17WZuP5V-L1?h z46D^r3V!EP)P~bnbOy;T9m*5p7?wY0;KY(7%bGo86u!A>XZ zW)QKFvHSIVIj@h|x$fV(m;@Q1!cGvS=n<*=D(n|)iciy8oH;S7IM1|a)4)`{Ch79Ogm`-F-6Y}7`Vo@%gPE&of zaAHIw>wJRkJ(1o_uCvUlEYteDd!Sz-0_%L?JYPk9UdO&JK&#%Y2}5njayK$a@!pZa zeV^q?Tbylw9OBwPOVH7_ z0CWm>e=H{SGLU$;{={Q-xAQDeebLxAM{{afNOms%MVaP_`435BYAJFO55|Nr;tWia zH7U$c1;!+ts1g&hcs`v~H7VIVCWFFA03Y5vxBK6J(9aFcH{OIK$xN6;|HQjZ5~+V5 z9poCMiFoKOQytE=9&DwE-VtCy(2nS%m3OVphq5nK74fZT`{0ew)1gFD}RzQ zv#23|Uk&i#HWu0$_maBqR49;|d1$I)LS`@c*llNdKg0|E*nD-aoN2`KMpXMVpMOkl z5MpmQP=w^Dz-Vo_td6^qr088`)%zQIvFJKOx93@JX3P4$w>O7+ld%o*ViiShR9x-W z46%BNMMhZSBhq8p{A%JGI-~Ceq<&T@-sb!Td2oEK?0H!DI@yyN?FOYq&!mb7kL(Re6Wa|bGQa?9cm ziWEn(K_$*inspwI!|cv*)Rea+WxEk6^9fk`hT5an{e%vJicV%lUn;c49tJxaUpW>P zl(nM`n^d!hygi^VzMn%x(JgIQ@^(&tYf)SSZsV}%Hb*E#9Pto8^8qc*aoPle-6Yk9 zLV{aKtoBH21M6O%Cc~(v0euqB8jz=D(37iyJUsvm$9RL3pxjJXHp6ly7Ah7WywN6 zI=K|^gz7@vVXf#a?^e|M33u=EEVZ$~Kc7wGGG?&6UwQW2pI3rHm%q1YQ?m{nlq);m zH88k4S<`^ZK>W>q1Km8j*y^Yg=XR%cx59E)PV_H8q2JtrpU3Ynn*;r0(B=zI` zpJm!|g{+#1YR{K<2oS{$^B!1#A>lJmX`1=1)+c&SG>w!ghJYe>quh>an}Ws?4{g)@ z%iaNq$1i&u&x8;WjTLt-`3~jb#XWw^CG}fp2MM#dc>{xH6jK_}_IYS=rlb^gobzxI zF-MA(pUDqc1F=<;o}%zndX4&>xmCM)?H8%$N-L|AtZzijV}9JXFTrbnej++f6^7!( zvpiw1&ujdIG@cNB^f49tyPAt3nbM6VPp!?Dbs%WDWE9J#w#bUkMyO|x<#?15Fq%ny zStx3JnAu`;;)k8fPYGbHtx`XSlryu;&mmjuIlgR16}SBv#o@i+^=KUJAIE#oNQdr~ zI45QJHm#JZiBc-2soyGpqVs#!ymTVRu2>qLjy^(oc+E(<+vq0VcYoq-N&eQrhB>+XwH5bvmv*@MJha+>>kGT6=gGRL$y-I@ z&PVDD+St@x5w_VJc5vHVvAVuZDpOpUJHroM)q&W&3!KCC#v4fCVZS9cM(+ZS>^7J>%#Llk-iG!SptM z*m)GW@$f3KdfQunZmaLE*>Lsh-tWH@dQ_zbtbNmtq`eia#LA#dY+ms#N0@SD5z~jM z_jqmcF&5k1H+G+*bbmzKV$KM>V0S+l@}ppSxF~cDtbak-)Arh8=1mF}=S(KA?>p`I z<{ItUD?wtt((Za9uMc1M?lDH{_T4-4RInRQTx+}4zirKb&1Rk}hh|$Ho%={N*Jh}B z&pcI{!|WQ~jdFG^b=1UvCx<214Q6})N+>l0+A|b|(7)K~Wu*_^=lsg=tT%AEyzsu9 znM$z19XCS>oFsC|-MdiZR`TS8o#q~SZF9-@j4#_(k-Beb&W>vIp`>{ZedmA#Y8oGG z4{8+R<)F2H09HOSb)TnN7(3PjF*NMq}|T3WcSM9)lU$|%~zsnb+x82O$e?|L)3UK z%17 zl8jw{n~~ni)k%F$%`MNTtC7O#H>D*lYvSo(ltrK0aobiWXe&Qdi8>a+!HlGtl@DMt zB)cqS)+CtbNZJRv)T~(!?3!w!e%T&fow}{ZHBX?A$)w;IVc_pz)$E;`Z_H34_94kB z;bl5UPe6q)hJ!octE<*xby=}@Ws)5?UUu1kn<9LiG5D(|u2*O>(LTnDD8e{oJ$Lxm zE0$Dowr5WzOWb%Y;S|l>qVN4aBg$T%Wx-;eZNRtRDmdUw;WIUwq%17&%SYJ}Q=RE< zZ`xH1$Jd`Ex*n7;(4lnvWNY+4jLzV(P^+b z$IwzMw`HPC<8V3B;09d7Xp5jO8(Ijab}24QZ(V#6=;N}YhDxsZ?Jfz6A0><6kxSWB z6UALHt6H?!Ue#8O;Sa4f&rVST+WSMBxTp;biXK=})3sTly{y2Hu{36-8ytOqoxq>W zO1Gt5cYw;|`a#pK)5fH{kqFAm)I)M5OIja71Ea{TrvR%#xl^yW>Y=@?`f62J? zZUHBI-M;)eQ7y2`IPxTa?(>3%PtEI=@>MEc8lF>IsSk*aLE&kx#HYJ;Ml~zr(<(k@ z+{FBd@;7OrFrhJF@+7&ox1ChwWz}pp8)O6$9_6I?-Jrf>)@d_~Kr~NFN8-|gDra|E zAdgRbjePazBe<^Gk;@fv_ED{B9j&VLO{X?cb;alh8t#0@&`;EV(<%#<8Afm55>Blk zc6&kNdRe}+T*xF<>K=z=yDXGKQh4HtcMFsDs`VL*EX zE0HyJxs2UsZn=PIXvQhNrNDUY*QGB5%Tl5dPK&oQ9f=Wwc|hJUB2>KpqmVb(tyw)R z_uYqzFA+W(qll*kKaytBH`!4 zvzx~=I~3Wq(UP;c%hyLl@g2MCqQazp?&H0fkrjO?bJQ35CI6%#qEFziX)WfIlH29-WPK@FG5*O3>s96!;Clb`T&tqkq6r!BSKQ7$3#; z*uOre=z8~m69sVI?Qqw2Px!p`Rw)By9a?H=k6H7W-_=$Xk{{@q@6Yh9cT`jRDLbsB z=gBmO>y}MQp*V#h>e6FI*2dkUsFBXb&{x=>T1h>1$1h17Qt%3k)np~L(jVSo>lbPb zZU(!?f;dBE>d|Wy{shOzrh4LD>SNqfxO1g5 z^Xp|KnS3$zmZx)GtR;I*zSa#LPseKzA*^rt#cM<$Vqd}GK9M_fdnx(UEqROaTdfE* z^;EV40*BOY?uj3BJG5l4d%hf3ScGt%1g~Rw5oz`|`0Sl%0GsL?q&>25nS7o$e-IaL z_H!wJXL3PYbQn)Ak~_wWKs&k$JEYH}pWHfDX{HJV<%-K*2un6LX;ZPhlx50IY1_5; zOnn2+hrNXGPbAeDTd`oGHNiC3g(ho6^Ft&BBuIk=?4M9I__ZB9xrUu|QI;4}U_V50oI{-M zor=RtkWXsA#~dI@@MT`i7WWJ0RDw?ye!CEJ4UfPKdV(uEDm=lugB>di6f!R#Q(?_B zPg`G?nW-5i^ToDp+qP}nwrx9^ z*c01!GO_LC&HeAY_tmX>b*fJF?p|Gc_1b-^Yu6zm5Vf;)R`#$rVW454rRM}Fi7Lu4 zFw)Zl=xLdtNl1hoO$?kZ>}-V%oJ}|ZY9_`2B@=r910&!sgaMiaAY^Cn;b>uI?hGJ* zH=_8*2~f2*Ft)IRF{}MBGw6g)oh$st)%E>B!14M-Al!X8Ww#EQy@xSS|&Q6?v(I!TYHvg)Q z8sPk2%i7?-mf?S`|3)3%|83DiGcW**EsUH2h9+hfw$OC{(oMqF)DFPUzDo6ismxYt4g}aHdyoK{$sZ9;6|4Q_aU(Mv-=OSZbY~f<_ z?|hTLdi*_6V>?@GkN>;n-!lH$kWNufUPV}y>c0)}Pgum($j;cp)(oKJ{8vi@N8|rG z{t3$)Sp2(t{zK+J-2`Cxe`^_k17}AIcYqc>?Z4WC{$J03ES>*{5)`y^_o887X93VK zG13DVnE$>wm>GTkhpv%}qoawf^FMr)Ke;Uce#NEUQdTrUxh%4AKttGU=SEOjR z5}aywT3>}~nE`lZs^?nkr^TSTvEH9ctUG0_d^cF!nE*qc-HRQGyJkXvgE$k|qlw9A zf^eN>td|m^N;BWutv7{&*M@N2D=<||8zWh;>xf(DjPEebs3T8H8B(Ofl_*mnp7yy||)j&8E|xTcM4HTn)T z`dx29YSKe5kyfIvES6m~lN}Oqf{tPqMDD2?SQEn?g(!llU&IO?K zOr2XR;fBJ;swTS=Q1$Vr-lsfcxj&-t9AecBl^<{Psz^3TxSI`sE?B{w6NPG*Tq9z~ zvNq85>&IQDYx$18Z|xC`A47T)&8oZgQ1uuHoyZdR><^5<; z0I;+VhJ#TVrYlMw)Y@1#NhKn8xorLe*JXNoQ!7 zXb(wbX}0K_AbMJ$(!*^MxPvr(oou_ibfdXr+I;0lote`md7Iff#;DtQ$K$Jydun6f1I@9k=odDU3wnQ{ah z;gnqZPdQp9>5rp`2_HhQHzei*%lh}`<(-rLUR6SWxYZfN0pbF`1dTEso@TG`sav^r zB5Tpag#YPo>xnDTO2Y6*!+f9Ht}6+4(eaM-qyq))d2ed&qDgM{T$xb<)j^!CEI4kh zKLfuaXK2s-3@@{g?kum)tqk(hFSF2fh5?@12L_I&ufCMx7CxMT&hq}I&yu@-Pa}A~ zUbw4&%m3!L)Pi8$8lPLvY&Ce*{&kh4NrR9q)t$Ws8{mc#xKuqw!qX~##?;d51z%-U zWH#~FG5Jfp0^bc@W@;?E(W=2hnE>Ar?Y2I33$^quV%zI%Vu3pPb@Ff z8N265DS}Tw4fQQ2e%Sa;^}B!}XM4%m(Zob{Q)CZGT=&AuxKc1)h0H|({c)wt4k;7- zO*chwO17p6fuig4sI|#BzkyMlwPPzDXUN9y9HNFKB4v-8RUz-B*fT$|)@`U=gnUhZ z{QeUxR>L85k&Ux7*bN9(lmjn-ICEJ{X6f)XTAUj-_hSQ-pQBbJK=(a(`t6wE)^C= zOI=)1jZcr9zs+|hUZu+`MXq0|#f%Am)2Wg`kEMh}p4N?UeaBcm#9ENNYE)_$u11~I zdn)oE`mSBzfy}N|gH6Xk5guehBf(m2tmdBe)?!4bNC@6S)rdQg+*l~LQD?Aa+yo2b zd$$6_pA+YS>eQT*Hz@sm!r{AQaHw}Ca&Q@ML6ibF3>}Kpr>LOyc`TQLPuz`vL+aIw zhipBW$$&7*6&HHjQ^(+-ReZ1z(q>^=lzzK^hAL-;#1%12$qVHOK7}S_9m{ZoL9?wL zrT}H*rn+*3f&hSS^ zA)g0|^NoI+Zvx0ezO5uUko!C5G*gOA$46MYZ0S5e{FH7!jq77VcHsGOz*9P1{b=Yy#1!kK~ zn4EU_y+6r7gUY?8%h=BCjaYoToGCHu-sQc0ko=pR&E4Ga?;2S|RwxqOGo)h5N@0a< z^>?-=E*1(--@F5^Th6JQ0eVmGH7?4X0KFOt_z*^m{$$p_l zh8T8q28Pu{R_%)o%~1sIL$R&F?>;-G-O|{TvVOSfk&_3lLTb!$uF=;?xB~>rYe$+r zQPmn~1_n48=0l}~NjTKYJgKb|^USwPKNl^ys&V7;H7{mEVaJPq_(@G36B7BC}0HOFA%oLm>p=dA(oMx6n`N+GY#i&;!mtUD3F` zlb)1UVE$=%`sMdSd>rf=>cTm%Vk3KgGCciB)!h~1X=O|`JYDn;|NGwZ;U%>VmBZnQ z@B&9-tKUwy=o-N*ydd`+JR)8C78Rv#Q7nwy`|}_k>4><0tn4+rbtjcls^cJV98%BA zC`~>E*t8rqeGWHUR|R@bt-~5Zak&Q~V0~)X5=Jt-jWv2>%c?(kjh7&HPOzcymjVjy zFFP1V4l$$D3+QJc+8{KLtnCdk%~{srP2KuFo|nYlGz-^OD(O~_Hj%0myv>jL$3R8q zE(XI~^Y&_gobq5z-c?ZLv#lQdpi-!X_3I43jv7gA>z$aRx(j|K_Rnb>tM0V!L!jLK zhPHcDL4!&#y=Brp&?C-am0rwLnvIDc!nb>hNS@n@pyHXoDo%EZk48Xm{C?azw#m0@ zXV*^agSbiZTZWc>g{AK)uBc4=&kWGzea89Xl}X8eA$8R4HW4`=9{C8bCS#>Kvl{Zw zVpD;S_PFbkEfowl(M$(7VsP%l2k5uwegube?LJYqffG)w&^VQlHv|2#9}tc$$`%5ZMBjUm@2t{{ILyg zk(Z)`PFy^RoBZs`2GFGEEWy)I3YW$FBxh($?1K9cj%qUFmA1UwGzunUM$5INVU48!nFuM#WHeZ2}H%<)kRgM#;Uc|MTXSN=R`Y(8W8XgVjz$nR;Go@u+-jj8-_5@N8h*)kNC>l$D^DEkaZs? zc@$-&YtAuB!uCUM29SK|S8gOHtTo0nsp4SdAgU2xz;RYvPL6g{K=&CY{R9d%g!k6f znBc%O*7As#&75~XKT$@1M|qQsnqc-4MT`IA^mfPqMK&@S!ca^FIkSdL4^rr-->@x2 z^|XDPfNFMS*h9g7nFyLo+s$?xmmyI(!n5eD5g5bo&@rGI63qKtPE>WyswOg*!IS%ubWGz|jrG1W?&_M8{d19jWts4D`}QQg4(|^F z1;pD3Ehf0_NqP zcaltq0oi?^R|_|W?(^@GEb4jn`fbcXv{}9%@(7$J4nC8N>hRinda+!)H@ClOrSEd-f8<8bM zx#j)XEywe%3ZcGQ!swRI;wTeWHw4q25JflC6vok{D~>v3b8f*LiH(`&Px_ad93Icy+*X37r=<6UvlPBE|G&p3Om*WVbA z*(8)~zfSm0P5jRkR~v2l8(=<=!IDb1#v_z|Ou`P1t$&m$o|Y5O@cxv~{}v?XV%GXi ze42y<>DXo+sH9eF}j?`xPLn*IJKlN*@nY64h8@mgknKZGUXavtC$>C~j z+($NlyxMjQ5n3Q>hlM6iPl5MIK$-pMe(q?`DqHCOgUQByo>%!h^|$^E3x)5V*2{0@ zELy9gzFZNdCf{!sbf|egB`TVk`A%7w_bUWV5H&B0xw;7V+u^jWRU}HuvWvWZnWQ5k5GDmaJ6jTBmcoakJa?rO(*Tx19;8+`+Ht|C*WOp$oQP;D2xRtaH`H=lF+*=d2JX;ZrU&WQ<{DmqAp?@QSOdtO88w&zadB|%}Z?e0K(>f z#OI3u^I9L+Qi8D~dUWb$VNSH;v*P)f4GwgsL^a}uD-w`)mGKqvvX#0@mxrbwg4xHu zD4%!Q4DT)y)K;XzL++$c?tD}S%*ei%kx6eCK$gD|ilk3WkaanhO1U5v?{3O4o9XpN3K-1-6)4TbML95jWv8e< zVd30hzS_i@H5ti2@oO4$zUh@nVlM}b)W6rRE>YW7F}P<0E}5c4MtzWDejOiw|7p~a zNw~JkXn$FlnbyM?@v!W(UeL8JO<@2;qJV7j648GC0G;X;jUn6K4JjEGLwRa2^#bO# zXec9Vljy1O4KE?mLlhWuE!mx?C)M6}Hy04)hsE0Qj0N+Kai{4twb4a+26V}M#DvpQPPZaF-& z{)dJyOYM*TM?cZoIWjgngcqwUg4+()CA;@LlJ=(PhFgGoi{H|#irhOcUN$AJv{w!3 z;ZQy5xr_;@)=%|`%$#Mjcp6~&O9|+t0^j&wUjiTt?_wSAucVp~0tr%oY(2)Nbg&78 zT62vCS`@24sR}6ufa9M=G?-=}+Wf584!|4>@OR*+EOjqpGaI8N-A3v(2}?2DxuQ)& z)B|NZMl&?fzmd@@oEDK~fLX`Mk8j`^o_;SQGArCq6B{oJ8IkSh4SyvQE23Tw+7-hn zOEwc~U!E80VBg^jlJd@fqNfT)cQ^aJG1>83kKurY{k#T)U$x2aN*3~qLj&B~8)|L4 z=0*17RZ*Sa1xLohA2{HGx13FWxNTsfoDijhQ~nScgux@i@dqTkR`-`B5FvZmuI8o7 zHs2L32tE1;`&FU~*I8dLqX`WT`!AC&s)_%xH&Tbxqm^{a3ydm%kuIB*M1Pb4<5Cak zsilW4Z*KYfmAWMVUWrVN!yQ>ms+Nb@YI=%tQ5^@K{v?HN1`Z!s0>&K|BpKgCY);1#aWN&^{|RI~8mLN6gXtnmW3f5F%b^kh&I6b~mQwVWrS^dtVK6Lb$HmcJX3TSDv<_aY6L7GzE_NCWld*O;wYb3}R7dnoD}wwv z;W2oMaVm0ul8PN$1zoTU*h15AE*})DJBRpFTzR@fy_RilOCT>vyHAUuFH>fQMFeb( zR3-)^e0k7`EYu4Tb_Uml zZk`Ic%*}d7%+Sujdp)-XEjC9A63k`J6^FDqc8w9uvr*TJ7Zj!FDA-Q;L!=3?P6q|M zdK!wSciuT_rhVulvtVsQyk!vOPFa{;--O^fj575iN^!v1iU&%5Pa?~4!5a$Ff5}(_ z#s6r3w`ioJ3ms%VYgBb{8OhdKhr)6-UwroEvLC`o1KvKdt+{A|LAcfb2`MM+%MyeG zA!3(O;oj4v!$u7qW9V^QYeRB^$lPx~?rShiLp>hc0gta(;6xc>mpU53x98#sWpb{b zlPjW)&`GgF*W@i?GwHJQV@VGkv0J~sd?dGjKw0qfEI`ZE#%;0B?`=u0CF`{@#G{oX z)8EUAG7c-b0)skvLAHD=JR32huFH@wq3Fls3O-#<@$Zva$CGE+?^ULrX#hvvC>cw^ zj110RuIMlp6!xjYTc(btE+u2gW_tSZ3aA{WK^|YcgQn}oqg!y-tjn$_8g&M5cvK@q8I?UCkvjcTosfnCEXh0OJ)tCgCE}LEN{T6jvh`~00%;f+;9Oc?i zC^NOXk1f}fzf+9)x_g=0)IPM-O2kW=txkVS ze<8`7#mF`S=zoQ91tdYeAetv2(#6F}sp*?1vkLZ_DvlEAIgiO68{ zsM`m^IhIT#nL+x27Hi&D+I)R@9pV|%fAM3Htjm*F7`wLY5mA`jz$lWqk~A0rWkS8p zcS6KTX>){&6@0$Kf;NGq7dDMc1cJXAiMqZaK%=5-K@mhNlW|j55V9yA6)sR$I@pit zBmr@N<&^#OW}LPYt1p8*r7Z~bt`gzgd`jX$s|J;jjD;gNB}OxO!$hcao3De_e-$=U zW!}rKjPCgwAa-rcoxzA@PgjOR;rYiToI7O`%xBybB`knmW6zq2iLPPIZsaEUEib9% zJ^DIfohQ-`S2a#X0nYFxpx%4!TrQ-CtvWQ*`Xg-bqh#DILFzTDsM~Er3vP9*hAExO zeieo7C};u7J1`|883_}_>d?m?fBHrMMTgElXK8S_u;bb>4wJSfqO6t1`8YAnjBW5t zv@Qy6vz?ABRa_e$Nu;I*I?;m4Z{vGv3LtH%;+f9v!o!<*D6-DrT-Jm?j;eK>i+L&P zqg!05gpk?nqC~-~;;1VtEOen`#qI_hQ?hPNZ4yR!3v;&{o^CYX=R@dKg@8b=!?Ni$U<+ zOPH%APkS)BI^?9qy2Qts4A^Hd?Bb8&v_0)ehT)5 zorIcfb!IC_{G~9mrqQ(ll(k{OhxGSOa^VS_2EMCILy}-Rk6CzW9){TR`ogU-I6(XX zmV=oo8GVOjh?%BdKbL4R<0H6z+_3z!ooGqoOu~hl8D$5eW2BQef2ze;!(o?iugEM8 zxA+g~3oQaGId6N~9vw8aP|IvYA;Z>=?WaBxV3w52Q0eTZTlz-c#gI7T&iV&;!QyqG ztZdAQjFo*8s!7bYhldr>NXi@1pL*{6ZMJJ<#C6}8DN{Y^Vz>8`2wd|rgAJe7r7eN#S|rg8e|{KOQijpt;c@?DcU8_W=~aYE%Zy^jhs}5A5nx2bhVO5R9tP(p zN#J*@%N<&~J3l$F!9vkS?c>pa?G?%3_@di18%% zOY~)4m}_y+0DOWmC}~EXxA1o$@0y#OxJmFmTgrK{!&D+^e?3CprRQTP8(@}TzmFvr zNH%lleNPCIxmF9aU=?{x3C;2AkCy#Ua9r&l4~Ku42C^y`VULi2^hxxrg%Z>z2!N`d zNO~Jzn`+qWV0vsQ7dm5-h&dX;P4S?dsE5(&F-EG04X@?Fp6y0?MB0~h60H7=;hB*H z>u_tu8vY!(f90OrCO#VolRW*sr2h?Ryi6?{sur9N-p)2QUZS9VCqQZP?8Z~0*SP>6o`(Rtd{Q)RCEsEL) zHF<+e(eL3fu>?)_FGSTC_IM(yqke6Y%nOD?O$Ue>5I?8{f)wR&X45wBdv+JfeYFl%vg0 zNdtJvZR|Eo5I-Xf`Xn*F;Zb_ch^Y`(tnZ>;^Eam>qd zx!GJMIf7O_MUGu0@b&4Ci>HNh6%zx`>C{7}X2@99A9Nmq&|K@3hy-%b*6ji9DYLw? ze@pdq$7IHqbbZmGUUOumB)?sKfZwKjp)*h6fD-!c%nzO8EgWJSc%@=TS`_UmEMA@d z&Pn{jIxRT7UoAJ5CqlK<$9km+Vf!+YV=*@VIA&49e}*%{GnVm=mMzd0hJAFKWyq*!(>mGf{(#+J ztoFCqaSIy3WAvAPh7Ztb0gL|yg>6ut{*=k2VrN=>PGYaNq-AEx=qux*pqT+#lZP$t zW7d`p*kWJ7_HOtQIlb)wwGIhA^jcAoq97Qed-N^4mqX?wa}6GI7-a0S54)%tf5|N# zDe2%t83J+Y2%5c7WsNJPdTH4bAl1HCd-DD(MZ11ulHT&N;5v}uYBw>9_R zwu;NAPR*;Dbugbs5+(nW?8blXt$rvK?zRyp;9?nPYAoc@(!$jjMQdu_xnEvme&2QkG~!e{_T59CYOm zw@FdPz99=>ms#o~v95vS?dlW?DwcosFSckw*A%VgL`^A1`UoO+Uc!)AR2Fc`lsbUF z=pD8jlvib6d@b5!p2HFkD3UAkb#gkVf?4r+dW5L`4V1(FhTYCTEW^Rm#kRlJhzZeh zA_G^xItr}ac0nWbW(*S&e@Z3-DHUXG+Lq=6U*X*Os7S;dzSc(gg7!2`{oaq;Qcwo=Dq#2HVG7w%~R&6y19j zOa-pv7YNt7tNO?uhG=`Co-Tu_3z^W~Ps2*n5_C9-oX0Rhe};_s;?<^c9wO0YjZQtq z0yWF=-~5_}b+XpgnkPK%ntTv>ds{#GNz@chwT+rc2!ql;))6HTdu*>-g!tdn`HBUP zQ}aZ8_-3xa&PJ79c*=_$+ILf~w?N_(|+%-7zq-@`Kh# zm{=PE|L^ZN(4}wi_n&ad$nf(|%V6x`VT4Q9PT1c{U;XXui1tD^i%Ws`yHLyrpj(l@ z46>-yzL8~-^k;DUlb4PeuHwCFqP6M|v%q9c^D;8be}urrKr6JQn&m32T`=|%7iCI9 z@23!XR0?rs0sAh$l71>~?++TG1ZApo9KIIgtG2W|_n0+wp?(HDA(ss2$I;OeKX4Z2 z*G8nMiL*h{a9q>=SQ_iqIiYe<8rFfGE7izZj!E5V4$D$#VfKxk0HWu5jG+p0D^CAo z;zO?3f4rFu9UY`p{oZ}ALd7@9yJH_*CkrO+v=^<%ry8m}!iwJ>9Iz*kbg=vu#R4;} zSUiB=`3^RS#wyRGz&dl4=xS*qrZkuN6Rp$1@K_x!H0+L^HT@P;6DkQWZF09%un`?P zu_2IuS$JR=d^liB5cp&c>z8w~V|P=M0nAiSfAl>&jO}oq&TH!0UP**e_BoRLBDg%f z8v2j@D7kD%=)ful6$fomBJF3*Sv@4}83U9RNf#P3eWfyVG7dxmgH}z1t1ioEHg7AM zEMyWSpf=K&Q?PNO`9)GHJlP-bGA#5x7IMuVW2DscbbwPSb{@SjRhv6D%SIkViX|y( ze;}_Aa#c^DYhh?56@AInonDya_RB?fr6j}#t6l+s8r#AEv9yqcaKB?xl^UmHABB`3 zU;zQjXbHI!&i#TK7>2b<#GT?P^Ey#i7VTG7OQ5Hoc7CS(?XryHni!hN!%@8j+u9eI zuk$WS+ZIS2CqP$%U%gChZXUB*tQc}of6N)=#3m_7t!;Y3>VhmMYZZ>#sOALi^6+T_qhB4QHyT3DNFZ1oF4aRxcXX;NzE_&ne?^R& zs$uRI<;%|ow4}?G$DTMNlGRv_26UdfJK~vp$1uH!+?G%wQsk)MFkVWtPpEx6rTuC# zJXR0jAKBhj+_S z2@HQvsSGI@6P0y-qCmw$O=p*RD^D^YUS79b@Dl1+%gu~nG@axv=Yw`sSPeeVGRs;* zp%$F--t1x5-YcPQ%$#8}ZqQSklJ{&aH8=NFi-s`ZZnTY+Ke6c*F~jMrf1V`GV8kqz z-m6MMkj*yYZz@;j_g89Z$!>LHiMKyjcvs5!)JJ95@biVBMA!K?c6&F~KtWx+| zN%n(}*QsZ7aw5j~b$Brn_4!WIAZl@&jD{VwrnILo=`=+6s4l3Lk2MNhf)PL^bKwk0 zbj{pa3~1Z}QMKTMdZ~?ae_Z_oZIy)y=trSgYB%joy6bkb_6%o_&BT{t_0pJprpaA) zrNKSA-|bpY6l-x5$I9$ie5T~1ly8^xhCKUaSo6>|(xX6TT_sV3)IhGHTo z&E^zz*zm3oe~z-BRgcOdH-saP zgr>C3BXWK%;gq)}0w=4Mr)5?54QuO<=f+LhYkD+8$Ovt-tm;uHR^@GEBK#c=r#zNS zkP^wjjiAWm$&4GcUY?cbQ6OCFEBWpyDFidF$)*Br)RKu@1>tQUH0<}MaxL#}lR!jm z+?rcpsgc_pO)-Q}f8_h}dFEAe84b&=?~42)P?|II$sV_8k&jH?KZGv_{D-OmAgh55 zeOgqgRW5z#z{*S9o@X_BPBWR*)|5d@qWX6*s@+s@q~d{Hr7k=ehWTl2L5hq6>&SqX zD;i|Q{3JWPJGP3wE#3@e`Os=O7m1c8;|)80AIIjvc#xBTe>xRIy>DSr{<=D__b>a& zTwqy+##{3AOPh+S$~E&*_j4Ph#Yhr`H3j5G9ODSgIB5S{2No|&3ThE^E}pj2j3V8z zyYVL#H7M!*r)2P@-)+>4K1D;hG@V)vrcB~BJMl`l?P_G1l$a3B-187#G>L7$)8SU- z6X2LQcvgr7f4&S}m95|r@nVcu8dhCTrc;i8RaDiJoGl@HyN{oy3^ z9&-hTI)Dgd@+9p-joBLBtXceKS}nLOjh8gl6ni@7#mr%;q78i(nuJs0sEZikSeIGC zxYGM{1?L;9NFR)c{oz-wWl#^KB|$Vo<7#M`O_ms95>RFq<+J_g-r9a4`=_uh`6=%2 zV#pwie<=dcbAqyr+~1_^vq*iJ1pzru1GjJI$hw9n=;Yp3n(>4`yz&@YLa&)87RtgD zL>6cct+b)3dyB{8k0(lfxcs9!3~k~1;3W701M}!jM~LwimWq2Wv`&nYu<(b+!RHKP z#$2H_^MLY2b;56mOo^JM1CCV=)&{d(sc}hMf47C0`Gkzs8H?y<>a*V z!51*dhu;xpXC{gLBuL7U{wq9>qlfMKz+tlb(c6`}v%9PVml6Rb-?hu}a;s1V-o^h>%eTgVVZT4~nOe@Q-9?v-JbS zN?_)V3-Q#Es?jZN$t@RtAy@mc;(BYPYg5okhNTQ@lEYjAYp6_8)y-MS zOk*wCIEkTD2pr#{Lp(n;c~Fq9|KaPS=~2<@H;+DQW`W@kU&4^dDz}V11Z?ZG$!`pd$Al>p>5BdHl!xPKwia=s6m&Rf>fPJb z)lyXt_6JJ^sL*FncT;yGE!rRSHgSDJ#KmTr;^|SJgcGlWO+S4DjZdrm_n!id6iesa zK`PUD`U0@u9264pgc=+K_qSYye=!-fUr z*2JLHhlYzu5bW`OfvG%e<6K~J)IUm5P2=(Bdb%wxU=(9lshkWMyCHB#z}MKJ?;2=L zX7?9a9ZXY$0pZP3akG@~&9X3G_vN+^TA4#=rlZq>i-{t2;DV;`#V%=Pe?_WxJvoXC zg1@UUD5ThD);5oLy;;OV2djx@_?_Uki%FwvGz&vOTC(2h!Yx$A?<%@k5EEV!NW3*% zz_M2vWCO;ZNo@%t2#3WH)cU|)e72wa;*S&|3swfyUb|0hXT8re*)X`+$qFY{s$uF< zt#1(QDO*u0ePcPoZO|i_a)U$=KrcC-VN)xY=d*VD*nxmfloGW%Zgq)|8P2-$CFkCmXvxci&6HasJ#mq$x4O6N9NQIO!{tXQ;Hy3<| z=^ky=uRk?oqm&bf(+h<>CGx=e9dylX3(}G~D9t(2YJyK&gaBO=DC`wB+^P^pL)W$yWx+Qt< zMub1$K}i7M?Ks3K&6SF8)vDbqrZ!3 z$;lX0X;>N#Jd*GiVoZV0XJc@Kk2j`7`nbHYpBbYE^?K0N!Foddm!@v#Me%Ir=Z|Pd z(g>>B;UQ)*lf-5IrGuBL9itY5?QIVvIk;~8va2ODd^b1>YyMnv%MbPVpj|;nF~1uh zY5O1by)?lWf3Q`3-V5pki;B&Y#l^T(-t<>6RD;nS+=NP#7cI7`cDRT|B)z8JC4-)& zYd2ZOk5SAXqY#(XuF--f5e*llb?mSsXU7l5=JX2JhOzM$*U)C+pRGW>eT=FUwDg08 z8J87Ly`#pgs1mjM*Zn|rsAA`#@yHVKTEKl8wNln*fAka>GnT}k1YyN42RVT|mnC3; zk6`UpwDsW;K^jpA+mX`Tpzn8P{58?{bw7rk7k2EQj9_YwrSD0PH&w*+TQVBfvCKoLCpfewQ6cPR@|6X* z<}VfGe?W%L5?j88&hQekz>=&~9QTYCGX?`yDAdq&_H`BT`A*&4f$>eU&TJ%1(bj>4 zB})V?K`d;XORsG>_`ZD(Xw^6|mGIGU#b(gV0MjHjtsM-zlcSfoX=>^Y5C;4hD^q=j z>Tl15r8=;r?Ll;0o(;qsiv&k1T%0M`Y^u*Ue?-6-lLq7+-^;Am3^eJj?K?Dq_@GwV zh9b}UD=lR19F_IqzMQYCH7s#8TCn%w+piA3p|oR|L-f6mE@koXC4ppLam_Us-f}Qy zt4#YSrW1v>Wwr%j7~nag{Xnn(I(oo;%Qn~Yfk@+boXM*^E$o05egw3929WUN#NGN+=%cGQ|0&lZB2$iSrTHE}V`eZ|T_KGyv@DiE4`Dx$6A?3`t;Q#r%;1nApvPfQ z1Fy|rH~^lM_glmK{^(|H-x>J^D(t7WfAEF9 zmAdbvIgkdHq4sC)Wnn?C%|o_%c(YXz+0nP>^pkEC0=U0m$kuMirM1{bF+ZHP8iWZd z^*tXV=cv!6@c9k9?nlg8t&3{)0`LvFyR65Kctzq$7i52~z@6CWhofaXAdPUkJ}*W( zorl)RuQSvY#`l7V6#Ouwlf1a0ysC5f$tOqG&wgilYu}emoGE}1%GST1u1Dkq>&#;#}JoBx;v#M zXMlkzW=KI4k&>1M>5}e{5|GZppj(s%X$;`y>U;0IzO}yf{BzDe`>eCiehw#_IuhY& z>W6}e2#SD&WdIX(V?7Z`Q7J$e^cM*yrwSV4;0Z+{R2@7aGJrV*446PrfQTp{Dl9BQ z!U?D#QGb4DsEey7z~jXG8wAW?4qzx8iU!P(Fr+us$rZTo?d`4Tjqw7Zz2rgHO(qZs z;OPnhoS`rXpkiQXsim(0@M!2i05l*72-*P#7V&FglACr0L)4RJ!l z|K3gj@ccJ|Is6+r{u}*UMf?7VKqMj}02u1z2{=Mrpa>G7zkSm}I3odxKQPz}^-t+q z5awDRz;o>(F93!(U$ebnFntF&1mICY!cktH5Hz5N1VhjWz!(X4K>WjUfJ0$^|1a;q z41X<8hie~{5H8ow3IBnh7U6=U?<7V5k@TPe0_^kLw== zBM~sa|Bk#~AAd_(8R_dUC?Y8a2>vA^1&I75CJ9K3Nk9HS za-F=;Xb8gdx8c{j{FDDaBnZS8;zTktiFA^E?v~ORS`w(1k1ZwO$Bx-Q;GY!1of_@f zx2A&jxPtB0b{P*%8FPHdSjK}K<(7Arv<@5C9bzG5Ux!Dc*uo!9GM*RSD|HF1Tz~js zl>5CV+;$J&i~;VXkG~&r;F&f%^URQML@Xm~t5VyeSdL0VB+CAEOBcbd#klDY#|RDH zhuqZZR+nUuRsM=wSl5ueJx7J}m6;o1Il;?h`mU|RIRW){vbdv1DHMzGHFZApOyS`k8JynaV`Z(U(!F_X~?c4dy zQhQg6?dITqQy}ePyvJ4K@_9VYP!L-fBy^-pAY`Ebd)b44FG2*y(ePFmP^Fc@#|rv_ z@;B>+=Vvsbq2&yccES@T)PI=hWI@a9sY7hFa$%J6hed;I$Ej^<-SX-_d|$L?$az&8 zv%CF<4+kG3+4zm8c1j}}3I(3N)m0aQdXas1_l0*vaXvxP?m(;$0UqZ4KwTp@O_@Hn zkms>|8I3LkyIW)1)>K&TrzpnLclskAqt&@DTZ~?uQfQ_m3?`9=dr0l!h4tH z49c1#lSUsBdBH8^?~W7`;(HkFQ>{EO9tkX(-7vj1iRU0V$YHqmfmst zXZfzkbn4z=+zEDwA(c}~T=`I;aMqV$5nMu!Gv0#TX`JAoDZ--&*4;%GZP>WW9H9m@ zr#)8t4OgkRR%uUe>VG%dZ_R|~7i2okj|B9|J%6)K@l%48VSU%nVwa%& zkJmZ^!%nnYADJg4$#Y6Yzn!k5BV##sM(^!K<X-BoZCHLB{F}H z1IqVaCNi6lQ$z8%=Ecw93fvn*uM(GBg(|`C_sgRNdVgdUSGc;p94Xla5ly~?loA#X zn+!g?59RKZy+P}z$UwqzmcI7_GJ}_oZg4}_z0t?AGLhT|`u>GqKulxY=X-->%Y5r!h5CKYi~;*p*jy%TVlgpSL$b*?(ll=QdjtRaGi4S@>?1bT_`g?EHLp z_>-ipv|4LJYC);KkmUB4yS-fk6Jsej$6Q=aTWrW^=OsGr+AI#CI7J`zH=pRrY((lQ zmtWFHO>FK(O6SZ`Hr!AE&r7Jvzu-L$W!O#gksTm?!3M#@tu-YF zU4Nt~w!y8I#_p}wvEA1%dBI~|C`N!Pd+#iJTNMKt?CJ$Eus_?PR#JejYmnAeoJ?3j~vmR z3$jX0k>HH`OpU{SuB%z?TLKSGd!H$J8-GLfUd%7wf|WhdXBodF=qcv&)(mm>0#`qYhd%v(n(u(iu@VOB-UbJ>h;!PQi3BE;ISG?cGVBaDy}sACiit^Xr_R72eIT z1UZJ3Wg>x*E4FeaCHdh%J?Q(HPKthskX7}wMrCGwkCz z)jc;Ij0ffPX<^QV0R3eZT?E?Za%`r)o!v^rL`_2zwy~;zhii3qht#V4tu4(I!2axj zfrwu3=TZh-Zt(-u*Fs7nLhq0{8hs;DYC&BB+Fw*ep7X8oU`dE>uV;(W*hX9QP%sIk*T6UML`cC01z9 zuJaV&uU96ir%JQC3h}1n9rlaVH@&t<(?~t7vWT(Uju2O##%dAd-c{E+NZG$=%Hff~ zJRO~+q9b;RZ45+qhpsY$qrE_B#lvH+_Hdu^`CX+M0-FT$h!;3;(gdt-6o2qi0!Dg% z&ksM6wNHHanAfgg_7QVxQmF!rMv1&8IM$Ie9J$oq-APOA|1gNV($n8=g|}a)#Ao*I|ZjX$<~@9oD==#ovC-FV$d(p4OC z+_!q!p+JRzI5jsXtdFxqVt)^aYtZb8wU+fy%w(BV<`$~;VkTPiWCxTn)U(;B$WMFb z06KDR@W*5Zd8)Mt1*@T8^AD)QU+t5Ts-p(hyW}6%4%AwNLWQP;2ZPrp#AfO>D{~ME z9;siO6h#xdx(?CgonNuI3+)R6-XjQ!C(lr2oBcuBYV1F&q{}ZBQh%8B@v1$u(rrVz zePu6mNnPHTp38=hi83$WTj;FQknfwcZOty-Rl8$4$3^2YoXqh^j~{K4F>y-R>aq;Q z5Wbe!qovJfUaq3WeZ+T_7dydP9V9wy!%#_hk-d^CJ9k%emEDGaNqfo>1h+%qqcf7+ zAgR(Z_er36KVF@f^?&9FwLdBOi2sBcIQ{(Ny+HM_#kQ zX_l?8ZVvbZhCflM7&@Hk!sM z%L7&BMXZOg2DuG>H0Q;&9l{_ zcj$=0;ZvZVqs>i_*S!Ri&G#YktX=&Dv#nt)G+AS2Ykz4MQlC6T)oYc#5xlcxyg$f4 z4jM$J@wSmyM5x_2KcXD}GP!~KrY7()H)f3;=E~Q7H53m2we;odn-gK>H!ErDCO{Bq zROpl{e*0KzyT~l`r4rYMuA&HG#e;Muh=+U4$5QXuFnl)SAurrLO#luR@A?|K<~aJs z$7{4Yo_~RWypUmg^6*d{am)H%8WWIg2Tzw4!Couac2vh35u;_7f&=hw_7z%v(L-S}bEFc#&NBPI{;bXTg9ju#E54wb4vvivKxN~$ltG}ZgNu~7qjj>eGgjk=|Jul)M@Zv|@B!T>ul{*N z&R=vK(2t^wp_7)2bS(Q4Z8D{=#)KPuEPrecJMJcoKNLR)$NM!p)y*!G{Lnt@`ziJ_ z%YJu_VD_tR=yQwxsAM)&fRLu@sVM{huZ8;Y>djklW8kGx2=N6#JmliP6Y$w812Z>nk>%A{InC z9x3&`%=SD=SEhcA#f^(XbTzdoVt>obdFBCG;+x}(A%DSu2xdRCvW^TAl^$w{!xmK# zYuy!57N5IkisIwEPpGN!i#p0S;gps@kodr%KbLMu!D1*QVa*pBtAc*11A4WCKn2F5 zubu9x{GQWW{Tu$R~DD+4?&irAv-a^r)MEe1Gev;+WTV zHd&w<&k0J!l$&yh>|CUz zhPHdS8ZE7+larlr7%k&yqWUcewziAq4b}$Qt=gi~Hg3uDUmZFbYBj{t-91v$>o1mX z2qhJ&lXy&Uk%c<3jY-njm47WI3inaiMa9Tv|6I$2$-4#ATBW+Q#GN>OPv_@LT(uvI zY;&!7Oasp?dSw}Vv8lH4xU}rOm$W6mohVi-_Djp^_|5LjR6dh2YL40-*WTHb(u<6x zFQ#1lDDG!^i$O6HIVElc-zWv*M~#jodBj{Vg=$x=<$tYq5;~uzP=5@FYv-k2jFw-? z($2MCsV!#fbX-zs@SGW!l5Rb|Cvy;F19aaOx-6E8Xxz8r5B)*flis{k?)r*JUh^xF zBUee<`7@t>#e}Y0Qswr9^7|&~0}d_E9^B%Lj>%w~JY%$dai?CDY8>PhfKBv4dge6j zYZaWLh)wbQm^%u+=zkV{dN<7$1iKN=Z^@D+9%$mS6CN^T#e4`9S?V2>2_M=XdM7yc zIp)bb(pf`dv06yezOWj!d3{4AuG&{k%PaFl#AkVrd$ucgVcwV@8NU}23U>%mBI$!x zoNTzBG3CV!TCuC){JM`9F`OYcnfFoPScfv3R^8)*YB4Cw-haZfGWZ7au%s(z#qzHy z$uXn~{Km6eejTda6QR@{6)DU*OWlgiajS30E*6FHTWF3%g?_2*65Sq#?rO{-sl|lZ z<$3yujJ~Af6LCCJXjW{If4eu5*s9PqdD`^3=X`uheDmSPqbx6|mfb1yikj6L-;<+I zZRv`Bi4Cv;z<)`QwTxt6GH-%4y$=TYiShnSD6x}CnVAOXH~Yv|J__g@y;O_pr*dtJ zj^`*Y6|5rEg$;svi9XVQ&g$t89w{G4GnB#xaTiL~kbaSQvc*qC&5yLB6)evY#4FS> z|6!+ML`xx^=!eycoOHn?nCG&om?QYpV?>d@)m+#r6AWWP`%;j}e*owviD0*cM*{?F zE;2ARFf}nTGdDFhEig1EFfb=63NKA>WJF~c_muOYGLZ;>xWDo zRF?T@U)e}(Rorlzwm|fps~1SQ>hPj6~k?t`LnqC%*Xj(AOf@=T^up>qt^}R~8#-)bVOPi^o)kJ}ItQjO{6t5X*g%=gcgjgOac*#g|k?2qn z&0CZSVIZw662@h}Txpdd2GZs=#VpnGG+t7BNL%hrTJR#kZ3>%Ynx8{pRk`R%tl%05 zrxk0@B(j0PVv>&d+D0>fFt`3PM8xOTn~1j`+LknvH+gi~^Uy>hy((%wt%}j`NMgH* ziEScK&7Yj+_vo3eJJ1RrAy1>>CNNE#nB;FC-u(B!ucvtE^xvD74w#@hjc(Rzs0L zlk1O^Hq)|!qAhSmtl=@?Abmbsy1i9e?8D`s)n8kID4N?x=lqr<#p302ssCG-;wBO+ z2ds{hhwOi7Wd%e<;K*&UN#Pa}0*dp%pF>v&9F#;CL265Q<@Mt zdMMp+T#3420*PJRCpekHMk!L!OK>|D6HVV9w#_X-tRbG0a-S#UYpV9 zz~v;+SavsdvMA9uAjgrlA-leA^@C@bWQ}bQPtnSna@IK4qVhiOVni6Iz9uXEk`o$#dwK~jBCfoSk|1Az_3IzQ&w@IKcf@!I=!IaafarV zbkcL+DHE(Ro9p*iX;lNL%RFoKmscX4e+|!+yxTK>tykM)-f|8i?Hw;^ia|OLvA0ov z!CLr!s};uzX&dBAT%j4yy5UdI0&+B))01cgiEXS3y?6f;8B6aR#xle0nJXdFXab;)m=5}puam^0FI6PcY& zOw?k3+-Q$%j;+*bq}U-5WE?SNH9f<(=Rr8+N=oS3nBcd(7fT5mjztdVoRU+jMwY9= z)3a5hP)M-zz-TgZCf7TZpX1==5nk;Tzs(U@A!FpDSs?+0R|wh;>0v_H_Z&4Wc{}Iq z5;gRKf{_F#>7Es}fAx!>$1PfhywyPxso0`_WZsVBVhl(n10Qu9^DIn+PBX+m3z?-R zjmhI6MJ0d%iyW!}(7~{=N+I2#gtnppHU&OOBl9={M_z$5=9{ z&XFmglJSmb`MhGv@T#PsFLq>p-$-mgLEK5C(C8wabVYu)%8&j|D(Vb-w3I8HR0V}g z7T8iS5e8vUC3-{^h5L1?;NwOXHR3xI3##b6R*oEDdZ%#!xddtfsEnZOkJvZ0G{bDs&&0!@8$*0QqXR%fB?kG0#f>g z_AuJgsb12EE-o zMs5=MN+>4e3lW!KP2?~ni=ty|!WA<0B90q|jt^Y~IHXO&R4LrjmOH7R%E_&E)u5=Ku4OWKSMxBt+pgzI7vRe8a<=g!b%wmmDmsZxa zX0f-D+Cy5QBdu^LTh0Q1{CtFxYzjssE!!BMWt=)8-$dQYcc`+)xR`Sq4sSqO!@CsD zS)l`(zT{hA4i2&oEv~6eYlzd{HVo32@e(kZ&1$q|k5yOB77EpNp0S zC@Ex09B`$zQ3~UKViv`;^kw!TteXIUEbY%OxfMWp2pxLXqFiv{6esi@9d83N2~ZEgq!h%1gH(kiLwUV9Bfywg&Zf z(boy5O0g!xfpLelPevkY)ckI-Ue?SN=5YsrYPpzYfux6j7N6yseA9??0LBwRStG#U zE+ygy773}W38=342E)wz33nBmgIWY9tV5envy>w);6qa1pr+^QSNbw86w6trYgNb` zq^DyjW@RzH}8c&W-W)(d!6P|cNMcYRGYBoBZ96UWgJ{|Mq{%m~qf$E8k`cr@d~6Z?DbKYjQ>HnH<+$R>;?n~;xDQI;)Df-3FO zCVVu1g;gk?EUn^+vU9r#deAPO)?4*<{k(orzpQ_%U)4MHFZFKyYrR+R*YD~N^{0AN zf2|Lu1V?>XAC6CFqk3GAFRmu1({oji>G7yOu8&8&;E(#ep4QW|@$sm>U_@t=(dpsj z=%~IRvzZ>&SM{u(o$yP4)i;y+ztn4CY1hGj^5<9ETid?@OMferN@XOqRgZ*Zbc0Cl z2~zc>{tv?d5N0ju{5sO@Y<+yQ`xB&#cLWa>kMe}aGL(3Sc<<)M&^3qB7>*(T9}5K9 zX0X)$-}Oxko45`(Z=QbqefK$Gvp3{KwwXIolOBT2BDDH6h|DvfuzND8_b11MOA*X} zTA`;t7+p@!>x0SV!S&hEDFvp3DdAQhPG_S7=Fg7x=k@5c9^V|Cj?U_%$zS98d~!an zr}T5Nj8{dlsxMBj$*WE-$K!hT_q4ttr@EY$(57Y`Xy0$Ye7e8O(E0(Znf?I+>h}r?czR+2rE%TML}EBJKXqyPvkV0nU(tkj*EDuki7oU8Ki`EZE`NRc%gdji|M2|%i=9F3M|OdLKS-jINtG_3S`zZ(Qo@*4ae?4U z`Q|Z=vVp6~jo5f89L4OlqG~k8_EpdQf4T5;d{yq=cxdWFjDGKO$YqZgff5=$^lO6GbDo-^`G@6^1f@F z`rqpRwlP{Oj{W-b`Mdp>f|0dD0ayj6`nIfM#>hLqgmnKTMtg(-%YM#Mwk2CDe+a$b z+JE`xHA%L&Gpv0TSu%~k(sOhK6y@Sjwb-m8l4<%S!Ly<$__=3FsCbFJXM^>pv`t7jzVyH~^Ro$OrU4gcXsxUZN+nsKMfrS4}3e+}0b$1dag(n%Mg zec^`72ruznY~uR-kc{VGdO0R{xy?LoiTBUX52lBc^J9{Uio`K_Er0Lkv+{SiYo%2V z8I=xl@>Hhb$WfWNG+{cde{YQl6vne~S)Ta?1>Bx@y(m5;0w4^*4-g#?CnRto2m!9j zyYB_hD(ZIpr1FeHXc06?@vXR7C0Br2rH~aQN|D2M84>#jE&^7iZOkF^%WBvgp9A)n zzKN4@U4Nb7kq0Ru+!|et@s+3ErDw|{`2WMecd1@XF0W>6iWRy1f16S6Q|Yl$f1Di7 zPOkX>=(yFr?&96OTpkL&a9+!b|rr=Hxl z z7V;g|Ju_=cxEr&Cf4jMdd$sH24(oImYnzsw_4=IqrBRzX{|`7F?mDy#O)vT9uXD}= zAO9CPYj3Duhjcg8(?rxQhj&XeFpsdIe)-VdP(KRzVnf;%(Jwv1hWaUPXG5wN8cgdf z&`U>&%_D56pJ{eC)QcFQM6{r0h12q z9^5&i6{EEMKe$DCq;#=fO zg;-ho2t*K{!BVX4B-pT)kn?o&%l~=ag+nl6 zyE!o>5@J%Uh-EP=mc)!07ZbuGG6>(c-LfjCg;!(}p-($Vifoa8MTA4P^NAdy>&wPG zkxL{FZCn?Akx!&bY*!!x#MXz6MWT?{xw0`Riix9`jU^&PoV?jMFUmwIarSPz4KXUp zMTMvoW1>n_iyBcY>O{S05Mj|MnnbgRh!)W*qQv>8z1BwDIack&&y!UL89cCxk;#3l zPV)H1s*AiBu<9m2Z)w#-zU*4{lHWnAKJqvHpZn=}(%%-RvzLBjfX?Nk)gWEGS`E>S sUt0~+O`Teeh)uCY_dW``&jI`c!)`DMmnO;s9t$`)G&l++B}Gq03Yq}>5C8xG delta 99186 zcmV)BK*PV#oDa{G50E1RF)$#Lv12HIEso7f1TheV@ADLWk_1dlcm9vcI-uam=tVq4 zjS9}rE@5O}-^A>ty9=tns+%-j&Ex^SB(w(7Cy+*|B7w6cb%gW*FD!i*E;MSkmeV-y z9-hWAb01iK-wu_(ruzm9fGDH2)L|k@3I>E$jemyCJP@mS{b>O5Y*&^gm%4RP<=Dko z&paT@^>-ce`m1K%yr(|$(vv_Ni7iZ!X*JzIKbGTG_TBWxMVqCLe+ri)j1=Lyrvp?n zs))U(@lvz}xBuAgOrAvVw}p*-**ER>m%AUo zd#|(U)_Akiv466K;azu+0d|>0wi_KCcq>gl`i>_xe}CFqIJ&L;X{+<7@7^MZO=6VE z;n+kOCznaoc4y-_`r(L#m-pM;$dz_!l0?-ui8>y7{D~vGdqPUT)h_zXQ-^Uw9Nlks zun>A&Cc+R-ywc+XaByzJr>ePh@&z06sOehL+2!$Is7ryBkLmY58H#pm7Y%L{lfwXs5I@qJs&a@UH0}k5}WzQ2&k5!2~g=sjItY!NkJA7RW zXMUR*o?@aSa%sbkUK7uNIEKls^$V6j$^^IMgMal@N`P2j9YfcLGp~7|dr<*Ll!rYG zaFVIQxVgH6>u6=SZ-uX~yN0JUPcZa|AE7_Mmqg8BxIrZ|W$iohC_8+1CRM3KgV&xWNAJnD-;fd=$}ks%*Lt0#RCEQ*+gX~ zW2)-Inv371u>+5c_LQh15l{bAp*f^+3aZ?(Gb7c-nZA)<@_sOwIMbLP=m5ba8Vo(v zIwBOOn}kg48)uFvE7->3f{Ci{LVW;9W`7y@EaA>dgQKfJCU!9B+eAD%*CZYd;SSjo z2v$!)uuj3t1osgd}rl2q)@ddpAIxrF>K{z@Gjvq;(Tt17V z9B^Lr7ba10`py0VmW$#QKEr*{X8`JG3lm-+MyD~4oncJ~E(O=8SA~#}5P#w?3&BCu zFykvmSCCH9g=y+#U}v_-y{N26Ek*#c3TvXn&*JKT7ic=A$t0rySD(&qV^Zv{y=MvLT-w z6Q)Yiu;-ch4KF;QTd2t0Jb%g-$>|;{wkkORimoJjyA~G`SE!V*hK$14-!443MR>4_ z@SqF3nb7@yjUOZ%HnCsFQ22psoH_xO$8O3FUKp=lEQ7dZHsI^5Q2uM}Vmqr+jj`oQ z_myzWqova-&$9UiZJfZLK@M)7j_F**8Su}c?iQi_p*e1;ggJ#hmw)ZwQon=l@^(nJ z59lVPq{G~s3xIH`9mCV~ICR4tVzr1@wII6}+jo%QGE$= zfFCweQN}yTBMChsh&da2R7xx0x{{_1`vPsVg#?vwySPg9HsL&o|^e9tkN7%TiP|l=qnYo^Ob;6iR zLa8SC)4&qTLEh3;$ErqD+xqj`lcW>2sB6EX6Gj)!+2F4sg4L3*p^Jq^?zOfu5iu{11aRV4yK8rF@{koHZL^9_!6W^Fd#gMAv%X&ZGZJc7vfo0 zYwV%j3@DDwCylaskL+tZVP626G+(32JC6B@V}o~5I!79(uKmZcF^2txWed^`R_|sl zNVmuvh!=Mu9lwdr{YF5SxycuCdls0+uGuUwZAmcXKz~5JsSbgtbnE-JDns{*m^6A5 zNC)K_E?&CCiX4l{SV{9q>?TU>|yGPEdTFNLAV z64yL>JwOk3)x%WB`&pKCjp}2I==;^)Lw8}HG^TPx<4}Xc?tN9y1a)ncOA8JpC-HOi z8gLys;D0zEOFJ)J5CK-Fh4cZzE#;X*y9+?XULLQG%{nLt+%ii7>CU{;&pL@;=mg|Y zH%Sinr_XKEmCbn!?*<+2{2^sn%?0Be3c)e^{Od}(1q7IsO_~nBTdfG8EGwq1iML#e z+|HvXUk+3N!vHAGLIq$Ap*k$Oo)6atf;?Bz1AjGuaw^kvXY)GzzDM?D37Jsa90T=0 z2txEjoR2YzsIxBtsV!82`jtRRI_k@E^>T2OVCi0gC8}1rhUL5fWv?@R1^*-u&_I&Hn(O-Z}jWWo~41baG{3 zZ3<;>WN%_>3NkhzFd%PYY6?6&3NK7$Zj(BWieja{WQ z>(38u(`}pk^?yc~q+D;LRmm4s(czU${@AQx`0YB=NzqnCy)B8NvH?Y@m=xJS@}D$E zrYpm8le#IEX`xmd&I~L~?4>F96Xk58VJXPwDP8*sYL&qRqj7=+N^&KbFf`}mGcu-G zw%Vjj<$gOpTW>O@ldHRuMB9RB7DdZO(cE~^bq#EWO@Fpk(U&_Kd{^~%v^V{lCwG3I zZXwJ5Y?naYWawy1Z_0j5fxyu-aM_HP(T5UO0fJ< ztS@idqOY2Iy-`|EnsnlV5NDOi71+{=GG$DeT56hA)qRvN&9nxwriq{h!v$!e>WHu5 zzsF5g+J7WR;H&M6iiE(Q2YRqOmVRnO{|D03uH0AkEe(}z+q47an%+aoq!5`i0}KWV zsg|21rATgC*dS7qNQ&*Y+?Ug1?ij!)Z}HV~-#Gnms~&gwfu?|(X$~1j(^dHThu1Wa zE%qcYd9Bh}@@3ao2Qc1A^9w_dsU55}Gv>K!uYclt&p{G-qIZsZhn_$+0aDWsMHedm_a^`M&kKEW6I(D?W5)gaXXf)-?yepEpI-(w2*4 z@9g;<-Lzy6pU_>&ZrLaF2DpzK`pbXaZhs>b<BDV**OtJJ5P9;$u^=M`@IbzB%xMQN0)Gp~ zfwsH>R7FMM9YUX*KfFhOV5f*N&NO4_B9vejVxdQuZzJfEGYf_*S)O_A*CY%8UIv&A z&SAr(V4hyUQUW9f*h#ZxdI5>a+|5#EIKYEu+}lHt~l)&kBT95{j5mxG-;AH<99NX}EX-L|dn`S6}gxy4K(13x~Lv9(Oj^4!eClz(~Zd_Lwu z795B#6625@%;0jEafVxn%sjUf8DOqi!{+WDp1?0eF4*zmWx$;b;OE8Kio^v1*rTpG z-0v%w3SsbuCtj*Ch?+dvwU{#F6*B2z67H&cS8Yq5J&Vko#_?;?^eh7KF=heQ0}L0f z4;bx`zHJeSDH4@G_R-LrhJQi#~$y0>D1!~q(`MN3k-oB!jI=ZduVSk-jNcX6mZ+1Yk z?tm#wTcx(ip{T2yX1_aIisyzI8dvdk{uK`yU@3Fg6adwlFCxLh)gf&UJSS7=Ig&g_Q$D6I2U5tf zAW+&o^owt!8v_&g$bVJobkywMx>^YxW1((LU#lVCa+c?>w}r2Y-nA}0@y@m*C-lz> zn!B64!tb0bPh4*1y&@Krxyc-_8x9yIeOUfaRDQ*z;uvg9W<%ivikMA|0R(gU7%{~l zFBt(dMh2qXoC?Qc&W;H~XsebPJA(O(7&Xf>$)CrR55!R!VShz!MZjLn3}A0l9V{z` zxv-rA12WZ~L#KogHNu+Y5aPvB#BenMiP$)$a>WlBw@S$#4&}zzq7P__5jeKe)s3FU zTdaTvG=@lmj$ICL5iYJ3(|pv|U}_6BWiHpbh$v!?D2fM&A}RkxkqWv!6!-Vuv2uz% z5uD)Cur!wooPSuPohh3{ha6T!Wq?b40Tm&GGUHZI!ve6csBcSOT|4#592`l6U_y|9 z8}4MZzBoHcPgACpS!DDf6M++AnUag-4>65HM3m{6m3S@@kl>v(otr=`?Gcbgjd^&S zS&&aD{wTAU*XE(+sxXi!U%siK0(8&Yip;t9QIN)6uz$rD{QR~+%ul{|Qan7iuL7$# z{)~-91I@&cH-bxZ!!oVmOvXH-M?qS|{HzaE>N6YBSn zckfFtO_qkfBz!H30OOlMcX4nukXvr@DG!SW0BTdY0ARv^yC8=J(G##%J{@cMDb_wh z@AESuAb%CB8T03a)KLG-h5Y&qHJ<Qb?-}Q%~SS9F82?+7|EWWydDVDk}o$zH8E_PpR z{iTZ)ux8;f_HiI@&3a;Ghe6X7;K1`;dFCV|1L&VRcV`pvUjR1q5EQ4h^ITS!$^8GcyJ()+ z>KIE>*x~ZW;s9~oZ+vw_qdxV?lCH;|NAK^(`f_Xqz+ka&Tv80L6~3*bIB3U&$%!ks zi_zf2leMtl?emQ=n~EN10h)3fFOz@yN`EmwsTA$S*0Nf*mc#ROVP$X@cZP2xgLAk= z4>{tlyohQKs1OGO`|6vsO5P1m89io2oCz-9!!)DWuwqt? z-X7ZoI!F4jd%)wIEcpE{E|pdJl;3Z73MF{dZiEB_3<7C-0s0^vQ#ShzLEld_q9;O; zybMJ$RgfCz<5zQjlY>#bQo=KL%Ej>+&Fr2AHP=3#9`}9A#HJ`>qlQ+ee^$bMgj=gli3z2lL1yKf8ASK zkK4u-e&1iAzHw1&I``ou$V1a6NQ@Rin?(@7aSN`NYY~=2Rif>=e*(Wy&QrrEBDrjZUV90l7lv3vyFu7u$%q!F9g2pb zq#X_gk6g0FK$53c1&@;3cFJR&S{2H`^xfJO74Q!WqLI>=f%$kVS{-kfLgZPqF7d%; z$G5jU&&m(WcgQt?r)bMS??aI-J38-omxNVf0|gEQmmd- z>tG;ZWR_7R+?w9gm;?;Cx_7%OTi_fEC#0onYhQT?Qe?0rj%PJZjc1}zV<8#8o4%Vq5K}sx^mI%eq?GqGh@@Sub zPmdLBnuAC5IE>1o}y9oOu?Pj`YjaFoqbO zF9v!|>z|X{*hv3BO`Im2`BUs{rvCNmPGfWPgAS~%O0SRQ9Q?Ewe@ojgBZ{en?Zz8X zgsFJ6D;edy15YLrL%8Y2`CUj7Vvr<^Q-LIkDlc@OnoJVLF}ie8S6p{0b@^qx)TK{S z*Jy(@SBrt*b)4;D;FC}EHMgiY$wh%P>CQ`jKaqIhu@(7kR(0i_6$zVC#K2lUr%g?T z1d$2}aq_2-Li5Ore{o%MpbQhITn+(ALrS6$69ansOAX1KXRBfZpE=9^gzqe?4}egL zraY!5rVvgkQ2Wq4j4-mR)) zv-ueRCx=zs?=}AKRk?41z+-AxJO`uf4|y}(55qy+``P_ie@cw)fFQXAMe*$0+gxOb zdvI!iMBDwQd=XHSLFW`PY61)m8xR)Io!5s)c-Ce$g2VR?As+lU9*%+Np>CYoj!9R7 zX@u_b_m8(rm1jRB{ZfH1h_%KQWtd&e<9~>0*D|sjpi0;B$5l$tikRVum zDrgR%_*DUxwDGWYTkMlQZUIm9Dr7X7fgF~A#pO2MD1%614J3O+z(jy|ffS?W%tk>U z5PATY*sxKj{!}fXh-Un>6o?C>oJiH#N|1mYABSeqf7fbZP@LGm#)B1VHpjS zyrGaO4)r@Ino=nn$`2(zja4W1v}9KL$igw%kh2sd3oeLZVYs&m z9{~U4U9kI#P6R|mF>uaCh{3{czPY>k*A1p-Sl?q&%+eFpz+ZAu<;i*hTg% ze_Ie^TR=~ev4)4|3ZNEBIm%9qB~B$8K{uvtZF_T}s`can$cFiH)_QKWLN8i-M|%WV znF_6DnCGvU`Z~C`Dmte{=MH{f-a2AWuPXF)lQoFQQEF9h_wSlABu_aR_r($9h{I z_NaOHju?eomNl*>c@wtkfAioRY0je;Dw-)kj%oB0zyViuJ$=+U>Qd;gjEyst#3C}r+JSgx*{*JaX*KH!O;QW6e*@@&YnohleJWqd0_k3a}6A%s%ij=^Ps3As{NL(_gDu(kEdU?H$4_l_H`@ zA{T;S-KYPFREL)buKLL}KWENxe~yg7*rHWK%4flbt&VS>&I3&IJScO?NZ2QYGbbj; z4Y(Ev&M-N{h>>SaPEZXSonvv5xf1jL*WxgM>X{khd_mS`2s88Yb#@GTs(HnMUvP+| z(w8O}cb)Wic-83cA59>)q|C&!&#UQ#1%4+-jQ_wNn8I<7 z_*y^uPpoVX1txjFicR=Ah~X+z=cgf9=qpohfa`3h{cW*xglN##{ktY?!*e9<=8m=h ztm5?|d28I2=p~w~#aO5YkFf&yJQUl~=jj2B20z@Rnm(q+9R+|Eee^_a=BiPbM|NT0!%J2wEO8O!rQnL6kzeygZo_CNDdH)4K zHp)6)5?9wN6jv3YUU*-@QMADK9O{M2K@6!#K__lesOrI-t5=gT0zwx?&p1lBTOJLr zF&Q%;cd4G2d7Yvh0g7mL1=j#o>cxgy*=k5{`(_$(q~^*q>vPRjtoQ@nu3gzkR%NAdz5bC2-% z@cGI1MzojG#Im`p7YC?5Z+bp4{g^=)RF2JAPMhKOsn(6L zTja{dlwKdzTXOrDf9`z}@P85X8mFIUD)4MbI@6w@0Fig_kIRYfECa!I3Dte;hBF{g z5)fnC!1J)rxc&zmX@a+Q^^FL-qbv3s@n1I?m7C_B*f)pN^>$IZd|%^w;P9%fA+TNVNOVMR=h*pu0yG zysZu3VdK%Rf1d{*B47lg2RWbC)6FOvn^W0;KRI-cww@E>X_v((a4v^LY_49js6Li| zxD9NvJF=aB7*r4NRwP3&AVgtCc`i=6hL~ZCT$1Fo+9~{Hv8wN@BB?A1 z7|M1-eV5MQR>>!Iz0JP|ojBnxiMNC)-Xm~OUQDQOf5Qzr6tgUAZ}8S3+TwADaup(~ z^K87553GH)TOG=62)fSekl@GKWsSi&$zD;2mO~K2^h5;gDcUZ=5AGEsUvDc@(-%Qs zq!ByUkPe@G6`o(w$<-B{9F`{S6FTMwS{_4x%@XZycCv*M%z;giK?9Eee@~;QVH2!M z%wS_hf7DVr>H6wPt%*-`{j))2#>szz{)13Lx{rZ13;_zbqSjbEleSbC2+GJH7$Ohs zM>vyh6&N6PAA>=N$ZW<}-V&JsCiwU~MjS6s{h`EYES4u4u}|)r@G@ku#~Gpj^JI{- z203j;{9-PODp!4at33?HcWYO2O3^1=_x4Z*f7HKw2*1}mcctu}(gY*KBy;hvU7)nq z-2$POaTKa{*XeHXz&r~`HOIg~BmMa}K|Tw0ZK5~g2gB-G9Sz%N;5D$V?l}-vs$0&3{WGxORWQ!;St- ze>Og=`Nmwg`NsUV=9?S}auGG(40K}8cq^TtQe@sGBGwyRw0!HDPzHUNZxj7K)L))4 zjxkW3yXOa$UO@mk zB)uEl3Tg@YGzdg55X~HIwHx#Mr2k;SJVYoWpi0J3AOA_`@0WOHR9s`b~$$0D}FA@lXV0WYMZhm`t@y&B-W{i@Qrfhb3HM5FPkQPzq$P3 zo9A5j-$`c+PKio|f8C31y(_AG1rKVSyq$BCeDdRFo%_Kq+szl;CVAzrUsFzhEW*t{ zSLJ@^hd<@bx^yd7HLPLtg_J37Y5kTac~Qe2EZG2L?mBP$li7yM7fR~n6@T*tri@BH ztn;nEfB6An3U6CyxZC^QOy+l5!M4R~Dnwqvb8x#UfGB`I;>!e4GWGc8zwKK>0_EV} zkx1G;iBw927VxBd;w6A)lV1WYRevEy!dch{dY7$+tDEXrI`4 z;a|4bOMe}-5dae&t#{cn2Z5J@CYN(7k}^P2_61gX-0Jd)7uACrfbmUGGx^3}dsPLR zuP!(HPP!3OoOL9G_xn@CnXHa8FD2T*e=%`M6#bHt<^En%7WNgQ$4Xoit&QU)JA_fN z87L%Uw9_U;ppIaKQ8VN?H3U+FY6MM^s^i%7R2}EB-4v0)ln+mrDXqHT3P9I#cw`+@ z;h77$UHP#W4dBC%yDG2iz}z&sDyyhk;fzSoRh(Fp-ldK?&=^IsTld)XiP2`Tf6Wub zG)&w9cPmFoB1nl#Eh;z>lzk~p5vQwFheg?@++L5&#tJ;(rL!B6 zSEQ1poc&K|fu~WxEkF(%0h18U?U$4AQ@zU1DW|&c`TsEriyNMT9iOo5=1$A5y=71D zVc8WOq9TDJ47isbOgoQ~1#~;Z*CGc$6zlS1tSd*<;oQ@E#!^84!R1Xoe+bYqc{_>s zhezXie?;$gyL6y@K=Ix>8o{FO3WH2VfSLpuB=s;o(RwthN|(|!B}vgh38$F~J%3e<5A{(ROP`QAba z!thiCsAteno$sB!E4+>6e_&&M;OES2UKQ`>;A=u)3A68e5#5xx11>m|>=bv0pW^Od z=F1*jtTt{&*vhv}Rz&Up!YE=mq6xI2>9M?wdBD8P*-CWMfP!3D6kieGT1^>v&?2ee zpU;QC`2O&!RCqDok%CtmZA#N2P}V8Q?@k3-c;|PM)xjW;f(R*bR`xhc+DN z`3R?a8=c{>&T!Zhe+`HIl0n2hEeDTUj-kwRFdHdI-U%|Ff-;inT`~{ML?pcLG?|A* z`f){GKeosZoWM!zV?Tp8{3^B&gp}sMfR7+}|GggDo4^=)pmmXYi$OJj^0+gmB>`^< zF!04IxB9#CW|vh(m+vU*;FXnrrYkPE>48H89-8-we8${Af3O-B*|6&7ijS~jSXrBJ z=(uIXGV@^Bq5F8nw-Y3Mlpq;7fXpIW0BPYM_}88TIyH;(CBml>dwbGL=ZCf2O{0E= zvImx7@mvS!5KxgqjJ=q#Hz2TBV2KsxizR&rM#AsXqrqhyZVmSry=9Z7Rd$xx+`G0q zq`$|aM^-ohe>TAuYIp#^Kr*T+Am}oqa_tne0g$S*ptmZvF6S0wEa6Y6uV6)-PeqTH zTMc}aN5?9fb2vX#(WoDI+kb&A8);HDYu8@^L#KtyYE?h+*FH@RgZEB7yE2Wt#@bfC zSw&@CL8PnYS5k<-m5x7b=?oH}Qk6~CxGoedLYE`NfBThXTyRxoH@T||(=NdP>k4O; zJejIGOuD*|BQdtI7`T%)-Z-IV2T_NRW>Dd1jU?93ce_pD!0H*zYuC2Y*+jAMnT+Ke zOU~7kU`yA<5&>EJOTVeBIRuNkL%xgH0`s!0VUDRH!3Rk5b6^?-wY7mj4!(2G>!vK}xW`iYIPYQRuaQofX6`Mb7 z!|FOFj?6&h({*1}cgvx&4*P?AFO*PVe;%=6r1EdcKV~<(jXz{M700BENUeu0g5O6? zqCTxX5R77{-$A@REY3#kH!FYTxfuq*=6PBJM%>i{d$jI|5GyJv>>az+uGaTTQ_${e zP>8&Y6e1;fPsclq3~b^WjE3B%_|Uv8@OZA3_m=@??*26F37Nm%xWf2eab zaLn&>c*EC%cLDK-jP{LvHnL)QcR<$@b0>mMjTtG>|o{6SzQoK@x$CShSL{UQj3gXyEuOTUbGoLV^>ER1JTkUG9Cro= zk873J%c^+mKL`l!ROZ)jifx`%e!RV8iWtfF1X_JT7f3-fNi|+iK z4+~u&ES>##v*pfveP!(;CmA|@@gKHc=aDwzb-pP=W3m9?Fj8Cl3pAAZ%8$!^;|J|W z3vPjLdFB(&H!cD15*=8GF)!Q2t&@jIQa2G|MCat;b==7lLiUCAEH7{Dzop#ty}ZyF zj>s*1;T{6Qymyu*uHC!t;3)@T!ao?7f59ji>E6O%dtx|( z)?y>KW6~Iip)r^!?x!Oh#y#{_la%>%hH0g8B7Ie?+Rv-z?RRIr%-Er!)(0@Se!JQ) zWBIKSqog2E{A>s0{;H$(G#Z^-w67;d=R?=zAJG6O)#`y2Ouw~ZLcu6wrxi>(tziD|!@X0ZJ@L5Fp17BR zck~FD{5`TWB?nI{?mK*4m}CsWUzBQjGhlyjfQ- zph?;Eec4f-w*iq z`TBq6oV8D{ij}+7)Wi)UnOQ-MOlC}gfGje9ab18&1WOxuza!UagAKRtx|l<6Fc8Cj!aF-lquTHkok-uSLQ| zptJo+QhKK_F9TPi#}x-XaaOaofJzaooX`lPs?U30Ylwo^b5IP~>anCT z_A_`ZKc?&whSsqN$sEzy-!9I6J7dsH6P9oeau7UGQV}ka`OVquw=`M6z3&oAGNF?9 zp7O>iw40q}^3&Nr&%SiFI$xMHN zUdec~nnXRAAOWfX6Ql{vG9+vw$|VThdyg-o;slopglV!aOTib$MhT9>X;@^KLzNy3 z6W#2go((aKJ)q}2ZY^5rgARMfts#HbX30!YP?w-h-l2NuhhC6_$64R3tIc&;-{75h z=&ikreec~aI7ze&-d7n2cyg#S@S^>gH8I-4Oj#Mcjg9+2#=zZl$Q+lksL2SmJ4bR6 zF&{8iE$`#s^ud{E{acucA7b1yNg(RegYFwH8N2HM`_8);?V~mU%4zrS8a02ciB_zS zSh48FrK2wkpd-pQ2%1l|Wj)oF^}TFaPqH}OwdLkO*BrD$PV2cR#yI@4L{oLpn7fiD z;Z3?{?IP2l`(W)H^r-dt->%NV!kgl%${nbJVHuW|;rDw0Q*d{lFWrBdeue+n)uLSG zO;N}AfEdOpkyc>;Kc5?sf**h3fSXopbQthQrJE`swW3&HOYz@)-gw{#w0Vt z;#yaspJt8s7DYX;%0Pil-e>vFJW^XPw>T=-w7%@o==8_j@pJoA17pEklVaNR|X--AO0Dwb{?@0zAJIKoA-#Q*qWAgK3zL9^#ev-W>BO&8@GDg@*O z0eQlNct(Jx_-&i-pLA%7dm!X*dYQT3@VW{vq)dPDsQW|IJcR=N)At2l$01x)iNQBz zJ^1FqhQ}N_?mobs8`e#Nc$~eAXOF<%v0j4pZ=xQJ644dxI8)*nQ+t1Yh$}JR>UM-H z$sdEOs7um>>s>!DFx!911V9dmsort|(Dj*MJOvher#4wR=^fpQ=2fCM2*@S{<>&xx z7HknN+I-R*pv{J!02?o>{3cxHtGP4UYj9SJ&=SoLIrZb8mL94D>ERtPNX|jXH2rby zl2p%?gyG~(J20P_yQ_hF@QsDfqSs5zb8DP4ZXi5oeP@>k?5BV6>Vp#>13^Hh9T~0U zglhH}qxJKq189W_L^z7vZ0m4=NEYtaA8y=z3>oWX9Ew5sQY_+g)TqyS5$gwlrrPP{ zW~2|(S3o_AYa!X$S;B1`B3rdX2rfdpftRaAIrnOcVsKgz1X2f)I?nMHQ9kdv;m zoG6+ekr?md*UOP8FFQRl8j&hylU=F4j7n8#b6l#5WRQPAPZX!FzmmSk~20#+BSSnlppY^j%;j`8dndVi2AhmdnTHDZDire(+B$hec> z@_uFwJ*j`V?78B1g*JrLM(!jV;yH|Glh-w%H9y4Wx>|3qqJY{0B4C)96OkC?C_YAcbWhIpbO+g=8+4EZfk(SDM2La%OhiCxQp8rL zir9l)9y?Gl*?rq(G_eLyEQd+vBSECN^35`4;=0CqJK&!be%q_qaCf}p$*$tN3!OEs zi7qQS|j<TiUWK5)+uw2fD4orf5O4SOw|L_X6wApGC<>gb+fi863? z73B*2?!NG2`f|?G=+)7o zB&)SAc7Z<%0no0p2^xGw4gA(k9_p%m>vdU&ZpusS=6ws4;JWsOREVTxC_Hr+ZLJLS zv@4fc;v;Q=XN{C2%QOOzls;Wur1%iVoZ6pqnww7fEXM^f~buR#ngL9q%5sG;ZsT_sf;vUymIA z7jSuO28};8X^zaGoH&Dm2+khsfX~q?r*Y%z9QizCT#6WT$heeW|KY@PekAEKPlG@; z;0oURSb}X&fLWea>!yD_<^|3EfLQnTJ3NDer^`Oz&D|N4cJ5jR8!Tf*ud?u+0AMh|N{n4e^ z@A3NEAO3|GU!Pk@_x)DL@dK>ix=jsA+cQKobORTcdH9+MFtktm;l`@K^D{J@!=dR0 z+`Ky?Kls3mL?sZ>lge?Ro*65T(+aBCoeqanpX_#kK0R zT+Ps5?!H%`-S-LzXiBDnroh8_I26|PNbd0(Q|sa;(A8U9yQ%SSkfQr;4mND6^}A(p zN+~#^5n(aLxMz z)X?~AIHbM8du8}tR|{uJ75;0V?0#3LSk>V?q;WC`jg>#o4NYz#3!l9XMCGc)WiQt{ z_VFH|3z5TOP{dP}CcUaqHCxiidF=g;r=M$@ep9UG#S1JhL!DPyS}uwluUwdQzu#{+ z&3g4(yv2XNc*wEFKi;6>w+4^X;N^A`HC%{SM(9sw-3USg+Zk!twGCtO!xXjbZHG_hn9sOWGpvNwt!9*zX|6jy%r3wfbc2Pg&&52-R*2+XAi+ z$%|^M+5QJ5=&pQ|T|g%RFp~inDu2~lS#R4$5PtWsVA~f8HMe^oE&39mK^mYzTDw7k zBq$h*Nm%G`DB5ZI>pROOWiGuGDVdg?CyCT(XLinSX7|bY$q!Gdj0i>s8xozrkF-FT znMfLmFs9M@JbE2x*E6c)_2N2TeV8ST(Ky}A-kv{)|BCj1iDF1{8YPq?fq%98^WTn= z>o#RVkfb`oj^x^rFcv9f6s{-)qFPsUOgX9#A(k9z!lM?|8!T{$BS#b@s~MJ|r5G~2 zA%IoLEHQ+|KZh1$6iKmN?T>%}V?dn0_!=>(BdZ4Ph|VohlwgE4j}nEbrL#ZeAqE=$ zC?nuvc5Ob960}4>OA-k-sBg8OzSDoOzKxMzgTC{wzH9Zo3-5|h(6&-?cvEa>QxHAv zT@5Xh292SlZ11L5YA}9_Y(ir=8ZR{@R0^bFWiP(ZKW4Lp8WV5Ui>oqUuk4eK->(bz zx@>-bgBdS2rF+OeU8N1N0b`MPQ?HUQFBe}zo1j=jYLbsVX;7uZPE0gXS`U9Yv9e1F z9ZnjU@Eu7*A_?m=goSK2pD?+V+q0#CgdrMP&@ADM#Ao?3U!(23;Ah9)RXzzj}X0{A3L#h;r->7Hu2<*5rX9`JWz*iU&!VzCx zy5eTNapk_2AB!xrUt#BIQEq?2d$ShQZYgdaVuxd$?lKrNTpJfN(sQmZQwEi$MKx*6 zP#S+96kj2sMkVQ`%!-|)hmM(wond|4;6djK&cV6rD+%k zQbgFJch85#fvSxIUj=wb;K7DflqgU(NShGrOmxU9WE zUS)xT@wi0)8MLuvDS1^L$Q#TK($vKq5nbhN3{f5W05wG&MMw)&zSE6?v8lDmC_9Wx~N zO7tCJyE-bJCs%v4&qxQNb9em{9q zjpuw#F>nG3yW925ysYmz{#DKL)D07T9j-Yu5vVxF&H0rxb| zA^$MQV=J4I$~*-I3ojR~dhn-21mZBEcI;&aN*0#(Lo3s`AEiCb8|C-Xyp44AXQAZ` zxZZwJ-Fbie72JQDq6L25j!~{fY?-WvEbDHt#6b_5J{-9Q*`~<5#ppMX74dN89PTmWJs}N zm1B+3r@`w6>U;+jZ_2bN>%j_C<6^yZmF~Z+Sl5NN8Bl-PLF>BynlG~;?B)VVY&ybv z+No6RfysYD(t^#UX#47^_UyHaHogn zXpQEc+5>-sb+PP#xy8D|mlx^6JzuzIK#~^PtNF^H0>r?lVS50m zG2iZw;;`0*(uZih8zanwgG6+Lq?^!vR|+~1;8RWXy&jmMdUhO$wccSHJ@_cX zW95H*X;hTxeZ%CAy_}lLhIarPfzseOwln^B;mZ(&RujU+PAGZp`K$(aFN<22oYS18)PdXYVGX+W#oPanYK@z*dXC#&2Sg`y$qEj0K?T4hZg(rUNshN?!A9C zf;3zQ4&>A*5U9pvBsH$O?UdY}YY6a5y~h!j9)xIo2Sj7A5C~Sy3FsXW8i(2|ZRIkE zkh>$aFbJl4gy}$#wz3DXo*ISq)MQvsjl+6sf2{W^99)#JDTC|AM5ADz8r2-B)*42=Y+Nq!&>y^zz{r0j3mn6>S z?#&>ul=ggK8epl7HvpYy_CQ?4*=oLV!h|m~3!A{ikOV4tnMHQ%0_~30DUaV>ReB;f zddgQ;D`obf0JYSb`ecvW)B0$<%(L+2WDYe7lgUPm6C8hd>E<+CFEJ61{p2~bXJ^dY znGFkFN#WfNPgnDvaWFPt;|(;0ZVu_^_0_S}x^!m;L}8=>-X>7ZWplo&8U*n_Obk;o zlLbpB12{1nWT zRJUU*q6{8{N7mWmVa#om`j5q!!7ToIHh)WnNb_`s1B!XF@b^;~^J$Y5^K9jBJk}g=r&-scNdBL^YQ*L`hj+ z@jDzfVuDauf)i_EfB)YhN+z5zs`1};+!Hy?g%puoKGCdbXg*1}6xE<2uq#1g(9eUr z!p+w=1?#c5l(N8#uu}myU`j1?W8s!;1TY*J6U8J} z!+3uh;UV^yv+0IKaLM7XqOuxCX~1$cQDBKBWh_KHj8LOVZKmr0@rE$lSnkfL`h*ez zvrG)B%)Dz)Abt*;(pzFf`V{XP6-Ume_ zZQRQlf3fp9BVA3^MUg#9+b5FQu;Xbe{a!w7`TG!BRl=2NOX2t6n$9b!gCcqeF30;U zx684U3{L{LC~u3L(QeCQ3M_#)O>fYCE@^t|3>*%bo-nMB>Fr&0%i*NM^kV&cG`%jK znd2nIIfTZa@5i8@#_{k?hyyDukPz?vn@di)50Cnz{hsA0znuHkxMRvJsZ z0gPQG~{3d&L+p%Jl=$ ze~;-E{g{_?!Ck`PPr`vfP)7jpSu_h#$73RlJnA5PR!M#9hvh*@k?}-J8U37LZpCM3 z9>&~6Y3^jGqQd2P;uw^60{64^yv*j{tvtI=K2+(Q*p?|B_~s4eW?J0#~zl_{F9KKRS@b22UbV{@N%N$AG`OK%2SoASl%(ly>ixeLQb%p0cGNKenSBK9skd=x9XBle> zPVWc~!WUj1EI))3HyT_7>cO!5mOUxIf6xA3 z2jIvsB^@Zx)@-q@ zOS6;qZ8ZGPz+x6i7a`J{^Z0yTZB&;RHpd_eO$2i{nA+8Ky2Bdu^W}6Qmq9Vm&|scV zyt{gRd-drG89_(zyv7C1NJ&ntf7GMt^6JeyI-0?kKrJ|WJ$iIQmxx#`#{gk5`t9l; zS3hDAs7bpp)MZGN;7{QO4_crAe_)VOX+_Nf#U2aP#G(N*Si(F*D#aNfKb%TI12mUO zr5rTC16pkMYjI<9Uok9ZpjMz3JHS|mfN?D-@xa&xS&uH3^w+cWEfsQ=f6iKgS)LWO zxNVsf`TTQO;$WQdaWZJK$r3d6x`Kh4+bSia_oQTi|E5p4zA^fjWy>Df9l5Ce=M@rbK%0Xj?%K~yuR@dJn120vtVf<$Oo>KTbRh8b1Y&wMp6I!aSgGoVGsr&LkeVIh|g7D^Wv>Sw5JALW4t zQS@zBOvA8DUnZhGf0%bX?0wFP-7eyHWR1`u4NZ&Rq2V;Q!=I6cV^~3153kd9I_`PQ zVp>>6*q$&uJ_xgQH_VO|p|Dc{*g*k^J`HBaF#r(h;I?3*MixE{L315epHT(ptD@Tw z8qv0iiM6_^0RY%kcc%nIkyicz?_b0jii?!S|8Rz1r!zcze+b56Y~s~$fkk0{78V|9 z%{4Cfu;vqKd_Hxr2$dL7xdkvIqv4bQ&Q}LO$ap7y)Wnsi#hz^7!~lAWm6M@WasYp> zzX2Iu_mtrdT6%67UJsLD^Uwv^SqQihR9HgQwmWF<-&ff4;=^M;FUq9RG+W*$(_-DZM3Ans(Ju}${Z7JOyB%NyYo&BTSxDteL9VX_cIzMk2w{Cg$ON(RHB~6 zW4gOy6${tnbH>K|XSWdDs&%)`!wl~%8q_}C%QQk!e>oOVh3PeAGfleH(4Y;+aCK1= zPWoC_yTmrovR-1H-3(z%FLw-apj&DI)O{&p?0|=dn+P>*$IMt5E6>@*|8jPG##dST zHlt%f>s7c*R+<(_?OmzqKk5Dm@d$HZN1dF9QR7+6?rf+qYzjiVbGKm%=Z1RyjH4G! z7#Ie2e}x+;39jQkO}5I{$0?C9ACP@MHPLWRmAM4SY{M(9L@$@?kf;HFbQvJ}m222_ zSi>y%wZ0lA&V-M5qIr3W^V_%k!x)(NP_Y=;qdHWq)my?1aJ1?z5j(vle{b}Z!wuIO zVQKW&U;gE9{4|bL1X$U(VH{{UdA;p7kyc`7f0DZr+lCOlPS)$qGW8=it7(?!=^`1k zsK8bwyjeDi;Mj0`IOmEe%MO*+*-m@-&YMU?V4zzYmaM`rPynwL8{Ut;+YRKvac$Vm zc%pdOo`pN!ZeB*&7(0F3W%;#?Tu&ErYvDg*B4dM`^R52|u!;-aYn?KmHc8p8Q_Ou& ze+-Kr=Zi(zmk)C#%|0Mj{W8QVTTO}_+w>pGRv*lq;JB*kCRt6(N7hBYnHH||Cf&YD z;ND7@Cgm?qu-cDUI7M?!KG>MEOlR|?%FVRs4Vk`Ru2taJ4w7a*N#bcw(d^jM+h$#Q zfTbvVT%Dv@IwG-dq+F7F|Hem}CiKWC~jfEp|rmxo6bG;&N zd;dB^8Qmz_)KDxCG5jT$xJ~=c8zKxty5P`$+w4#%+fb+^tWcWCeih7K0d?q9g`H6` z;O&+sBmHh9v3A=y$5~jN;WVY#4`c@cQN>AHwHy2o=!UOulh{=!12r@_ld)qde_Ts* z<2Dk$`&Vdga&3g*{iv-}?IyL8N7Zg6S#RxOk^@JgZEY;ck?1)2_uCDC6hVO$C2O2a zRW4%=MS+b*_t#%H8v6X^>eIJePZ%YRIySkvomfSva1-q`p_ET<7L#|=oBMKoJrjaW ztNRi!_;kHl?#gg)v%dcE=9^F7e@dH-;|N!BLc<6@P)@^BLQD*ChWdvjF-A;g4F1^g z;7{=>nmnaBuSfa|3s0m{GfA9)JNtnix0}b}uBgggkh0jt@2NyeVwj%HxFAfiT2!ht zq8eh23!<7+MO7V9g>;kFK%eFG#~4ve)kFO~BatP{@|;BJ`xIfk{kDPmf7#qV_R7WUx6Aq*6sKKme{AI0~&$9w>BQL5M*Pc$XXw8QM~!YGo%>qQ45p6|FV)Y)5DbHJyg^P5Qu3$4!*E3;wTFQwe;rDBD~S(%0%AEi zE!KADMeKVaxcPoy+7y59GE3hqhk9Y+u!lv`8UY(2yXiKOvm$f9( zXGywiNx|nBDg?bm0RFk~M9aKTdYDNJ?9a>UK5&vaNtoEY3U{hahqkQBV)q0p*p`cM zqwB~+ruVz`x%{tu3 zlR@TvU9_B(=bcn?*>Y0J1YqrQjtg`j-o1py+r`WEqKxYee^+a?=qNMbjejCa3^(9v z8!p3wo3P+GSgjKV0n5r%CpV~*;-}^MF51&Qd?T7t+aTd?@TgCsO-As;>-z%#6HGR% z8?Y}a6-Xe#eN}kz->zp$xAc^(zNd!n9NK*KkDIHXuh1{)1OlsIM8cGnrGx>h&sSIP zex#EHdf>RTv9oU;3I}LlBZvbI7 zN&}*B%|;XEud@mr$7K%8rA$w;f4s(|XrmEmjrM4*!BLhM-hiNO z#Ogyoc7T4!_yi2orF^N)3kqym^D#EBED_WU*}M?=N`0!$yW^?{e`5ebEt?0Ovdn;x zGC7vmbd^I^;5)!yeX7fdb0RuP43l%fuVNjp-$$C@v1@m~LEL&?*YH~IAWv-|ke^K~sG_W*0BZAOzyGP4q3&ibia?f&$$*YGo@0oouV zQDDjV(iiy|3`8I+n10%S<`!1W2e-bK=Gs#x=Jh;Z$Qa~$v{xM^7+c6XQao|wpdY<)d#ep)m7UNZTlMn(_FUKtJao!{ZK)9BduUd@A0B`7pp+{VrT=GAy>O)x-#CxkItp~r#7qXpFmr4fNIlF6$<-;$SeR*A*qcc6XZ#1<uOHuhQ?gfrMh-w_V0Na zvEx7zv?mGF?@On-Si?AOi+NSwe=4d2#uxXSd}*Fd=kZIvG~XU&yQ#wVL5^<;Fcrzp z!?uG0l4-kD&pw5MTuh(s$iuH(?mAO19=2t%_$}O>Z&r^_Rgatcy@^H-A0DS(R*&I zv6IB&u7fbX^nQAGP3pYxm`b%!BZZ=wD2>%uo@9m)^Z>{kr<7Sg;6y2gIWMn){z#&( zFTcNWn5gSX8f9~}$hgBHAw(S{>L7-K2QirYXbhP@B(l!w-ejFyPNj`#>7I6I5@9BeKKnJ}N+%7x10 zrL0L0?v`=P+}!I*bYS0Uq71e{09)Wf?rHsz2xQ0bI{O;z+Vm#c>?o$AnekyWV?9LT zkYLMpG4Is~_9+X|+HC0SG*KUHw>%?KVk)m+i0+hf{SH}bix~Y<3LLqJQ7md|32mNo+oX7DpsfXGqlH(i+SLBAnd= zoyc)%m9Luso3;SLe>34=MPzfrAs%LkonnwiG~KNOI~b6uY-2XJTdp1<1Ieau&i7o* z1khG7+*YcN8(lZ$`0QA|VRHF~PV$Y84H{qWfuJS-FnkPV!m)kw1Ufdb1EYz632L7K zygVyWj#$tjHwcOPWoe1#1ZK<)^)0`h=&p}PcWhKQ%K73Ae`ogMy!F&L*fC4Egpt5? zxiZIHH@B5LgDluZ4gB?bW`)SMOry_@=`K9kn@-N&F>O~8$KdAUs5D=!>*$bE@uchM ziYzu7f~FA5~GCr0N|OLFBZ{3!2&xR^a!sros9;_G!$@G z8TPIHqyLIMf8dr)zfF3;;l|ScrQnt`2&k)T>?&NY{f;$!`t?8m6Fz=>?I4`atIakS zr>RFURmaPwJKd`3-1jQN1%%w?L$URBKZ|3{H&3CPKimjiig59MS?t2qV!OPJpKkVT zgYmIyxx$uktS~w^t-rF2f9IRkYO}6iwkyjh#d5v>e;nJxxAVXn;MU!?Sd@*XTg6UL zLTo%|$O%kOE54-D^4G^udWY*!Ifjc}RaEgZOu%c=|G(JfyD=?rCNcgv<}hSpzg~iw zGwyi4E{1JLRGf=g!)*ot|4f@~a|nD(2y^z3zvPF+b0Fsq`92GDDuLFbH@C{XqLo{n z@QODhf73VM*ea90rB14e*>BJI!!}@n%k})>X;F4eHo73*Dz~e6*;w|X^fmmlKA%E~ zHl6b+;VhE`#*GJf?pE={2f_-65#pf~d?4`iJ+O4cv1^}|`++i(Z{U}zIaT&q=n3sJ za3%HOa2?OW-ORpaU;|4H>mZYwTwLp(7dePNf2P-@*ch7{{hr*Br-VHVh!=SF)z;BD zS74Zhr)D4utAvgm3yJL^|~X9WK|^*wsQtibVSNTQAIc z>YdH?vg&aSsj-8cD*fSvd~>Rh2ki(QA+u1|E~XJYn#QL$es2=N=WbsUKmcl>YK{Gk ze+@3R56cCdvl5TMCNNk2{8Uq^-d`b@u%$R@e}qEuB|#aV{cn$?5Xn2 zsF;fgsgIqpXG9or%)s=h1`Q()8#MaQf7nB&v~RItDpzvHDzCD~4oBnVo{Tfq(*Ue= z^Gx=zX^=L5xE_z+964Q&d{(>Uczv9HP=uVW%jfLa&hMCyIB{=Vhk1q2y?xc-#8jW< z6c<=hJ7P)As3mPObT&n z^}O8HtuFrbGsK|Z!e=4Y;JH2wCL{|*Cd52C3?M37BkZc(v38NLrt`ZXbL@C(B);}F zf{w&_J7yfhvuIbmSl-y|{x={nJS$Vz^x^fJ$Js-9TlM_hf!>>`%eT5XrpBzlRD(aA z;Q(eEZTHQVNXAA6&!H8WNj#2Cf4Q$i8N=J&z^C{F9d#4hu2_{R*XV4#(e{~#(|(6Y z4@H?z>TWnRgs0tMS68gHv`=_82Oye0!~YfY4WyRq`uh>ZT2El&Ssyp?RuH?%Vh`RN z55M}dQTX|QaJV(rW`rabt8{=9)|%GZ;s(I~0Vr4vwhCo#WOH|yRwOMbF8Wy);`b@cbBnV(Q9k}eLi3YL(UL0 z0Ea_KS?`Gtfemz{@qOJ54D|i^$#?I#o-s-sb!>M20dE;`M$fdhgJ3c^5(Mo{@M4ly1K=m?fhc>=s$j`+I+shd#oDOQurJ_JggpS5%;y| z<<2Y;=_UrjSXA7o@69%t>DCsKQ);GST3_{W9yLYN(4?&5Md`7Fr ze?MM7y*o2{zPxz6y|0?L&8H-x=%H?Yxw>CJpD8t8KCW+r(a;q>;q629_8M=OkN4{f zs1d|T+nxD(%9}jVBZt0D#14N* zbZF4Pu9L(DY`>5 zbF&4HK1OQ~h?e zd{|$7sovjRJ$+mRpFxYt5%Fy`$yZNRZ*>0Q{`R`*xBlV%>Un+pR5y57UBD%3fBBEM z)$7M~<^I*Dr{EEoiI%%o@&udzLWR6pUilAve!qHnx_V5_r=~<%Oqb$BT2{$;mz-6~ zYBw^iSw+V!H$tneMi>RFmkn(>E+Yypg@V|6VAK$O+dFyAmP}-e*{|8y^6Y(Znfe<#`We{(}P=UY<@ zAW&_WQB2R!p{`rKPtB14ZbplpCjFD4H$j}L-RZY#%~K*ARy_vM0VCA`BmZM8tE$nj ziHY?iV6Exj%x+s6R2EWh&t7Wk6p?B=chVhq>WqjIZQaX`$PAB25v^Fsh~)8>T$@WB zMr5`}^pDiQ9b9ayGeuLfe=s5`HjOw>c&zt1mO|8oYqk(ov9t|j%l~@-qh$w{>JTs| zuwvSxSV93u{4cgAC&@4iu6?NJr?Hx-(DYyFP{oSTuT-1`7f{K80&ytq`u|Uar};IucXGWXm-( zoPTuJL;{9J+M+u~e_TYyuYd`Ph+t%B*+&HWjT1r7BFE|#LZqUGwn)I3)2|yscalUF zQq`@#4$BeM;UfZjsn&@4mXa)*!nzz|#sz&H^zoA3RKl^~%(HzBK1{q;($O(HC0wa* zsp6oY0}5=(!qYEgBB6+-`kQlqbMCLP4zlarFHdysVlixFf3=utWHyFvwd)p(O`-^F z62;<7yQWyIQu`JQp$x(uV2#iS+v=u2udmlv%lohkAlUpv-2Lek+d15?iMf7CvbE+( zwr&gR23&tmjdVNk{Tw$A1fPFgrRy|64(W4QOf8keLsa>IqPr9Dmw{~niN@^sy8u(S z>+ULaB3KUee?tZ*k@9S^OP#D;TjREqi_@e$xEu2uScWKS_Y=5G3Y4Ki5XekcpxsG- zI!UsCV~80imhnul4haCDScv_!=N_$=3BqLnp0|Amp%*Og= zU5iB4w^0QY?sQ0v7_Fy+B`dV7stqilbu0}Wq3dK-e_^3LO4zVfE-5=!=lu2bj(Kng zs6?npSoo1M2?`obHixyFhR~2m2D^g!nU5EJx|SuJ4B>36b7m6YZbPXbJZkzkegWwmUnpX% zEzm~^qR>Z)K7g4JD);JB%Nnmws?rEvVOR>K`WSc~0`U@kG%}6B`Ke_IhnW;3)TwHs z02AX&l!mE6Efs{wa8@X*C8y{LEL)zgZ zhPVHIVVYEAD`waph+x14>*>JJf>{+*5NRecK`m-O3#haO#E$P)77zs%STGBj+@Bf) ze*miOf!y^|h`^7m*3(dk(L@+M9fdIGomz64Qzl}5filJXFW`beAS&zNgT}jt#->?PMwJK zd3DNJBkaxV*JTaAFU=9M=jJow`~><(e^Gm>e=N$d3Bq_DAPlVnh)qHm3Xb3IIp@yW z4KoI3yFvQ%0AmzrQ_L9SwdsLV3O_5-Cc=DyHpP?yZ8&3NwCS!*J*cGAvfd{gRXNP~j>i`HmHGB`dxyExpYfNB(C~7bLRa$?syj^C2QP+=OH&4A?qyGRo% zWs|Ur1h_ac6}$L4x3s%>JX&SYhV-;iq%sY=u~`ZluW|~V8CJRz6RI4!r9kCko|2Rp z?T*Y-u!M4a7sAI{q9LFHOB9pYf8>@p?a5@dna~oEr3x%j%y?J^)Y%Cs&k!Ec_YUQa zRyuN7Ug>gP#PsvxwSNp=L}1{kNburVGeyRmz)Fp%eT;M@@>Fn6IhH(6)8uJ9;rY|$ zxy;OQTf&{(SE$)!+-ZpArkqGrPGj&L#owpUI8x_$jhE?Y!5BW0I!_0ve>1OfF>`W% z0Nxy*IhkQ2`QmhdIrD}nCeFzX(Nmr9<(ugY5y>uZh+^J^A+*xdl^1IEM5Ng{<^dxqF|%8TJ98&})T^BS**VqI zJ}X55I3gT)js^F@Q!RLje@B1b!V%2e85RTVP%=DBmfwNZRlmZSz`KWJ{2N(tdCm7& z%-yJE=QN>|{tQx+Q`55rr&5PkZd`apt+q3qzuQ63k-vG zDb*0LH?piFqH7qQdZrTV4B1^C<(d_YDNirp&JjgqPK0rPQWiSsf6l4;PPNp8RND!b z+mdk{>e=vIrUQ~3QpMlM@^`Mt1LDAr4?%5VyFSE?O)9UjxRohVUP5W=sw7%8KLJ29tS!F5t z@Ooeg^mrav587|Vf3s=UgF?D0`HQRvkEJSU1m}EzO)s97lK_f=G_VrpDeIq-k9@5r` zy?CMCX8Nb6cJ$WLY~PoV)VCWLT1zN=#Ykc)KmJ2k6P;z3e*uQ!q*5Rfs)zV*e+glI zqP)7a4a(nzD+E{fA8zljt8eP7(>PWVo5w2#{bBUq7oXP;@%Q1vKz~DDeLow%yZw;9 zRSYSF5~GgD4?pcS;e%uSquP3S;=KRXo9+b<#t}+wIG|7C>DtV}{LFCMPo?kmKw3st z|G1D?P?gYqf8Y@UhvgM=cB69HmhR8C-e|6+igPWdRJcWpgA)Na2W_rKQRv&+Lkh%+ zR7*~hYN^spOZW@*pnTpe*+`)gg-Ahn&C(kw=)Dpx|5RXkrX?oLw3x+^u#y1a-0{PX zOVy%;za&*m8&{g$xYG6KS++=Zt`T+lqD_JB*+OfSe${Uh*dlEuJ$eTKcrVu&c(lVq_X3p5j-H9@%#F~14H{zysIba%b!(j?2g zg(T|*_14mkOR}mQi@lY-hIWQkU-+b}J5h=vR{dt5gzdkeK^HzwZoiHT8pLZ{(7;PC zXxMKqf4<$%@a=wvw|YOrxSiZK(NzG9ILkVgE7}wlE;=fW;*L|E*l* zHJAIBY{C(O_+Zqi4e~d6#X~IF7*leE0M?su_!$q!1P`j&L|GE9B=uz5&dW?dFne|{8P-6soq>*h;8QI@}hq-)(5-D5|L zAWbWOIUdJ!&v`L_zDLS}>j$JiWX9bjwr^y8rMBlulI`9yY5k^s6&pIyU*Pcn6iMk& z^WwQ0k-z8{y$FAYiaDsl5k+BrJ8dVcaHw$A!3gkK_S`@zo$Z1TK*yx3hyL1pS!78; ze=!1oXL5llbJfE}7Hp|T-ICH1m4i(!^}8^BD#u*I=If6F>xzbx8ySm4yv$pq9DDr< z_??}Qm#iJV1opBX>>+3Z9et5(DzmnKgw6RL+BuR$MlbrP_z$ieLioLJ9O(vT{gz`bqfHlLxIml%_ za+Tg0U|9YX-skrQ7<(%ft$d}*KMN(|FNaUq;+TupBrHxj+;S9ES8WQXBL6+aFE76CSk-CMA_#W~2f5(}|q zuWZ=Zf4{H#OWiY^ZjOes6#3Mn9?om>vFfp^$ktC6XFvQ*u`yaDolJA_dy`mcZ5!{R zvU2Bj^XulH=f7S2`-h*MYl2Eax9y_h5Spz~0hhMbpIxgt94mign@OWzvQXaA@lc0* zMT#|djV`27qnm9|Hkui_<=MEEcidRO`>xfGT`ShpR>mkc+z>9Fx^{MWf=SADxBPI+ zD<;m|^HtlW*guytj2KpdeZ$l;(>DA2`Igh>g|=z0*BGaQP5Ah>`On!eXFrK4&7a&u`Jl-A`J+wfyGoeW z)N(G9=UAq|`qZ`lE;mu&0N)!$$#tz>Xzeot4=RS#$S{`BY)}rJ+)mo*^Q|Rs}&Gn}og@zObi>`TNkDHM@L}w-)g=Ho0L=cSbO?Dj66wi8P zoLB<6b?ynMcuEcG2dHPtyqz;|b5GvdXqAqbB#WDFaGd=oJKf3;p^=#~^}d@%Oy121uEk* z1?YV&;xb~+m&|>{g5sp)3b~{ym)AFW`!y8rFxM$5 z7hhb>u6dm#0hdoue9Zyzl`cR9LRw*d(8~(M4^V&4l=r#xnsw>5i59ijqupL`@_9jf z5%!bgI@;@uO632F+Pe_&X|G}~;`_XyIP0XAD~>FvycM`+Qh&DiA+HJx|_` zQyiqYiNokE@RB}FVt24NNE7v}J1;Y&Ib@0sq{U%uhkQ1%m6SIGGwp@=>XxErxgtfT z&Ub&CZHh?yrM3W?CvHA;e9ZI6nnMFH8ZxV0`3T%Xy6Ie7KWIl_$L^r#)c2eR)!C^# za8%m*CJ-Lb58dq-9zv#25HbaYO6|tN19xm2?kX?f^)BjOtB?3cshNC@c8hfx*fMNA zL5=oQC099ctXv8W$Dk~`lj<^eSdg@#igkal!psa790as9K29oc8T-fT4Q_nkJ8!hf zx84|HTWzuUFgP$l?!{q@EW1m2CUS9dZEm!h2n28_;|oIENukaNfKeg&tue?Es{SD3s=?T(LQ1<90}Dxmg&65x>NTFyo>hP0 zI;PX}f-;s|7>x|Q{msAnPU`8{@pLasq<3MWx@hHRt;7iQxGLKW65Jz>k8;_eT4g}* zC}h!YtR$0;R`5esXU zw|pOyA4?wdV4|ydj4NSYBn=`?BSC+mGj~BkKf5#AM_d*W(}_AJ!A9ve z>)XfN1S$Qeg6(4@%T9*|`7~n2)AE!NOM(QZnj6UBsQu$Ob$<9NW33)TrqMGf{xtfSbkvm<^W&YQ2e$X)T<&}^+L2}W#^ zI+m})&4Bd?+?-rMj>QFJzi>`N3=`^6vQ_Ai>dLlE4dzFz8qB+VkbQqp6AlD|JLyLR z)jF4d95}&_THb2I7MfTWrzh!L~>bh5(^71Taw|L|cdY9;-h0 z_s_ZgRBF9M{B40V%(;Kbot_Hta(HF|G3%!xdMt-HAjG4>_E2;f;>gY5&Xl9la7;Ni zwaP_GSfgScE_$rvxS)M5vKtBW-I4nH5O{Z7~!s2J{*n2HOmqDyrc>9LMugmaAS7vLkT!3^b$i~N5Mg@z>ne`_)R;l+Ui z79$o_b|@41F~R(!Jcv$AD|)N|!8H6Wo(DQ6t&k9gst`XwJp%7#IRynowPrun%^l3d zXgL)bF$QZ&cv;W11}r9}ALI=F zgQuO+it3OtV4Y0H!{wb(dEdRNu@Gk#HAMbB2-*$gp-n{NwzJH;e+x9OWNDVy9-#fVbnR8}y_4evr|E!PQfoj8$ z898a=5LTF}hKVlyA29aTUbD`9oevN+ISMaKWo~D5Xfhx;H8(bw;cNmG0yi*|uwyBI zjgP~{`-08X*6}%rEMTqAO(mEjGdcoZ1<>2Dt z!KA0x1;d;`|FL7z>w}=~V2F#z-#lc0p&%ga!6pZUJvgdCTmUK_P5^FR0Jne$x1b0Y z7l4P0OZY#I5U2=14hRR^0Ms}DDi9ZtJ0`s>#MK)LwzG#l?DL<$048f@0JpHPAlvV7 zfV49R3bqEi0MvjmdywB#|fcISY9Kpy3K~`NLWD4+l2DpN9kB=HUKsx<8|TB?7zr4hC9VL!4cKF5X}l zJAf_N2?WqkQ00Jm!Po#m7n@&yjzA}O$U{634g@;^tsWeHmktCdNNWLr4;}v5pSv{_ z>XGwTnulYScd?O$I6H$}VD6Z|>XQRQLDmoF?#=n<@6a|!bZ3J3r|ZUB&%wLRy5uMKp)T|vJg z_b>B94=;ROA+7-1hc-Yjz_y@=A533&ARGjMK|Me(eE$yqxx(b;2H1eDVE`+T9oPl) zuj~(IknJDqhx>G2?457@&Ps6ifv!R6ns2B1G?R}EwX_Hh0;RfYk7AI3r2#m?!!2MKmp z0DFOKG{G=y`#%)(hh6X2tT};QK$;MD@UN!}fSsF*>tF0)z^ok~o*?cIviyxe5A*ZS zE#+OTAvV7TjfYmSVO?~I@4pA7aF`Dez5Q~NLZXFizg-zwz)FZ!RBdH|Hf`5Ylsb1*elHEO=oqxah zY{2fWPC)O!!X8c$4)TIMsL>t#TkOBcKXhsB0ewgd`~B>AaQn~t_uBvj@&Z|7&P_wC zMME4ugtUCGk|y_L-y9MDLceM7hMC=W4%+JR0|zacxiTYY8G0$5JkW)^urAMZAvI5Z z>$~4rix%F0^jfR=#_y-aEA8>kX3W_!;=a*>ed(HBN(>5iU8ya z95)Xk9L+p}@18x1UNyZXUq6RUZ)$B-3Os-Ovt)ujRxidh@ZBVRu2tp~DeWT|J0&^` z{)yL<$&1S`_}QcP)GDu7F<%_S@)r6UukgfOPx&l=mg(}icaS|JGbW`(zQF%H&fqJv zlcGX0<6B&~ls`!mXX|>eC~0!38whjs$YA6r*1*yPaDN*%;i!-qkV!s}fp8@aV}I6% zpr0s;2IhbB%-$!zD3evQd5%Vb9L8X3r0YuuFT-{o0JJ=k=ND{J^k2@!Vh!Ro=`9RR z6O7@1?ad?>VenATHIv!EPyyjRE*QCk-*hqIuSFmUsvs!iC}?n^IvO*}A{99XzV<17 z%OY54=mGak>%oqBHy8HZj$t~wOz-CrA*)=ufplT-%JO6l)gk3Z|CDB?muNn{88j15 zs$c~X?LICWFIN#Qxnkwz;ikXs4;8+UeWBTZYhQShg4%iB_kizf4YcY0W!tEUd!A|V zvbFxn@H-;zy8XMJePsj$EN2x%$EO&MC~<^SyS@C}L~>cN5lf_fCPM}gSEqGzro&@V zq6yESRWXBG4Z{UojACNfmquxTkVjvMJ#+hKR;6AeTc^HfR3;ifO#0D|pXc2WSl!Ei zykzO2oR24+JdS1uIiN?oa7o#Wr=$N#%B-qcS;0db@zLs?#Q~{Vs*66`d$nN3k0yd8&#G&IzP?-j_ujxGm(eRpUQFKwPOdV7f-(QlH< zfB9rnUVB*d)2a4utY{JrZJz*B@B5nP&zt@qT69b!RJ zBwHt8nM?%KV)KX*vFYS~tYOSArZoG8!U=g8-dEdDrMNj;|6Hb9SH`jbP`}f?sc;EW zzG08hsX?L4n!^gAcG=ke?B`o(O&wwDe+`f2deDIZlZ zBAN;>cn;ijhiX&Jav+hUWp{dV#ppT%9@oQ20we_YvV zo{Dy(GwU_k-hzJA!rn5fa-?h9&0CUd_>fDv?vb6YjNP2MZBvK_VSz!}<51i--sg*U z+cjX1lbzYuAPMrzYxTy^gqh^;_+>@ZS8m1JvpO6@(|N4%EnJ@>1H@LZ-kH^ZhG$hw zJEIw29TnybV5L`5--x#w=-V4Te__zR^DU?03HZ9uvctHq4i%srsE)Ua&2cQS2qv9> zKfaE>TXjdAP15oH>G0}4V~11(8FwGiDsP=H&WYOd#e|m@mp2x3J&M3Z-F9hYE5yO5 zVJ_oh8Q+b9Tx^@^&DKXeDwio08xl7FLG3T-kt5H`1Y=fF-ps@&ppVaze{|~Nihiov zIVfi};Y*M?V?m%uZbx_H^A{D&sgVQlBZnGDBI#T;GtBTN7mqKUny79bUYA~;m^1pu z{M2OD|6J>zE5nw~&1Gyxse2PUCCfty5*3&FBDm!8qf!9Vk1YFQifVyP9xpJb?ne;o zU^9K?nFWpv_DGW;6Z7M+f16M*qUQo{lYY8&b!*+85I8N0kW^q44OqGzPI@1Mv(GFv z^4m}ZcL~?jp3}7RS24Nok=lw4%5$MND|s#%?@QR#zUvuQdQ?cP#Z9dqEljg1D)d-t ze)+A)%h581J@$AexnM4?hLhqGTSr++G(wZW?242HFS3|LMscsOe@=q{rEl*agZ(kx zao$DY6Wx}1hF{0V=GSNxw7%5etB42%r%$ScsjiTI`9YtUOy)b~z4!)60fFo%tq5kt zEVs$RUH5V36BBHgY4=c2)~Xr1+$KlLw>KHqFb0bh+1_Va>zT@Cak)WST9z^*CfoCtOldddHoSMr^vEm^AnSe=SDPNBXa7@4HZ>69uNj z)O`a&KhZZOo5hmK-F&bV-I7q=Z>ibJ@7uJir^(2b)dBC!cE5qxj`iD-L^+Xqh(LIA zyi+LkP8RcKPE3K>sKlM3s0WO%S0ZgorB>75!e`gYqV9}uD;*xI%X}~kE+jnR@cszC zFyQUJ!Ql6ee~9_?j23}Flzex_=%-m}oMjFTnETZC=Z9+JkSdoaerE_}A^JLO@JfM& z-ZhSXpz|}ob$Y@%iSdcGLuTCo+4k*}Nk`iJSG?4O>yQspEZTZAY;n^95gTIUbbMWW z=$0{Fa(yQ~h!7F^Y1mgPU$qbcI+5_yu!=M@&+VnGe~WZk>5{BuMhCN8@td3Hd=aSU zlt=Q?-Qoq+BO*g;8k4}j308f>0h9G2E4D>SXW$%5V-#uPuz+x?aa5JrU_o6I-q?+d3U|&bpfLHS)_u_R*c?Z0Y4iW~KHPMaT zBhHL}f4V+H^zsk$ML4Fx7|Qn<5Hm)&fW&dYtomhao1UI%)vx$x4R+;K(NC0VNBEgy z$$+1;sMDYL?^EKG`dUmdSj}bGLd7UHph!W_$bq)n39tKmetek6jCz!t)h-Ocd`w3j z_p$LDI_6}s|B|?+$$*Ot^;Yy{)lF87q*AOpe@TPyO8?;&vORfrpK|H~ofEkBc*ncu zHOUi?P+^l~^dUU?&Q9Q*ys3{gzX zrr9IPdD5y*He`jfE0HRt+}XrwCnIcy6eXR2BO)-xr&mv-I>j&u>GTzA4rq zfBGCEMEV*SBj|9OZ1mJ)7}6Hwh3L)?64m_>v1$KUO#^CF%LS)B!$umDmx|m30qt>3XO*p8(lkYN3uei?zBUaJE-|M9giHd9_{Fo+Xj0QOp~n%QgCaw-d5AuyivEAuN&%+EE5dMuafag{kfNNJUI~L z*&^-X@kzp0w^z;XC}W?cXrj|@0F*Cn;8k>vt-0gLxZ*M z05k?#3tvK@y%!~yc8DuBYQj_eAnDbDaFqV@5jtEEhoeo*TEWMK9RhVvD2z5b#>}>?tu_iSKvtTS)HNTu;YTLmso0G@;+qIK++E4{ zy{3)XMp8#VMO#!ko}cB|Jv~E3K3^H5R)m;bdK18_UvVgBf9kZbCiDyA5;=_M)vDUC zM%2Bw^+;+ND(vxh*2=B6rRsK9JXIU98e`tmHsV?Bk*M(Iv56E%`4~Jx)~xp=`4lA= zbhtnJ^IIc=P?!{p7>i`x#um**d;-UTcea_PeH@AU^jPUQH^FDOm)*x(P$L4nqYqVT zakbk0Yn;(IfB1WynCBLT1G6I=&29To4@T)_R}T;Y>(En6BQy!OFo3}~L&X*Wo8yS9 zHe=jG?DkXQQXCL=#wJ1dJ$g{m#p#a>-Nx^E1Bb^J;h|j)=F#k1W+1KksE$Iuj|1Qc>R7gN$`T(z*#etbe2J9hQy#)p%ZHDz@9{Rb1Pp zdEm9ne~b?<4$TlJ^rv1-5z2G}b;h-$gB_;Z0oLwx7#N zq4^O)ZH-B2gt8qIsu6?R`t^r(0sh6p3%4h2fBdM~sVS!QKT?>Qyr*c0<8O=1*XH(- znN;7^Kj!A=opXSP`<&ZHO;Akj3hy=~RYYy2k_%1~7+=U5T|PqGjIDXu_*tWKr9^~{ zrXlfGk1$mB8OyxAiDFFMp`wESt3fX~gUU#r-704U3 zjLFG=@EPZK&!XedeI&=3xHNZsAT@zbi9JmF*2A624qlm_u(=_bb_?H=n|j0;7j9d&-|qDpG@Xe?@Maz;ZueaQkTraVu_$(|17C z0?>micpU>15uUkRoL!JI5_XHnf5_9ZbYmLm>tnU%D6eR03GI`mY7@#0Ao$@ zky<%pbm0{^gKq*h(+1ndIW#Rl7;p`bGxD5;acxa6AdJ9oJe@eqK+#Tb$ASV5DX$kP zdub|+Qd51>r)h_7gB6w?wTIuY$+%NVB$7qqcQ|Af>&U23NPmAiIoGUOnGCl7B-j%mceq??lvrif_( zNMfqPKJdxOe*PV$ayoXWe-p2S*O(@nQsO*L^b;hktjkY^s((uQ?=%?_n> zN>$QA(82J6DxP&M8 ztCYFq&Et>TGIjK>e6(|cWBS@Pp{@QN@p6>&bx+qD9!jtUJGbnqZ0A9@f_yZ*|HVjM zA28rm%u$2DfIj}nf8Heq@lLJa3jnA+5rDUoq3*T1WiE|7)3g+-? zJBWgqkv_vwcgdEWcJ^abW!zR}c8g|2*hFsKUOKnN%UXEKf3MX%hl)T#TIb+f;w{g) zPbW3*znF~&!4JE6PK*SSCg)zsIU{X+8(tfo9RX7VUO5dtMliI#XFrncv?g=J$63`B zc-s;nWJ!HL$_LUypwIgB@j7?Ia(1k_zgJ(9Lr3f2^rW6ToB*MCE2&DsI!(+jY)@rs ztz4fJ`aOPpf5OcEYJPPYw(PFSdj+w4cl$&je~C99k$tnI75jS)HCOBGVEB?CUyJIU z+HvX%88?drOQ4)$9sf%uT*C>5KKGBWNIgHXoPJNuP3#)l5GCK+aAzuyrPGv|YXjIr zG+^{mD)G(T7~P~E;|P~HOB^CUPtQ{#z6J+l-!p*Le>dH!+$-e^`ZjripOabM-f8Zo z!;@GF9nH}BFA?N!1h!%&%e=ODSA4(HH;h%vpB2}E_3t}!?j8ER6jwIBOVZ2_rc(DZ zNxOV}Joet@JOEE~W}cgp&H!x;UYIT|wA3z;Yvc3!W2WliDNOOmieK|*rY9RmW@|j1 zUGt;Tf6$n_F$Iyijw9p~zFQFw0vY`)DIkT$W=cn!t%ry%wwa%}0cJn@71s`1eGs%a<2BP z=)F>Uig<{F=)O}w^n)llImzm~P02PB=PyThnofiBZQ8yzdJ|)=3QBD1B~Ro;n=B_~ ze|lm@aV%8|vwM(Z2QWwh-y;)I0{oAF4BIb1XDWT-32qdMT>HU35SF4IJtQeuGUu!7 zB1v^kuQ<1z2aRFH2<-rEN((h}@7I!x1FlIV$Y1jy67_d|qun;4BV+qgG76}bY3;5(rBIC)-lB~qa-o;+hSjl^FUcd1^lij3-*!0n~UjH1a_VS@k~;O zDdZ6(=xnTmk0nN2Uki9rYwr+HSm&3N z<3~G2omk#^qMTrEbMTKWD7Gg$hPks$lV$&2SaVi^~vYowZ6Fv5mOv z+GLsN`6M-XCP`JzL_hx)+p}=!f4URNea^F`xGzuA&2*zPix;fUt4usUp#4QmR+~7H z(Pxz^q32L80(RiH5;p?VJKO_epB?&a9ZV?AW}$z=$UiHS%2iQTc0O7@*O>{xczhNA znlk$hjse!=GW487Cr>yxV->V8JY!4*pWf4V#vUf9dg+Rdei7 zS;STU{AuGTU1Pp;Nh0lgAKm@Vv~rT z81e_M$&HM-Ho8V_Dq|}lY!jBexymS?@!%s7sV)MF84IXtMk^kTJPBHCLKYbo&$`Nt zMqvb9GOzajI}S0A%UzF}fA5S;FPc7_pk-tjDK2UX^5 ziltS-*Rna*B98OAXsT~&NK{MmzXj9c1l4_4w7i9_5bffW|EIFi8tme^xl2nen>z4w914 z6xr0CbmS1pro|grv9Z%XOEH#W0X6D@0n}om`e2IpWJ74m6wyz_yV);vIm5$-#!GC6 z%XZ^#IMFtl+;Sdo^{3+dnt=r82SUs?qU_PW5Hd^j_1E&r+xiK7)?a$kgRex6s~P3n zYSTzfpX%Giw1GB-e>d#YWMFz1prq=yE?-5Ye=@oqZK8ne8Z-(uCAkEK7Lb5ZY`CA&AppTdN@Q&9Opv z(pheNboH^Gi~l2=#n@nW3cxh;qNPY-rn`S`Ol1h!_@dkWf6Ee~D{MK*1m>5-4n?HPg@AlfFdPY_}O*WOAU@kGkw&fT-~|b zS#4v~tfX&pK;QCxvxs&A#bn7lvqtQWS71#%Az^;u`cv5&|I?Wo(qImP>j|a0IsV%B zvz{tk2=}dFe^T2BY6GGwd1%wS@vLkSIbF>Q7wh*rjSBVPX@zYQ!dr7PFZla6dhCmn zsN4SgFv@6Xgs<7zeL6{p$CL6+l5!e&A^eHZKCtN6XjRjT?=GkwV<)pjpR+YIFDuVsr#QsyFF|(uOF}kFJbMt4{Q- zS`PCPe`}cmEjZ#w=9lx@R=-NS->#N`r8=Vte})qT#&e)X$-zmdbhds7ye*E|=DWWh zZx|@MiBxsA*Mv~?#*j1M*f*^A&GYwT@7{*)TWr*n>zaN8pk@U_$`3<}Fq0u2Rbr_{ zmL(3epgcE!N?A*hZ9qk#yX9gFsnC#kUtpSyIPQ8^@+ ze@KxmWJJ87CK|fU%%jx80iMvMEYCW;8R;LqJyF`U!MgGM=wMKf;3QslpLYms2l9>d z;p~#~w`H0pvAASX9^`+kpISn(8gw7yYzru67Mi}hL>j<7%gp$c8We4$PPs6ar(iCt zPyMn(jI03=c~qZ>#_YC~k`dOfjdR-Lehx{6+h$&59;l<#@se=y9$ zvEF>O7uU^!!NCEKcb4cW!fDjw$9vmPQs0?SsK%7r_#u1_I-b-ltWwm07&+*rvA_!3 zt{dR8>7!k9EVRdgRLU91vATMy?dK8a^7$H%iDYHA3c;{0(n??XDkDx}e7@=mdC^%W zY~M3$J}lgg7cnCQxRNO~Hz3k3f6l$--)8h)LkDnvEpq2vbZZoPG- zRLgK0Ak}>oP&HhjLf5^E)Sb;sL15x?favY)fLLMd97DKf{Y(ZB!7%6^e~_!p4moF= zL|U`!bla@+{Mxbnu@~!!Nd~ZF*`|)&co!0(PWkipN%axpxkpi`j=_~;F`6^+eeo&PS)0*QW}cxX;OV5a(avl}pBZ4nY`gt8R~ud;6g- zSGHpSckA46kqa9tP8U&Oe~hlfdA_6dLx)mH&L|9!`*`8BPa7&8f?8gun2Z4>e*D

COYlx{iucqdC+FhDz0z=34R zrDZ?p_<=9Ri{)gLHS4?brD8^NevIeUpuC1Fvpy7XDQ_f4If`ja^$$isw6? zXWHn6c)mJ}$M3VVcR%&1PYDT7FrP=oK-tm2lZp0`o{Eue;H9VMJ8e9;&-?98 z(hCFaj6o81w$Aj-3`{%#QF(c3W+ng=6DtD~6AL^Ag_?!4HR#`RcnS@WqmzZ5Ezf^h zh&qCdoZn?)M$Yes@^*i=02vo+05dCqnS+O!lZS~3z{14D{cl4%M;?Hfk*fs|AkP4h zv9kp^!BdFZ*?Txzn3+4j=lS;|fXaj#z|76fN%s$TfUph7(Za;Y79elrY!0${&uC&~ z4N$c+u>d)H{7(ofK67VhdmctcH#av1BO50MJ4Z7CYC3?Mg|mM-Kn3Ika&!d&0e@Ns zC>Ys*{?!@-JOx0_+`{Rf3ROE(XE!595a3;4ZD9hkb$WMku?2!00q@xXs?u@*MSGC# zKaJ)7X+Q_~*Wmz|8JPbQ?qA-20$JGp!`aBh#LmXv$kxNc)(l{3VGRN(O2{!dyF1eX zjBJ5_42`Uv?B0LsjSJHh{{Pt3v*Wb%IQ9*qCGTq|2UH(RfNlc|L*(DY9mKo@&Pbz2Ju z7m&2rzii$`@PB1yAZGwO6Bj2d7drst006n0m^1!Kpyq#J5Bi6a`H%R$2OlqcJ9~iX zdmA7h3scbh7rd8~kt+z`?C1jW@%nGY{}MbiGXQ8|;tVhbnOWGv|Be1G2ATeo-|yei z!X2Q)^ge#f0H!~m|2*lvPZ-e7*4pE*`9H3hQBhu2N=<_HUoHPfDI#L$4)CI9WdYE$ zurmRenb?200G#g+KK~m>$;jegb^MpFw5_Qf;7_nW^}Zj}ziW2=*AP(sYeT33{~Juf z?tOGY0II)}uFJ&EWb*!p`Tz60|HI|~-(j?F*i>VFo_+QJs3Wanh@=N0qr#l-Y~bnjbcV)gzSaeAN4f2xd} z-dE1~9~b$DLGMfTzjcV)n%DvVY#$3d2f)bD(Z~b-{qo<59pJ_MzNSEs`#+`|z{p^0 z=lp-}0(kG)2ViRF2><7zIoJV=!hb~nBn|+h$Y0_FFpB;qZUCeBe~6O_z$o#Tm;sEE ze~AUaDD{_E0gTdr={=_WUwV(J_#fhWkE!&R-eW5NrT3UBf9XA@>R)05Fsl8f_Z~F< z5*L6`>p#T(p55p#z3YtsL+tOhyuZwB{_21K+z%u0FTSS%f~=kY%i#U+K=$viEIV7~ zzryz%p#L^vdN1Adzwo_wv%mO8OT_4lV8r~ktDgLM9j?+)+F``?ZI5xIZ< z2U*@Txm*0zzI%KA+x&k<*2Klp@qMQM@veEF=YR7*emy`ScaRDE@}ivyZ?I)uaL0X( zFuoi8-XtH?dD^`e3;krFKCJVA_^iQJg6h|-71?r$<$h)feamhI5r_Ni^&eMWyY<8k z9&ESt#1aQ)#Kv)pZ?_-j6TR*TNEd%mTEOx&Q$&b(N*o8klnA3xd*B3tW&^4eDBhHH zeM^aMpD;@$IAuaQ6uNq9O0(p!3Ai;*wpE;4jfd6t*spOYbGB{11norYMx-iakjnCP zJ-{cpRikbWjSjD(^%M3+1<1Gt?p=_FI-`m64ikv6!BlIk<|9Anl(-&epnHEAOJWEe z0|zQLs8jCi6n>lU{yx?tp-SrEG&f8#jb=Xad>}-#U&RzjbIdK+j|BeA4kLzW9ui2r zbJFNbw~+e2{%xDkN+v8s)?;P9Z)Wq^MK)DhXKFB*icUU(|Fv@W#HW#>Gse|46ugbH zCIxL*oEAHa`pCyLD1VUL`s;t{Emg?8CW{VNnt6wsK=CSfaGSpt8Y?T3t3_IsIx=J9 zuOXNs?OQKTw%7ctt}c;JD-P9BwlV0@o}2Zn-Wi2?kLS#cBMm0$wb7!UZZ=!D-qr3~ zdU8WHc11qlJUeXIPd9&{#YWrl0En~8j=Cd*V{jPSB1pge-02U$A*z1_j{}00D&$r? zUI$=L4BB;ovBJBS21Gv|d%hflX8;u7?HfFy%9XHqHDE12{+ENw$ zW!P+lnZ{pKSeq7GX)uSqx@hyU+jh~p(Y8V?T=u5qlXew_P|SVkF@93TA_Zb94+kA4 ze2MN5-n?$jiK3pX#h-saMeHc$4}fLhF8h^re9dZxk9U>Dk4&u7WkCF9{AOo>bs<8a zQMmCq7&r#g^jnjZ_!Jj>x9Mx<_f4bUhjyPOoD}1!gOds=&VekyTiv1++P}?73EYVJ z++4u^{2D)?os8UZ+EB}E`MD~{tP~l#o7uRlHA|-4$lI{XJf?rd*pIr`O*`n^MCTKe zWzt2R78s|;y%{`4nmMj&b4dOtC_f)``&ateBhy8FfYH;U0sH{IHJhi#;njhy%GG8! zp+O8tsJfm8+|xTHK3UU(p_zM}I(8^MQzTS1cEgEv>dP0aTsr+|59o&#`mlRxQ@I>l6mpHspG!>D)W?{Xw~VAFYh!#{BSB zAJWvOl$gDy12FI~ZF3`H7qTT*yo}X4$2&}+L$^=T?D z=Dfe6l^@hb%IW{x!8v%-^wFmWeSap2x+athQdMP6E7{{CI$xGk1B+#{qJGC#P#Y>m z58@Z~uWcclUIOzmjJcK7Wui8A8+%NX6qP=C_CJ3=0)Kg#W3vfFqDR8$yNMNF2!WKZ zfyn(3M@AMv?HT<|q3%XOSbIbZR$hX-0Fi-KVM5T;6VcH14I;!0={H%E!+isI_-ldZ zk!Ll#8U8{V0*scCu}6(lf~ z$u8G=>s~KuN4Q}$;>jNuu+q^q_D8z1`!JLjaTkBA$sy%1>S#bi25BE=_{2eQl(G28 z1~Hu(Xw+a&wnxMK9A_-y=$9)B7q zTP0RMYu9?%xlcD)R-L7~7u2bCra|a>G*a7s6l}}ZI0%$!!XhSf&qN zikiSt`8KYRP?`Ojww#h+ zeB;pQM+MQUeO39}1&i|qq!oXGWMs6#sk`t!#Jx*anje;Antflzj<^n@$bZjy|IQ|9 zmWbRK9gl2z#XDS)OXM~1g9j?7$VihnwWaiF4^u7SVB4rT9AMlP$mrlC_?j-FLU7Zi zRB+U9e>7lzESU3k10b{?ml3GaK?yQ{5e$MwxLOpRAK37)rV8AV`_O+n<=mc23~{a= zhkkZ)0M~d<~42iZspnuruu*R$~D zJ1XPs98s{ir3RGOSLTQ-=J6o4+GGv6msxfXO<8YG|JkdZ)C=#GCTEyJOA+8jJCci)-$yy{%)AI-Z4#HdmN$8B@#Ru;2< zTCB#DPtBA?J0bNgcfwN00+&jEwum(;|X>16W-D@yTBjKYMnP*@c5i&&e71I_{ta(lfGo@z2WpS-#@+moq2X?qB@ZJ4_(y-R&-GvY-(J;=DQF%!@O782 znnd=u5?A8+MvwNCqRH(cEWi2p3?91mIfu|%l&)J;70Q&)XE#6313J}<2F5O&4z%08 zT88-K!|Q%`mJ&UJIUju>N@s)@+u8%PkHUFbfcke3(;+JP@~ZK>j;3C`zcYBHn$(0@ z-!sJ)gj0W&V6XUz!lu!lO%SvYEPrl!wI>IBx zO0|EiC%=pP0}TZZ74vpAPCww=%z|Qat@YZ}vo1^AblVgpkf~LnxVv#8<1Rj@EHWar6042ZC5ZA%Fsm%_@AubTgx@j`U?~BI^RktNEoU`a}I@TBQg( zR+Prq>gRc@@0Nyszw|k^2w@r|I(0CDr)Gce zNQ8F>qbMebf3HZjK8sp6*OfFh{%~tV#8sHlOis1_dsttc6{FfAqhbE$eCJ9OinQX* zwL7Zi#_|;nEJiRb=W%sRm~gInpPix9iKk0%2%lGqr7EPePSCo$q0R&oefJeisp#&S z1O!{~^N8M=Id+K=k8vp8m@hOrarJ-2>WOjBYXkalCdn>yG8ZHG%fukW&PfrMBn4W8 z{ba|;@nEz3CC^;)qwULgauZemV|;d!@`UU*rsT-&6`>H4lqTO@F}OK0E?z{xyx$FP zS5AL6{AQvT`SA?_Yl064$3Hw_cw-Fo5<47yL8bty#Oeq}=Vyezs{?-y(K1d+ zv)IZ1KGvqFUrZXS9Yi@I5>PAm>K zXRm_U3`<3_O^>&{UN<*tt!#gRsG&VM-@lY7nJjC#Rb)s-VUX#sM*})=HL36m2_`Nt9%5#S4;$ShX#9hXerI-YIF`z9eS?M9NBoecEQAQZDs zsAS@Vg6dGD$so)8bK8FpM|6hJwH?j{(O7*^k=(7QgBnc!HOIIa!<65cS=J8Us95yY zy3-Xv_+MoYl9=iVPXtS5?U_^VE)n!&(taajVxbu-`KrDV^UJQi35q}L%i?EdeyXRv ziYRc@C1-&n*ZC36=)P#r+68vJt*xF{=@10fNCR$|>j)^j6GngdmZ;7(I5c1vM`Q1V zNbrCpUUX}1Rbnh;t4w<}&Z`n1ZJV7C!QwF$T8$mN+~h;lejt0eB&(qoL{`Ctw-ue8 zY%k8!{?dj?zF1RWtUr?0Y)U;5@SqC{rM@M0uMi(19~d_CbX4x-;3j(vt<#k`aZ zwoOb5_b6wXX&8Upq|vvx6IOImrwgGXFBBBx6k`` zMe_#SJQ~Ke8lz+POEGcvxp2SnQO8h0!_%&HC55%;HB*L>uhXwYF(pw2Hd)=Kwcq=K z;$)X9wzGH1q(@s;WNSIs2|}v5kKQr})Nj{Px{&zLm_C1WNwco%f?|Bs{$nZUdWD%U zg=fj_7YUWy>xYulLukE;P+-j&YUBsf^0!+aQD7Nd*ldjQgx)pH-DElZh8%c@$v&r;D)Vp^rkx z?`{y?TcHls{-tLlk3$hQ%u-}!hf6R-F!}FaBX6TYr%rkXnXhX0q^!fjLZ9|MggQ^Lx90*Gp`k;-ds6He zZ@)Ot;32ppBwyXoj$_ksHl0gN8Qd%LUE?sjIw|_M2C03h|7o?ro(j}*dQ6dutqlTN zY1)5t?m2j<%<>HpZMh@xU(;u~hC@C}PGS1gXt$nunxxNPS5MJXTYz8MXe@3}Rmx?g z>}Z-rm3?@1oaAS$Md|*;ETQHju6NnNnzvD+NWC7Eag= zOSS<1t`k7;Ej|mbK%8Tj&|1?mj1QXa^=$j<%=bo_~k?7iu$nGQl z7Fe23;{j@%6vzvq6*2&+wh_RZ8>jpYo%w?XMi+ghk@~JFi-i-HXu=#(z zoul#TOlA|A&w@l?ssayJUI8|x8RTK{2CTZ^I`!_niZOr1%+rcp zbhCfjfj}e&(oX-7FLfH6Vgh_c*^rhS`vfED*p|0ddMOnMmz)u2U8bT-5}{=?k!a|q zH=BS-{>F~X+Tq=Pgn#o7F+0v6?7WQ!Sj)U_yZ)pa0mtI3(Ho zEi#?6=yAGJowTvpBUCAIb&YpHGM&@hH_4tR|DbIa5&$vK zuh^B(eK~j)#jV0cflPnN8}zpxMLi#!(e=eup~WJ1?Xyb}D@tE63*CTy^$2)4$~`b5 zAmnta8>GfIxj4hJVn(JdC}ik;xg;9yEX%x)A;TUL!Zs<8t3b5Cx9s6ns0ljQ6czEN z%I_Je-fos|nUiDtR?9T>IN0%N75_`YE2i=Ol~`{_JsNtH-?@KUHfwid3*NKnVF4H) zKcZNJS+~!nP^VypyRV#LQ&&9l#j`qH^pIZ<{v%c zZNOhrCONNzt)_ohe!Q`$AwV77V%ijzx^yRZgj+hTcuA(ZFAz;zvcy2x;p`!^5I4P; zHK|S1|5{2snYziYw;jg{t|5l$mx;#i}2m%tjEvPdpa-c>X(!erMJ2cBmIkAsPBEny}{FTDElLwtKHp zoxdZdH>-c+mic=r&gzjC+)1`;{6+&Fl}amWmcXVBep8UZXQZVHV7tLFSDT)az$41y z5E}~7uS8c`>vg>l%uZRU0{OyL5krO*#(=^g<1?dUJ6|F0%H|kq!K+tp0c-(us}#JY z8D_>iwrXaS+LtG2&lb5zzwL-f^ zDA~bb@T7HOY^G+bg_}N5xhFN=>fxLAr@Uw-UgbhTA;!~sI+OsbVORmeAlO_#GUT7> zadCsKuLV-d?Pv1$Hze0cqPrjJBV8n)C+X%~eHU}mkHzow6)aGiG*}kNok=3ZqBnJg zrp$kSO=@<-J&JmYEuzJm3alV9g$~VALS6?%a4toDHDbV1UYSl;rXjIcSUV^#rHu$r z6TBi7K&I>F)Nw%GT7;o+>0D^Qcu@`X4u(RhRNBUh&pml87aE`MqB73jzjzBzfT17b zbaIyxbVR{1D2ALbcB-HI)s|stq6Te(TEBm^$2vXtWb3jMQR3x5qW;y|ZWcA?#{dnt zR%}IF&G}T_#PprEFoB{pfrDF z*XP1%O8v~_OfaZ(h{pw4FLez{v@aYJHw@l#rDlt^f$M^n&7S>e+Fw_Dd$R9J>hqCG zo&`TpWJ^=9@TGZEA?BCUIHku&$+-_HElrQ|k|9IJ@Ub+M^=X|k=fnY%;dVbPPq%V~ zfY&314>eXkNA4D6Pw>rX*2UsEe!_o2;V<(P&wly=kZtsb^1e&QHg$|41CEQCAr+DN zd~nP;BK|22R8ki99{Ye{Nu)G_RF>YhENZ4x(&fvLk3)J0!y=`{3yJw7a3o|~0^t4l z+p}l72*(&d*h?m&WJ16Mc&HCJQ@>!WsW7Au zbotK-Lq_W20{eb!;gby+k?HK7LEyfA>7fdV&t0&--CBv;Zd%TblZ%R3tP6vI?TLKxZj}M^o-^a7U z(#RE*W1;>nyr|RVH&v+H0=PN0F%)8K%cq`sCcm*i=^3mTc^2?ZPjQ z<33{nGNN#XP}Y4H{KT<%9QLMCyn{uO9Ab>W98Au43z&-96*0rz$Sh;sF7BCyRNdH8 z-OD*Mdc5wRU4@wRd{1m_WL%ESbUl(=X;Qcfl16xJ#$N4Q5GN~z{%kRS42XPO{mNob zT3#I$&}2sR#Slo;g1zC{ff3Un^EDfXQmANSJ|-*qo^p1+r@kckgGtA&u20nHmgOo1 zKP@YUYzwV0PKDqx=dS?h(G+C+DB>q6q6uD#*yf)+Th_?DpP}2>sJT;%CXv;U`PnKc ze1tE~f5aKuD$Svau?OFOu12P`b7(It0ppcpbcK9Oax6^m;|^X+vii1k&?fzWh`oE! zHzz~Av^L$EU4UeK`C)IEAh7u9yhJs2yI#6Qq(>IqV>eLE!N=wrwn8<8PMM0|p%YVy z4W81qS?fAnW@>&d=Hjn)?oRbGw|$$oQu1KeE}ZVed7I+fG4#-Xsv5CI5m%pSt~5%B zY)Q{PYYo*K(93YUIG56NP}QzHisNrv5i{dW`g%01JqC8VEiSME=q@J&iuX%HUXHg$1X z0`B`roJVwNqLp?zo{LR;n^6ZE1^C9lZTOsE*ot2VzXo3I@@ zN7^cNGA+*1evb@t+Kd_mC<_v|esJsgG^c3m(1x6FI)cA%e=4~;kZrcXhau+VVU=ud zyZ6~^#^zXm%XzF?i5Oa>#qop>DV8M2jQ|2JA=|WupBOKG0Tn%&iHO$>z!#dNxIx70 zjH;>in4!=u)TvmuCa?SJd1l0;x08VhoJ(#bvq-Y<_5xF5J3dau#M04$1!fz$nNM7d z$&p1C;e*kI%-ln(*e}+7{G-oD+ub}mo}l+jT3Hc;__rM6u(d*fVH4c4w$-mg(z%}eAL zUnLxW!>t{kb8|ODTJj}DWyz6f9`7k;B!(nh1Bys#!MWY!)R%_b> zJIdpnV=cBUg#^;4we;OV3gG&I0ulVId1 zk;WEEJq?hdAD^T~pMiO8gTP4C0k@gdrNkTQs9bwHC@)`x&cM8{@$P4Dh3gATw7dF$ z$R=YV`yh)zCtO705^L-~g> zW*Kn+1DG^sQgQ5_$-#%m@rjFPHv8-G5Pc1Ze$W-QEO$SgrY|O$SxemzHK%b}4iSa0 zg(Ov)fh2OxA>pHL`mJf?H23+B1*}+qcu*&CDTZR0kp?v4)U84k+`<0C9MtA!e2K`R zh}~LLR3uu03NFt*uK*uD;dB?%>-B2_!>m0ExhyG^FNsu}b(OWU@l7<^etW;fE!ub# z$82ZMkh2>VGKqOQBN;?v)0|Sp`cT(%RnZ@3% zFbTX<#;p@p`@n%hhUxp^vTTg9A?a$Iz@T(E#j@{~MK5PeuO@Ymh+gW+LG)h${ooE# zXx_FBAxj#37Y}F=zx6sJ%uRxSJ6?3i7JPMl$GiAPep^%QRk?=s0x4Z0_bWf6b7QFv z5Z5*3dk0muos|A^!k@U?-HATg=s_7b^>9tH9mJ3am{830^R*1iYVyr=UaA?$_BI~M zeSd_hW3)?Ky}cHPj{*bryzMFyAQ`h*+0$o)DWOZN7$_FseT>E~CgQe#STmO|xkhUW z`NhSJLKC#>%^Oh41~;8YHDIl6ZKYDA!qlBaXjf`d@}6xt6YLrHs37Eat0O# zRl2&HFhxqqp8C?#%jilEtH4?7Q(NFMY;6z_-r3(lj~(I7D(bg?NB-w9H75sIv$F73 zbU&HAMRq4h5Sd3ItcC>7M_Z=s<M=3`T1zlI^tk+KS*EohP?`F?7t43GDC1@@G8DX#uJi5V-;f8Tav#^)*89 zHFw8;1;?}NMwSJCAB-hQhZf{WrK`+Asp={HxJT@96f0W7n_j zR2?-4$+`f4{gEVZapRgy3$K$B0;h~M0Z~|Xh+m=k8tB|BGDNP%^yWs2oBC9 zu5=wF-Bj2<8Ir#OR`HGweznc@7Cyw{c=m762qZ0k4&gP@qGL6EO)l*{SPdPL=d7%_ z%>33`ZvSwws43)OQye>r*#&DCqrehU<9G%2GN$)ALCr}$ch3RSMOXSaRtkU}SLtEzMIkqBoFN9N?4JQJr z7!wsh=AK!LEVH*S+dW!WW!cMp8tEy$gJuU542Ai4(N%n{xibJ1(93pUMN`wq?d&#V z5tddj=P2^%9=LZq{4|s#z&A2!wp?y`AxM#bpsjvo$t(QmQ5b_ksPLRA=y&c9C;H(h z`dCqPAo#ob9k zMa_JYLuZc5?<6QX+b>wocFt1>K*Xw@Q!m9zXEL1|{kHiL;m2ltXL~?v`ez%zm?Xoz zpPuH;!gA4W2IA4=2b^94;7wlSzau%~UV<6P;@8|8CvzTG=d+%@BDd~_CcN5_4qHKM z#}WexE0>RG)#j}S#SHLt2y0Ix5j!YVj?wS5n9JtQu9z_%FmW+;K{dLU+Jhb7!5Jz4TY_K zp^JUXoD?5@vSZ`+G=<|zF8qClL&MZuu1l4|uR2BpdzG!k&whdpcsN!@81NGOCC+ml zZ*8t9UQO1^FkCZ!X@lzs21T=f!~0yD5<@%e-O+Cq#h6(1YTqoN!53zyyjN+iYfsBi zrV{+>^)4Bvqrhv9T1fGrD1W@RnI_O{HKVN|xCLh4&ya4JmAf~t#$dL4nK7`b5$+_N ziPwsN9dp57x#yF)|8GYQoi~uDd6m3`SzpwHRqTi^b*Dr#BRtxbU@oRavxxQwJo;smE z%}`~m6&0#au@8kT#hG(xxvnEBtk$%w}mtsf(l^_({W6 zYXyeHsHN-z;Lssv5T>7n@`Ec22uJfM{GsIBDCQz=$(=L3IYO@KA&Zh~9*P=;7`M{O zbX9t}l18vr8TxN?_4ziLA1P%G-$oxX(lALDa(&zY*%WrDn8T2NmT4d0OYKlu0+!jK zOAI)Bi9`VS3ynQ)i_YvBl3a_js>Ff%$`SLnTj#5COf9W8a)g_(<&f8-NVNfdf8aY*1uj;d0 zidE(lgq;$)52<6I!O&SwoxXr9);14RWQE-hnzCrN>=iA*Dt9Mo?Svl;#t&x@WZzo+?|bpRQG&J!rD`C z-f=DmtQ9afNC!#u!iyi`a_u*WKpo4S*?J8hzPOkSaa$(op+mm|I@c1N>Re{XQgBXplQtV`9zq* zN;orQIHh{{rqx#}Oa0~azCjoC8o5e-JAFnv|0Jcy_3g$}By9T0ZINIDF<-FdZjtsp z+#FF_x_atYk8s5PYQAF_ze^4oD`UBNBuD*&n#_K$^}%0yQ`jpcqn~Xt^C0F5LNT&^ zR^*(2OZW%Wb)n_xh;8}3IpOTo(#ei3H?Ds?65^FeO??g%SBMqv7xa0kc2s^WR>GE| zyfajmf)idz?*|~?Pz}*dHEs2sGa4E6nh_FOl1*r$!H(n|jpQ;~26e6_@+ej63+<|p z;PiqCh{$N7SQ|dZRSq&E_~waV-(uw^uQgJCW0xaM_15de`6b=Np{=tY)|v1S5R^Xw zYN8rg@&*@&?r78$%qI(Id-5CBnQ^v!Usp*+%{6Kn!|jc5O4MLcD)n?;5aigf_itVB zWHJmGQ}^HE1s@SCzhy00Khb1@hoc(q(A8w9E9ihxX%^e}tX~K(lx3(<%TgN^jEo3> zjBjf_Prza65=(8Eg{9Sg{g|HRS9r8!pNt3roqAG284h3krN+4LGv&j*t3#s4P1EO4 z-9)!^qp7a!eU6D0|GTi8l00xmq~tT*tVc~&wrRh!P3_YZ&OyTD9tzZ7-+k%RUyex> zjhS%!I2CeDKiH+-gn9%dv&QB^w}B^ry~OW+7d#6G&On44Vq~7C8JiCBXGYUE$g-tl zbkV?C2uUTe+ZB{;-D$7`?7+C#r4h<4SVm4grF_XsAJ2=xZq}ImDB(W(T z+0!iZxv0Av)3??SCGR-P-} zQ@3)((`D?zH%0x~(p+eHm54=Y{hNvqVwoU~`pc(M#7Hn6uIleXz>_Gaa(V()He@hy z_%H??OU~a=Whjp_b?LL4FfHZ#ebt-0?fUZMHf;{NIR>r5{ImFnKU4aE$SGOyo1lFd>(!{yaB-)Pr_HRT9iQ$~jvma64#D;CkzH(ocM2pSzw$FSrsp<*OM6_x zN5!dZ-|a$wUeOkRV^=O!@IPg~c1%Y4OmGy1wD^T3B0DbHWC7@p=rDuyMk9|xVoFjH zlmz)s*CDUY$-IJj64bl>>&>@`2*U;uy|Hq~SXOeL1L_b{?jaSsKkSHQAPi1Z*o98v z^I#E#4_7Lo6@zoE2y;A`(gG7F3vI81W+02Qs){wB9X$Mhk}bwPkBmp3ogy&tsk*L+ z8ZMsLxvv}_h80n(Xs(S0o z&`L285|WaC6eZ-tx0vL@3oX+NS|z^1uHhpV+v_Qs}3fHtCI+J4^~xY>83#K;}z@ zwU8U_LZdMb-?==K06YV_Qf)^cRb}}q<9wcx*kaLt*F8DZ7j|ShfOV2wi30HU3<}T} zO|*N=Mc+QgbrqGevm1%u_oF3}vBZ6O%HfiAyNqt7&gaax-HDVOuH@zG#X{bh_E3(6 zv=j z%CZ-KoeVk1hR5zUi4?YQYt=t|9e@$FLZYaTILow;kSpUA z2iMgqF-q2tRDz8~3@3girauWj+6K3*LIz6MBeLNIAgSYy!y%Jsu1Qp^^L%H8!tY%E z<-=aK?i-#(j`eE8)i1Cfnw-N%>qw6*uMzZr)zox>q{&3LNsuE?h-<&0EMOgvlrKUA z8qM?#+aWS{3H*8jGh(*>bH<`fsWj5(vZXg3XLotC7ESr-)ppkra?P?7!X{l(G&q&m z4R%k>a56KKbKcsPUL0hZ9yAwHJQy_Gmd``S;J0lyapHMeig3M9I`k!;VJEsW$xDWR zdHIQ%%Q#-%`zVV2I9{d{IwQaa&RI7`2Ce*dcf6wF1ynRS>tYzj(<)%g>W>y}UBgcf z1%!?^)fSP%d9`E1;Vk`(J=V^L5hIDyBimF74F&98I-BtOHDN#MFqP2Yl265Z(btS= z-77CvWzA?erZAaQq($sm=cYyK_!irL#!?yS#cF4&B>Fqb?-f<`HI7A-QGh>}hBJaw zENx$a1`%Hs&=_LEX1Wu|pyLI$KF;xIplywCH=y`XAy#`7d62vYoAEl55N~n#MWKu4 ze!(tnU_w^j-4e;Y*Qp|HzrN_NK#5{y-z*1$2up}P)9C^#uN$#$*ZyG5MyGgS_2iZ35&qE=yk3(a-o^w zGZ#oU5%FX|1m;113HvZ-(@tB|C28r@KKyugea%qni^)qrONEHem}uR9&FxY<6|b^4a^($JB7e;u0Wl_fnPVMNXh$&1Hkl7&28%A}hdCg6;TxoS+K#UMFFi=?O z=#l(V+=sZt%|t>Pp!zFz^vzCJStnA}N!+@s1V1&wuvIP2o^Gz_z(q4l-kqP<)tEPw zG^WxszlOoTAxqyXPAex3akT*L$Mk4lUokbyx~Yb9Xgc4eP^TP!K8l>H8e6;QQZqd+ zJeC{laGE}xo^DcNh;K4!F4jDO)~a;9lk+`pdus?99zLv=23Ohq7C9naX<^o$j^x90 zuBd63favkT$7zKZFG7Nv365f(0cH{ZBp)@v$X@;?D-yId3k2CD&(ssb?ysmJvN*tL z8aV&&TA)Z{VsyKI6_F;8EJ}_JLdJ_brrS4;`B*>Xw3u? z5|@w7MjWgFGcg)HI1XZ$ZuzjzBTQLQ#P>`IgDCY;l9^I}Wc7CmQH-`>N+}szO{4j) z@vQnW)^q#uib+LyikLE-pLJ{4shonYYR3ek1`XNc?ZH`VdpY^b0eIA%ojHp;BwJKa zJAM`0E$-Kx@d7H9PO5lgFfKuL^5O_;o{IfD?ZFYK{xLtW-9z*0`GPoBkitDzbo+sPZTg zG&ng5FHB`_XLM*XAU8EPFq7f(6$3RlGLx}mD1VJ~1yq#X+BPYvDBTRwQbSAk(47*( zFbpun3^8;`ONY`8A}JsxjWi;SAe~ZzAPo|JqrT_7=RNzRGsweM^1>)tGk z+Irlw)(9&o2mwcO^YH-10P-3dD#8FDP=E&r^}nJ zU4NlqB+8}$Mxx?05O9F1yCZ;40Kg|K#wQ{M1OoVhK+%5%B3#7)3SbYIH9&(0po)M) z-SAoD5zgMOFk3q$YMXy80qhVC0H3I+2-oj)fUFbL6$Syr0UBVW9n=Z6BLwUS&_h6A zP^9-iO0Y}VA(75vyu6;Co;+YDHy(tmt$!2;7r+ySv;*iu-Jq@>P;0<1!T?RM6Z8)= z9()#nz8%c%k6jO8gY*QuLIEg)BMbtCyP-1N;nq-B0BUo9o{Bm^%NYv)6RiFxfD7=~ z*#P)>`2Jn)uk2riVDR6`UjmHh<_=_U%uQI4pR)ky2Bb=O|aHJdl zul^KZu22Z-*u8oG+^ho};R*Ns3)sNm);7OLSi3v(8o*&L?obtlzd}$Z{J(9sP$WPI z_*g{XF&_Zx0)To!?0A2b*Y|dY{(pA0X8TSP=A;W6!nMi>jw6K0+6om zP=DY5bo>+H^YHjQ{PElS6m`d{KLH^9un1eEfoZ01?!}|DRQ~!GEy7x&Z#2 zssgt`0Qi7^xyAVXfCd6J2Jrt5HG=*bS`DZ*%-!j~ zy(&mBY7k`MwkR=k^9k|*1%Ln8VQwIp7t~rChJ@Jtk<1^v!LLzsgu$WO2shZTw*{32 z1pb!~HD3@1)cfIv(&Zl)*bOyo$lura3qw)k^v^yN;ShxNueswF5(a=>UBTY?sH;aI zA(RqO18NQR`mJmLFAp4nM5O>woc#ed2v_`H*Zi0tz^nVq^c#ta0DpMFf1}3$UaP;6 zD1aC8Z^Q=_0`S8AhA8Rq!v75g1OU7UC#Ws>KLUgSyvX11AN@nzU0qQGf6ERqWIJjVJfUhy?aQ+J!Mc_sFZKxX50`35(Svz3i+xwKC9b z4uKaO>Qdql$QQh9I-oSWX2LPH&x*8rfxk;h)K-wO zRb+>FmU<~5)D`kLHTToQ2-_%MYl%gW?z8r$&k=(Y6z8+pD}!Gg3Eq#juxBy(*;SMr z1qOVS)r+=ItAB);aPt`DL8nRbdx#%-LVyJ4O-g*J5?(pIua45%!^8~i*vx+BmN7Ju z>cZ&g<`7nd2~(!*dw?Ua%S4xZ(y_Gw&j(GAtTQ1_!odIx$;84B?? zua7K_1yTs_{2+4~%_T4$+s5!TCGHAbcHM1L;0P&=8-IL+v7>V|+A@#3z^r&kxnHzc zR1*8_-3ai!L+FhRep%*x8eEkSVzrdn^|X8f_XR>{D+4F3E`)8+luuR8yzb#_0{#6E zSy-e-8QLQfc9CZegazRqJ5!%^JY*Fa^qTnksb=JTSyPt3SIm7J2sN9FX640~RsQfs z&IZ?9i+``IRL1Z{!Qku~f)6P+OkLS#sZewICH8=YC~N~Q1Tt`JZdS-}7GP_)TSaD# z&vB_W&ov}aK&z8nx^o30jEuLCcvIB8SV;JW0Fb7b@>32hk+MwLaKYXbITYh&-t9|^ zROeU(ygJq`_uQv#=*wC>G1(Nx&TTlz-zrJ5j37a}F}j=9if9xGE!cgiIOO zMmjS5AChU5&}FFS(B}k>tQ?O#yHqE4``_JUXY;ax+bVr9mmjpo#&+1}r8HlKaVL3j z#J&WePBnA4L$i!8bN(f9pKt$pg8&tLa*odhi>Pl7G&TPT6XQvt?RQnSLZVHlf zDM@eipl56rk}0T08{U|@cVm?vk&2>(X$-QyzoiqWui{w!^dK; zV=OK_I!H6bgN7LMA7JJn_s97S)~dj*rR}Mn@3S2f-g(=@oHnBM^?!O5 zL*{8P_Y6tZ9+nHgVa>$}*%-v$Gjw>rAQ)ZS#8_JBAO`E<*T|bzy*}QX4zHvwPgkAH zGpyoJ*a}VmPxPG}4(QjjOIIDv6vxM;8Cz)PHJrk>T%)|oAM-L8@7uHi)>P`R^F|Vq z%r5y3Nm-PW2=vk15xJ393mZ?P+eXylbC;^LJou5i?ggkiE|{>O_N<@ zN!t5p6vcKb@7J2l6GCJCX(TW{#J-#D8xM#DWgi#S556%RBz@r=0^*|8P-7Xz!5EVF zEJ?Ss!g8lPZ|dOMp;$$%4?Jxp9epLWDgTWP-ap!ue&kHrhWaS{qNVbTSo^)WtdvRPir3YW2Cs zid_u%u8VAXmA9b=8{gs<%9I9E%9xTOAJ@k(M4!|A{Kli7_%(z9ykD>z%!v~VmST1vCxM^=*K-tZ~Cx8oh` z341e&p$g^mRrRW~gd<4CZeI)L!BhgqIvP-V3=#7qEtDmjJo>p*SuyqmL%Mp<4fVGs z8u!3D2>+%#@r=RkE>*sR+R+qnv9{RjdCJgT`j+K%QlF7B!U7=JGk-j0N=Oxf-jGZ> zn#pW&dGd|AXgb~K?U9B_klhtajgm~kOZ5O=CH@atf!58oLOIl@n(lC?9AG~QBh_8Y z>(pIMKFKDF!|eM{vm$c)9GXSH*IXt31l?_7=9d}pbohxDhGiW_rEo}`s{yU_hFk?N zV1EMaKU>^;J@K5?I)866?SSFWk9d{HBl#1LZ$2L zd$w2)e3`Q7ZSt%dH|ME76$co{D5xZ}RESy9IjwZLYVgjetk{qAW8Oo&kLzoVemPj` z{X_l8XWwF%mR-M?dtPzHewB z316t}M;3CP%=AphlNaYl5-YFhb&au79*@gf@dQmLMKHa=1%YqQgw>vpODTnx>5Wp> zmlI^Jb;25|R+b+1yv0njn``qP;!0@MJtp~5|7Ep^wtv{xdNPSLj#__Se5ysZ%h$Y& zCtc;_bmU8^QSHO^swt~pF&m0<;|Cg@ePkz!Qr9nLH7$Zfc~c|%7|GD8NK>^|-f%oj z*VxB<2Cr95O&LEHrzveb2qADu9b-FuI%ghV1We@FFIwJc%^f!Pr0uJ8)AIibAM_En77o2ln%JCB@zxeBMnMQCUIw2 z(uDM!o*fSQOLRq$X%Vy8-jV<2X zBM`KYcutRFfa^fyTa;7pJbR`HW@{4f1eQ`X+&z5}D&i9LEebmRpkdBIRm1j2Az8`^ z?_9UY#H>7&5`t4!3-NDfE(u$I1M*6Fo_}a<(UoY;$u{~7y!qZ&UgMJJaKmf$+k1}B zqrOb9E+%y{yA%8qT_!IpI@)(V(tH{j7a}v55_3j|+bNhIUf$+)%WjX8yv{Tl;=F?d z*@`;2<<9bIzD{wHv#f~Y(EsWO4Hr$CgU z&m^?EQSu3v*yP3KpafYPb50iGZIUHXSVE8DxwePPBZ9pe4VinC_ckPv)JD=R~okt6~^mMsoni3`;F_mhO}xwVivSt`}a) zINA-m&vXL{(Sc-vs@Q&L^z)@Tv45dl4Hntz`VjsfnFr?Rn!r}Y1iYT@4)N0uEvVO{ zX~&>U%rbGaMQoticvjx8%-Inj_l#$crfJ3ZXQavxb-IkH65-WU6+jt&)ZORgPv~{l z7S1oxV`}Rd=u8u|_CRqdva)o{JTXd3jfvh}OyD`*a*Vo2Z4j<@!UJNMNq@KXXp>&o z=lJTNYLG)wEpVJ9h*Z~d^Z`$Z%CzFqpiaewEe{U7yG35cma#POc+g|`r>Y{UTi1)4 zX!=!-i1BuU8vVg`|VY0S%adBU&AG-gHX z4=mJ~=y0Ad3H_X?wJfqy!j*y@4 z&)RB#bhF;7C{p9RygEfpns1HD(N2l#z&Ps8q2CZ!V9Yb zA#<{z&Oid_x~+S6r)O#`aT`kEjbETpIJ?Sk&HYB_%i>q8J+uQhDY~@4x1#hs+a8SM z!y_WAZ=X*;Iw$sK_1*sb&gg+?#xb?`Zt_K*M*0w%#N)G{ERYlC`MX!qMeCF%W9_M8 z7$=tvK7V8M4%u*L;VwgJy%+a4dc{W}Xnr0=Qi1Vg64}W*OovB2L$1x?MUIYuPP!kB zx0?7vS$DX@uV2zN$*DG+la%|m3*Fs{7KLBdF4u`uv|8t)&9PpYz)lKu_|%D=#K`hq zUGwkCeBmVU4p1)0xJs{4bHCRRZ{$I)3DIVLPJdyAF2Wi)R7!M=K~^KMUgk7BsRQnK zQ)C>p*tI<#lJ~G7lRDGO3p~(|6ZrA2j|7H1%|6riHwu=HNJ4wf{IF5GM%TDRVd3Rs zrSc&<3vwJvdg0j5!B_)si?>XSE{|(jmFmmU({8RNuv>fkJJnl?w#0(h(jB4!ZI2A? zXn)uBvefoxdS3|S247yn-+{V8ah7{)g3h~AEp5Bx=0_Z~Pvcs37G)y~OZ-an4(BpI z{b=mB1K|fNaqXK~v~-pZ%u`X++7}CR^_-S%l$vh$A}x!plAh|7i{|0_mCDWIg|oUl zk$2azadJ;w^a)`nJ~*;xqt&;iEO@=4VSm@yA7)MXd>y}BXG%AFoJqIfS|yw7;ud7w z&z4&V5-0d@gx@9n_3(vFT+N!TqqlfNeD_L>iu6DvxkjX0EOL$qaze~0B2X-ZmaO9A zTsXtAkW3Xi`%wft$jYvL$dvFi9WAJjv+0bO?Yye>iTR7fHe#JqgNlCP$OPMkhJVhJ z&I|O+lpbs=UCej+O1J*0Lr?;<3|XqXd}C8qe0i{scj?!LUU~$n$=>D_SNj&*+R(cb zoi+BvUcNRhh1>f>+Q%2GZ^ndmrO#T&=}a69a9dU|S0mGhr!8(?=K7i*%?wstoW{I&E$<|KQ9rovT4-+XXMGkSH80=4~G9@}xaTV`IpCd7gX zZ|KL$`K)ec>lhN&xd(hdv3Re1o#MgURp)$Jv-*Ywi+BL1d9GtpD~?D%#S~8#kd9bz+2 zCZzg@Mb4GX+tx11d7QSdqxfZQrv0I-n@U|o_g8H~zW6az-7as5ODL%_JlmP6(*v@6 zaw!AfUt-*~*_DBu4*QgN(RVb_%x_n#Z;!lK++7YHgf%tcQt%S&QGc6T;}D;FVFf&9 z_v21{&4O8yx-jgKO8~6Itx7E@ExQ-%X&GlGl= zf4#0KCRhKMCl(JmBhEbkW!$Rz!#jt2Z{34yrl~ZFo<|37Aht@T&=9X!>lTwSKtm$;X=3CVs$|%Z5x>cq&uAgoc(*4+;&W2{R zoldHJ;rV_Sm&~M#53|D**w)^I*si&z$!8c=KzC+wfQE+4*xYcu8`8j2pkmScbUVJ# z76+!z5p>5_HT0<%fxXnTguEQfI(Z@rpO#F&2;59bl;dqi$A8r4D1Mk*G#v3-hu#oZ z{4uv_&5(NU(X`;mz&n=vvsuY5@o2T%*Zb+UA*YH=K>#!jl0BWr5srM-iVEi}kB8ng z$_mPl5*3nunO#g}Drn5Ub9@#yT8{|MXBQSs3w(;^NNW~NzdhPDiOHTtpGVpzDsry_ z*HS8=q>FvVxPL_1qVIq^w1x3CalJA(b%@ADI6vLcf|ICRSv=DjUp)RWsB6M3RdMB# z^ibITLPO1D_hAr|T3-AINkv(rV>zv$G67euzCDbB_8}7~kVl^2!s^IJ8_ymI-=ujn~3g69$^Qf?C^EN2;23cE8u z4(;8C4^mu}9`d~Y__eU_8#mxp1xTlZ*Fc zN8Fnqm?bOxNp>pRJ!|w+8TmK-R(sAmL!xhPo3rPyXE7v%_Pkojq;cz+n(gbbT};}0H%WTbb};(zEt|s54gu=|y$UAZ!r7C$czn948oGng2W#_m%t?mZ=)woZ zCyi!UGc9l3j`P{g_p@R59vVJ8EUrXMd>(Ezr4#f<_2z$i)H-D)Y<`D7h^2QU@G;=04yGrY~XuuZRV_y**WUwK*TKj-u_ zZcoSics-Hsm7z&ERyAWxOeA-Dp?@7QVpd*cXl6*wqH7WOb<}0Gi{((XrbL0q5Wkg1 z$?5?dTC_UQC(PEvg+6w3XAXKtH<F>S5Ps|7IVfJZ3(>%R{}|1Uf>r0 zbolJ)|CoK=?W@JsqVpKU`C@N?8Dm%W_RzW+KHyup9vY&5dkDS z4-Pa610H`~*wC}oXn0su>C4E$*Z^D`o4Pm$*(u^n%}RX&j2Uy)p9}-sjwsDbgWt9L zFc~_^Ts9vw9Etd44b;Q6aCbLI+fjos*I0AXYVcvBAl7))7Jo12LQmkwZhgYh^xdtP z1V`{;mh5O-BV~;gB&D40|)t9nT23-L7Cms;%Br8nDfi%UATSO>$%_j;_l{o2-jxZxa3vZT5L&8jEs z$1ouJFbSOwqkraQ@hcAcUK$~KC?ma4{~+%VVc%Po0tCVLrgLIjx$0Xw^TwoxtS9%L z4&Zfti4j?*%YSjQPwe%P8+3a`)=0=jKrzXlbZ9`n)Dg+#Wos{-f8f>=mwp)Zp+cSL z+e>+xy#>?ppk}q+6ti1cJ(UmGkwd~iLOn=5UjVUB)^7^J%w@&D`6XRj+ z&FmaqT;EPrK+8FUL49`0dk^WaY36OA@;l=sUq0(%lZ;4nZS>iP*Po_`s31nO3m$ir zBothQC6m-PtS!O`mVK7DilJl!Yt@UnejM26>tx3ZVi+2dEF3%gzFSWN%uanKs(d7r zXX9~Ls(%)fW+7-t=WJZ5<2>Pq$f#ZA2L+6A)@H0T(HgEt@Se3Vw-Z6!8J#jNj+T}A zVmbunZ25M?igrJpwHi098APvVShTgsU&SY1(<^Yj|M2K)TFkU#V{Xljd&@xz$Q$6> z8Zl@WPe`9DpSs}Dasu}}uEq-i?N4}nP@EjaXnzqJlg^U{fN8yS)XKTulv3E)Z|Sg_ zJ_;0=oIC==TS@b3N!B*{(M=K>v0%q)GzH9M8`n8)946RJgftl+x$rUj0Q2ruY$Sa> zRkMiBU+U7C`GC!BZV*&H#8?f%G}$vf8IF3zVwq{Mo~>G(?YN|MHQ4d$0pP0A-!>LT zJAV*x7wc?N&>NeSf)^tDAj5F{>tH}P>!U{wDg#n(=>G2tW=_+|W8NI#yhuQEB^*9@ zS*U6ruggaJ82gf~9Nv)#omKQW43(d>^fnShm~1ON-(cm-6{-PS(RozgWRoij8d-Q6wC3=9l2#L&`>DBTEx zbO=bdk^<6Fq9CDk2na~XH~RYCd*A#2ul0Rv)|&a9XFq$Nz0ZF3nOVcmqG!l2?})Gm zt03S=evkn0K0s01&>RE=0D-~+K%fvlJG&7S2?PI)I*#Sn* z08K!$zfiBg42B2@($~%t3_t-er~?@8g>vzRJAyp{sNDgE>RJF@cQE`fvesV&KER*D z0e}QR{|fiV`&S?+{I|26g9F0N-45;#g*yQtP#74XtD+@<^h5Fi?BI@nzle4)F9gcp z&c_Z4v$IDLey45+P?6UM*r6)?Q=gZEC)6G3CEx{x{i;#$R~XbWE5jWX5pHf^IMNIM zSAI%RPp|{(-2DarG}jf5@P!Bdy@EjDj*wqvIC{Ga8pEL;-e7g5KO7W<|8L9*j0A`R zCB?))A^0PN@BEck1G10#QT@NeU97*#`1pgY1H06~=j4uV3!s1N)=FFPMF0O{!s z4hsBF!#`K}AP~S2>VO2;gPovo{C`JB!C=T=YgGR|p?&~MAWD890PxrAUr$yjg*hVN zF#mtkf45jrU0p?8M}zlI$^SAcC?Na*f&4;}0Deg^AOHjci2=la#YF)@|BRz&2mO=B zfB34yAqarvU+JRG>F<<%{%C;f&wy|P{uxULfl@9Q!1ZsTKLm;b9Z+we|FhhGyZrxD z{wvD=D)j%(NW~il`)%j?i}3&0?cAU+|33_ra=nqLDbPlsW&!@+R8#O@qpJ;egnGOE zw^bc!hnfa?xD!f$(flA00ieiVIMho8>IZhzgCZTA|5D9gxbd%fgF)e7J%ktZ*A0X6 z0s{Zbh8i*lSJW-yg_7oP6Bso^|J+v@?tpOoHEcqnVgNf&Pdk5nRIgDhQ9vLFHIL@Q7z9Ll+k4tMfMHy8$6OC!OEBe9U08k!$orkcg%=CC-_zE|X1xz19)! zY$WS{uvQpW(1%II1i)_SUb@wuL6nuBn`@zeXimThju5u~I!SY3`y?kBBxIE?4U-u9 z{6axY560v^3Nig~{U9AcLB~#^r;ee+;^+$YkFprDUUMFQ(PP7%n4dTkVo;Eesn^l1DrF%jxiHC^ zXd+BfXhb$|q_v5brGsaFKT1AyhLo7X^`L_B<%epqch9B6Tcy(_LV>|clSg-y^!E}; z>(>eNdw*bAC)s-*2@2s_YZi1{INO%#aB3h$lAz7IN!MEn=F?$E;&aOd3O|iQY$(cq zgC7<^o?JcszIoboSYRgK5NiR8OY4~qS+{xdj&d;oF3$8#KeeXIGt46j z`w`XqL#&Y{u&U-n(RRg8gOqW`mV}#ELM7NR^nJ3P^D>BnlKGM1oTDK8uBdBSsK&Yh$;)AIDrfKhg4)1XG zbb8Z1>Oc@(oL!pgFf$tDD5o8l?q|0p&Y+)Oaipzh!I)KUsUC)Ck)azngI+SJ3e8dq-Le=@bps_b%KO{S2M4!Hfg>ako~kl&X`JN_q_X-HRLVFb*~c1^RA3y zhQRoFUf`qk@89)n&YNqn#y)|o64J;o_mM4D_DYlQ? zjW9tpWG?x%=kKM+_BNz3OQq%2OOJk(;fowxFRSW)$XfNIIX#DZ%3vRV%f~=5eW3(1 zPhZIypO$z=&W104h-x&Cq|23@>WMuBwkfZEp=XU=*^uqKm_t$Os6MO~;L7E2E*#-^ zmBbW39JXgTVyvg$014C_uNd>9iy}N2Gq3F|+!x&Qd6PI{S=e^9z|^Y6u3IR#o2?cR zol5>-S&#Fn#*5LV5TE3KS-wHGMpkFzGHuz@hF#g!RCk`aNO2$Hd1~n;J&;$>x++Pk zT(M4ysP&O>dYsXh1_?-eG=R=uzcePIO_w{ek*FFdKJ#^&oj3|FQkAgyGQ}X^1;xn; zWIHfs(wa=k`Qzz>jiSKp>@|h-(Ve-V%h!X8`CdX0PQ?@d<+VD0o1vF8FXgNpm?To` z;dJ62oDsBN?`Xzei@54aQ}6$*lAALIq?CVz@qN-mC_i4N{_2YUKAVSF9M=QG@&gO@ z-uY$A_`=rALqtco^*mb(N5YqrV=FQVSbE|{i&q;*WaJycq_s6`?i?1QFa4o*L?`I0 z)d!1{4XadPU52cGg;I%I>DS)YXohk4@}kGtVhYk^OGQ5LrEH^h+?wpf`iV}~sHyV` z3M)bEG5(OCz}Tt5VYz~t4Bp2KIZ)y|Hx&+ca`rS-;{&$EG*L^>7WXot@1UOy_g zkMaR%ZS$)-#Z=)NU#d+$Y>W>@^w?G8Se2LWNh^eZul%PNxBmHlRc$sQcLl7 zm!eY|o?i!~y3p=}@+R*e8AMuDf6BEFP*s#=WeJn1Mu|zm6=5C`)qn1) zW7=f?dS7MX!InZ$L&mmi!%`p4iorhDhuH~hp#^qQAiDhZ&7NCi2U@~7$u{hfTLfa} z?Ouflt^SvG%9_YR|7R4BQWHP;Fq0qh1}7C4F!iS?H#t0g|7sB{(#5FMXxT8pv5GG8%2B4JhU6q3KJnk3OUg5d7HCycjU8)n^g; zs4Y(E4%46rKgo|(pz^+Zb3C1e;brTI{LpHDOf_z7!`oHbg;x2Ew6-^0NLY9MxY|vj zC7Mx~pVzo{5o45I98cqOFt{SI6jIua=Ii<)hKA`v4a6;uTb>AIeKOg17|sS{T=*H* zSk-4D3+*8%j|({2lo%X%)Kenkc!jusXgN#VRg`2=*g`+mi>fqOr;lj6D09k_m&J6SL}%3lT20#`~IQ6n-v+?E-jw z*kc#G_Mp1CSKkQx)N^4)79#|G>mCeKconPxBg zl1VdXz@o*;J9)+r+<5SVvk8KRS)Ct_!2hTpX z3iYylySr>0bNMJ2E#n^c4^flIUC5Mi{EmlSSkU?P^dsrpgdEiGnO;$U-A8(T*jrvX zlHbaho(64vN#((3U)zzd!JX1_@(&Pc?r5=RlJzn(*-<;t2OWaiUvgEIZAi zu0AI@T$-ll4TOdI4l~baSET^9;HEEjf1H6tJD1$z;^UkEB8S#4xjr2Zb+^p?PcLN5 zSl+s&gTIZ)jl-yjO>bGJO%&C(E}lueccq?9#(Lm?k*DKLWS54sQ&QeFAW%AZh>p~0 zEa{Jh3B4k1b(L3tw~FDW*1jMKX*MkSdTXAs2ydbbe}avjojA);&SU+QaVVMd+CdJD zWR2#Uqh`1IrYXApI`Z3{#Y)~Z2jZI0<_Cqr{+w=mUJtU3x5FgeS!}w| z%k(=xeBaa-^j1v2WNS?P@le02`&r>ZUUtGVd(FmCeCH(AvEYqDCreFI!RsU;t9H#whIi;Zc$(^Q?=L|-v9^EQa5|}nWXXVLKdf>Yh z`tNaWi`+Dy266;QJ(%su#}0ElUblpbznh?H+|7IOjgyD!#=|Vs=nniC`G9^l!Sz@W zSGGdPjg~uqbOLhPR=c0Rx>j`Ie~)Xu)|UN4U?n|&X&FnWK2x3`ki%=muk94FsZhmR zJ?r`SP$C>pi-;FQySUWVwqoaANI;YLM!QvFMz$&ivGhC=6 zJ$;T=qm+{?j^rD1E^~GMqy(7l%kKwLwzHIfn_uN8an5mmtQGz4!G@4-w)TEcbM9a|C9x3V&5PJ^@aX7v+) zn{AK*9yUoh&WDhP<)LJ2Izq0HBD)iWw}!azvk=mq#$%t=ou1PW%_Y;oJnflfVcGe_ zCl%VqRzL2W(n{SW^I=YkBF(}wTa&_yRA5fQiz_puNEFapRhN=2U@!4nhhT~dtC+Ds9Z+Ty8~v2`qo)2$B#@SMWTt9LdN=HUo7eX8 zeuN)F!)kTDlI5N6wV3WFfuP6vp~&6Q5K*$DB9pbziU!_lvXYkSn%CEi;_(f}Ug0?} z=PCyMH@}SZr{WkDBq)krt9m-E8Dsa8ioRn@jLA&kcvP3z)Dw>zoc>9*a$`XvKXZqu zuohd}=gSJ03pKJVVtoZb^lhSl2>xw9*J|8qKp*{`DNU5_LNZ;f8?ivbi>Eb5cm|f; z)RS2Vod+)WzT*Dm4BzbU1l3S15WkiRVkS9?dZ-=p%wdk}{sK6$UiK_1dY!@|TZBn7 z)+q+FVqmMdw_=loLM|cCs5%WW%V~GU%08(1$W~u7=yTEA^7{E)QAHQ}s97y%#H$0wQmQ->%H9XYWv}LSmL#+gjxI}H z^TfiWF*1bN_vq=qWlSM|InB}?DJ6N8#p{oBHn4HC9TOx12ds`0+}fTA#?TTBek0BA zn14!H;z;L1``8>k8rwYM>?gA?!kyxDJDVk2xnJ*@xQZ--W}@Fkk3@3qxP~?NjZ>;Z z{Ii7dfknN8r>9a1*7}LM6{*5MdUzBFgc~Bf;T;%kEi3AS#5=ct1va|a;Geed@tL#O zUa#1O2k}c%>I?Rle9>+Ihvv&JycrtanXYTP!$i90yn$gAUuu8UgLkvtu~TKUBlKYE zVk~2j7n5`k$eX8$R z+eC$O1Sont&g-gw{zb@CQU;O{RM7$;oxJF8J{3mBG*{iW7rInNm-ankEo=OGdXO}S zUobRmNjakx?_7ZX)SR5MfqMZVD(*_T@-y`wdkBtN%0o21YQOPEr(U&Qe)}bA`43by z$<{Yw7O=+loy!Q?EW{>hqR`yvXEPb642);dTo#U-9A&lsGWEmBoQuUl6wDgAp`0o+7X7GM$`+GkfY9fP{et;J zt&!!v!yLBNVK^8)o>eu|n9k+NN)>jbfBX^B$8Yw&x1)YCmA8ez&D~cC1K68rs9&bgaq#%eWB@#-b+@4poK)TD+S0yB;t z_$%0di&wx{IQ$aZkFew_V%{I7m5V?%9<5&&gp$H@`#c}W=Z%8 z*!YCHuk(fV?8`J7?%8bqz!u%awmRLpOCeH&^4>-gzqebvxXiKo1GuNY3Qm*BYn?ZS zHy!!8tn-zyT>GQ50I9b6EOr0chsyI!5puj3#Vtn`bOfA zhUZ`V*%`z3xwiz}4Tdh37hhMh(g-zq<7X*@Q$#O#`xooH$}EmK>2UAXx0QX*`n+i$ ztN)7b^r+4dMqc1Da0W=Cr3=9Ep+zHI4qXdo7ogA#c&Kx?Fg|kgdi|VAc?XAY9c&_h zG)*S0O^u-7zRMq`;V@+Kx%mDxo$;d3RIAJ|D0cpBDl18kzG?gO2;H0SQ^_Jcx&c@1 z0uHSwE)Ho`<{Z~69~TxTC=&N}q<6*1)68kI8_zD@9_{eSi^50LS5)HD1@mOD-^FLI z5?R@K2{h{PY`!vTZvae5Cf$xT%Ss!6F-_BbX5DgI0WeiN-Ffa=dFinPm%(^7JFeJyKwfM1}G8Kj0Ii=5E_L0kfV|sJW zy}fJ)w^fp0C>mnHP3fDGqDnGwM0mq?vfvfK>QoZaDo0tl+&3r8lxmZ9ToV5XSgu0a z5X^8sl8y{;`5r3M_YAxCHT@vC7>K-7%OrmcqDYyn7_bTsUhLZ)N+6&-{TU(B@F{3? ze4_4Eu+t{T3 z;x~$$yB7*2ZGCBDN)*mHsY-a&?6jJbHp@h3J!Aa6^6PE~o+h8-PRRLx>plS0k}u)0 z?oCRC$eONa*_ZV%bubcpWoEm-`g-|eEIVy_Lyikd*}=?y+s=izILDJtW9Tnb$yPyA zMLQa#8um;1l5g>===+1C)mGVg4X=_Pc8L+EcyoQhcZ%ve;@a%pim_OMcD!{Q07w;F zCV$rzT1~sOVb|S>ipAuAFsbOCG!_4(_&f*8CjZj>ic-==p|x5=YEXFod#t&H8rHl~ zgi?AsN&KNoLZary9UgD()Xxh7Eqn3Q)o$ckU@#<}0QhDNyeSyFaP|?atacCh72jdx z5isV5%fQXlE;@1ek31USW8S>&#~p;c%NsOM4s!uKI=9`1%qkXthKJ@uXP9h>VI;at z9Nf2u#>;%hhT(H@1^4ncV)e1LVvg2+2=?xr^Ih{&%w82P!+D0*dUT~NB`k(rP2PS@ zn3BxuD1zr~704ALE|Wo(Bp*6z+}~CT+dVEVo!y`!>yZC1I#IO4m#( z^x-=B=)xm^n+-%n)gsj0W^qlD0s9E9NCC_*BTp|cxAj3H3mu&A<1fAxG1jAGg$B8u8 z(`78G8Z_3N;BTJf4`=UqRC7hUo4AmM<{If?b1A>8G~MiCWiTAK#UlIU40yaBjdNu< zp(NLT{c5cL)e7(|{HL40&lQCuG4kFqs~y2oxCBH#s3gg|UzAp9+4mSngnVSRqvN!z zk@a$^Txa@tIvz)Gj38;Awkf7UU;y8?3JVUZE6F*(m0r1YEi+Vmn(urygP?{WRfj;j zlQit@KjB?F=mFau*;{v*f?M&d+lSImakpB3D4Th@YRoYSWSb#Q`Q_DP(L9Y&rJvQh z*>LYR28f8%m_<{mU-wje1vK*MIZWd9Dw0;DVgI5(5v@)ZR!G&DCem*F=9D1W#EaAn;ZEgD-L zJ3F>*+g67=JGSklgAO{jZQHhObdpXwwsZe;&OPVWt9rGnR(%+==J>`OwQAO)B$aZo zch&H61hF!*GO_Rh)TPuES=m@v04z-G2$YoK&L9(4D+hZC6IT!)KpSKRPzN~zSlIyo zKv)qd0pbphUd~n)mVd4Q8X)bzivTTK6EiD2D`$X~gRO(R70?nO;O_1&;_l+ccaOA8U%E<``2^~0N4LTwkH3JO#c`Cuj}mjpNI*8l@(xS1#|_Nf-J1;5t#p_ zo2_7k-aR)m`H&>7|K+(Yr zya#Lmjr>;D(`e-W~-CjaOlYH#t6axDKTS-D7Ad4kMTtX%(*+T6tU zABp~5*9QIPTogfOR&I9xSr7V0kAF_o%)#E)>;G=~&lvySkXcq-N?cBh{(lDecU#gP z=wN1LZvjwu{YOg^XS4qm{@qqFvHFjD{!8Y+ZUV6WzkgiO#MRl#6QIw+^e=m`{OkE| zWbpq`Vqy-SK8&n9oB&34HWmOY$3HJ#4mQ944_%;}vopxv_1}X3Gs}PTe;Ww|@&o}9 z)>j;W{GryVE#c+(DZXN#+vjitl+EDJy-hQtcEPjjDBC>-)i9Jc_0zZ2AK-( zo$t!tHh+_u#DS2GC#QarMi{K%KNpi%Soqg$zpCcH)JGUzLTTaI0hOSxB5z#NH`aqy z=%zR_bIxkyoJs}1NwfYmF6-!rM%#&BTfDcIrZu2O&(Qls0v*s-qs>`{6?1o4_>_sH1s%uO8Qx(TLhp?Umi>huTEF)Gj7wUw4N3vUf z5~D(%e-Ox9$x;Ze6Y`tF)Iy1V!t}S zvzVSU2Q17;T!?j!H*QxaKWyN#WMee>y3{D7WPA=s!R`LFEQ|L?52Lk;Q*fZ=1tJUD z(1utgYLQwe_~y_%_N3npXYVNWlV97c!xX9?@>B6aVtsf_gV7RvOrKftYXo*wiGNq( zU6Tl%LJ07SV;L;3rm@yfwudEfHe2;gl0Poe8xhyn13W2hB5tNw(E~iAq_$F&a|49j zAovrbdgq+Wn;UTYM?b}_hY6*y(wWPv+k?Dadp~*PKIM1)!#gjPm`DbGHx8B zJ|T5S?%(eP;OcoI(ix)CTNe_>Mt@2p`f3;LjJ#$7l>&QnbN^BgtbeJa-WUuK zg7HINKt`L7%5UrDXlBYk45x(3Oa^zEd_VB*t8F5Ad^I2}KM=9(_Kt_T4EGr6wA0jeiUtJ09 z4N3$nv-RC|pS3{UzHaD3oqt4ESK#%4{GwRxy0Ay~TorWX!BwRks9s!&{?^fo8*ohr zUZRsM>unQ1Yi{lHOrkj^IhW9MLh~H2Dtt|xkrK-TT+{H><#dy?nou>ZP!y>{qwAg%h{8+ zEQ)!mPcz!9b+aL#H@=Vgtiw~3Jn2V(uFkfL2vYo(&TY`JtD{`(SV97iIfj=Uk!Qh0 zTnUtrYQ~bN@q~IthdhX6%R>#Cj=OPEwD9V0^!ij>z~C6+`iYI8D{RA8HhFy_xrW#E znz(Ob>{)kix=YJZ*{N&g>wF4JKg$&yOs+m1ssC-L z@oA11JOyN!rqa2TP2wBu(50u(J=cJ=qKh&{L@Fxrl2p;?z2dP(<6GaQC*dF`|FMBt z-=qtg-3T$V8EuE}Zsk_Mb+uk6jZC7&HR(mdW_UGCFyIp zHbn=z2PfSQ)+~Xdhgd;;?{<*PQ^EpRt+s2@CS9Ok1WK18A;a!uHWAwmgnIC%sZ*iO zG(Cc`p!IU-AAe7?usWThVS8^5YB1a~wZ-1{lyPJPO+S3p)H%c!^#RY1aE;8cxI)%x z74dAb$MD3=6GZ_i1n%{tWUwrv6nEZm=!Z7+04qzKtRxt=@8J!`T)}5nskfEn*A?M* zv<@}hF{sFwAM_Nr^Qda;jJ1(bI9L!SyeB!L8T#Hx;D5efto#=#vJSiDaH@w-5(IMJ z(I?v|149^hU-(PHXGMNSWBd)45gz-p+yc;qec8zJV)S>;>m?VNPmFSQ*)w}V1gKws znAOFE?ID|ltVF$G3(3cIb>XcZG8Sr+4ca$%YJiBJ=iTVhCYN=WE7F`A!}3X8R@K?^z8}<(A!R-@rQClVft-F_u5@^{Zz{fi=z)!{mL47? zw+)<Ep#w9AyNd`MDI@ zv0@aPe9$PsLA83?Qa52og_(AA2LGszsyvV$o~I2yfa6|A*?V$My{ zgVmkqTW6`2^#q8P)r>ZKV`7CDo zBY#a4ico=+*!8c&*xL=nek?+uHf**{6ENM7GZ$hJcfN9ACC*smQ(NtY-{+a+Bx{0) zdJ|wq#06k(Po&UA%s`PEBXF@yK@%|rhEL0vc%QZvo1k2%KJL`#_)nY)n9?@D9E<-W zY?6=v)cb)5laTdNStbC+Kfe}n_Y7O)cYm-su8Hd6VrSTPnBop26V>3zHLW;|_timR z-(o+Vdz(E1P1E%mmaG+_`IR`DWI_R7BdNmZv++;IPcTzlNPj>Ok|!i;C^tnVP2U%fZ*- z)Z~$bS`0lIzh#M3HBKt7>l=#ZIk>l6wN(h@VEZV$Czfn-IaaEy@$*9YF zu-x*UIX~A*e~<_aE(o8NxX^(0BY)X_As%8IJU4w)`7W(C_@jMY*99Zotqg*j)tTCK z*wc+Q7GGs~0RAIt5EH5S!8AEUX1|b*Q=Gn+seYa^elUyC%&k+{gV#^I5LUn z7cw}Cygj2M1fQiNWgYHt`YnK5pW_RD1mb+VWN{z$4Y*wsA~kJa+DjdO_)Y9ya0bYC zi2HuOE8H;Ve-yZK#Q(y}D1RZdR4q^9qs8#MDz6f+%<55WJ1W9XY6ZV)IQf315UDY} zE7){)aZdI*U~)$Db>oI~x%%D2bp<()S>9!cxv^VhnpSIsj8=E1qSqt&Qg7uaaJH;} zTNSD17R?Z9E{F2#9Pg=>RxY>pEr}FzM$7Xy#5u%s%5?5G5suz|r+-@>WyBE~9V|97 z%@7Z1V)stoRK{o9G$fR#$<=dVY>Kz#--bMY^z#6b1a->5%YwA+DWAQ;S zV181ZGKqz*yajRW(M&J5A>t>fhKynOOqDms?e-0;Bj@*=&uC0(c!)tKVqu!mY5z!I zt=`oT%aXgLI+RE8tbcszqI$I90z!J!m7}@o=Q(DaIA~U8uK;Si;ckr*ZIrIoN^Y zH@T!lQFX9~aT3Y`x0@J))YGeL!os(7Z*QtnSGOL-WtgXRK7YsDuIWkExnNlcKWL=* zoCH-ebZ#-)ce+$1x!;mNHe{=f0P7K5>v?jWN)6Y?YR*QMG+CK)`HT@QlYt( zf&0k~j4n>9(iF^;YJh9D&Jw^VVu0z?y9oKgxcqi$*R|{kZqf`HK`cuTJFeXbH`j2) z4B51C2o&Z9TYq#IhcF;cbU8k{G3{<`a{7oxknC4c#$m#-S?O?(nifb%=WiJlNz zQ|ZyGVyP=Qi9y2#;rs|(VV8ESoLtq~DPn`|15PIO^g*sav9jR`DXABqJ1^onq`&iO z%!7YJJ`a0Rdd|hKd6n%jb3!>)g1HJ!2M;C8Tw{dx4OjrDFA~s3N;$ba#{6)7R@*D4$txd3o+vz@M~C12wF zB=_S6Cr^N;5jaIPBa7{Sqk$t}s=bE(+Sy~)i)=g4NRwkuNG2$|g4Im!K(rC}b0T#M zTyz@g6m|gG8sbU8mX*N2I0{1{4Bs8GP`psC%?tANSUerddXKiFF(0-%7|`oD8hp8p zxql7f?NC#^<(2#KoZ|RKx)mly-HB}@gf68Bj#v=bO4#$bEr}wLwKVf4QcZ9$9P^_2 zFOt!XZyHX`kzC6GvIG(KPI9Z?dlFHPwHV1E&v_$C;k`_6dpFNJ%Dr2obFod1SQfrw`{ zQ(~NzmHCrbPRaMX@gkqa=)!601N|_e?N?lNl|FcX?eF?&y^bZJ8Y_qShx10znV!=D zRG18`{FYLK-EAwOkg~jt+>$%=5;Cj>kQLMYDK0y?U2-_Y1ZILbD5Ez9TiLJDDt{6g zOI_C`Cu9bbWlyHX@?2b?Zb}e@W)pdaU4v&xl(FqR z$221Hr5j(wrCCXKzD!u&YI4Cw4|OGQy9D)H+?OOK1C6FI>rUQDlf~y3#nwEvym59s zZX)mB!&thww#!FkKiJ_#wk>HEPk(oh?#?y*U$e+wQKGL!w6W0c;6Gh~*&&9#y{2x> zSOLkw(Kwf$xA}z_fBOF#Hn%(8u3z6LTmY3ayt>g2No`1dcF1$s- z-dfUtd2|D{NHZK~i+UB=`-OLDgUiSZfex5|Im<24H8fj1MXQ_4%@IyvBfyHCE+6#I zWzrT)Yl4DuMx08gE$}6h{1hdbcB<|h`hM~Vx=Lu7i(sSRHOUIJCU`%A@T9(H;#egu z&r=;;jdIn`HMaAuJomcQ`+rUgjTz4?=~gCIFj{GBrTTB_3uG_aLtU16WExQJvH|tY zSBX%B5Ilx)E+BllmB`AX%SSqsPJQOf7R~Fd6;9|&kH+c~ifB@jlO5&wriXZyJn#uL zBrY2C1iS~4NJ{nnoYl4{*LxW?U3&=5Wtm1d(xd=iRFun7<%>5;Cx35P6IW|0oTQX| zx9>F;zgxEg&jKNVJx!M+MeR7eXu?T2gmA`#905fISVyqF7&!tUpuOrmQMcKKhulIrsJ$aPP0y%QX7+p_tt!*!+k57GIbJck&PN zv8cG2aJGW!^)G^eZ-46E#=9NB>q)t7`exCUa7-Uw1o-sCW;d zZN+hJeI?uC;lKGeTlJ5Yj0hCT&@Ab}PR<5EoYA=tNqi16~oYtC%TVoy~1jwRa119VTe7jwrpBNm*jSwv>9+}L4Q_w$q zyG3$gNE&MT6BJ$B+i1xXeP6FtwuWW69T8Lrv^24*k_r*2o(<2Bk+pRBg%MqCx`~5Q z#^*d!#t(VmVRgaOY-P>sr9`2 zf9NnoH}Z$Ek)0t1Rxr29m?(N`drCad2)cB+0D*h}G^~DAy>q8qE)3~NZrB`8YTN&$OIY0FhS63jg zh_Ac%^+6AlVVhDRrA9AQ zn0A`d)aOL;#z*S6=)aZ{K!3jhIudY`7VrQZoiuh0{mEYgJY3lC;v;tG;O9SWNm(MY zfPakNv2+Yd6QtKLD);xzJHmJ$I`hH%MH^)*mY@LR-}-(St!b&*rB`; z4^SX@-0vLeEZbum+eM2c!>L7Pd75U=u=!{O-B+DeG(mOAsyL&|=r;ZBIWicCi+L;$ z5oU;J^?wU}Osf;5s~&amQHKcH-0Sah&)6v92}l-+8xJuF#?W7iY;f0sH_*H+^M9U4 zv%pc3?xyGuWlwcX7~_aYsZzluEd`T_altNP$1`tSlwj&9R$0OdFIRvG65uQEt%u=< zfv@acjT;<#k%Um-AH9oH#_HF69YBKD*Tbndsbh#(<`b^qR1$PR&7XvRr8z;J*XsW5w9gp;f36o zBscLE8Zj-0ffbTjg#m%#WLduUq!}g9!?V!0E-cpS&k?o+PDra*$r#5lseh1{JCsw= zshIFYCzPBjQUhq2>-xITBZh}GOL$|vz%VKO{+Pnzd76B46a5CIWKDbc*z-EwiopPA zApE)ks4IJh{%Cg}b8CjDT}-h}V+%(L?&vKA;a5oELDE{f8-jXRk%ma?Zb`?NzLOEL z?V(&geyRk_@pDUwVc=UlVSh;9(^t7Wwzf)0P49ns=jScPbaYzI){k*%pOC1fs|kLjJj1d%#BZsM&8Z^$cqZWtTGufqLQK>@LAoHX?B zdom>I8R^Tyenf?oDek;}w+KVx?)g|<57N>wYMkCZIkGkR60SLjP=#S*E@ttKX-a1^ zs4r--D>LMAtYga@@qecmw0)mz`np7IM@V=EU`**8>AZVM`aDF-q)tL!voN4YPhuV% zapJkW^8rVnzcMc=0AhX6>*ZmD&VX6iJFZgpJQgk20ImX8O?COC-8gePd`lU;bZ;K} z^Zf?zYN>#ahK$7_2hUMg3n?s2kZ;bE>}@|O7AAFv4JB(bzJCt;k0?p>wWQlgyZ)}P zpjk*^zNlcEtBPTe)Uk$Wq&?v6tFEB6LQ$ZgL;-40Db-F;T6tFO>(4wYTR>MEJWFPm z<3hA5pMhRGG^rEGQp{uM`ji+Skw%eed0QyC%!n-2b_E*}s~ci;PR3s+ntsgLZ--Cs zsrO3eV%t#Trhn3x!#Fq(g_mDAR5};nKg3!%Hh!6?z3^l+7-*x+IXB?h zIgLZV_9e}8#>|ac%$E;K`_++uILR8A1uzUs>A5%y#>Qc@gX|&X3&L30BucUuUg!q= zmG%|uF}!O@C+DIV3^9);sDY1~NH^DWhNxId_vX$-oqs=5KJ(ATtR-KG`@AE1H0VgH z-8H)k=(g*yr-Wb=<0f9xz{P&u~ZA|_cZStN^6DgxeUy(P_%@^F*)8I9^ z_`78XhOWcjL-QwDKK;WD+{xd&A(iC3id_0E=xlz2apMPHtakf9Q3#oLIP(bsJ0#vU z=nL1n1CKuW^5V&pHW#uk(X`gMe*7lNMmiqpYJZYJXsI+$;&jXMrfIq!MYj_fROUYK z87w2;sBeU|zh%6s(DJsdXG`B$W#_#w(Z>)u{7xljvh%_LFZ(N^^n)PnZ5vWqs-m>T zcC6obcmT!i=`PAHX{fMGi?EF|6;qM*{E=g#qtk0&Ypjf;g_^0eC?y_FBSYVT6-h3xE6HdxSAM(B2AoT9-l}a8W}4zQ*ViTSRd$ z?sU99##Ef)6|92_GF8PsxaZkJA=gj_c&jcx-C1Nk%n41SFPdZJ$?3ieS)G+u5OOWN z)}ctK^|8bs+V3jAff=Pq$HU`>P_q>4!1yuuKPz_bElV&t;oB0|xe{8`70Et^&3|48 zm%JV}V~Iz%aRPUTQ%tajP=k)~Pb>r;&aMki|H5%r0*EjF$EQ$S_fh8 ze6vixCr5-{k|Pl%=6hj{m&qiqmIWXUR*Q|CQ7%?}N7R7dgC(K$jH{)%uU@TXIA2ci zgX0Q(*c*RF8F{mWi`T8;sB4@;jepU~|6t031)f~)d27EGMT^(x&p|JHlqaW{hOG9~ zXla?I)PXtX@)hIhMw@;7c@~F@Nx_lE0C$d!?l{~G`{|{yLLH4+4O^a;T(08vHpMB# zj1;yy+wMP=AKM`jNe0tyh#6UBCE)kCA5vK94BJG}+G0gBf!la=N?S*sX@3`uRvKrD zo=>oh4quEsz{)5>P`Q6pRc1BU#gbk*sgYguv_%!h{-t6xtGNWv`8_ygU`tk0CRb?+ z5jz)sc%1BV8x};12uIx?Wn_U(M(Wjtfdp@`N4%JdydPdEA?UDYR3n|yc28iNil4r2Hj`9lg@bm$GiDo0hB_4&#P>)08#?6*~43V$zJKrHV(%Z<_b zpvDYJA2EZaa7u3bZwbUrnVe(ar0X?5(GG%?eHr*1loOB-UKc|O zh8*=M2p@FUUa(l-4}aJsVF_>NCff6J0X|JUy1}5`!*7JWLy#^^)3w{SZQHhO+uUuN zciXmmw{3H`ZQHhu|M}k88J%fHjw+%us&ZvsYe=kJZB$7(8(P0FnISVYq;UL)=di3s zj){y&qEV~tm^B}%&?n%28U8Du`ziN`mqOHJ%?aI~8~!Y2`^gY%?2rrkEXqi}MOfkh zjau#OagGXbqg8udh*z2NKxjSnTQPlmnkFQZXoUT>fNPSEs0a*EyujB5y)H}MY?TCW1pZw0(|AD) zh89xPEMSlMhv8e@Q*TpoK>o#PcMQYfswK{Dg}Jp<$dI17gJTR>lM^9wmDM3m0s#I@ zO>1d5#%JWG&D~jML#889z;BA`l7nJbK=?}wfcCoC96!&WtLdr<-=lYSg? z_KXdn+wF3A?FSolIDhL2k|e-eWaB7NVh63caQ>tZ9q7D4VyAgK60^P709UE5q;|*w zoNg8e>xxr`V$*9e>cF+Uu&`U#tM5U@L14f=jGHs0epHfXY>dHgz%wBaDAL5kD z7lQUt`x_Fu)G&U+>e(VFM?z5iFriKWv7(uA7D~q@@?v=;^q~vLKXPvn52{R?Z`hAt zva?a!WOESxW1B6BaSeMU6)q~-+Dp~DxUNwouS9=i#$Vg1f45vt%1F+e=Fmw+SHYey zJ5RkE0LOto?)Q9N!AJ@siQ>t=%1{!8ipuwilj7)DjiKwUUckU?#I4&wgDE2b=ZWH* z>ydEYWO*X@Kjw^{$)u|r8yYIxqsPJ*eH-<{0hYXP3Y(TB?SXvj*f=?jmv)*O$t7Zo zZ7Xvt|A`5#eQfdwDQg#S8JFE%cl7)vNKqPL+JXW~iPAjl4BYrz6G$g}9B#&>I6o{2 zJVQXq-?7}N4#N#``VlNqTY8v)b05lEt{=$$=OiZ|%rK+LX~*HnBiv#pH#e_-S2Ib; zylh{ZTx{SqxYq|X>UN+3O5aZSX3Oo>+7aJj)$RX!c5t%gOa3j_XjZyxMlv>^SEY(t z)?@UkB5qsG9fmy9M$q9!TQ z9VwT+2kd6EmyiRRl3$zBj6WIiYu~aa{xMW0WLehNct{9O^bvZ1!|dzbfDk2`<;G@# za8OR2?M}j*t~ec^eqM0^{9V4vMiT8Tg<1*&2F7>r5Kq_pk2*T+i@k8aK`lfq*vg+- z`p7^kGi6Qm?C@;-z9p71#xU=gXm<9PsiWbg5Yzq0UZa{gat`lJ>Q7M8*+d}`4ZQV? zA)U5PsW{yoZCNw5hta!j5In2b!tQaf#L&*xYB+QsZU>5vsd0w^gcmT?+~q-`WqP)q ziw#4WJ$6>GK~_{{UOQh|s^0Ct*zK~ju=$d{Y>HWIMfsl{&CAf6uQR!}SKvv}eEbUh+<7#TdOTc1 zBu@0KDyq!8F1~*NaU#fB`LTb&U_7)*Y%PCQnk~kRbcu@z-K*kCQR{___)?S2M1|so z&e2pvq(YUZdt_B^Xk*;b)M~@h#Ys>X--4~U3?lL-F-1@Rh=o<3m)}?ZD@AU!8BA(- zvC<-`AnLO@%@D1zCuRK{nEY;6{Vd`{2fI%{pM+}bj{+6GU?bC+@*&)E=|vPo zCy|dK&<&s-k7COGT3WXCx(3yh03+pq|1#s;u+KRE2mTYr(GQKhE$fY;7p!X#ujZjq zkJEm|P4Y)8anw9IBU`kzTBzFOJT00>oLC4oX)AyoC_5di`%-jnLTo#hRmcWiUK{>k zCC}gcrcj3Q(gNEK$Mh@-70dj@pzg`rx}=t^A}C%B0Dc|%J|9xVez)XWHIW^N*~upT zCN;=}jy-x&r9h}jo%5bi^3ESb`L|zeKe4^Um`4DQ0>Xj7fp^Z&#P+2(9P!69U6npx z)zuGGre`6w5c4D3O(D1d9bbn^aEfnJSULmtV;?`!l$uAw19Sd<@k(B(kbR<~S;e)?u#tcJ1CcQvX0?2@!j_^JGu~ zMQCOsNz~~IOn?KkkH6-e6&l%oOm{yar|i}fK$F{x+XKR4AWYc{Go38;eJTy*&@ExO z+A)3YTo!DZMu2Z+YTRg&m4QwL5A@a~G$CN!qxV0;`l=I4gaMQHN4n$N6)_8Z{cW`@ ziz=$C4h0|KqCR;0&5vvOgdEiqbVQt{m7fs5Ezn5eEi>6k=;CaZ?M_%riQei<&k@^y zw%&*#s;Dv&ijq_Zuf@O*R{B>)0ulp%+*K!1880;dI5NO5OUw?4FB#VjXs_#ZL|51k z7->Pj9GH(GtU2#3D58t6R&nj0*mtxlXnY=H8@N36IM?@%2%mGahFoWc-lmqHn4lJO zlvFoApR_7RH$A2`WFqedf{Z)AvgKcB0J8D~1cMDKp3_W<$3_R#^c`lJ7iM6UQK={K zR3UaKs#I|O_8KkPEdbU3txQ|(;jOs7z^O>I3sE=5rx~E@_(nfjf@fF!OiDQ*3i}AQ zWjRbnMM&9an1u|tzsnAz`>o{_iFAvt0A(>olGb)-oy~?0hA*+apK}D9<6w$v0Oa-a zij@VXNtoqS$+pp^C+yobAW58SKfYWh!dSy{)K%julA_Bb>O?%>yT1n(k|lOLjv<%N zH&}a#DsF{upiC%X!$}Met04$IM9K(ou0>XCI7%izYzX?FL<=zuZ8;EnZ0AH}b zIc1hg#8bPg1Hhk|=)kF$Oj0PDRqi`Cd`C~V&!v{9JtAo9Ey_?X{A3T@m@xl{?_ zvmmD9w-8vD1oZ3plU2TKOZ8-YBQWgpZ5c=lD0^%vhELM&EkPi(+4SMfuaibM=jDWy zksLj>jeq@C0vcRg<8DaC0HM%jcB~?e>hBY^pc1-?W2{*u5j?GL&6Cx~U+i^Gq|h3- z0_;^5F|ez}rFxDMpM%#o94MTZMZ^=^6!u7;$l1kB`lMowt9004! zX&(TkRBalb&du#&p8ddA^af9~OWLy?itau?Nh0Ga?)D-v-|kNnz={IA+Rd6FkQQ>0 z3?%0OXnpyFJtL_PHB6tb(%J0<3@yt4LG-nQ1aG0#~b(pfHBLi?>h z-s&fA{2}&YFL6{dRGhPI>X^WP$4+3J**uV_@`lpl?2irl+LMYIWu69PKyQ2TrcR)K zd2RZ41AmT-Uda#{pk`(Q$rf3wcVl z-qQ?^#7XASeLdf=k&QN+JK1omK$Fyyp~UxVi0)Evj`S4b4^p_2$@MG~JYub?SLRR( z@PQArDpWLI7^gxh%!59X_rqnT3?xIskJe+lpuD#Y-u=@a;5!O--=ctcRm2gg2Khu5ldn>Iy_slp+=^R<>oN15O1 z5<0i?4%lPjmy`IaeppVsS47Grs3mPlC}sOPqg7--re>!6*VH|ZWHc-|AF5~*R`lte zoz*;4E5KF*&=#v7i_&v}xCj?8?be@%xwV5*ZmhUXq&{4x7fxZ0oSX^Bw-4+;TYK6Z$`z!_x&fni}`HH`lNW*%3q$O=r1p#A*^nkp<|+;Pf!LFZm-l^ z7oHxcGC=#Z(jBkXS}kB$8M4tCQzvU|)!v7-RfLMe%z}d$zS(5^LIWq;5~DV^l-g5; zUGUZkP|0uwdKjzr)C3(ew{xs_M51G`mOcEEi06j)0qL$k9A^eg zoekF&c|@KX`WU9m%xhn$^&kC_gQ(;^pKq`V099lJ>K*bXGI6!k&fKVEsVDQrtn=?V zw{-ON+Rj&e1sagu2(R(`IK1c2{Zw%fUg-gIt2U)kp_uE*PC?q{+fA5;$Q@9Eecvc8 zc1~ljEM+QXs4VT#8nv4r^9|wP4sO1z+Wcb8?G;Nn6Bqd4gOxlRHszd-SK{>Q&~-}& z=y$CJQI6j0T@Y&h570WXw*`h2(^M`G2K4Lx*tW2P^OH++6~PexqQej4vLwzRMprT& zSy*AWfpG2}(oY?l5z0?QVOBn89~;#-X)i1Y5=LDx4s^#xpHyQGG)riDlxrR)U2Sv7 z@5fsoG8tWifR6kbAze^ZL5J)-+v;@-U|VR-%qryV+c z51G)BX8DXh&*%dt@W;AXiQi|=OZgRQJ%H^w*V)4qHZzEUP!km^f>Z4w*J+RejCWJ0 zE{vCw*$X0YI{dAbV56C>Ytye(KGVE8 zq(3jHqir!j-F^yin4LdEu|in|XeH;%;ZSs&!vpPb`jo*zw2>;ZJ>rKI+15AhrcRGsaYFs4X#R%xy(7wrnh%$yP|7)7?ot9h4~lC61li&v^MheR z5ll#{dror~>p!QyQ}i0Bol4L}s6#rh8EhB*xHiEj@eZVxF!^$>rXYnLUfg7e-D+8$ z!CZ1LUoBrtYRQ5%<|*<2y^<{WX=2PbfGCrRDzvE-OZ2f;Wl<|vB~?ZjXxWm-delYa zA7AGHU9PbVm*He%0%0BlRHH-P_eE_rN`cOH$Q`ml-*W@PbA*5;mU`}Y5VebIdYPp^ z(zry6Mr=TSso^$WOJ>Cy2OS9V8~GWgfh+f2ejgysfhY9PRb-W(*XnF@#izjv8@Y^c zc~sN`&nk(-Ei%{=rA%JghL0RP^)1HG1!zQbLpu_s<=wxtM574-++cMO68dCy_AG$p zQSp8>7&4Abd6n^AsPhuyMErj=7Po<@kRx>By2rWE_qGH=Fy3R;UaBt=ZyW~-XWvW9 z&s(|rl6)q`%Sw9twwR#Zpv+*TqLd|}pL^G-f%goE}! zMj%-zb*EP2OG$143y!JkHbvf=m0Oz1scs14ZJBGEBW@E*1l;}mu)Qd8M$2`JX0SV7C(S&e^Rp^Rd!t3M;NcE!ffv$Lz$k>_z6O%S9oW(pP`dsxD}M@vV7B zD`kVFLYWd+NLY-km9uMwA+*L>bWih2)MSn%_1XOio;E@OPBVz>@|{?MOZ2K+c=%F7 zh`1mQ!GfB&Y2xrWiBNht^&n_kj5Be>?eFOm=IW+4D`kU(xDn}O+XVmWIM)aVz0nN* ztg#|k5Ln^d*qM624l`wa%6ueF_Wd(A=27(nEA}2=w*Y(Kk(2z9hmq{0hbF}ud2mTI zhe&r}h2X6R^x7*fOlV#V%pDCu-Ab`2dNb*Slx42p7E;m$5C+CjNv2?H;)_;lb3q!z zxsOd%{cw;Hq^nks-A|tv(6U%BWLGSc(pp)UMvRlFX4ki)>xmJ{mZ+7TOn%@V(ukswq>^j3GPNOFxb6s+>KOr?$w^wyjxcNiCV`&ck|(mH z@83Xu`;_R+sK!F~IG1NvO<+IDfyUagzp1V(xaEYr7onFP~4?uvDG(vwSl-$(E) ztM-agN8ob%ob_%))*O6=R_UdTGXN}A8r)nyBqdYVQ<`@q`GZ*( z$#D8kMw(YHnH39G1$v? zXBMgaY5p@WnU*xf^3o4SI;??e#-2pm`?-8BvC$C6b(AY{%?&V%xlT>pEBK$WmuT|NNwGdfR%Z^R_<4UOE&{F%q%dD$3PhFL$uJ)%Phago6HS`fXlXCaR_u89$*GFktmNJYMM2*`ZUlt6veYPE7sj=UtArYa??H(GAS>2C z3)BY5310;wM~vY9*Zsn9%(7$}=zC^~`2HYRpH6Mn?Yat1++oKEVoD#JyhrmPVu}?+!>+kpr!S)D^X?@0iM;6Y!PnN$k6pjTOH4_cp zdIK;%N?csKJH*@m&y(*33^!f}(D9^oDT>`A$d~alB_nAQe?+cmTGW65YLdMoMC;%t ze;lagxD6c8%luDEnG5725-wr8E#jiSxz9Sy`;@D~v-ymLJ8Xy5roy&I^ExqBJf;-N zo6|xo&ik3Dvh}w%j0r29m>@afUA()Cc|fcFEHN@~@s}?^3%&%_%M(M0d4}bG(3sg0 zEBp}3M_fh&W8-FL{vUGLPQ^`a>3XH41X)a`k8qnB ze<2rSA&Iq*h!vDolr)M>R2nKGz*R;nm@0Omz!iaLftu*}c=^(2wQZ#>4=}TCk?;1h zKD%$E96qQ-(R*Wr42&#njNPZTEu|=?q6UM6(JeXEUl0VeSw!TRQOOTO2bvKm9KgJW zkAw^^78(i=kKhJEZ|`CRIk*Y}X~*~S4-Tlv=7$0aB?3}y$K8TGI0G5;^75kgCgul6 z&U*!~%Z}+c0y+kP$RV;f5*qHC6OlCp-CLOhKw17rrw!@BH99-rgKz?KC5|(~LYV^P z>PHUP%m;G}85BwYun~g;U<14Yk;`q26`;7#=2QW!$|{_5oWM(JA#!R!K3Gt5%iZ?j z1qm#xw)LbSAG7XXKo`4X(?7do`@3hmGy|uKWKwh_AOS>iRDHl#aDm9M--p>4Q_u)f zUxC7THvrkypoG;Apc@-RFCe6~^Q`OhlTrsnaL_Fp$MP;pm>8g^Jt8I$2(12sm->Hn zK2(6A>DS-m@AQJu#(yuu&?mmvId_CmL2BV|0m5NOOD)R^FZQb#-y_p~|G`NR;etFx zexHKtzT1D4k?>AVK6evWZN3Poo`iPA2FH?acR}CuHG;VZgpo2>jbb`q76^bpFyHh! zn!~?3^8T6p7@!h8{L`By2n~1x(ijN(%?StG3Enz9odM{~&D-Pu1w<5M5jiS~!60=| zQb0>ZOAEdWI^**rLovZUZ{A(%|D60ogob+o=0#DA9mF>m)l|9gIxY!c(cvETws zThKZo(B<>`Bz!l~4E%wdO(D1_k8i{6h?mLE^R^$`WK7HJP_DgJrc$gRMzPaeS_%WW z2>3f+L6!DDMnqqv9-~uZ4Zgmd)XQ4V#03wWFQ6&BW$%eE=p%URrso_Gy{0-&c59E} z2AtIV%?_s-tl(9reogN&{knokG7APEE|hsdq-Qr|SKGt%3#pLbM+hyw-Kj6BK&VWae}_Y`nrChTMR>==_w6m7q(_-i%Jt7wFKGZ&3}+%H z6J+CP#%>0)v~J|`j7oE3obAJ`M)4ipp_h*+5XnWz@ z{Psw4eExaJXqlXv^sXaqnSvDSBe-=&=!JIoUBH__Lxw-M-G}>Myla0j8L30OPu|iAJ)2s(*}nqQth?P zIr9)jSf82?_zz9HZg;M_;fh7MW^GeH*wG%81X9t{LA=lGPxSZcm8h{s+h~>+ znNhsbwfbj!ce790Nmk1})Ai`Kgt8=cDa~vz8vDh(+kEXAa5m*uo>lfCxt&1id|Dp3 z26x*Z4O0c5l+)6Pa`6D-Fl$iJ$6%#@Gxnx5B%F+cP8hS~XYEH#-G+Z$sxa8X&XyzN zfYW@GSqf&P9+~0|_WbyD;OgL@vy@Zv&Y1!NBRazC*|XOc0Du;NHO(GgMW0#|c4 z>4)Vk=B^Fb0ZmPN?j=|Z`u(xT_SpjB7S$Oq45{n2Q!K^@QZN9Oy|xd~&f|RDk~f-; zRD{p!+#!0Qx4dd!D7fE(?JJA44BvcFnv+8_c6#c?L{t+CN}li!%nv)s^~=FM0&aty z*D#E`gNwDn0`4HiEibj7^Kzxf(YmBv*sZjy0;&pvn4ywCmcQC>DBlgq{tDpy5OydE z#kTch3}Q|zPlABXdRL6bIJ8tKGN}X~di3`{Et!)`weKwi>`e zKl|^0Bo9)P#NXb0tUzd1yPr++`1qptfwhqYnXd)@$ZJ4QR*yv42UR>p=R8cj^wC9H z?ozKF{IVMQt;C=P)a*mBndoAB;?96kuH{V0MrKJmBX<@x(j6Z|&8 zpT~uf=Fc$4{`j^j>O|f;cM|9KkuP`Ul**^ZeEd*_yDgoI^O{W z{=fi;o{(UG-!6n4u^HU3isy7K_qj{y6VZvOs8Zh_^x#|Qdo;@+nY6QM{bEboh<&^A3)a&u6<*{YB1zd*Q~Gvaq`}l$k~ukXxO8_|W#Bs39+_7n_fb0+ zv4&Q%HR9G(7^r83k}Do_3l4v%tewz=noufVi#+27&)OEd%>@(18Umc0yeP9-C!XpP zWr6?OYNvf>3}#S8+ZCn9gji=rk1!jYo{OdR6WaCj&_nq zxrLy%Gq=3mL8G5v>{N%yRghjpJ44n2_+cW@4BuZ`TJBaD({1onoHdl#?}*WSQff9E z-=Pi1aQ$~9mtbxk1t$5$f{t-nQTwMvk(rGPV8( zVoR&#fY7_#R4G0F!q>n#f@gEGPE01EBS9r{scrSy16zKFJ-TA z3dk49dCkicjt9Yxj#s01C0kWA(k$&(FhOG02gxH_?9w63qt@oMl+*FJG5weAAGezC zlCOA;45mly|dWX4TgbRMQt{S#bhg?ex>`-uWfHdAp zECdSKmXyM}@BN%d*Kk|Br|o0uHR4saAs!XU9xVNJ4V&0cd{Fy@@=vQQ zA3x9Vj-L;?b#_?k5OJYP0$u~A8l(4zbE-=0N+DtS-VaRg=Mk^M_WB>p&6{Xs{RL#z zoI;+1)`7Vq`>AC}a2c$%h5}+IfL#PMf48DqsFA$4h4SN)+DqKTlwOI!m6S`|6{R`Z zvTGXe$7LLLfY7Y30InjXYzqqUKO3q!M~H@ht1NLE_)PU16u7$Unl>mfs98uqc-<@{ z9O^~dKMC+OidmtW#N78aBP)*U*r{ z<@7^&S*h7~Ft06r}jMBkNDIg^(b z%2#|`4CY}A2wwB$n!PVVh%8g?F9Fi{>Fu_iWHkim=@&bmlXADsZm)Ua z{Ho3)_i^=RL-PZiZbr4tg5n))Eqs<*2Rwawxe8j(lny2FQGKuUZI3}Lb4b!!IaEgVa zoyJn>|HA-$n~V)T+rMa@h>=^%jm!P6jBb`Z%BhT%^;giU&~4}MPBh#M^9j6+xqQk9 z7Akj3V`Pok6wWq4%AW4mI7}6;(VO`JL~&T+>?} z`%|{xYhpvpcEjx;Y1@p4M#y%KHkuJ#w={yV;d+fHen$JwCL6IS&>kk{m;WQO@c-p`kZ5IGmnHm2xO7OM-7$xw9-95h}cRhIw8d(OHbIk6DaS4l_cs6I92Dg;?0^qB!d_((#-V z!kQHZ!4v%zL&$a3COQozUQp^NPFTyLG;v8Ju|=VW7EJZnm@U@T;tjn^m%qQhLE9Vq z@5xt#W!=y|Og4wQ?RYorvmWYrY54(s3cnA?YKGFj7DK!|2gaZg^zZ^{Hu!KMpx97* z#GNvR%*vvm@Y~w08qQ?(q|}L!@*2k0^=wU~S_yhe^zk!8hwfWsY(yJyM@*o9(-hsa!^gnB4rYLyJ zT~5=kL$074#KIqR%A4iR#7GAYV{;|;(mAv+m!U=K?w0X&8N%6ydho9UR=*<4q6uHF z*sLuF*Duqs-P285aKiXg3^QDw=%Huh$aL)>2!}Fca9^V8>!G}j$v=3^ zUuD7auS|C4Zh#uY_brd`!bs6sy;&)?{c=yn5!vhA=(2?~$y+(yYri9Aa)C;q^PP1u zX#t&A2dwWUrC5cJlmi5S>)a{VL?|oW$&y+O{|4XWXhl3M(qZvDS%g?Jw8J9=ZM>ze z?F?oaU-oe6+h)=ap5@^K~S)F$W_8`yVrTTsx|!k&{TzLcCK0obEBb==$_7t z`X(2R2Ii762SmDD5bsfFypKr$PpSV&N0iWuKmJ~C z{YpGk^uh49J8AM#uhOmnzaNg9>G6(A&nJwyx=;cO26`N^Wvw`)Mu+h8DIG8-vfAWJ zculX8RMBp?mi@`)T{X-~ewWp&MiuW#a5x&azB5)(JjFFyx0M!ckfbIy|6dc|SNO73 ziYhh6Vhq&w%HelFH)BP<`<*l)#M4c4q@S85+_;QDF273h>=Hy2h^v@MM%(sed``7R zv%h)jslhyf7q`Xx`nn2fXWAK>Y6Wwv;!N}mQwgSF?}^$cX^5`ZKZ0=ZJd{@47^A<( z8o`#dJB9A*#(`BFB13#cH2Bvra*O)7Fmj$(fWoF`L;bP`uVQ1w^ z4{Qa+`u_xqTR}%bnArZ;t?SX#R>d7}^gq>nI_zOK?zE|k%HTqVz>QzM$MWHmeG`Vj zc10wD7{bao1hD+8POI#)q62mzRjTMro0?!upP-RGtE^B%S1mc)-lS3A(DqhesgT*6 z(AGa!1NVrlPgN;hXX#au=$L4iSs&3{D$!F(jTB?b0!%EtS=x!Ksu%XJ zXm&~mVyWpMo66F~+R)%e<}d5UVR;vh;)$ZtNFEkGqBGLY6G>L5YNSRtgPGGfobeAu zVK`KKpnqfIp66;&m$dRVJkY4+X^R_zo1`YyfFwE+s|jlw%olU>SVTf>us;Q!~Q>V~Gu@9n8!+AN9Y?WiQV{EU)3)(N={>xRY`nW!_>{P#gmtFEUyZIGrm0eqch~ zA~#%&5>|P~Gc|1us;AD-HZ~mdyr)=$8=u;fJK2)kZ8v&9U}-3B0%p$IT*nf#Tlo`Q+759!QuNwv zwO#`xKLz+Ub|CYe3%~{NS{d`}It8O;n7Q`&*4)yWmfGP0X`^HSP@{{)K&` zwazE@Bs2`w57h)W9Z)^u^LE$KV{eX*o&ow+Wqf6}B(5t{dirXHnht|G4_q|m27pjs zg*ciJ00{Wlt9?hGTq)Kaq!jLZl7ILG8!v9+)L;y8WT@{loX`TTz_;{63ArMdUs3$w z8L?4&P1#8kOVRwn=l%4ayvu_Vxcx5R+ixY^P<7*G^!PC~-5$Y{3dP(IlHMr6 z>^7u)b_U=c#VTyif=iGwX!4h?u%N^dJMH2Dmf(}k6 zwAS$h??5pfFFOKuhrsO(xAI+~wo99+@!^8nHeL6MvBW5w?Q;I%bM6Vt5I%7PuD09p zSgkkbI_qx~xooyBPMX=pY$CHuj%u0u&QqGsV`Lw174t1Kn{ums)I4wco^Wp7FRtVR zmK5}&lQ#6&*hFMxs}?%gAg-H54$whrsM4vG>QeeW3&~0r&r%!zYNrLp)c976=;)aF z!%8E2tE4q`N760+je)PT(^?SD!%W;IDV`?BSARe5p(JQaXAT<0F(=5kV)R1Ok~FG7 zBLFi1=HR5JbZFye&qxSJNkFPJEolq_)cl<@_n6e}G}aLPlQ9mjE0cY`CZvqfo-`cV z$8kZ@mWXcqm>Q{}WJ7Z3kUA2zB=e>79zhT&Kuki8 z$~js=iL_v3RW{b7ZT{+Oo{4ak%sspCs_;Zj?5?32sCuen=#Mpf9eYv?JnazY7G}Mk z4Km1I!JF%>x0myvMAQO;GIU^JXn{}0Fc!GOMi8v2r*pqT$M|L=Usklq9;YJUo zR~q6EHaeUMIrtI^7&Lr#NHfU*K<2!Pr@2pRT2Oj38I=xu_th3LTycuseKHTuL-XZzL!0uHBRy`0Qm695sHs~ zGlp{i0OI^5wS2^tm<;EYfikBY(S7X&>I-{lXwu*U*_D%AKw24o+TRK}Wi8{;r#l+Y zL64VCkVd>&NOOsN7jR0Su4DYTX*!uX=rJcV+p(^io26ijOtTm}Bn_pBjK)>2)dIJC z7F987zKO;od^w;Es781YK!-R629~aaXq+fTJe#s;4?GEx389EPnfL{t1Ql%PlsN9m zn;TW*un*L~+SYVbO~PgF=d)6{m>AM%(dr%xiL%g<5>c$7*iMK;uxe(&_^h zfCS}`PEYY(L+Vjt^ZvboAw&<$0K(;EN+s};`IRor z8c>KPaS(AV)lcm`poYbbk98jE=0aacA7pu;cyyl;!nb9RViz@4i!sq8cLaeg4?wZb{wOmF0e5T+I`TWJEk5J zJ@L;g1euIeNo(FFQ>& zF(GeEBmL5urLkJc5#Umzn6PQ#>EZz4!{Jup731O+)KCS;2YM_-@Vxjr7C`$Rh(lCl zD;$uUV{+O^p)fijc2rnU%nTTyY?iCSACRE{oo#!jP0I|q)GLx(@m}?lT&hJ}r;NF{ zQ&W;Q7)wk8_Wt%&9g*p|qlTdFIIXR!3sr94#HW~L2dop=$gN>(t3dipQ655|kY`J( zo=h*D=RObE(Pf%VjiDvX`Hc2-8#0@Fs;kUl^0LfwqTnVJzo1Z~bxKj{C+62YF6>H+ z=NiYS;eses1`UwI+EQmg1v7Ecd5NKie#VBR#6DvK$X6s@YQg@+#R}^sE zP80ulO^)K*%g!EI6$*c>6m8T<2x;o zIjMiYb%22*Qaw0S7@Naa;uM~vB{|%BI+qVbU92DQa~1ZjqJet=VpV zxH@&OlHQ__?}lbf*qxKdI7yj_4I|oNtx3X(vC;5#QEL+_FdDX*T)WRn`iSjNN@ex| zjWl&YB{{}2XvGZIsZ-H+Dl1(5@6TekIh=qc@JAA-7y7lk+NHl zktY)d5^~lmCirHY5ZbER&Jxxxkv8x=jLhuL?Ptbq@5RBMc1$csEEgd$5T~e9sq-qQ zRJ%3dMro!YohdA(i_tBq|CLi1eCkkuthO`8-X?}jBQ+K~2FHjGcA3H$r<470l^C|E z-V`@{I44ofzCO%n^&GIg;R8JrBqVk?N?S|m;*gaCCPam-4|K-UANGyLkxE)0*ih>( zwR);@wqRQGqrUR=9=eF7VzXLNmjrg&TV5295P>BSEMfYDG;<3E4HXaoE(C?X z&~|W_SUcVOV9{KqN2JMUd385mQuj+m${Lw3kh!fpmQQeYDnddc{bXUAsBx&Hf1++H zmrqBFhhL7w1eJZ63FK=d8d_M1Wfj{)LlR5-+-q&33R-oFUS9S7O7{aw>l^`0CH)13 z?i_t!Wv^R*$!(xkC1%|5?>6yua#{qdb)IfaI&;kc-wlwX4uki92m@b#n}=%>6G1qN zpezZc{%`4_8rmc!Y*fd>16|m~71SF_HpoV(3#@RK{T!9n_5eg$-(VNMe9sbwYmtU4 z^G=P>DPe1#utH6VBKnTwDe2a^mLbtL*&h%u{(DlyyH&(p71*GM|xxvMG4fLXuMTX3J1c5m3T9r17nrXBePPlRCuuPvAr-(k_0egxL~On8%|y}S+%%0Zo(nRo1>qXFW0*aP^`mT zY#N-z2L1k5*wuq=OyKs89)FuTFk5H%^W+~dxBvXetjd%nC)`^cfVwt;a;Bu86%=2} z1Tmaj!px@vXk`!oD>=RI)T4U4qIlW!q5ZA;-R-actM{)4P_euG`TY5@`qAdC0;oki z0h9F8B2-YsNcQ&j=jP4Kuke;ZG`uMKupHR_t)0E_;up*%khc!#%8*w;urTahIyIwx z9QCoLK!buZEYG2pmqR zwg&t^Z=;)KA=6#Vkd5+}LT~RgxeeM9s`(O$ULa^Y1hW_4>&W{mLv;$x6^Im=k4+y& z?oN&Xw~ylxlllG}$123r=yBl3y0Yh|x~g$${vH9Y%$ya&KLEwcruFsayv3>rb@9KI zvx>E2WpRw9i{AHc28PM9`ctx&s!h<%gzowLJAlc#59BJFMD=k#s75|pFl~(NP@ITn zT!7^Af{m-#POZZ0xanI>iQ z`ulhr0v_)0$~UG1U~?NB&y+$~BhIk9Vr;ie3Ndh`U3qGzcWUNOv_l(oyK=zS@%=1d z)`0JO|2({Bwdf63fAY+C3V^8LNgG!?7_xMVux)Uv~@JV8U z-|N@ubse$p)kC6$G?PGkT2Q|^Y(RW}VdYhir=}QJzC>2^rPOpxpPK_l&f(P%;Q8?r z{@sJmgG$C(NQqx583x$EVv984nXdrYL{(_h@^q-+*mPy?*?)s&?md2>9|t;6A*RsX zfgT55pTx^Yr+k!@(tl6JynLB%JS$$Pk^xSi4WGdux@oT-cQ1ZjnK!7MzaOs7Kff)4 z5?f4Lt4&76czg9-f5{|np+M8VV@j@MT9uJL>YIMAmSvN!wlAHotHzS7d=CN3%5#h} zA*PZ8fAACKSowhXsN;YbFVfe6{BJV)BqxA>i9|DUR0IIr+`MGTSkoQ?hPgR%n6k-M zO%fB%WR>~&3Jmd0=!w|-@ho|ak5#a1OZRP$hv(V~RKwlQc>DS;{$2x%qYEV5_FwA1 zZtR9~h=Tb>LZ3vYYch;w08{{MoQ#OQ@>Pe)zg64*;BQTKT=1jQE}t$&e{}Q9Qf$>$ zn^bvm$#p1IQe_)`)|<;OXe%E=dwpxw=B0}>%gFBHznE}Hf8TjR#OyGJce?>EH;92` zXNi7V;FEdywC1)%QVW96;{-Fkwr8ksZ_EeS(O)gJrxMEkr}tgyv-yC8oZI~PPp`(B z6Wkwb$@Z!Y@m{B@o8$J`ydM++1_A?!x70QU)2{_W%>o0E9Fg8aN0gfla7QWQLd3gdq7>FfX+K=iJL&heV^IgzfCISvAGY9y_0ss884oX|ZV zZ2Ga41I6BN_r-CCs0aY~0GR}J01PC|6S5F_ud@5o0IjC*2111=Q<;vwkdnF=RjBF+ zMyU#|F-VNM@v>Ir(D79KsIobhTf<)m(dW?R=!cEXiKVt`7M9PM)I5wgd6L?HiLL$M z$`kCD67EaK+QHqa!$`Gy?ATD=Iro=W^4rP1ovZigcf+a3XB+UJU{bbnc>U3xdd?It zd(!VP)9nGje2D+iEuY?I2-4Vr)Eh9lF@_`n0H0}yuGK#-xWIYzu|F(ldpR_CA4h~jQ@R~9)ZOnkothdu_U>O8|+HO&VbaK zyTh9|oMVD{GZEgvm}lhg3kvJ7cM!Hl!jbb})XJ2zB@i(WmTUU=S9l0&dM#)Pl+H2( z8(n5Vl&&0LxYYJHa3BYV`P}HHug4>Q@f2Wh?^dqG)&BkKM5y|Kn5Pp? z@HPuyCiY|ePX62Y6}9+zd^?mnA=m=o<}GHE^B-c6r1_z=^-Ly=#C^Bx?tfGCAhr)l zKo`;Q54SIwhqgHFmDG<__BiiSmFLy?Q4IWQ3iwie-x=D5&UHAE)Dgf6qxT0|6Mu@%NdbLyM}dwXd}=)z+?zwJoi+F5)C1 zkvMSn1w_(>i|-)ffDfUGa3*nZaC2~TaH%}+Tz>h#PtuvGh)CWLu|NbOUSXxkDp`T~ znAB~Pn8bh}q+5b45Sz@Cb+Sg{Bu$pd23aC=q>vOq+%Nj5Sz-|vBw*>be@Kc+5hNJZ z%|qOf@RgpWqy%Cg>A6L`qzsby(#=Q8AsOeJD@g@pe^1Y9QUy7E*3(aFAZG`9CP^&` zK+cbK+a@tmN9sufX(UZ#hBT8F(n{J$JLw=n(n-2VH|Zh0qz`iOu5asy+&lk#0P?e| zH3<09T0?-H(h315ms-O>L)Nbq2JSw!BEYNj+bHnu(i#DNKeR@H{F~MojKf>4aTwVf ztqB-^Pg;{OBRQ=pnDJ|^X_6s3Fdt$9Gv|?i;2|*)mnY5x9t$@(F*yn)B}Gq03Ti#X AzyJUM From 8dbbb1fe1f3eca333602e4673d8c976a5375984b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 6 May 2022 16:45:37 -0400 Subject: [PATCH 28/36] fix test --- .../tests/testCombinedImuFactor.cpp | 30 +++++++++---------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index 2f12983c37..8091e3ad21 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -230,21 +230,21 @@ TEST(CombinedImuFactor, CheckCovariance) { actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); Eigen::Matrix expected; - expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; + expected << 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 2.50025e-07, 0, 0, 5.0005e-05, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 2.50025e-07, 0, 0, 5.0005e-05, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 2.50025e-07, 0, 0, 5.0005e-05, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 5.0005e-05, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 5.0005e-05, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 5.0005e-05, 0, 0, 0.010001, 0, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.0; // regression EXPECT(assert_equal(expected, actual.preintMeasCov())); From ce7c71b7d77e8d92a04de8fdd0dbd11dd2115f4c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 8 May 2022 16:51:21 -0400 Subject: [PATCH 29/36] fix test --- gtsam/navigation/tests/testCombinedImuFactor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index 8091e3ad21..48a89d7a05 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -244,7 +244,7 @@ TEST(CombinedImuFactor, CheckCovariance) { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, // 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, // 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, // - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.0; + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01; // regression EXPECT(assert_equal(expected, actual.preintMeasCov())); From a17134dd6a6c462ca488c27a487f84d8d528e7d6 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 8 May 2022 17:34:14 -0400 Subject: [PATCH 30/36] minor refactor to follow the math better --- gtsam/navigation/CombinedImuFactor.cpp | 45 ++++++++++++-------------- 1 file changed, 21 insertions(+), 24 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index f2349a96e4..c9f0a926b2 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -116,7 +116,6 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Matrix3 theta_H_biasOmegaInit = -theta_H_omega; Matrix3 pos_H_biasAccInit = -pos_H_acc; - Matrix3 vel_H_biasAcc = -vel_H_acc; Matrix3 vel_H_biasAccInit = -vel_H_acc; // overall Jacobian wrt preintegrated measurements (df/dx) @@ -143,45 +142,44 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( Eigen::Matrix G_measCov_Gt; G_measCov_Gt.setZero(15, 15); + const Matrix3& bInitCov11 = bInitCov.block<3, 3>(0, 0) / dt; + const Matrix3& bInitCov12 = bInitCov.block<3, 3>(0, 3) / dt; + const Matrix3& bInitCov21 = bInitCov.block<3, 3>(3, 0) / dt; + const Matrix3& bInitCov22 = bInitCov.block<3, 3>(3, 3) / dt; + // BLOCK DIAGONAL TERMS D_R_R(&G_measCov_Gt) = (theta_H_omega * (wCov / dt) * theta_H_omega.transpose()) // - + (theta_H_biasOmegaInit * (bInitCov.block<3, 3>(3, 3) / dt) * - theta_H_biasOmegaInit.transpose()); + + + (theta_H_biasOmegaInit * bInitCov22 * theta_H_biasOmegaInit.transpose()); D_t_t(&G_measCov_Gt) = - (pos_H_acc * (aCov / dt) * pos_H_acc.transpose()) // - + (pos_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * - pos_H_biasAccInit.transpose()) // + (pos_H_acc * (aCov / dt) * pos_H_acc.transpose()) // + + (pos_H_biasAccInit * bInitCov11 * pos_H_biasAccInit.transpose()) // + (dt * iCov); D_v_v(&G_measCov_Gt) = (vel_H_acc * (aCov / dt) * vel_H_acc.transpose()) // - + (vel_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * - vel_H_biasAccInit.transpose()); + + (vel_H_biasAccInit * bInitCov11 * vel_H_biasAccInit.transpose()); D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance; // OFF BLOCK DIAGONAL TERMS - D_R_t(&G_measCov_Gt) = theta_H_biasOmegaInit * - (bInitCov.block<3, 3>(3, 0) / dt) * - pos_H_biasAccInit.transpose(); - D_R_v(&G_measCov_Gt) = theta_H_biasOmegaInit * - (bInitCov.block<3, 3>(3, 0) / dt) * - vel_H_biasAccInit.transpose(); - D_t_R(&G_measCov_Gt) = pos_H_biasAccInit * (bInitCov.block<3, 3>(0, 3) / dt) * - theta_H_biasOmegaInit.transpose(); + D_R_t(&G_measCov_Gt) = + theta_H_biasOmegaInit * bInitCov21 * pos_H_biasAccInit.transpose(); + D_R_v(&G_measCov_Gt) = + theta_H_biasOmegaInit * bInitCov21 * vel_H_biasAccInit.transpose(); + D_t_R(&G_measCov_Gt) = + pos_H_biasAccInit * bInitCov12 * theta_H_biasOmegaInit.transpose(); D_t_v(&G_measCov_Gt) = (pos_H_acc * (aCov / dt) * vel_H_acc.transpose()) + - (pos_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * - vel_H_biasAccInit.transpose()); - D_v_R(&G_measCov_Gt) = vel_H_biasAccInit * (bInitCov.block<3, 3>(0, 3) / dt) * - theta_H_biasOmegaInit.transpose(); + (pos_H_biasAccInit * bInitCov11 * vel_H_biasAccInit.transpose()); + D_v_R(&G_measCov_Gt) = + vel_H_biasAccInit * bInitCov12 * theta_H_biasOmegaInit.transpose(); D_v_t(&G_measCov_Gt) = (vel_H_acc * (aCov / dt) * pos_H_acc.transpose()) + - (vel_H_biasAccInit * (bInitCov.block<3, 3>(0, 0) / dt) * - pos_H_biasAccInit.transpose()); + (vel_H_biasAccInit * bInitCov11 * pos_H_biasAccInit.transpose()); preintMeasCov_.noalias() += G_measCov_Gt; } @@ -291,6 +289,5 @@ std::ostream& operator<<(std::ostream& os, const CombinedImuFactor& f) { os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose(); return os; } -} - /// namespace gtsam +} // namespace gtsam From cb75d92bf6938007fe7e3d358138584995e5b3f4 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 22 May 2022 16:39:06 -0400 Subject: [PATCH 31/36] use prior naming scheme for bias jacobians --- gtsam/navigation/CombinedImuFactor.cpp | 28 +++++++++++++------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index c9f0a926b2..0813bbfd12 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -110,21 +110,21 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // and preintegrated measurements // Single Jacobians to propagate covariance - Matrix3 theta_H_omega = C.topRows<3>(); - Matrix3 pos_H_acc = B.middleRows<3>(3); - Matrix3 vel_H_acc = B.bottomRows<3>(); + Matrix3 theta_H_biasOmega = C.topRows<3>(); + Matrix3 pos_H_biasAcc = B.middleRows<3>(3); + Matrix3 vel_H_biasAcc = B.bottomRows<3>(); - Matrix3 theta_H_biasOmegaInit = -theta_H_omega; - Matrix3 pos_H_biasAccInit = -pos_H_acc; - Matrix3 vel_H_biasAccInit = -vel_H_acc; + Matrix3 theta_H_biasOmegaInit = -theta_H_biasOmega; + Matrix3 pos_H_biasAccInit = -pos_H_biasAcc; + Matrix3 vel_H_biasAccInit = -vel_H_biasAcc; // overall Jacobian wrt preintegrated measurements (df/dx) Eigen::Matrix F; F.setZero(); F.block<9, 9>(0, 0) = A; - F.block<3, 3>(0, 12) = theta_H_omega; - F.block<3, 3>(3, 9) = pos_H_acc; - F.block<3, 3>(6, 9) = vel_H_acc; + F.block<3, 3>(0, 12) = theta_H_biasOmega; + F.block<3, 3>(3, 9) = pos_H_biasAcc; + F.block<3, 3>(6, 9) = vel_H_biasAcc; F.block<6, 6>(9, 9) = I_6x6; // Update the uncertainty on the state (matrix F in [4]). @@ -149,17 +149,17 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( // BLOCK DIAGONAL TERMS D_R_R(&G_measCov_Gt) = - (theta_H_omega * (wCov / dt) * theta_H_omega.transpose()) // + (theta_H_biasOmega * (wCov / dt) * theta_H_biasOmega.transpose()) // + (theta_H_biasOmegaInit * bInitCov22 * theta_H_biasOmegaInit.transpose()); D_t_t(&G_measCov_Gt) = - (pos_H_acc * (aCov / dt) * pos_H_acc.transpose()) // + (pos_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose()) // + (pos_H_biasAccInit * bInitCov11 * pos_H_biasAccInit.transpose()) // + (dt * iCov); D_v_v(&G_measCov_Gt) = - (vel_H_acc * (aCov / dt) * vel_H_acc.transpose()) // + (vel_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose()) // + (vel_H_biasAccInit * bInitCov11 * vel_H_biasAccInit.transpose()); D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; @@ -173,12 +173,12 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( D_t_R(&G_measCov_Gt) = pos_H_biasAccInit * bInitCov12 * theta_H_biasOmegaInit.transpose(); D_t_v(&G_measCov_Gt) = - (pos_H_acc * (aCov / dt) * vel_H_acc.transpose()) + + (pos_H_biasAcc * (aCov / dt) * vel_H_biasAcc.transpose()) + (pos_H_biasAccInit * bInitCov11 * vel_H_biasAccInit.transpose()); D_v_R(&G_measCov_Gt) = vel_H_biasAccInit * bInitCov12 * theta_H_biasOmegaInit.transpose(); D_v_t(&G_measCov_Gt) = - (vel_H_acc * (aCov / dt) * pos_H_acc.transpose()) + + (vel_H_biasAcc * (aCov / dt) * pos_H_biasAcc.transpose()) + (vel_H_biasAccInit * bInitCov11 * pos_H_biasAccInit.transpose()); preintMeasCov_.noalias() += G_measCov_Gt; From bbd1e3f07a9e8b03322d9a1b51efded5f123956f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 3 Jul 2022 15:57:54 -0400 Subject: [PATCH 32/36] update Lyx document based on Luca's review --- doc/ImuFactor.lyx | 73 +++++++++++++++++++++++++++++++++++++++++++--- doc/ImuFactor.pdf | Bin 249424 -> 250191 bytes 2 files changed, 69 insertions(+), 4 deletions(-) diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx index 7b176f484e..c335e69496 100644 --- a/doc/ImuFactor.lyx +++ b/doc/ImuFactor.lyx @@ -281,8 +281,8 @@ The noise model associated with this factor is assumed to be zero-mean Gaussian \end_inset . - This covariance matrix is computed in the preintegrated measurement class, - of which there are two variants as discussed above. + This (discrete-time) covariance matrix is computed in the preintegrated + measurement class, of which there are two variants as discussed above. \end_layout \begin_layout Subsubsection* @@ -309,6 +309,20 @@ CombinedImuFactor2 is a 4-way factor between the previous NavState and IMU bias and the current NavState and IMU bias. \end_layout +\begin_layout Standard +Since the Combined IMU Factor has a larger state variable due to the inclusion + of IMU biases, the noise model associated with this factor is assumed to + be a zero mean Gaussian with a +\begin_inset Formula $15\times15$ +\end_inset + + covariance matrix +\begin_inset Formula $\Sigma$ +\end_inset + +, similarly defined on the tangent space of the NavState manifold. +\end_layout + \begin_layout Subsubsection* Covariance Matrices \end_layout @@ -564,7 +578,15 @@ acceleration \end_inset in the body frame. - We know (from Murray84book) that the derivative of + We know (from +\begin_inset CommandInset citation +LatexCommand cite +key "Murray94book" +literal "false" + +\end_inset + +) that the derivative of \begin_inset Formula $R$ \end_inset @@ -1618,6 +1640,42 @@ where \begin_inset Formula $\omega^{b}$ \end_inset +. + Note that +\begin_inset Formula $\Sigma_{k},$ +\end_inset + + +\begin_inset Formula $\Sigma_{\eta}^{ad}$ +\end_inset + +, and +\begin_inset Formula $\Sigma_{\eta}^{gd}$ +\end_inset + + are discrete time covariances with +\begin_inset Formula $\Sigma_{\eta}^{ad}$ +\end_inset + +, and +\begin_inset Formula $\Sigma_{\eta}^{gd}$ +\end_inset + +divided by +\begin_inset Formula $\Delta_{t}$ +\end_inset + +. + Please see the section on Covariance Discretization +\begin_inset CommandInset ref +LatexCommand vpageref +reference "subsec:Covariance-Discretization" +plural "false" +caps "false" +noprefix "false" + +\end_inset + . \end_layout @@ -1645,7 +1703,7 @@ It can be shown that for small we have \begin_inset Formula \[ -\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\approx-\frac{1}{2}\Skew{\omega_{k}^{b}}\mbox{ and hence }\deriv{\theta_{k+1}}{\theta_{k}}=I_{3\times3}-\frac{\Delta t}{2}\Skew{\omega_{k}^{b}} +\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\approx-\frac{1}{2}\Skew{\omega_{k}^{b}}\mbox{ and hence }\deriv{\theta_{k+1}}{\theta_{k}}=I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}} \] \end_inset @@ -2033,6 +2091,13 @@ which we can break into 3 matrices for clarity, representing the main diagonal \begin_layout Subsubsection* Covariance Discretization +\begin_inset CommandInset label +LatexCommand label +name "subsec:Covariance-Discretization" + +\end_inset + + \end_layout \begin_layout Standard diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf index 9d7026d0978944949f5f6d4932c85dbe112a2a10..1823cbc4a6ea54b1b6a5aa5dae7b7909ba75a784 100644 GIT binary patch delta 37371 zcmV(_K-9m`oDa{U50E4RG$50)V<>+ukIiZWF${$7`xH7A8@j3`{~uG@g#_A@+e^s7 zw3`&Nq+k+4-@bO7i!=k$r_pm7o+kD{9+|9xvJFC>+H3aytGSTH7e&|WK(0hj^13BzrLX#JDn9v5`53*fD}d*>Go(q z)3RB^=-6}uwaMW%4gZLQL6?&j0Ve}DH8_*8V<>;U8C$R0w)wrk!jCo(t0F0qQii=` zScVkHP^@RbfVLPETPH`UZF!QMH2d}YZj>nq@+X+ysLu-U>yGvYKYY?>3# zj7R_u&VBQ_?Jk4-!G?0(4Ki7u_B{AZn-6~-P4C(ff4?GjuVCIp$L%hC-!Pes=$TN! z6NTmyc({eHwM;YJ!CXRI=?>3#_~{OumxY=yL&)qhoDpfL^@p||GP-dauGA_sh2uN* zLwrVo0i;Fw!SywN%$&;zn#2v`55$#*m~!PZp2L{Jk}H?-@2@qk`uxLKkIk#a$~k{c z@QD`-R=|iQGmDBTyT=>Pyooe5;*Iv1_GYewZ@Tdg7n*x&%h0j@g=oaTf;a@g@B60Z zRn5m95Z%9T>fr+F+BZkRLbi9nEjad5vl|)k<*wb~PPw!>?O4n9jqIoo2f3MPGl3Md zKH@EXvn6WsIVX-ygtmUb6iA%_O+J5F$8rLejqR}+#^%g(HLQD31t&I#J^MvfE;b+jM#ts zDdpq0Mee~RqdlmsQo_G4E!sno7of`ndo$8qgp8eh$^F3~@}@Zx=z)W39ZbE@dQDu6 zH_0-waD*IDRxp4UVn?Nf<&T9$jh@kA`@M*Ao-0j+tP6 z29ygo|0XMnh?_nueYG-KW##-zSni@lMIx4+YN=a)5mK(Ha0eVI0v0|F#Jle!&MybCzH2x zleeN%o=x70$=k`5;`nOva2I-*1H%{EPAg}-9|~=YKxojDM8qLrIM+LwYfr$udXHRl zS|}s9eCw3*>s)8vyXSwYe>qeCxn`7^DlMz8EMtyd(@Q&BZ!{?GGj*RUGovT7C88Di31cb>BNAWG3!nodK@tlm=fLp;B8M+$`56bC2mOUn zSzi2Ze*x1~^$efkAN3i)b+m=(u1}NGn8(g0B?Mo9>(fagC=!1{{w zN*ChX%fL>zNWQqPC@e$(vrdf|M?L}5(I4PSI4_}$fq-Q}=h z<>5_oNYnRSkJy!yaYXy~-AUFrzryhcOnM86SO^{Jql^NUoC9O(n212h`e*5t6|k=W z+neo7<^@p2`AC0RY@Rx<$aJA!=;Tx9V3DR{7ypONRym(M61`UGW@mm%CN|46fe3|} zMY;ZCk~Jk5W%)8<?X1@ck_#tgh-puZiJ}f>*1brqE@UJ2IKF2>F?$)6R*0!T{2+eY<~yG6a8pBGFt>TlmZ?MdbRY z$hAzae-^p^5puz0gBnMx>QTsm5+bRJpayzU{4sH}AqVvGo5}9s=9>9ME(g2@MSld4 z%ZV8r1#wF9Q%YMHkX7+at@Se#T&98sV$%PZQO~?tN^j7_A}b0viKi?~^8mSwl zV7=C+DaLjAN#Va0j`R2dm@>Rm+CnYgM6GFPLbcCl$)|uLZ|H?gP?NQj* zm0zE_cA%kKA441Dz*F^rMS1AJ)ud7ghx!!rX8wQSt^kfgT7X9dSUn7vW7tQf224u# zih=)b`fdwKimeWY{H4AO1D9QV*&T1IlYtE!v%acsm5M=7U&f*gsowk`7^-4<&azrJ zE-T!kxw7lX)lUfrl>>!=d}{35UsG3=pdW>b5ON94;UxCyiqK~o!e+D#+k1tZHMsyA z&a;0E2=}Ml6escy2tM&w@+>nIINV(V02esP6v2V&O=R38XmH@nEYVO_a~mljrK+&* zp;eWmRa)6cG70d0IR?xMl7Ftwk`Wy;oqR%y6W55mMMXzqk|q^bBO3cKsia~8TojYWe2fRr z4B7tie37u>squf};Y9X%*>Yu`RXQuRS++uFQHMhjwhhsvyyD+b=CP)FZpTv9H}xn( z*D^G^AumY3Z^(M-Pa;FWhlCJ_zD249<_OlKnF!7=-&`PG3A6vy9XHgyW^*ak?|Of_ zv4w26SU~|wQbZvk+$!$4cPFiGi|xOEUD}?y(iUqWQbZVGO~*U;Jtj@JBmV{Ru#v(L z%2#*~_YoO<Qt z4DIP7|JM9@(_BT0ZE@r%)P>VSQn`P=0wCLlRfr*b3nW@##cIYVRvFpi@OTotaRqniFGqdNhiA>pf4i-P77$z0F9zJ*~I z(GbniuT zdOm#>m^j@XJ(AAfM_>91`V^lvYP=^#rimOQhK0!j!O^xhq_^2 zcOX#S#mI-Z5?=7lYSMvf9l%rFLB79Z;1mL*K!oLopwQGOhFuGg`K`$UB%j%rvZ>Tn z>C8Fxj0!}XsR9Wn-Ah?-)wSG9W_Y=Jy!6Obb-(mj))eKn-AOLUv+pIxOIJu85&U^B z&Eh=R0uE+xB>)I-CAsv)uZ#1=8x2B2V$PNU#fEko3Y3TiuTK@pKG;KPdgPhJF!H26*krL-_0?BJ>Z^-azx#&k8KcBe$7UCoGph&{Zl;|k zl=9idYWA*ZuB+{QAq2xKyx_&E{*ek%?coKtMN^mS(4hM1f3|Gu-8QzW4$FQ0Va|$r zdleqV9-ymzIbSGM{Ht0vyZz_zwm!_?UwjKPsi91aS>iOCEjT<=CJ6P<&{EoA%Y`ID zVnbq-4efr&_2`Ioaz;aoAE~0b&LrWIw~d-yH-aR+u=#=;TYQN>rg#@S6?A5ZGt_^< z4dI5*7K~`2f5V3&HWPzpFtq4;{*>uQ5~EGqK;)%2(B)v9-_I9Jo8oPzH^vBOsZ{h> zpFHg|qZLUkd`6RglHnAQNLOb zVTrV={o*n=JZhtx=l7X;TEeZEwm7*3|7(81tvYYPf6p-@cT&!)sOkiV7J^FR82Yjx zhRM+M?c9o@T-Pgr3nz-ZIX8vJk8lr|B&+r65bit*Ia!q9_Aezu)!mz>Y^v~LQ*LX( zrpw)W6 zJqqa|6rNn(ZkLF_@w44!`09t)-irkn&1?KM#fRG_KDdruMhSG3z=WYh>`4|uHM;{$ z1#sOf8J^aym@qOxd%dkzev&jyPel~n1)Trjf3*=~3B(MqoAslqR^)~0ymKbYaAQEIuI_c$$TrUfui4@-Cwb8%)IOm%xn&=!AYG#ZRMx#kz zAJIEZ)DfZBsd<9w7@N%V`+RSr4+W>@*?~9s0~alvWhV_Yp|A)K7WIVkQgj@3Cp_Xk ze?`V)Ya!eesYEYTrW->HH?x6W^ZMt+8kgw*nY`$H{ipU8W;!&tI_G;#U~dw@XwVV` z6>Z1hQxL4FhRK3%Wc0o_w>LK)XLbjKBd&`3c|>2h4)KD^;wmELHryh11qGNy2=Hsp zJ5Tz6jSGZ3R;&=c4Tg=Y+jY4QH+OSHe@6s5gh2p0_{jqu=fKuGtN2ZZO&P*0N8?eh z9X(5!7-#5pU9*>kM9{SD>@>tCP~Ud9U0gwW02;lkeWV>Ae487(PKDW_;@vXaj7<`EZ?!azW9DO0Fpl7(Tojg^5LgvhvxIn|}7e+Qe2 z0Ev;j`1{=QBIaNpw>z}v`_K?)ak<}Z!n=3!eSrFqwY7|An8H2eDxtwH%X7H{_6%xH zneNC<8F4*b4wMH5>M0N0-0$nAsp90zY{Ce70#eWPl#KBS5$3;ua7iX%9|TrA*51#I zg41mBU9KNYWX0o%BZ;E&QC}Lge|ko_W3~rTcPJH#Jxo%5q?Bj9j%!1tghUn5)kNdC zzpnOGc63H0>jccIOb|Lq9y!l-1KD67A#xMIPFR?L8BZWhwBV8hNgTA~S;L|*WT&^o zE^DdKrgz;WZa#2ffGW{BflmvBZ85_YhmRg8?iYv8n@!d1>t$%LDdGB4f4E-mfbqu^ zY`0y-+L6W7Acrd)(kPcxtUjt(OnxMd5eIs{uC~i4V3gDrAj0js!NEN{fWSm3vq?Hr zeJYntK&2!Vh5ML_o+@i;L1aXzUl!LNMWjc_zMVw&!NR7oee=R>U!TBY^+aC%3u62H zQMPY?C2XH(+5SjC3_S_gf6v=5BZ{e<{fIA5`Y}2!=#ZnRs;kEM2wqZ ze~#(6uUA@D{4pf(yFKufvZ)Tak*N>!3P_6Y;=7xs-qin&8)e+^f1>@}V4Ah9u_Ap4 zPxjTiuHyA_f4i*9_4;%Ak!LLaJv?E>vbt$vgUj5kxCN{1mw7#$55rDES>n`u9O$FB zT1+fCFTTOrJklQ=8ko`MW?j9G+{vJKiZp+{54(yEI9||4;Cap!J}C_eq7ze7{*n<%I)VzvwdmT@ZewvL;j z4omkiFWha&$*LTX9X4^_$0YkHFcF~@qo?Kx>d+cF zjEk~*?dK8#MKsIg18H_-hudzk1^9Rh&7x1(qU7*RIzKlo7m2*!3`oYXUexY!ltIJW zs=m5LbC2bl{dK6|gtb_Ow)vt8qe#{!n>?SI!YS3o(q-IyfxI`SGv$7FyIo~NHY6cR zoVA&G%&2v1f7IDJkCOpdhMR;ZjL`*Sbmti3D8y+nCp1R=gb+6==|86qG!Zw_^b?(a z(5U)!6Q~SM<=qj-!o=V?Di}u!7~`y^C4lCU0x35TUag9DpdK&P2+=`0&O6g51Z-|) zTE|F>t$oRY1?Bm2MSmjZb$B)08}PNvzL-5e=AwWye}QVSlqA`cR>e$N74?FvGBntv zU(Sg{R~Ef5XGt93qm~{fF+UiVITA01kfm%~=h)rH?AZ{_JFxqb9sxuoF|f{f9-$ZP z)z=rVetLzG8RVP6k`c-PfL)fTfxh3K^O^hy7x^tGe@Y$zV+=cBPB+5mWPV5Ee!bk$IQ9{r-f9GveQLW zrjc~xMx%DUxlr|R*G&kIYteJ-C3?|y+`#}=nS)jXah|_G=rgA_AaL`707ZQ4)@rkH(>b)OqSc^!3H@9v&q& ze_ifaeuj*1*Hqm`TV9jYc@n*F068(ft@6IDjh#Tt-Or%qBdC(v3~BkK5=E-1Q5YnQ z^Ks6fqB8P6e||w|Vosy7#DlE%6fASbiGvYwBSE#WylQemiaWp04$()nhhssf69);I^09>>5tX?lsUsXG6sE%Xc()U&w>s6 zaXhNZ2$!qo?v2eahsx0oQ_t6HLx9V&qAa6BIg8Q!Gw0pF{t8Ee-)x zpBEucpY?ro3wAOFJ=MHM2U$6uLd4tz7^IC%^G~?p=yxGaEN)3zh(#Y)^8pL|e@>1{ z{v-YZm!gYDZS*^Y{>$*Qs`u409@3Zbged%CY7-CLgaelGb!^t3X&Rle1hCN0Tyg_q z=Q{1vdvT!Z(}w3qh98&E1$|ILm&eWd zQ0339Fy|ibZ>Ak3$%8mjf7HmG-x#}vRW7aR^{Bo&b)=9{0pB9&HJ*8%slbzvbmD}9 z0!H4^KQ51)(J}zG3(W2(GoUOV#$yBLQJ-=84>ZyYUEwZ^HJtlhgCv$w#9OLb4@*cJJY^*9&kD-9D(X(g>T_sjW2V{q;9PQVuCow(Qs~3fxl^ znI?zBZ)U!kpyN9dt>Ne^I}HfkMRTl z@}roHC$ogHA{z7(7T0R>F1Ik1L{Sy3%QEXqLK)4io6d#9;&p$Xf6l1Vll#n!@GZ{u z(NliTPf5Ajubuvs@57)3I2>@(DJ8(63Mi;>d@&QCIf_c*L<;Li+FxJ@XCNM&e0|j} zSNK1jxZ{WSZMFDVd#Lyi*7wy_?LVu+t7v(q2snW z09lhBqe455bQBpPs(dhhQ`_t8Mzz)FQ`<){L^U}~cU03@cdxU$lORb>cZlb0)uny|o<*!W z7nZe)$(|oDSf2M>#N$o9%JV-)1V7SfRl0M-MXclof83Y|+#qu%9ENVr)&|jR>gm*z zJAor(S>Hs760$c>Ph-H()MlysYSlK?t(R?HubR(ODUk%x2|O}Asr^UG>pUcpKhhor z=${Y}m(6;QtNS)L6VRKI((P!I&LsgVCgy`uJEE35N!X?p$2pnZCpoYn;EWz=ox9g_ zAzL^mf4aV(&K#wM<7vC|$-qE^&Xw2;Cv_N{c$RMnu82@NW#AiFVdRcr)p$xCc=BV@ z-uNNW)&l=-mpv|hS6AzYRUKIQC(yt{wLlHDP21G#?2#BsO1l9}l})L%QUx+58?mzf zCgJEHeVs+ahCqM|Zur9wSrnlE*tekYnO-z3e`Fp1T(*J0p^4s9ZPvkSB4z9=4&p;w ze1Y1ON9WuZa9cWR!B~fzP@;&EYB#Ul3d28zd~E@GnCE1I)DV`WXyS^LPrP}DaFXy+ zXM>$0n(5sV0{%-FLx~6#j%tNRCHZ9DtglwJJ2)u-uXiAF_~&ZrsuRvSR!z0Ia<&2A ze{r^vGf5>0drA|(p01^R0(~kH15c{hD2bk>V9zF=^gC}pH*@C@Kwlrw6@1BB0|yku z)<84j0duvkw4!+DcJuWJDKSggi~_R+Rx$bG7Q9n9?R6a-QSpQnN zqMGV_Fg%4qntm$Csi+{g@GtVYBDD~i8Q(5n^~1MdA`agaaDLNV;ihl=+RfUp(=6sS zMg$0O@Z|k`kl@;n4C2BIcv|_#PjN^9{j5o-qM#=*B31S!Dx~_WS$ymwO)$%pe+f14 z)<@c(ypA6OEyCxU3jgszEvpy-!4V=TvQNgtN&F2kqlRjHE^Rz2Prdl{^5WA4df~DF z(hZDKz?Ovpf=o?ub$9XZeOb)mL$EhsxvF?{L+_A#35nF@w)pqOzb;;3{k9j@AjTUj z3!zIO{d(*+%>G;il4%VVWx<1tf6k?U&+0>4t8Nl!A9BGTwS z+t5jx7hZ#)F{K%zM|6uG4OPif$nz2sX$V9kATNyzL^~kQIWDOVg}mLbe|j)C3O?uw z^7})Q+7Xgw%yKwP%y1!M>ku1%Z@nYKOrZ*4;)7?{q2ztzV$EY$62IvR-`Boc&L-=- z>h?D8)PN6baWoKBuYi}<{T`>Ckj%MPGl}z@RFatid}30?I3$@P&5WPQ%;+(tmO(3H zBdtvDwK6u!%Gi-sMinC*e@TtxV^7v$lw%6H)NM3O_BksPGv>%f`<||6%zhSiJ@0jGgNjv9 z@enPNl4v1Z)>+Dg7QM|m9FWw|!&`^r>#3R6VK1zf-kEU)8UYj9VWAM%mDx!u7?`^@ z1((8c%M*HBppW`6hx<0)crg5M?)WZCb0S~zO6<#5Wg`T6jC1neOzr_$iI6Z8Dcm zDXa;DiNYoUe=ED)zTtAGg=$WO;;sxNx*~7lLsE<*ppYLyF<=SGu>{y&cavk2lWi!+b+u{9h8j^q`9j;)73t}uyG7}W^zkgKWm^s1 zd}JJuBIt3xZL651W2+iyR{(QY>S#OOy=1fQZN0i(f7R9ei+_8yyt{vB2dva}DK>gI zzngkqow(nz#zJw~b;bPM8?Z#(yPNyRL)(Uy3!PwrF#u|#w&lkf8#DA8t&Z({UFGxjWTw#U5WtVO^K}6zvM!dpU@SGJvepjg>&!4x>VioigPQN; zZSZf|iwcQg%m9MHVweQw8WA1Iwg*Qa&%wX4XXozu$|~D?5zvtWPB^2-Irx5`fs2Ir z`6>=h6{n zY*bxW@2A%yz7p}(==CAz5H((USmWj}x1|T&7RTbDEg%jORzA;d;pGrq8XNDL#%{~` zDYsS8-R@^Y90yc_*L{>7Rs7ZGHZ~_x0+l`CO`qE#`JQwN@`G*%^}UHIfmy;|jQ{Mr ze@oRzl>&bc5saII=-7@Hj3OL1s9Xl{{Hz4h z5rZ035L37J&HOx_8P2o6sX&_>bItG^#EQcq={0^1bXt2(Mfq+wCC=uidNM(9@=hFuV&6)r6uwLn2@2-er&k9DOsl|WIW+^2 zy92SE7yKWKZrj9@hhruLG%z=0Wjo(k}9Q(hy{l|-96p?b@vRQ?{06te$CZ{U}Uf% zliT}=76>ylkwzkn>E!lq@}~I5X1Ob;Gp0%L&+X=M{%*csZr1+B(tYCM`{|4nf1A~m z(c|$`3OAuB7W1{g z*ezGfhxzv5ga32BSZogKDb>Z^-?#_T?&9rozVlai+vR=uc4J3AO{pr%Fl@hEl~YoD z1%DY+#Gfp~=VG&3ZPszJU0DV$f0pax_weg-yI9U2{H=G}`CVzHv*Hkj1UFtBP{Izm zFNj2jDgUi#$;xq2{{A>$-}&qP`*3r&pYOw^=ie#O{S8bzWpZ6tCgB>EkO3ENf}b(P zei+6wwj^@(X>e`0|MC8>#< zwCu3@yx)L*NmV>1D8jFp)9Pg;pVA}=lNXbGn;>bBU=xOn2v#wVrlJtlLsKxsKxyYr z@v3u*<|2cui~1D5q(_mF_ff!R0BrmS=I$cGfa9slzgW0#28@V;+MjnB905)iaH(PZKSV10kc}I~c@} zq-;WwCalIwi_*-GngJ^~hWaFf8cAo!mnx!*Lt5wXRTqaegF}P3e-SUx;c~stTr5J6 zQ2J9YmqD7U$o6vI;TK#IAd4fcU4zM2=Q7#!@>3?0aSpz(0tTASIHASudz%*6$n$RL z1J2GzpDIqRHxQ?)p!8Tvl6;WU5IATv#+APvVj9Ir1?4T41&Ak=jgnxHI))uA6Pi#+ zyD$o1)U+pt8^OsMe|Qk@52Qm+44AAD`nJn3iHM|LCpp3}Ai+^{z6wK!EgfOPDf6R1>(U(+bEUC&`QXWT9(z&G7nylvg?ecfe-o4LL0k#Z8c14P7J_~(QF!UGN1i9-^Uj6=!-UZwM{=#h@oZJonKZB$I; zcb;LN{vX+$y5@k*+iM)BjhIltW=3n4M$(q1v94pYe^7wUWte{RID07Xlh7}YsQ%bmDt3>4yAQhprCeAc;(PyH(!;_ zM5D=)@(FKX=}$=`A({?5X1gH%%FnugZw=wF^M5^8QH>O#$pSpSpNAfeE&|uVqDb-I z`CmU48SU+AY??QLOj@#R-Fk%%I<^GE1P^}zf ze^Ix8a?QmrO&vv^I9wS@tM9x+2A))e65Y=ewozO1OS}IJ}!V zqoJ|GLv3DSSNY-KXT!z)cC)JH4L{tLPs`0A4A_;6Q0&m)mhc&?DgW1Dmuj9?9`3Nl z^;*H9x8?5ekSs+dq~{veOF)p-cAEZ087z4NB5!95;xx z!IjuBbDRn&;RGc>MuG)Q%4)?RN%RI_^&nN7!3-u)bjEP==i8g#ZfyL3#Q{Yaf20_Y zQv~KGlf~-h%`bRz2Va6BU4VFYLsynpC{Ez=Ve-?>k2l}heUS!dlu-ou$0ZcdlGYaZ zv|%oYZEdJHD%nV^HyK_ft<$1yyFp?FW`_Dwj0~03wq-;cjgH33S{8_3f7PG$K-SKn z;;oHLt(^c66%BeXu_xKGrxr&Te@SgVE=Q`LBdBZz$>E4!jiVNpLdhdkouj{|7&l;J zwaEld(E^V6#rrxP-JZ(m1WD_FHyofNVl?!SY-d57gUVvoBt?=p0PpXlbh2Wf1<8{BHOmx zsx}bTybcGQmML;9lV062TRzP6Xb=VI3Ii!2P`Qx)B8ZXa@;&94Q!&JIBl2_v>6;7H)J`hc0Pc*TqE-`g_XGM}0^9)v5LarlT zZkbGhKY)pkVVU46h)RBze`Pkc4rQqzyl$BTfPZz%gz5_hN$q+sCMH^6VBr4}20DD) zc8nQIIeB{<51B^!bA98Ly~axkl&K~stmbhfUd|Cd!y>$Y-vuA|~9Hf81wOO1F%gelhMZ zO^{37?bNylfKH7Mbj?OF=txU8kx1r`kDdzfIP0>_BQdw5xo`WqfB&(^Rc6AI*(-&}$0yPrYLFR6wAv?MPv}WVKJCtxLIUedg1S-8 zoE%uQGdhAqWgL>b@O0$qtcJO>OpKkUmj3gpv`=>sJs=3VN$Gj23r9{*Vm8<F}c>{^wY^5OW;^>GTSqui{}@f6}5G$C#=g413v$G}d@fCI_dKO>iM{ zDSL>I_w%4f1}YAbM19Uk)kdXe>jf+r@>+0X6{GJTr!!%y=1;Sm30V$^OD5DNgfM?! zHkNSeLjoqr5eVXp zOOrbVinJ~lDAi^JWFcUQxdJJ$J;=gy1cGc;^sZ2(MIpm$n@65Nz9k9)McEFeBC=Ob z0aSd^J}4)}_K`ZBC8xz?(j#X@Yjio22Flziid;Dve?%j|q#QXlpqK8GGt#1VB)vq= zD*I^?20MWwMIxdzf(W(ep>>vtQd>**E?uNWZP3p3IrrE>43&K*YWKVC{TUQ^u^y@A z4s}i#f$*R$EEueYmB27VT#cfGNa`#Vh_njWiS>FFupAZ4hz6q6o*IKdDC(R%_FxJ4 zrvkeje+5fG{ZyF|v4j|F*PQYpX=3otkR}^QE|;bYNbDo&Inu<)pCL^)ir6Q9g!l+3 z!n8YGKnH}Z!hVL3*$^_ikX;Z$Se}qE=4S|*jUOPS)_hd_Alh!ZYhs4vi2;9Do_z4I zkn*|osK?od<6;Msr%Vz?hc0TropIS;)a!mkdIJ(aC@|-os~cJ;6{d!xwtXDkR7;T zUrLiDWQ_G0LgwOz6_WFD>kdNbY2ESEgB!#0Wa9=g^tjdasc^&2a9VUcb>qee3J9dm zf0O@8xWSRMV^5IdZITV)mZ7;Lk%kwCNRZ@=0xwD;X2e+VVjJIFp9bWMMF!m97B{j) z#%^bJ5Q8okITfA>c)DRDiX6cuL*#6rQo=opd|jXdO$b9zWB8?-s1PVa6WM4sx+Y$A z)U#5JsEG(u8Jft3JS9hjJB6q#;9GEaf3d(3$A$&Y$3%PHIot2Afr*e57|arwc&VBq z+Kr&4Na`#lT?se^!iIa`xN~{$4#M- z%JzGYn{wC<8n`(Gn_SbgVY6FH5$i@!QY3Yjjzn5V?8HMFu-Vp8>(B=%2^i24;n;a^ zocoDKpgzY_KJ7Q~fKuJr=h$-Ze?8>_ACiAAr(A|kv?w9%8&&L6WyAZh($7H|ak%@E za=)TQg=;3}`*OS7KRH{-xjm7@P4$S%jAAa`CsoFMGRobjV6?zV#c*V}?f%hr>X}lE z;M|=&&QJ`c;l;0Aim7N(?v9o?F34R8p-EeVGIWR1FI_+&8SOf?_eqgWW7wZSN`an)dkJi~S$X#{r#sNLJJ?Vvk~%Q<2!ECe z;>u^JAlr(FhH8$V7d!KHsa}uJvIdF>r_Co* zqZL>{CGJxi5(NejQQS1&uyvF-Vsq+QZ3%f79Y=2Q@<-pmx43G{e|;ivJ1GP^#9#r6 zyO$<@Ca2#APPN;YSGo5GfaS%}ttN7BzFy^g&4P1D~ zpgooT>+IS8haN1xG0?uEFTRYLcD%NdQv3e|u#3*h_y4a61CNiLL#msr+EWy{uQZ-X zSH8^@s6Orr5FCT%2LAvqZ-yR|9djlEGcuE}V=RA7bKEu(z3W#nH>t9N;Ijc7Qni(; z&DQQMwYtSQ$hH!zV#`@s71#dzeE=dVMfhBq6_q!R=4c<7FK&q(P;!aTLDzHeI@zS~L& zW`t=pK1jFiWO{<|OtwE!`iYp)Ci5FrZRcJ0T%AEg7-kJM2AGg*oBjQ2WBlbSE@Rg( z{&9Wr-wOd#@D$ArBV!w~K$@C2A1;3Wg*Sh1@ppI_(~6qUvE_$GC}yR{*Z0kTE`GZB zAq3Ot$(<=OOjZ;CYIV_2lfz~Y%E3Za?C{&jyG zdj(Vj3|7z%TFpi=V|)mBAv)`K_jivuBsan-CZxg_9-q;nxsR4apS=WHUJZKuM<#+C zx}+O2iV*^HE`lU;&dx z(_EPJwlo2HcZ~CQ_m8=u^vu8>F(-fgl0P23ltp8?81}s_jUJB&b2990LD=8)VNXR- zuQY~VqH84NPQ-`V04H>q4Hlnrel`HSJ?{8(dNyD|h4VEg1IEu9@g$QWvFJVm9%j*r z5(N5zUxc7Mh9uT`BhEdBxbGPizngv?8s;@|J_N90(|>hN@Ex}`2!KL@M5=#FeN@+q z2CXDq@65d7TxKjGe{huAsBAb$CJ_2N&uYWKbc?BopX5by7%Pa?SZJG3&i?Gl``j45o}z*Kk*8aE@Drjt!zg zVHXX$U4ySPY=%`B$r=_4p%$JBF2~ekN*xBv)I;U&L-W`f=9Fn4D#c;g^?Ax(o{!Nz zYBaXAjht=k3OLGB;ARxJ-Eatz^~Pb<#IxbGktch!%;w}InAf4UCZ>P6IMu`D^Z6}h zwz9^W>{JjSoVR6EO3y;CxpqU!9j|mP10&ILUd&4uwotkl+TR#1Vug(|4tYsR_og2b zwH7z8wa8|t(UfeX4>vXMy3V-1AljJKqD`7*XD8d3DBC2xYgV?gm~zTDaF98y5vz2Y zWXqs}P`a?v(2KeaP#AyI8KumU7lABOBtypDw+o4yrkJn^)YjosamVxOkMf}yDOG=f z1fgIkKzCXGNwy5ij4`^aYM5^htYMHRXgjE3PPfdAqz!l;B0;NV?6nLDh_8ZuZ|j9( zFSG0HD8G=XP`PXK!)?jG|769Za9pH&fvtQXD~dp^Q8{{39JzlzRZ}^@rt&EA$!jKX z%DXZ7fOKqLLDWoHU4*3K=z*sqD3=t(-WIsdkyxc5j-pqf-VJ*(&bgyf{UAarOe~nR zatV?|n9GoqlP@6QOc1ysp8 z?JIbP(qFgx3Of@$b-b_iv=mbg2o9P>6dkInW(!WGqKJPGJ?OW5LeF*AbCcg85Fh|9 zDee)7GulL1z5F?dBLh$DcMpM=+-Tk zTp{(i6AD#}SbE#8{{>hs9(7B$fTbE9N-N!PSQe`6YN1Lk2~~+Mmmw*qUWK(tsEQ15 zbAHsjpi{XenW`hp3a}?rFBA16G%8g`qe^6nLA8G*>JV?}pOq&dUUh2XT~euZnM#!? zVj0wOxlpZ7mE848kIYdMzwryE^1VAtnd_TRPO82sGj;z6*^*C zu?e^`mGZeS=Pc`!N-~IL%wrEW(nYtM3{&1V%9@ynuaRVWTLemT{*d+A4nliiHJ%-E zOeBA`@OmQrebkuAn(btizP%V`o$IbPxHNw?*gnh`5mw!q`yTP;f-2jF+f5Bol$ zE?txAY;A?)#jZ$ohE-nNk8`Mu2Kpr`9i$&&$>4$(S3t)|`zl^;ZB_Tu#gK6`AtTX$ z@5eE-y$goe2;K8~?}9^$D}37g1qZCT2pfOQ-rioiS1@wH@<`5M`q@fhy>|{DFSlwIFAh%q8{JJZJTT{rP)L}PiSC)V4 zL)b&^tm3^3sRopaL`AlYY71%#N4f?qTT_R?Vow8$3?DL0!aN6S;G?HGcw}}X!by7R z;`G+am83U>Hz0#**2{5c*uN z+c-|P!V-Mg_KhvM;&9BqF_ zT&N&Vx2ALxTo9qK(Cy3c_Rp76;-$mF2jHOSx`>Y z0Kd0&5cpL#!Y4AkVJg!YKm(fJNT#eWz{Up&i|SyLY&|_T&u~aUOvEL)qhO0rp~MZ@ zS`FNLTQzW3`Sf~<5GFFfQQ6@DG?y7AXX4yS$W^dT*8r!t^)iD}6$NFu->^rPnVQca zr4C-!0KT_X9r)7}eI~q6N{oNYlF5@P8y)VTNXiv`xpz=0#ekjwMRK)r{qIaU+8&2} zxjUni%fBtXuPI!}4P_ndldbCDS1Ps}3dw#HHtle_=Z;KS)P_cvAhUc5BH04hn=vv^ zbP8hst_~i;F*i$Y^-1rsNVz&-BwGi8p-XoVhWjKF^~;Wy`fYv=g_nOk6)DZiz+_pN zEGo^(7LXCPM+`t|N^Nc7#`o(SOtt^Yc&{0Y?X(F&b0|U z%?owP7SWb==x0bQD@>o>)(fRASwvgKg{S86u{DtIZJiHuEo_L%_MFR3ATL**;fzQC z*e*ev%0xoI_Q_Ut@M~3`2J52p`|E#k?)W`nVUeN)nB`h4 z*}?!Zaexa(EbJ_`~OX;y$@t%`$e?> zYmGIEPmQk*N}xaB-QcqDj*}Ri0@u3Dp2jcS+3&35$}U}N(i%PS^4M!lqa%o%IinkI zkm~x(0mStF-m^GvSn+5f4PWvsk>rMVC@GM!>lW3|@9y4QNq6~w?rNi@x%?cy--hq{ z^3BbC`{V0}+ne9p-|p^1gU65UU#RxS4>ykwcW-V#wSW5c<3soF-`_l7f=GM$zbmIM z|At?+y?nU++Zh&_V(`Pw~zNX@7q7!+`nyGetgB1+H@BW zf)s8C_YSuIN-1$4dHeqML-(jp?SX1xkUoU-Hh#PF(6U%yrvC#z$jcV9&V8K-0Zo%^ zh8Y1(vxbJP0RqxIvo(l?0voo8(t>f3_IBPuGvGnt@BZU}x9<=B18k;1N0ZfxCImMy zHz1R-V<>-hluK{hFbv1<{S-b8GEl2}Shlp=)(6_|i6p>)c0H(xn+SE}z*4&9+mAAx zpeeeGB~hfr|BsYE&rZ&+M3r$y4KqBOJ!M)^CQVkEiZUj$*&@3q_vJ%gD8|Ud&2yp2 z%Jz%AkgO!%#$ns{HWxM7z{K~5!)w&0y`%* z#Qtys_*y?+a~z}~$c~mn2+bd6w`W)CNQ|s%TGu>dsN)j^Nk-N-t{V7&7zLNMDKaah zVpLZ$E4ZYpG#KH0?2}WMD@GREd32Cw=iwa4B6c|TX|sDA{L-O=ac#ZZY+JYm+=tYT zIrD!S=B3`JM)RU9IXRyszUL`VK{kC8LP8-q;l`8{6Xm+58gv#yP{pgUL~1P2t@T~N zD&>VRoP2lBsWKfT-n#j_m`qJ2llxT8p}Yf_d2D(Y1_db#p~yTbwXJ(ZhgUmTDz3?* z32y0e-aVzUCNC~*ZCg0s^w9zDVKX#7bp3xg--Xz$1M1U^N~4bJ@HBWLYd)|B;t@^W zzPP0YdH+LgBo*Qf=%1?#1PiSY98wnKa(0c@yKSFZy(X)XzhJ!D^M|9k&~NxxBmWBv z;)N1q>eiiq7k90wl;u95ADigb35w8yglJ=f(s%lNH(aC@L z-%OU?#ocHh>X3GP=UV_i)Tu|4-E6Q`vAQ7qJz7%MAWyyGCAlEC-O7*e#3-s1Kd#R& z*ETyO^#M^%J0A}0*nwRI_q;_{kLZR@g|2CBNUxibS$f#%$D+v}pT0Y^qex@O6gqV2 zx`3-2irbTJyKY(sZ!si`*5t-7T;E2_Bl_VlB*DaWLfFDd7(KLFGD}>KSJ@a{+%6hi zVR4E<)LzqT9;s|&r-6Ef>bcRh5+*AYH4gFC$3@4kCq{Z)TW)l~29)wNfzy=H2Ll2p>s!A;%U2?S&WGO_Ri)Ff3EfUGPm z02U@TcuGn!7m$gYwWEW$i5rL)pan7qsDYdSKvuwC2oRnUAm-@g?P6_d<$ngCF{Aw_ z3DC4NF}Jq2b^&NQ+Bteyn^^()Jv=;wJzU+HT-*hj{x+$BKma!@5WvFP4g?TWQr3}C zlmgI5DQW zGx=|1`rqikRTr;+M@;ZQAi&((%ne`)vb1)9Xa1LNG7c7w0M37>&E1{;Q~FED^)EjF z&0h^^0p=i!zi4+mJ4F+F5P(L^(ca134den)a5M+GH~>@~?M)p1gMTuyx3=^C|Kk1^ zA>(H9R|gRX%fHI8{5xgsDrxNnGFP^C`zy7DiQQj`{>f{B{(UYAAaiSX`+xU?{_64f zM9m!??7aVX%fDm%vmvvnnzER>8vTC_@K0I7!OYRz+QAZ_=Jr=h6BqOUCjKcan^^zb zJ^vx|A2$Jj|F>2!aes5M_5$d!F#XFOEdRRx6B+y;N>tR*%a;+z%>iI!V`TvV+5g^n z*jfGmAG&7lE-oMkw|@lxJIjC8{}>4b@&cK`uP!;7@rBuBwntP2NR-S}L($LtGS;A9 z0)APZ>b=rKvmUZCH#)e$zfs38^h6|@4mK6oIp3DKX(Ka91b-nOO-#m-Mj0&OKb4VJ zTL#o`zNi#EH$@pJ?Dm;eWl{ioIIVS}ydy1-8Ipi4ZK!psCaFz|Up~E4Z}#nQ-j-rN`5)U= z=n}PkJ}O=atar~TFj|85sZ(n{^`Nd=u^PNTB!7Y@;QV}ISO$yBS-_@=Z{aB%ZPtAg z4L7<>JIA3baj~SP$wq~6Ekq)u%d=?ZGSLC2*w9>0TFBQ^A~rOf5Y;XD|Ndr9x|Gj zgAb8R2PN=8$7+w?u{#xU!R3bPcNZq)O=~-tex~ zDRE9Q^JzhYX9diAU{0~eG!U7=9|4K6ud$r=8aWEcY;*gk&xXHoS0`+)QM|i5=zq_E z+`MSRs*q>iOf6K+-c^k(s7Xwb{>I6g3-E{TOSyKsjE`;7w1tiD6N$#C#7s)-G0jtw ziqIe8oQwo+vlVqO9S(O{>v0v+Y6bqfwh$f2-dV@jI|`xr!-SyBEfZKncvQvlGRYo) zR?pX^r+;Zz*V9KI8Dxu0-!{}2n>IsUAADbnX~)MHInwt) z9qmn5VZ@{j?VI3XHz(PI(UcT!3k+{rBCq0$#BxYMm7E0;<8if|E;$g%hNmhN9aqbQ zNXgY%?CNA<;NU3X>aneW8%*Owlld_yHxQod!O{EGbTgBGcpejzDdj9~j zN-ruI5vZud$}>e`cgjXvjBorF9)*IP14aj?{n9RIwxdMJerY-CyH{D8Eq3$8Hb30+ z4p?nZJj+*BOI$rONSTvm(SN5x9LtGGJgk`!1&nceOSPl>)@jtwUyizJ_f{1^_g%Ro zgIQi_hFOe3pxh}$#6Wh~+s-~3t;S1EQIftyXi;>bdvefiVNDY#c#0M${n!kaeoUDI zYtV8_Tc->1k3#NNAY|B{$RlFC23HGNH+3%2o}!007O+_i`|V{O-hZfFI_%)XP7Q`z zsXG7TTgDg?yoNtMO6CkgyV`))dxUy!cwz}~N?9yV^dTZO_gH}+5}s@IFdghGQHBRk z1k`;edZ4wH_SZCMR{e-(W6qFM>&%-P@;}uP_Oy=mJ@F_=m+$lxH?t_JtBeiNF*sP@ zCOpUaA~||Kh+q6Zfq#4#88VLBRj?}ikKzQf`sfp#ltH14+s}OE5!1qPu^49|(n6!3 zRvQ4C@K0MA9*q9)v%2Y}7ULrv-44v&;DKs?-pw21!*`HOLYHD*u?6K4ySwq0_ZdsH z$OawSzN>?XpJv_ZQ70C47OS(ITf&P-U6(d|X{gCUuJK^-0)JKmz;?}BZXW%MEf{<8 zh=&4y=JuiXG_oS57AP7tU-}!d@c)wJvPcx_-3OBU6t50?K^SloYKzRYf!JKPh5g>C zAwnyCe^qduIhk?zce~NyHM}bO`J)H5xLJ96lH4?NNG#JPdu7YTSCk`)I~Z?oPMpsd zoxJ!3U$vk0#D5m6vo4;Nqw3)$QXJ+4qx!p+*aI=jOx|haVIe!b?5JC@W0H_=EFg&l z3zEwo zO7Gol3y;S?H+mdpt5a%PPd5jcy*ayu2!z55p$RIE-%l2%7@-@PHY9z|hKYu{act=U zk)c!96ZBS5ExgZ5!Ih`~rt?gV;(xhu!GaFCZz!ewD(ETVI!AKN{Cku; zecR*u%;n3%6bHqkIaKPXDj^w8_w*LONmo6}Jew0+U^^Xe|0x<)m;;msCFgM2O0$ga z!*~-Azna3#dm_QS$J$>eQtW$pL8(|;!!_BBXMcD74;FBerL4aQpUX*V32pSJIt-Df;=NCh!@2XNChE{nq z@FA%n$7l!%i%@(OP0XbvMm08-gpB-UuYW3=fJ0KlE1oaAMeiy42d68p&u*`2mJJD; z|IcG8$PGw%7lWf{cH$!yqFad{Gwy^zB|clhyxxxU(Ji%DE8U*=j`4TS@05Fk9JG^eyFlG1^jSk>6MYJas|nqPwI$gsgnRT{A7+u{zn4s{k(CEZ`YrNRnf z3JkkYE0v1v0((v3_?EH2vspy~wVPs)WH~&38m4c@k%7Pfym0>WdKJrtRA6oPm7G}r$r~4F8 z2R6uz&rad(w~+|#{2bs#G!RV1Icb0g-GJnG1F@o~A8^e}Uf9}>``xwG;)_K~J+u>L zY9!&3RaYW7HyeR?IU4NRHgAYam^Yw)nxvtiq`#jn?mR#2*C_)nS^81N$DAl9K)D{`-<7W-3(} zIUGCF;Y8UG`QgplQjnx~P}Fa925YuIUWZ%ZNcFc!QFyo(eVC#3viw{!vG&4i!Nz zOBCTreH6V4{I=kWaSmn&^ixCfDKL@RnFp4jIgIWy3M2_$psp-n;ewMIdPDN@rBh~} zbSlV&;0ttU=?cYIvwywz{Wl6y+%$Xpn0^vI1093MGw#eDAR8yIF%M*ifKsz(^1lGP%B^y>c zykAUYrHD?3*i*5~i)fs*4m7BRyHOPx+UEOf$-rZk5L#} z7Q5$Hm`;_ud|j>r)p(?9>k@L)6pN)SJdWbzyvOz0G^Fl*p&QYUsj?v> zfL;*`F;SR1?{A*254JAHwv!aF>0i>xxa^lagBi}}uYXr}v~oCFM5W1Nh1n|%rv-ui z%_4LP*z6ES<$b^FpD}7N12Bx{=lp`OTh80Ku$QWg`SITHoN5o1i4xgNtZ+l{_hR)6 zO2b39>#D>Pack2~NH}S4m$QFb9@7`?W5~2p1MW6tQ{cr2kHbalK~+d4yh2d+g?Ig@ zhK5;3hJX9Z5C&S6OPg5J=F{6YS>5r9Tyi}5Xdda>qJ6dyhFI1RttJ;p$t0Yi)8}J| zH0Kh6B7~{wONRWx$|eDI;bk;v(7d=?M2qM)g$&vOA&9@=JG&ED&Ko{ph3D(#)# zrX;6Kf`=&Xq6zh_dkiNd;4dtr(h!+a(L*Phqkq4gNL7j3qP9pYNJR63?Xl9oROS!p z7x>$1&YV^qEw2(}Yj|Ivk~^RDZE2>ZFSMM$iZ)FICb7rM;KlI>_oVV@G3-l+e{U9J z3;b^2g1A~qHWK9p;hm1Ynf!XM71e!rSaTm{+T{1A^@HiBvuc{+(fQ&VK6+6gyYr6% z(ti%#bb?4S#DjMCV{54aYMe(?w5bT~zm9(T`{U}@6J&pW!waY7*hlm@B^PwEXWp}PO0bNJ>8;BW}Z%BmT5>}wO z%ZbSp(*(N6tTP_`C6eDVD}ab~Kz{_BG8a}nIyKj5a^>F-h4{w9JIZ0=%RpX? zZ9_8be5)->sN|qMJfxt#a1oe$ja!^vg;6JDt{p+~-(c?Cc8Ta>&0uF%b{CqdZbXvd zMeXDL5zw40c1j`wg}x9}cKF%xXW&&9>0sTWomOQDpx~bf7Pzk*lc)TYn{a zbc7t{m2-~M4C|attJs@_c ze7`#CVfGE(wT-zs#-jab{Hq_3iL5LtN>O)RnB)nzD#wB-Q8KQJX(YvJBV*JV&nj5W zz{nUY}F)lOiq_9+r+46C!}g{xaRVGq5~unQtOi2p|=5oqtgSl(WDE zUb~1heyLkZlXaCJ8`{MRpled9)k{H{6vWtbxcn`JU&0)nF76I#O3rQ!88YeAf_VH9 z1*NXWw&cGKmsqv8aY09oq5=9r;Tf)%HsbKwxttJ5C-u73Q1KLkC2{br^h8&?mf=!F zY)trOBzEBO(0Z{@PB(5rqkkzefq!gj%DTx_ zt5?;MqR)}fPPn`3k0B)PbjL#I!5yopoaNy}#iPDX=h;nR7^jZg_J;T?_*sO59m zgrER#i~db8JB!CO<6b0z*B@4vjH@tV!xPii{ppP62>NZ%1_nd(K!05n2x8yy2446z zSIxl7`NEX*F2CpyyNO+?Oe*Kr+GWFF<+j* z5f_RHFsM87f_lqLjep^`)gKbWOBWH-*lUs>ol6CMInyH!lrRPVL`{#XKCdG6yuSL% zcK_V=;(nmBtNv1q)W^2Zm2=S*J5rsmjW4iD4lj3)oo{xtT&X5)s*=sL7UQ8DLN5JN zhHA5#6%pu;5SyQKDtR;>aM0Z$aQe%BbqP6vLVj|YqY)uibbm%XBiEDD3jB)9Sj)dR zv8n0VoXA+siOWpc=s`v?A{tx3xspq*p3j~33B=VJuYZA^|#z+`MsnR*cQyMNg&X;G>8QSZHX0xI?Xq#~zf!hdtzWzN>2_}<27Bv=U!MoD)N zyW$>lW)~&tA0j2&BT532r9H3BZ-6u`k06zw3c#UpNGLR(D=fy>iPgm-DHOHjz9;Ur zU+HAuyAnaXD+*KruGMw={Blvan44w%IR&q{!wjMDsftSM!fdU6(i_6-k8gK(?3%QK zfOr|N+JALSlFN+Afy6!5f>5rx^SQ@L%|3IcaPYIor4 zXKFl8;!hWQC0JYb+5ND|FKD)F#V55}d~8Oi1AG0{z|(w|m*SSTZGD9{*x=YjmktJ+ z&kIBLM<|o~(@3#``xHnqN(hI?d-z?PM$C3kGk?+q2gv2D%wNljZBs>7zah5V+pX~1 zllp&gEnoyiF6Ly?sNc&fPYc`Yu2jEg*Jwf^D}o@xUm-Hnn69<^IyZUHXxRfWx2V#5 zaYnt~GzNM3yHkn+sG>io;H1A@|#}z+@F%`ojjut;o%;W((Fq!`j@VzEFpu{L<{~ zxKsZiJZ4IJ9%yWvt&4741T4-AWQ;|>RS$yk2(0LtVK7K4 zGN9?U!l2V`$;81@n2TBg3yCSHjVJm9Ca>RZb&Qu`iN84CEDod4R6i1sUh>~)xc(}Pb;P+eH)WbiyfNW8&4#;r zk2bhCJI^p?(@he6>kcZfIfj$xM>)#<-3}~AN&{(SP5r~)eS~5k1{d(umih4LALJlm z;|$*;=$qdnZ!X-he&-nwyhT^4?|%j{Txj5@*;4XaoLRyL+(SH+hp(x?cBW~4{9KT;K z@~)U(?d;?I&N*;y6zka2_`Qw_P?P)1H1%Gc}mbq5} zEWO{PI+j=&Gw-&fbj2vZ5u}DGzhN0tGGP!=fMODo@NnB4lqiGEAAA_v#cJ!(PKSZQ zyplp8{`_uJ^B&yvFnHLtU6TUEYxjp<^6SaX&?v((A`S?9v`t4bK+z@zzVR5z)I5_y z%Gl$sQ5k1+q8?#RKY1*8syr`B!0Q?oj`pRXeNWZZNwHMD!f?NEmaC zsuU4=nF~rn4diD)p7n(4ykO2 zh;&y5igHF3h3!IE>EUL(p6LRrLFH>$m9&jU7sObPp%p1(&=r)>T8=dVgcmWV+0~KFRVDW}MRz`F8c1V**5NNMiYUq>7Jn*`d0bsiCwZzr3WU zieX@7cehagkk|C#axhh15Tj8VSh1rrg}vClI0h6=-HfcZHg}F zM!Do~36`s*56P$>yo1J=hpZUYqXH zu}cdCwPO$Ps~yDZaksJfT?xP24H{xZ32@dN1V>ARnKHnEJ_p8+`GN=oO5@()Rw&B<)4=p;X&)RE{)ly8}wBz#K&^*U$!NnTRQC1`MfN1$oqOs^frF* z=?n!>L$9l#f{nd!2KR|gB4`yOkPGX;BE!>P-hZ1N^`K+3Cu@5}Jyeegyt~!Y#=%oM z*s0XUU?BEo$j*wU5B7UmkeS*0JfhPVnp6`XcaY+R&*TW8dN0mYe|JH1fSc2OYNepo@VGHskd+X%bSRQo+~#`ZKMIbUlf5&e`862K!d5nq zt_kR-!XmPW76j6yG{p_$`~8$URN1$=%%RxE3*GUie*TUqUc07>kzYL7RMX&GVgT%g za#0P_Kkli3z9yT(a;1KUxv|TB$~y}FS$~*5M8yTsW7~JAR5?DSyO9iYaP^*x;7EL8 zw1q!%@y5mq(DvvLy=8ZDFy?L;b*~&Y6BA9uF}TSU5e|5#3PIs99p7j5018ERY#`|@ z8;W%=++6|n!@^~W+u8gX(dfPWZg(Y~4u(jkt<<84KI<;*j|o761V%C^lVhUpXMa9% zm(;SyVe~67fl01JU%_q3p4Uk~=XUlOcy%IOb{PoAnQ%B4b=97gT;;lZGnVC-i=s|o zcJ_;5By~Xi56q9D0<2dClc{i%op*JYB`-S#l<=ELHN!lkK+Ym$?;oL%#;EMhP<&mL z?bQ`3H6KCbGA}hKWlOBx!r^w^i+{*umfu2IU5Tqaswu)RJCKabY0(R?d-P~F&^fIu z%cZ|?bj)Mj3$NYw+9GUDgDB;CBHOqtd&UHWVR0EbvrlcY9ctV0(N;>2z>UaPLav<( zg4fH%;TL_=s%Un8f^)Cp@+bkuz2qF@@)2BGTZ8wA(2)7GuXeTPOqA}reJI>M5j zePBCKmN3u+kc+VVmvD8= z9)_bvyHq8b)LoqG^1A}t?|-B)EBUVY1X>2|g>PT#K}h>Qv8)pY4cLq<_K2CY#y%-@ z^K=git-Fu zTSoMZ)Y@Ro$%FClMUB;=zk4vGg^)CS=h+gW%QTmSq7$y)+Iv})-mm}N4%tRwTs&g3 zF`^-7vQ?Ng35|nBy?=r(l0he^h0QXKFvA=d4XQf`FL-kAML<-u?2j9l#GG7v#{Zc! zkHib%-zeODq*>{cgMXxxjnsJVr;0!VyJnDYB#cwwt3%#1SgKewB--H9!^Trw{HV zZUp1|=9jmvKGxYOA&>+#dG>F6<2B9kJ?Fa(xJMFtdE$}Np?@B>)=}mmwGgu@lc1?S zfz2o+;+NPali{I}1(5+h4}1LCc?ya2CtarkUYT(>dnIhkBX7fsMg#lRm`aWkwJeHl zxE+=xhz(r1EimkTa-Z~o<^15g4V~Z}j0)3ybAfT(AfmdZrXYGqEvE%kX^w`4bioK7hc7Mt@nvwlC#{9QgAd%wxrLGXG4f~PpE-#LBKIGU zH>kU;dWL?PY(FeMFX_bl8KvcuOQzdfFH6q~b(c(ZJ0LHiX7~-j;V*xLr#jnPi^Q#1 zfE?C#mw$~L`$^x}=_Na^-fy@>T8@5uC7kqYEuL_FXbwe4B(@YMO_T^D%h4Wofpy(1 zEP}~4gnlI0EZPplOraejYpu8e1CK|p)=L}I7`N_Avxsx+fxPyXFL=T2H;1mjA-V1u ztlb_sk5?_`xf)Nz37bGM^+D}DZbOaf5)m@@(0@)8T0nlzC%Caje^9-am8jemA+|!b z{m?9RBW;2V(Wu3?H#TX=Yo6_c*U>%a_7{@G!YjKW4zCfU(^s+3pP{iF zKZ2W_B|qP*(D?MWiFt_UDW5nE@qg%1b*NldB z=9;v{+Luph2c(64=*g!gcyCd)se3lmzuC$@H~>1 z1?;uTJ{?M*^r^K=)aO)F>wjltqGCAHBWLxE6)VN(jKm5xBH1Vt@}iSLG$Wvofl<~4 zKso_~byF;X@GrK-gG5E5qDV6}h8dVaBcTzYdCMmaer|*zZ@62{0aV6&ii7dGs8>(?nCLaI)DEr&dfPnnl|M` zFfV~|x=wY_+`47_RF^xI8-D~B_NavobK|`15PH#GTbD7ikuPgFiX01wW_$c$@%~Kq z<}(7qW+(^OrkWq5Oj&JuoLc=vU;@VkUN&>vq~nl=RdpmJv6i?$js5!0&w$AU6cn2o z92Fg`1b@b;j}Nb3J%81EmC2YSVl9H`8MyVrxgv@8;4W0-_G1&MXII?Phy^N~E}Ulx zeDQu;Lv(PDdeM_sV__$)f)k3CNyLU#2scisbWj72`$(xM@1q$jc2y-PQU3+JiKwuP z|Kldm5WL?Z1gd#W{K#&*tD{^;1jB~Fu z<-oCnkc~9R&b=C)yj?l>dJat*fqMrny|q_-%qBDID#-SZvuu@Qul2KJEjws~l&|09 zz}7-BJO;2bCGF{~;b$gb#7fk-ty**Fr-X`agVZ7dlZQLTVay9((RVn?^aekwcEqo8 z=u1f9MC&RK2!EWM430V}-6G#5rCxn__v*>}zp8NH2KlnEztVr-qmI|uk_xJj#NUZg z@_2S`BR)CyYP#j?dod~g0vgCKg-Zy_eAd1%P)N(1%d$l=?`+ChoylI*TC+WrL{lqB zyr@%Yq?S=|R(wVq4{i!7KiG7Q8422o>TEEUEp`{Dn}2TBDu^x$yGvl7N?MLN0KVd0 z{Cv_W9A=uQYBA(1)y)HLU>eWmI61iB_J(0|xNNZ5A1=qpq2UqA@>LA-q;;nGqBebJ zx@%mcoXR~q_|TB2vO%`rfzpSD<;d0CiZ-jcjU1Qgw+IUulJ-M?{ozJ6J!f~89dE?T z!M!2-Jbyt2slWK%XKXB-IXL@G%cuihJFGWtwaBh$825MbyW+%!Pg0xFCQ`hjc7YRk zOg>%e0}3;fnJV$gU!yskTWs4eFzuC zmy6xpaS0}-7ojL9wPJltC99ZVygQiv`Jr+<4}T9)!eEjq!$~UEYBZ@nwnfWU=9a-C z7Zuna>6*RP=h3-kss_kT>j*;gCZWyw8^7}aBA-X!5VRF|QBL6c;QdK@ro%TV%jo@U z*Eh5ik^JvRU&W;;CgT7QZTzo4ATW^qPhrr&!T*J%eIGc1NC)#&WEdQN@4(SCW-!m5OfkUrhnFQ zm|RB)$|W7DHu{!Ev5G7dJ?RT&UM&kTQHyK){?Apo2G;XeZ%H+%5NaFf7G#mPW&J_F zi_kZ>*1Z;CoCG`PAXNh(B(wrc3&pdA>FRjb(RETJy`I5OX)N$NX*>54vBUVW=5)q( zEG)!uM@VIuFm>8)Y9Py`HMG^Y4S&H6%R{M1=3xV;-HREibO&lj^r<7LD}v*8+z{F_ z;@D*px*}Job$9R(62|a(=IC}D5#h_=Ad`OYDnUOu@cEyY(gPShg|ZaN`H!Y>TjBy z?TQfq_$1>VrMMXJ=AVSVZ}+oqBi3#8)CN4|!w??9O~IpO-+7QDdXbWdF@k@{SZG(! zq>aQ+JLoAXX_ot%SAgYy6@pRHTK6*>Z>a>K>GF*S=d-m_UgrT_wjz1#+9s3~();JTqN95NEWZGS z47I(ptjw_}A!P*vAX||r{rJewBo;j{y^GMI=G`Z!Sg=aq>>GVQp z#GT7g*H57@6O^QfU>O#-Oq(uSU=nS|Cl;T|TV`w@Bw4q9q6U)d!uurAlt-p;5>t1n z5!$v-q$dktqZE*^w||y1?_xW#_!;Fo7w?0Uvgo-%pkbT#i7 zn88sn(fIKB|2`GV4|XrGEEPm9UrCpepF3d+uIY*ij=q++Nq=|&=zk~AL!}N~ukM-4 z3&h)gaR54*UhUzxoecS(Lm61&@)uF+Bu@}i?v`j1fklOBB$7(LRTRSC9LGBP!2$(U zVnncq`fK4^7vcC&Sd6NEk)x$Ip|dB%;V{n?42EzeTeRYePnO=7GZ zl%3=N;#?{cz1g|4`nd1koaQ_8OURl;8y!~52`Q({{eON4y<*3sM0s_?C|M#dxfTYq z?y;4&-mS5;OaBCpvNy?{TKUK@dzq{?N8=U&ZSuigCXsrLWW9Xo5$|2@?+e~rBBCS2 zw|w~(CH;25NU`^&_(FaWQsND@#iYa&ygN0prw%pl*G@(fl4E^J4#SR%{}Sz+QdrH9 zI5#F7Eq^@I+$F0{X$cDz7n051Z#uOOyw+4}^z?8W--2%@OEj*hP{n()zbl&B4*qPI zRSv3Uw+_{YC|Fo(7a}bw@ySZxS*5J(+7Po4h_Dxhc(BPgb@arRmu?OL0Ss~D`=Y}c z`~gaRrg?up1uiRj6j`Qg-er!YkcDLu=u43^Q-94!5In&(s4-O9Sv1}RtnpEu5SGa% zjJarK> zAnYewDYXS4MkvdiJw8uKD^Qiul;!LwFiy#h+w7kbnWwHT3OS~-nJ)w@F*6{tv^=Or z6My|?5)u! zsLg?(=`po5-K#TMzW_)RCoz({b?cf|^{vKduE~yZ)KV=V6$Bwwh9~?jndO%zdgrsw zmR0fH_>H5QAO^IHxII(F@Rk@OY{@U05^W2=T9#z>*$Wfwr^#P(D-88H=WSwC5i)jNU(5F`fQE8$3xHScP`fUNot<` z`dEH%HaFiqnN>_b!W0*pg-3aDDlm}IeF*Ps6NvY0Mfb-VnA;8(G4o37`iHh*z3Dl( zXQ9d&s%(sd06F7_+P|DK#@*T1UVr7}@+W+oiJ)MA^G235>j-qo(~`hfnr zYe;>a+1gw`Vw0JrIdeo=Qc`|fF^uU~x|n*`;BF*=Pne+FF%-Iz;;FdU1`}(y2}?(s zC=xc&_tGOUqE3ntiBG^hO4D)d4&Z_O1((yTNcOuUr~xI6T!8bR13c5?A07FKlb9WppYhPhjd8HA_)_^?2#9ZqXX2D^O>rAa6i? zJdfOE3_C}xh+yKQJXwZ)Vt+=Agv(HdX!doRG_t6Z=9#-wMWiB<1yPXm;muh43)Z0HIoJ)*0i$PrBYy zyUoffmPJ|EDC=CjY=y6*AAYGZe`ajOhcIgOX(sWFGX-6pj+@v&uD8E(8drQ2$?t^3urja9tBArQ*k%q( zx4siFx^H*kF?!f6Mt_6{((uPHtKL>7d`u7)GEY)@pdiIzKy#Dj5>@jfbX1bq2+^#&Uz2HDNYAm2?eQ(|?t#UEG@z*=wAFr7q65&Xzm_XC19sF3BZ$woKK0WiP zM@FVusME3+&^xwo;cs}bFGGw0x{%){-(wUeRJ*P&z~Vig?=HDyeVNPfJ5^cp_-z)U z{)Pn#n`R1}#c2DUX&AjjYF4x8PHQhr-rDs)0ojt?w~sdi>3#_}Ff%bVH8(Lgmw~ne z8VNTrGch$aH!(Mtq_zXc0x>v~v12HI#avl)8@IB4*RPnzdn;wlUWKf^LwMu9`|!F;$A*y{%HE zovpO3tf8u@oM|eZs-Q!qV-;1bjG?iOsf?!gWVej3luoKLu2LrIismWjLuDd=5p;(Prz-6ut$@byd|npMCz7T~p>nho zMGN=56zZhK8*5cXB#rg-&Py=OmXG`%E6+=@wh9fgq#_Ut=L~JF@=CdimgKEbRUlF! z(zB!YME#zcXmcS{vC(EL5DcDwIzy^xIffbu2S=l#s+4Mo4J}$JL!^m{Qjy9S2qUcm zfYuBxZBXez022pgn$T<|#!nLw+8fQbO_dT5rS^tK+r}{`8g6MK^Q4+ZjV9PY`zLu& zEs+qEq8ZKxUI5K-!RjsEq;iS(M+3a3b$ODV_nsv|mB2%Z3ZYKY<}rzXN7Ag&L>fuG zL6e>kNGcf815yeVtaDqMRu&io(hn6vLyt5uL?YsNOd?@$r=n&eM|%ntF^aZfrJxEe zm4;EpC+15PQnfA3mBbj+sD`j3@v21ANn)%_%#a5s!^+3=lSz8(#~-)qx8KgDRsDK$ zINhpu=ckM5>Efa?r0j2hw(2+2i}~gG{`7)09}O?32eZk}{HprcP=lvMhNM4j(e!hg zN8EYTzy1ZnPl#CcBywo3ZB}Uz-Z@0z7_AxQ~AGV{8o)r5kaVzoZ;4q?B9X+{Me8K=9cTYMq zrYD`fk6=~e+3_KNrOz4hORb1*iHRN9ky+1nM#EyH(wf63231-Eugmr zVqiR0|2KgsH{SuJ0OI=1-*&?TYq0K48@_|IMv4OHF!|EYSZx+DIgbB>Pq zg*&Ug8^niB-3^pAc7J`OH0}U8-tvyIrt^ah+qgZ9Bb8*2cIUQFD}`8Pck@PsXAxHmkWwd8%W^YNYgA>uIspnCm#)j*P^60 z%6n;C)J!3N7*Cuji=;UrIj;NA_73V^B^u*WL*u2))KF@oKr7Y^k~50OjFiHQl4L?G zw-mgjCAmm+D2e7JN{29zQU(d*vR;m~$`Au7^O&NSa(QYmsokY4*Cr)+5#Tn3ZBosT zA+V@i^t7$u8f;E0mY$&uItJb*$%wCQGy`+(n;{~9K9}A^%)V<`(oEju*0$y$i9~W$ zRC*c}qv4jsdJ_}tLX@=O)vu6Q$5r*!) z)@&ug0V2a%8)*g9qIqpf5o&xR)+p9Uh%y@Hth*$6M{v=?P>Rw^ zX$;yO7zI{PUhyd0TLhL$;URk#e*l}Cl#{oco*GO@KuSmm)v;1p z!B$Y{vb*6eT{ElUyE!2@Y$y%iB%dhpPtw9vU^{q>O zZA&q@eJO4j$3x&)@ z8|LdEDd8d`QKre61KCcW1287O7hl5sEEOJt;7J3hv;6ko6uzF%s^zCy|d@e*ff#14wy|8YsMYKf_rL)xqBD(aF)EZ#0e}&bs8? zri3T>80L)d+(c$)6BD&)H`*hbV=Z+We<5~A1Q~lw8BNcy?WGeAIg=8)HYV6Dufnb3}Se}pkA$Y)Sk2NNojJ#6^eavBcgB>NC zM^nnd)ajk&!fm`W$<7feAd~Tqd-=R#%CM@WATKs#o^QlAAR+DrQYds0PP!sKTj!;} z6N);+7A@%t2US7gk_EaHOoT!hWQiVLMd5xUA!K8DM)9?gtt-KL%Eh-jKnu8-`T_OE5ponf4321Nu8flqhYj)mAK4DS~U_jZLJ(tLhg!y9(~2~ZmWu= zLYDbehKHe(YcbiDhtm7lhFQ{B>t4+ zxnw`ZHW1*~6xvm<&WV|WzmWu}QzxRj+cscrFmMnpxc(YT0U z?{0BQDnc>=Pn;}PBQ}YAB@`3lg@{YACbAonLD8``;R=~*5yuTf$A>N)9Kt4HsuXVN z@(NH&4pX8ab!jj0e{#5e7SbH$$7LOnjj;)yMXlIpM9|JB&k}2qQ=VIlmoXF}afu5~ zkzCo!h)GRKtb_E%AZjX0j!11TafM3x5>q3CiynHLGadMAgOMSZQ71$+$WJg=MoXQ& ze77EgS&b3uQp%W4FV%oz8HY}YH<7pU9jc5m zF6Nkq-5ZeBur7sjR_K7HFZmXjgM*AiiEC=pY2vWA3xm|9y#!2pvlwkzW6_npg+R4k z30MSFszFu^jLE`EP+-){Ufzh*q-3r`b&xeH?>jpL2z{spFoIejEz8batfT}s3{<*+ zx(9cOa9Q$)e@9^{-W7@+rLyw!2=bOs<&I6l2T;algR$3`S!nOIcbROSy$Vh@_(kAUAZP z*&w&9_e60C>#h45S+8x3^X^F^D^W0**j9CiI;|>7Xa?#5hk{U{UmTU4& zBhCRRe@_Hu4F`j}l!zNx1f()1AiLrl4702!+*N3HY7v|;4rM~lQnt8&4@rH4oSw5^ zsY|<1EPI)*RUvbbnvS99mCn4bJb`NUTJ zAczu)r{1j}*H7xF^-uM)`epq~{ks0O zepBz&Z|mRc5A~$}T<^~bj{2ZJm>w@C^|YRzUCfT>r>dUP>c!lJV~zsc@i?!15T`X}rz-rziVdlVvR}EU}f32@N*u+h+dGYZ5AFm%1HgCp^$TmwOYSLY>S-Do9Mv-|0 z6kZ?A>b=<^;ZiuWj_axSC+G9ie|mp*zJGc0<(M4P{+w{D59W)>KJ#b8`s;FXTu-m| zk0&Sfm)YOb`gC?Wt>^SQYyDN>tm?DlOR}n?^Xar+e4W=z2r>WbOr79yWq3Z<{wY*wRKm_r>q;UOnC6EsYqG@k?b1&An_XfA}?&MMMqB zt|8X}1RJ@^XTQCF{`4t9u=o3DD3YoNh(!2zR3W$)1VZF?-h@M#5g1;vyF5EPpI-?K zlk@ZWSK0U~94W#L7|rqYWOhoRQ0EC-i#(lN9xrBR$KN{OY~*S8et!L7cNgG{DG2F& za`*`!f9)dO2R7p>GCTb;e>RQi!kAm9s0lrpK( z1XO2-{Mha=rgcmpxN?6>pGMKZ#q3ISyxbi5?2UH!=Ve^3I?69b zJHD!`im6%4SGjUG)^=mV-TDz?!)NsiiVR;-WGHdrJBkdKp#Y9B66%+l4)`xKiU5u% z1~{%y5DcExf7R!R`z~?nf2;r9#b_fx_UqHfZ}*-GM%Iq$vWgia@AwkZ{gW8IAq;r$ zr@YJV&NgyF?{@Z{f4+E5JA3nTT>2{V&NRNI=jaG1(#5fCu~}zJrWvLLkBX$==lXe8 zfL}T)@SY;VKS&WKCludbOim9-B}Sv4&zHx?)5S_uh9-PLi*~lU9?7iN7yC=fdO*1BJw-h!N9bv;wjd-nf)wnP7MLQmMuC~%Gf|qq<<2MC&+?d zLB%Jq?jzDMf8P4n?mjp2?mG|PJb(6x_WAbNxP2$Plz7A6{0O(*W)WxHD04~t*}|X0 zw#Bkb$KG1$%D1oVuyyg`;6*1cPY+0Y_UGqQvX|@B;~Izm_;i1MFgrb@JyDi8C9~xp z-h5R4279fv%08pgL5`lvH0(Mm6I&go)B0MMKz=-Le=hH5c|!ra=T)z=57Bt|A$TOX z2RI7xT<}7GtMcx9-m{9j>p&?#BOh9LO%i;^aaPF{pjIhl0f|uLv~6AD@Wh43s!Q$wG|4GNS=5-VA{_R?ix9js(ro%k0mGDo$z?X_7}Bp9fNnR8kl=n&@g}KFKFlme6b*H3-6ciVL`(f zx3?fQa1Ew&7UM?}EeJrSdPt@0- ze}TZ98d2$BZo$2GkJIOFZZxP^7`XlKn2#y#2Tx0b4t-%<6Hf5&&M)|f=a(GbuYN|Z zRQ@IY^VtD~Ve&J0NvZgMvEfaALvG~f^#QM%|_F zPBqK1@-GeKe+lGY()T9rPAI>bA8rYS2^B9I^B*F{+#Z+y%L8#yH8wLwFf~FqGC?>s zH$z4?Fhw>*H9YE<?9WA23&)P#>!44EZqS&Kw=@Oyk9p@e(!gZbCM$>QnW;DAOaDWu+~VH ztilvxdfOs~SP+Etwn7$2lFXA0k|SxdPL@f6q)0g_gE*7=mQAumY@`C>ebavji^M_f zkie(jsz@ay@}#qxI3cNo&OC9E8c6m_Z*`;=vRBaQA#TWiRA&RJha4a2^pZx%MOJ5q zG!Y-Z!_Kj|Qyq>FTu0O=t?(o6bCKM9cm$n}AKZ4mO{(F#L; zUbTh*-?`Q>kUrBI0ZyK^Mu9||j8+7=cWaFSAE#R5z;{q<0x14zO~SJOYDHlkmcB6s z>-I$}24hNpG7b~J)0&3KU24sc9kL7a7#5g!hx`K}#xUNOC(Z*N3pqA0ISM5uMNdWw D4TGtF delta 36704 zcmX`SQZznIlJSnpYysk2 z7GfM32n$gvusbjnfIfCw3XB;k==KrKCjm?*tLBRk9bZ91em>G2ikpVB3P}xPcgLhL z^@gGBr{jY{UL6+1Va~vu8h{kn1UmNDB9W?hF>*}5QY9qXT_@JKZI?INFrGN#!S${D z;SWEX2ANrQmT+i!9;mjGne7*=bv$xG%C{RRQP`%-=7biaq^^ep^G0J7oz(X>qQ|#p zr1g$5qv>U8*>EINk%6`h|6FI{r5#=SK}u!jrmCrk z;tH*{wj!F9OQZgGm+$w9ex{A)_;aPK&5AF_^We#9CSi|Pv2{n2hK(w*3_$mxBC``h zEt!Rmarq-973FRw7Ea~s*U;GDGXHs7O!d;z+aFD>0nHSAlg6;<*rs^RT2`@2pAh-} z%St)fzqmTZaohID^C*8*zMg$EHtd{ZqMD!e%vDdJYS*@fXWNg+68v zt6%t!j}6(7nYdA8h#8p!wg26(EDc8pW67SPOt@yZ#TQM)5!bRLKn)QZ=MO|220GLc zFJPiL4Vmo{cf?MT4qoz@#B3{+3p^<@?fzCgR)g?|>%H8=H@KY#72vIO)Q1jrKy0~_ z7;U^xR+2F$#+9#=6upnH_p*pjlJa_$lArjSJrf4VAOq{m4Jk3LI@tz_y4hv(WFA-!qSjq960^bUvW)0)5)&&)#yPT&nvwp@9)4d22T_PIK z5)A`k@J_@Q5e`$Xe%qMj!N+a)$MzRn$46*auzn?7_SI7ij&u9XY*X z1qml64*GE{9Uc|s*Uz*9aDt&)+>`Y0ePnc$*!!!oeAjmE3g|}?ApYs=3pQ+={Zl@> zEJ{u0eiwlFAgw4Nwx}AR28#z)1Yi}@tjQ|VMMj>RmogMY4O;G*eSfQFz-u$fU(#QAUz7}2r#W; z0BTxX!?P7k1gr!s!Yr*@*gGpqI3fo8pk9|r#k-;f{VkGXVWLU)cMwWZO#6kx;zlk( zO|DcgE|YCDbBSw{jdLzwOuT}z)er`70R-EwUx2xvyMhiB`TcOQ-3#`0 z>Cbfhbie2T@b%S7_M$16d?PKmFjm{0(wq#kp0|dC&dc{ZtNwq74($1N-5a~^Db|t> zaqR}8IT}fa?~g}7>7AJ%L-eu#8ZxNyqpj5p7=*`=ap8fCB<=>cw}9@y^GZ!u*s}zL z*3M%00%(%#XMD5Y)nOm?wZzCxOxL_YaipITbThzx%lquj#och&Ayjr;?G=>$67DeN z;d8(3xI9}>iZg2I@wE~%sU|ZDB%m12z~=z*B$7dmPJ4I6|Mn|_Klj`p^LnX@sh&7K zVbf|ZYwxgc6mx-!{!(AhbSH;uo}qVv4(53e6_z!pbVAn-xRl` z0;XZ|LY%^@(@0t~F{COfKi;1_8b6QkM>hq{ZvWTTDi(>d!+@3?bMim zZ*4c3v9JWVQ=I(|%A62Oh?>e^tO||$^4JsP@42PQCI1kUcqb!y5IEssexQhA6Ja>R z_md7zqtsIKXum^i_FO15gd{%rVJ~Q@LpyNk6k)5cL6cw4^=y`dDwvZhQzzIc0bIsG z^e1FTl=hrRL;7|tdxSejYbs((o(MmTjuZ&&mB~e!hf!b3He0+0=UHX*FG$6V{Qh(sDOYw?fWJD%|2s4=pW{i7v(75x7oGC2Ub{Ade0mmS=oXa$V zt-WZ)H)DcCZHIOe%@ge-`!6U!Z6o6)&=^&Ad?T_aa2R+Q`K&7H_gcbQs>bKS8qMT% z=!*;1?7#$deR-Og`IJA#>=nW-%2P59HyL=h6=kGi7E~^;Zz)o z%BCaBstRzuhoY1n8{U}O0yHdFogm=pOrsI^OuX$2`R;GQzumc=oc)aB9vDvx%uJ+L znMM+@pK0Ri>a6zU8AL_9`%fny%;)XMtw1?0%8;?O6I1yt`Q6BDrVbdd$KDp|?MCri zyhfQvxM$&4bF>Z4^hM^PJAF0EMaYF!KK=o=6e2q!#eEJyqoru60fmE(fx#$sm{#N} zv%D`@0E-_dTSzNjTsn`jHG`mH+}f?ewvEm3-++N~{Q;y2X?J)xSZwbjH+cIKXO^@W zT+bi;%tXRBg1ud|9l^N%zx;C742xTT;fZnbAjCa~%Bcl%M*qvEH;13`^c7mX+769s zZS6}-rP|Iz!FbsXz=MwiXRy||wBHUr24^1jH?+>qLf?S{&1|=Mi|*zv)igA1-=!=j zef~I^Xt%XjDxqbfpb&1U4m1{MO70#uQ@JZ>U%QJw2jk43Hq;4~{my|nowK%RG}kYd zWT<2d_#I`+?rc!>iQW1SP^ix<-ZSbhiaW@%|I5-%=GM43V0Ft0t;>@^JXy=9$M_n7 z_5~4K=xjS_aOq5?TO=iq3rZon{@dg~ymfMFGFkmHk^b221Z*$g5Hf{~tD{^``;g3r z=ICfo-%}z1fcLwIon{hZmpcopi6j$|2a2FGg1+}|)&c2axB29I{F6u0feeoav@Tx& z-*fq+bby-0LkwB8{w!g45?cTR;?zw)q#5RImo^WRKKh|d*lrp=VHo?jn5CXu1R-Wd z6>*rsq2%h)uW|nVQe*En&nMx^!S5}MsjZ2Vv!khDBL`eHEC?6#|9uQzYim1Qwjley z)++3log+tll4tXwnk!7f*R70lO68S4jb(}ake55aIi3 z&`a>|x_xYHSaA8yOQ9>R1ZX|w$}h>)?^-&v}~#5U%w!%ED5c?_2~4Z z&ycwQ8RctwX%8H>bcXLH*=V=EM&8)se|q;RR+C_MDIzL~wA{69Yc5;^g*>5xDOX=Fxk&84s@f6szmYb* z>h}tK0((o^I_wSuH`h#)1jM0bu%w1^OpsL;tqp1XF7?Lmnr?=I;(<3VU7GI_iwr$! z3M^3Ve?$k@oK(uvndGpdDSW&HZkZItgN#N`pi7LcS!Qn^y2E{_ zIN4|M-2?gU=leBX7no3CBJWHTW2qQLM+MymNOu5ECOl0T1JUtPSH%;~#$o$r3yc5s zezPeIF0s5}0{$#BY0gDQ?YzGH+{_%x zG>UQ_RJdn}Jq2GPF}Bg!k|@;-(i^EO_(=u<^`3a2N~*853A7mxgUoLlthKf4r)1hc zGKm75Me>BP!14lfdFC7ttbNSUd&ldjh0~5LcqUv5&7n~b;ks>CuUv?c*=*cgag0#Q z?6#}SIpPTX#0aejExn*}EtUj~h}_tfW=@wIHiE#&NE=&%&cE%k>8a(ZM=dOy5@sGw zfH4yW1O)7mKFAGke-ldAUIse^|N6pJEBsu_ zHp1NY`1?fyum9Vg@NJzA1^PAIYQUF>D@K^h8%NP6rl0qe@PYK51S-{7C9@|wv!C_f zJ8@8Mt#;!@%AYceV>QE%mx-1n&P8_ofsIQo!g!G^Y8Jl!o~q-Vk=Q-{=$}%{3LyeW zq9s#iSFT=wAIF>%2JQE#P`UE|dyiMjaS^V8k4K4y+FKDhbnmKWS9NuUz-UEfs$>zg zV9Y$?S%ohO{fvvx1aci10GqN0u{;4!#nUjZC7;E?2qt#(++^334rWh!mX*d6VuV;D zca__F1T*~Wc^h#JNvJ?*zA0a+x@-%$@UW<(+5a$Z%i)Lv8Oo~CWHe$PH>!z?&vhEB z)RC+I$TMQbO<)TlI(u)?nl1EGRMPf?dY#08e02sULC>F}c$a;y&uS$GNIELF#kQZ< zbEjg6hy{I^#{UY2arggRQ@tQ!u*dvls+atJKw(sxqg?AFeV~@cD+$l2GH1__$yawI8U#?KwmJx?wo>F%llSG?FepiI8Gf<_KD~)cvf~uy}U?1 z_+Hp*uLG!mvzWdaWiQOpz|n#Qta4YtOyuz?qPyxvh^UB+w(vilre=MB7aI;@i3{!6 z`;;eIHcrG!_@-!ysCy#qZZ`m)s=t44vK$5@Z`^{DPh6tOFKpZ!%2Qm>Yfm#jJ#-mT za~EQHjPGyvp=nQ+b#ZZZPR)ktHI9ALQ@`JtuE>_CW2Q&_`Cil_-ziRq)zj=qzWek2 zv8!)VmNUn);XF$vP&Y>FrqBEi!F|ATPIdO3mK9#MgDC4S5Q?fSClvrUGw&#Hq)!ZC zz1cHK^gYwuB_MW4hi`N@qgP*cn<<&>FjkRiB7uIUSyJ6Khc{(|T6|Nmt%QyZG>|5t z(OXa~;}DZ|Gg~$rY548ITbQ)!#H4O%<)nnVqn#`@5yeQv8Uq%o#P_*{_#-gi6gS96j~tY5EMWGAFjo%@X}h zXq!h-bg}rVXm$@i_F!czOzBex4v2@Hw3(#L6W{K!5NipcBu>CTx5qfe%bBu97XnJq zx+gdISgbEl3sO$Yo1)HRnVFs_sri#N-%3%Q>{@y4cNA|Yn2;m3_7aW zRN5DDlbs;-?`Z%?Tla-(Yv`#SngWFad`beD*Gfeib7g^^gX#xF=F=os{Mm%j?W86O zpl_^B;#G&ntko+>YMY^#Lr8^`Ej|7av6d zaB|f1&>l&Tj7{P=0bJptWJ;;1D>_7UVePZ~SHyG|a5>m=Jk!z0G8xkIk!eDmP*8ce#f7O$`Wr3{ITBHw|4&eRlmQBAt`i^qO+jEcT9@_}lcj~4L zj>^u@mIwfFXH4nA$)wpPZ(w?rL|SVI-T1A-3)OwG`9sW&S@?4d85?Gjm+_ZUQx zxih6yK88}fE@^Lhxbf1a*|PPG!t)P-B#c{?h4d7S?Sal{v>0lPW zsOgc&{!b_C6#l*h(?wPU+B-X79L0$AEOW+ z|Cg5|tScJ??`jtWr8XCV^w1UA>;^4$;ImlBfv7Z~6# zT^}i~`?MMIGkMoo#<9$kvypl~M)hT6g(|-vgqnKqV%@@j#K!3iZIG|ub_6jrbKMj> z>RL~P(~K@xcfckTUzEAk0^RFE!-!!Qy^Ad?WLGk?>_Dd?yr&WGbC8~aRO)5Q1^`r` zXPhEhP*2ex!QK~N(NqBZpsBR1FIBG*lO4_@Y~EVI`Ff*OP1~wgJ@nzi z%^TA6%`lZ?wa1FQf3XQF%{n{Cq*~Rfq>}6O+Hwb#oQGbqF46t|d}|fuLB1%KZ6tE# z)|oMbg0TxGugV|MGaO)pB_@glo|c&Q^4F zR`NFTD`*}L(Il#=h&_%^!sR9zz|K-vm7AllJp8MH;y6WLVPNHpjMB&!_nNcBR&bB# zyep&sJt17zb&ujL*o-2Svr~9g!f8cJd^p{2z=W*evvv11cr%37ouedo_5iG9wW|JX z!8qNV|CntkCh&xTibij}N9Sv694}<-5G;3IxcPXY=lR9o zo)M-(&RAdrZDO0f7Gf);ARgBHKbFlheM90{e$?E>4dcvw*9f9aQXSB%W``DQAF% z#va<5h!QQvv92G7`Xh}gfZfChz_a%mz&P=mcF*lynt5ugto9sm;i0T&6H(FywTSt$ zojM__{pq#|!Kd%d`FnkgTVpJQO(}u&XE0~vHO+`WsyQ1*oiMCmsq;-FU!;6xLIf%)s(a@5CVls*u*HxkPR2qumK@vwh5uF$l* z`Zc+UA>82*^-=XyyeG82jZi)3ryZy)=(%HLKOQWxlKOo)oqfgt#?KnShL$-?uy-fg z|GUZb>w=|MdwDDiP)!vj+I#5HYt2YY_)S%Ejll$s{GI zM2V+=Afbg04F^B*y%Qhx;nAiMLA(GD7By)Yi`*hvns_h(M3cXq{?(u|E!u?_*NTkc zA}eJkqJqQTBU|i~Jb}#BPi;=^Bg$xM?9iiU(Oxv@0n4?8MhwHl56ij=&jPMQmR5EXL&-$Lmg9fKKLpV

iizv|lmIW8*rbFK*UC(4m$#a+b_{n-+1+6wBU9*}2c{6uuH7My$7UdJm< z`^0nx>}=%pm2B;-Q*t7+Ktf^5QIdivkvZ^$DQKA-(tvB%*NuzJ zRrMNjiad2;K|=x-GC^1pNctH_np!fAuWb-SX=i?ypC{ zryEQed4dHruR(0F!MB(0^}2$Gw!+6gi(=2< z=2+3r`Gds+@PB}+|MXp((91);(M~JpWNGK1Nu%mK)dKj+w^-LPOfZq@BfH;oxdVsTkJ?haM>7v}m?#QS-UmoArPgyHdk?^Ma zG>8ziF_5%0bal3Kxh+`)rJF#b(_#QQ%>lNh4d(4u>W0Mkozi=G9G!BzSQ&8F!p6VN^ZPMB^5 z_n|cMCC>cI$ykYlWJ1VAg1%dyFmENlY@=%T8G-gY) zZVk_du&^A)b45COVb93C=BQOAVY8R$l2fWkxSxg!3wPVcd~u*}1Ln=#Gw`tT*2rwg z1vAB(msb+6)=iq0OEUbHs6V6-sOjE!71qc>Q!Lj?su>-y&peC=OE8F>hpXbDa%ODm zUs!VM!A85KH@8fA=~hnw<1kQ0QY|B5r`dwv3B}=7K1TT00*a&|ye^u0PYbyI!z^{~ zaEQ?UXr~Ot_R-M zA`)`c_2J&lIsO(XhQ``{xDGB>aiLwiDVhK=wmpbTVVnBu!MSxMuIRr}6nA^qM&+A@ zgh0wD!lLn!`9;$J$UtA18^1B%%-Zy|%3K)l?4Z4L(4ssp*aRugJXe{-wF&SL$WD!& z6RuH{P@^1`{12r<*Gs%|^lxWm1F&-@5Rp!;mwDkdn>lIn%l@%~#aFVPnvvmkAGIZKyiE1GMCJK4A!*6MT+UCwmWTvd9&e#5K%}T4= z>vUK~$A`#h=xM9cBDZu{x>1Su0Su)mRSdjRH_7hpt1M~+y@~B(gkTYGY!qc1rJExk$Gge`*{j-AS@h=AYOw`?XxB0euED>rr7tkoJ_3@v#Pr>x zz8S~thSKmK)4AHjnJ+ad>3cqL$B6^OZDszY@eDCd>yt_J`QcOw&L8clHFoy7zkcga z4rYcj00QX^q4qz$tX(2@6+l6bI`tC)f!nitisDXL=N?%VSE! z{1qU8%~lE&(1xJimEXl%1_eUt4PO6Il0;IMA6=0P(f|;N)g802*A0_EV~{0a8o1QDPl)sA(f4QD^uX zuM141GHW5G)@s{ZBA{_GyODfVT*ooB=n*Y|^sph~N-!SxICRV??uC8VJgU&~0`Fe4 z``??)L*_N;X8I(ui=@930WTOPb%N(4exu^#14Qt6MQOzFd6$ZY;YCocGH?dY<)1gY zp09GRZEo6YiUSzOOn3zzj_OWp$R#J$lqq*-6O3Un9vW^=#arYe{Ux2u#n_Xsvf9~z z%msrtya~3m$40k&1B8m6ShmN+KX35N=(0FpG0DZwd`z8vO0nfon|38{jp^kCvU^!w z$hmS$tbLa%-sJ)ySa3IxnbcCHo~jTCwy<@yt&mt#$GgI~Z4{5YiR||7itW8vOODV8 z&#s1_FqIq2mHUhOzb}lx_nE=KZWj!IHM1`^R|pxbm46DWMm>((5qCfgtsT_t4A-UC zI+f2pZmgJkZ+xQeZyN2J%`XKLB^_|NHEz*?h8oJ-8#VTs25e?KzQr&A^~=pomu-d? z`bhy%)my$+{DaJ7arnCnD`lM|{L(@lN+#l`oWL$Dw{Y&&=-K4`a)_uMB)zc(y08lfrx-P4_@sQAo^|Y^Wsj-(@4&j%2Sh+Ye}Ef{skz zfh5Al5IM4vW~_fQU+Rxuif!*4jaL|*MR`(j)!DhsN8dSHwFaro-H#g?^4dIMa z-J>GMop0@DH7VT>Hu=UR3~hLFtBdsNGgr@Ba&6=YqkXa`RpKkmd%g)r`VLbzPlYM* zfq2G@noK7MdHRzL>bGWB%h2O7yBwr=P-dK1xe1M# zf>lAe;YgC4rn4=>Cj%%@(f{#&p0(S7Wo912#u>peiq4+GVs?iH1<;EF<~OJ$*-lZl z;NC!K#n>oK6QIs1{s;jWLL@h_M#79}54($E z=ZeW9CXA+%2@fT`{LMn{_+0PRB)Rs}gi@_!Dk!_6FW$W}V2u$l&qB$lr;qoGI@&js z5oFIrIkq8gt1De-AKsP9 z&%Ycz#!F^Xw`4HETQ4`0QrIYERFQo$v;0v?Xw|*fd3eO`3rW-fX;$|MWVc~#R+N;b z<=ALhB}yZNyt2I6wYExNTnAX#*J*87{T1wk6%>;d$;OT=mdg`#uaBeC53K>+o6jX- z5c^>BA%aSRNfF90?dyCPI68KF@ITe*eAP9WnWOKHF5}lv^S_VnZwH2rzG;B0LEqTP z=Lj;^c;ui8sbgKhdm$XzVy$CWd31-Sdx(0ZO@H00cebwmF&8_0%%bg78=2BwMqzzZ zp{CY)oX$)U%VMRGnoO^6+BUr{p)&g-lEY~MgQ<5}U^(8V^m4)C(LC{_+Qv;nio^(u zvUaYhnUY0WkZ}>=#ASS6zAHO@(qQT4yN~;5$)imKd0-OYs)FrlwJ4EkGE}odU}R|l zcb&^Ko?omk&jt2TZJIkGa zSH#gRbNH*|YySD;XaC&6L0Rn&&iVwKsj!Ms(N?k4GE;uu&=?IyZ!f?TU>P@8OBlJ- zZ0;ag#zYOK?M3~qLIc%Bzq4~#Eg!ZTY185Oz@Q5d9c`6VKcb-3m%LNOT@IFvTUCAV zO@$LboO0-q$Ct`F-Y!^pJ3Y{~{L7`glhkueZ&z}>`l=|r&-msqe;@oaQHQW{oPa8& zx!9E)X;0`D>BWhkxr3h5^{lC^VIs?ay13FfHq1c8m900cK5U2ic+E0IvBST`>yriE z+aCrPz;3UV@5;Z;iC8~-a&7FXJ)sA*Y4R|x${+h(A8dfCa+&FN`Rb@K$M)v5)E`s< z8>629+n>0Js@P#{mUfPsYzNS64;aCuuMj8-vgZSr%m2|vQyfSv2+xtAilYyGkirt5 zc&a)S$DvpZpH*4mG?(^dIbX!li)E6$tDR=Us9~TViNk6B;tBQ@{$OijZ0&B+-i!32DG{*5;FR>y{)_+!jAyj z_Q0gnrGnBn*IRYT^MXu0Ny6rfFZjuD@rtI)>f9txpZsXUl$mQH(@I5%w1a)4;GdVN zEIh^sXQ2l@F*F9hbb}EuT>V>G*;!1v!SV2Cvz;fiweS=Rs=ah$WcbA`?9eCoC2|;# zGBhGe#M8OOerl4 zI#U@%8bUzgUyK(ck^_@bg(gKyne|L6SRb{{gP|%Q)s#`$G#Od>C-tfT z7Ws@Zi^g2lv%LXK4HE`3w3K88=S??lc*y*gF-p%qR@E5u2k%*)A%s7(*293hxK z2y|fTWHgaRRAMPu67ozc;3uSKl%bG?AylL;VBPAd{DB3$3s{?m2?(DTyb~@fcPUKq z4{N;Q2Fb-y$b|44Ns68+(;B(kJdp(>y}k*Y33aCW+0uw*!Dt`tx5P;FMqx@swm;DuW$P80VojeHIK7RpurP1Z1y| z$&}e@i1>U-o21#&=genoY61 z>tDLf>9%K7%n4TBKL%7`aka>BF=Jy58y%O|1@M7n@s z^D*L%z>3nVMUcG&STm^{{34jZe7^vae2&x`oDCS+*q> zJAo;e^`$ns8<5PQgbKj%UEhdFy6R_?{E&3zL*H1(i$7nr*YSvtYyL+kaDuZ;^^$&v z{M<4r*Z1!_lIXP|*eU+#%9o!&TzXWYIcHSkuHWGGk^4Bw-vc3_Ju2VuVuc9t{rHoL5C zo3B^Fbf)J)L(tL%h!}}Kv3N%U$@hO4lv3}_-%a=tT}`SIB*;%}0#$L-GA|#gWUXa zOU}0+B;`)tK&Q>@!UW`D19)5yMDsyP?aDb4mlhsM($NAK5b{&WqkXSTZZSMm8mhHE zB=i6<8jKCdapkHAl3c7_G0U_IbY=fAILKg#;UhF%4Pd4a5>A7MHdny)@2g(AQlt9N_nHMdFg@`X%Deyx)(9Aq@<6t{1so)=8Ep#z z6AOb8Itzd!zzB}3u76AzF+u@fs+w6L=&v{%>tQ~W(@r^gs_?*2Q!cR#Ll7RL3}z5i zDy7WSJNCfQ0i+v-O9LmrFBC2UMi?-5Wl%1$F@t*)gE6K%Q#_^d)C)Gt2}!7%)XZ?% z*#0BoL25g(hfxJ#3MDRk*R+XiTsAcO*9n{WIv>DfF6~S_u9wUu?d@~`E>j@t)OKiZ zrC<@S^mZ>TXW0B2;qjDVY|py)KN~qD3eU2E_|V;w`+<6yTRtQ0l(lGl1a2}cYLYut zaxq4Bo3?1FVT<+(vq9h=|PcDpQ| zSRTMos;S zodAzMrEm>B<+V3lr*IGj!svTh)m`Gs)Ae?2Yx#=$Fi!%?Q8XG&7jL0=EFedz{w7l*}W*EBHlQoBg zWX+U{1eY@(>M}<2>84M%x6T68_Ce7kMuUUSiO*KZECc`5TqE!(2T`x@genKQ-WH7f zzZB0cvVtd83=uJFVjH=6QWO8{jXI6ay0+Bs0Zk4Oo^|N&ezk_xYvTFA33()_waztS zmio+8d10}11XaU)gaK#_-6w8*M_`C)(IA8!xpwxt6(~pn5F|S;-hQH#%Li#W7`k8> z1}jmzxT$tjqR8Yvmic#f2;`{6B(Y=g%&9^i?N8-fjcBx@P`B0K=_nkvl8QqHJsV1aTGlq*bF-9H{!S0rmj1qt!>d`>y?{=0tN%E5Y9nc{e=UB z@iLpq#4TUnyiHi>OQ*UL0Iqy1`lqc@guRZY)D9s6T|7@t=b*nfwr8y3KtCGdPmdVq zn@UB3l>N_eF)FGzC7 zdx@sQUt9%4ui049ATKPw#zTEgZU<_nytL^L3?pC6*2Pok4wCMFH2-)fu~ipcOPb1i zc+B4LU_Nwbls*6wp;5Zm{j?Ur?{t`w_vhMbNejfNi=kl^M zDcaBdNte8B&RiVv+31J1G`85HN=jcCx4#6vSrN`B9a7+zyJn8A8ZdLl4_*{}hwX_? zheo3%F*PtTB_#M-O?KU^`P1I_#V4KQlQMqM_%;`=0`LU`cv~XhY;c{IsYpt_7i+TG zYFcg(sJP3Cr^pa^4CtiVOlnRg$w^j__)qq(CLr=(fTO(RL!aq zHs-KLMlYC&V!n7mNX4MQC!ka;a}@|S6%wD!$52F?mghBm)ge4|OK2E1e*i8T^e!Ef zv{FrXgi@c4A{_r&ZaSX2Xo@C2o4Mj-$f|i9Co-#wk$tgU8Lc}y8E}3(&lp|p>6F?o08vv1nzNl7&rS2 z=xW-@bZBKRAbuL4{e`NID%N@OZ}UmGu;~u%{>A69wlcS-=Tsp>kK1rRaz&1@#(P&Y z@DoRS<^9I;pFQf>aLqG^Q!5Oe`;dQl$G;~jDGpXg#(>ypjQJ3JgQH;Ar7E%Oqv?n! z<*$kY*sluHIQQ&)^}`xmFg(#rb9L>Y4i54w6#vG$!0jNw@m!#+tK@VYZm>g+uyUgj^#L)%xr+ zTOKn3S3a9~0JFypyycio)qu}Hhr*5J1n;!2hp2xLT$^kVA~k}O`R9U`PypVE#FCZF za_M!ZNE|IdhAeaqVdh$e5QX>+|CLHGer_-#9-Z(nMs8=jp|IRJ(Q~>es0&4i?6d#H znVSo9k&$ljb7eI1^DwZLmiY!n7kuE)Bo+yiYW?zvR-nk9!`*jpeO!@ zO)=%KUW(pPONb2m`7)i#OVk1`Y%zze)NM?VJU4P#)B+ibhukE%IO+Au3xM{<_)ouL z{`9MJ$a@hAdYZfj=ERq8L?8`^R_+PxiKIT2X7?KI9R(%Gn`a0cMY@2Ng6C`1aB|zl zvtBg7tH063G@$7#Vq)F7u~l=}Zyx7U zS=5@ii8OBs|7q)qw>9v_S_2UYNV4W0;y%$(Oy*=JThFzK!UmJ&8X ztiVXEqQOLz)NIgGN@Oga`W~K5ow!A?u7kz?++9SyF?& z1><91^`vR$AIC9>RbhB&xEAC)BqNSe`xOpW5NrJe6{^~|VuIv~510Y+O+YL>MxXM2ryA6*Oh^17)gF z>nXGz7x-*Kxv(0?-x_ll1r!^EN1be~5e;E>-c~Einw}qm<%$#a7*rs|_3D+RvrlMv z9GoO>g57&oH2|*>;9u1s|JQ(GSmU7yRLYE=H-!n&Hr9KC*l?eLQ`-r4ovU1S4sUZQ%Q4tGNa;)=S zZyz@7sH2STin0V4+?c1HEM0ZLZC=3z9T0FaOvj<1;Tjv6*ypHes=hqr4wI!71{v7leX#n-(M4<_AE z$h^v6M5M)6e_VgzMOf$`C0oIcH8725%s|8HCtY*_POsPrpl#Hg<#^TzkekIoC|x4{H(8--1K zY$Gc9K7O9QE0Ys2hw*C_*G6tHf<^<5x@ghw*#|+xw&h;f;=gUc30L&Jwzh$z50);f zp^-rV7cxxP%oD!GsbG>?xlfXD7U1n8pc*DOloeAc40K5~hjmL6uXUUu$|}r4EjH`# zU54z?INRBZ#Mua@UOqP|XDW1?R&u4n3pNS<>fWbNU>ddTKW&6{6^Z(l7fl+d!drTg zr!o6~t7wX(!p2uMp{0dvzOW-_IQ5-R7ENpcrvGzPG31BNqUK05=syq;{BKy5GP%GP zv&6ccmym=`;37a8Wrf<%mvB?5%SbdZmC~`92;qR>_Kp$mT>Is66083L$dTy0)BhH* z6sWW*UFaKvkXOMb*Pt#V|Icm2DBi&mddU(DMhL~4mw-rnP~o^V5?6W?&2p{C1F&n> z>F5oS?ZcAtO*Zd6&0adL6Kx!Zf^3*!5q}vn z$r+UP>qC&VU_7~o;;8e(OTI-x`AH1$dA&Oc8F=o@OeXgFPTt*p^m6(>xvBrWdtUtB zzTGxQjNRIs9K9jz_`Dn3PAv`P0KDdQ_WFLmEdhSNw^2(V-!Ff+zMd#R z=m7wJ^LtlLZ&aEa#t1fU?-D?wc?5S#X;eUsyy008F^;o zJX$Gw)-(8gCpp+YmKdvUT~k=(5i}`(GOJR8V3Lz7$dVqaG|lDD z%H2oWi_qwsU3!MQ#CT`gjm|nfhP#9iSlQB2_D;<_d?*)kl7k3MuepK8nUni8R8mNP+Qp`fPCv{OnnJ?vgm9WH=m^_$u1XfKrm_AYrT zK{!9TBRDS#h93Kycv{3meJt1~e;0zI+vXnB--pq(30r>!0;jAbP#=p|GhSyo=R~q{ z<}YXdH#(Z>nx$Yr=8Xr#_^Nb#{orr#_7!>HU73z(IGT@sDT;QAK<5jF(^>e=S{a!G7!w zk&<2Z=a(6}Bar$8C|Az7+bsS8*--)flL5CA zgJzJ2W{?55W{?7=a{)7x@bwl2F*7+ZHyZ6d-d9Vs%zIFArQ5*byoJUH({V*prz*oD2Xb{ zFfh{71L$d)ph-xC98CbA|#|coiHZZoZv2X;a+F9GVS{RuFxLsXc`CXk{XdPX6Y5yiEnV0~a%}oHN7S<*J zAvt*s30W}!xtOd9K+MF}#L>VSAn#&mZD9nEwlFfWbuys=#+&32DZikY4N}5w$4tRf6*pJjyC_Q zjvC ze+fDLYmfiC<=-;?*^o|APF_V=mFm9@@K0F8*2vD-!qyC+wg-_#Khgi2zqVV&WJ16GOZ=F!dIkd zwi29bc3NMBYMB9eWvb^|>!-z_xv}1#ORPI(tb8|E+?fDFp52QbiMwV(e}gy^*rSQb zXo7H^WvrJHqDnL0+O0Q*g4c#{-77FvOdBIvu&XW04)kUaG?N_?ae|Iw7DVo;8sp)tcb^q9>}2?b<56xaKhnVU>COe9 z^h}*wE8&L1$Eqf~6HxW>r{1SLW4S+~@El^*43!^m^r}cUNw}L0e=bZhl#^NI^V3 zhcRsyWV2DGF|j5%8G4gqq2LOU5PxUAVmXE)yDE7V2FKarUYN2Z_wVg$lzG)y=b3T@ z8{w2(`cFApCh3o(hzTD;uQw#-1IzmN=H;D}{a#fd@Tpt5 zb|P!h#DxFpZtICF(MrPbN5g!d+pa4KcG2;U^rQm??0Ii$?xIO<_FS1!0@XpBtt>ch ztv>_5B4=pN{0uL%knSw6&aDjc(=W5ob%p_++6M-Xrmwz~;ub!ffzI;&rq7bQeorHK zzFxSif6M>ox731Q-5Q@;&TKV!)&6yrq)CI2EY+R81smXo61Y@7MZ(i6e#X?&>jhtB zRAe^s*D?7^yaL}1US?`6yV0t$y9SGkq{X;`VWkXrO>>|ISkIi@`vWmw%wep5+O`3d zE;OR-c!_AY52IT`*dL0<#`2yA0sV2M%nm6N z{7pASa7wnO34x;P^Qg7SIKP2WoV8;s9%snL?;N6rBqC*xn^ht2q}Ve*vDR&Viq0%&gsNIs$CjC3_#b>?%2j9`(Gv3LUQH@WJoWIR?CSIk>D@Cqfsl|*5f77XwK#!$_M4r}-aDB&EJ;Yj&ylPZx7p_K~ z)O#xOAo{Ld;DOApRfA2(KoK5fLL=_10oUr$`9iLe+>nkla`(w^3)XW!wY{ z<9oLP#Ge!Af$G$plQ$^+eZt|pWN@f=CUS5YZ$Xp-Hw+z$)TgMR^?59pf=}Fye?#ik zi-&AInaO}K$`u!S+f&EjpjCXZ5YlF0T9kgfe}*b&g~SyxOvwx72tI`-WgW|KgF&;c z9i{+fazx(S)|=n5#3aV+ECclcE=#VU42p!-_0Q? zuF=#*M53dD7;qft3S??|!UB7Le=~4hrb^iDR6r>lJPTt>Y9mdwk@yGE?7VW7hR*Ou zMU<$K8@>RLU!Q{f|euS(Riie zy1Fn|4rq$h2nTGNJC#lFUglh=5GR&2mMYU7nnDT)oR&Ae$jJx;Z!sY;e|^_{f%c4> z?w)-LO=)^C@do{dv-%Lb>ltB_@?>=yuYC0Axu-?hOyl@^4j70$3)cqRL3P-1)CFdn zO_-c^_`N^LK!eJ?rpwsQ?TuJ`x|}I7>)z$PeUSW{oXy?b@b4N~L{=yg+%u$N%1U8{ zZS{AyCN35VPT#x(u3OH#f1?VO8JEsV5w$Smhz~OZ5Ph7AY#5MB3_i)Fp}<<*t;v3& zMTQu5bOwgiL{{yK4b4#m?nAMy!S6mhrrpxmld^ue>5-EMtwL(dajwzVNw@<9%47Rr z^r2blC&6)P{X?guNDp!s-_QfjKV8wd zy_24lS782Wc>3k{Lwp?U8tTG1uVN#6elk4$N!8sI;%Q|}H9TGP5C8k#^5G@54VA;; ziSPnPVyoXyx9A$dE4(2096Taj`W6+XZc!|Z-23w&9_fgPc#W4Jc22ON@RtG# z?JqkRM-DNg)C=fmAle`_kgV+uG0j=l;Z5E8KAxAv-ZTr>Rx0UMk2aC26THoj`o};; z<}L=qT=Vv7f1L7QP2N>d<+H6G{Gd{(h4t$Uzm6J7ZR?$wqq+-zCHBv08>{ZL?n9v5 z{f4%CR6&DEFui5cJC@>w~yS@>_?*T9|0W2H`}(Diq~D5>NmAL?)u4w)MCQ|>;cofy+vc2t)EspP{$fajbY{1_`{(5 zf2yp*@Qkv=rxf0;5##mU0y<#l`L%di&5vZ*r;5vqo?@|O1=Qs6FO&YF9zr{V%$FxR zv6r`PA)ydZ>G9ATQX3PDKL@lRoM#c>mB*xOQxlQD1V-<9B6U%ZI$hRMmh&r)W}*NH zEhSxZD{nr(89~?Fpbz|8pZ~yyPfKice@)dm3S^0q=^+i}r$lz0@7^~K@y3xIWZs6S zNUqNEPOe7;B-^cC@zvCD=TS{cM_mbicDa2wn$jO1u>TR`>6PPNwfBdlx zZjqOwgic&MiJScF$_CJ+=Pbd~PzsmD{3K^+OzeXD5RPgxj$obRt;tr;@C>{E`1t%4jiEj4t(3Khru~rJ!jAK@=e^!i0$I(4Q zMs5ETbjGT+)kTKX%jZNph8hs?4`LvY9#*D>%COYla~p;*&`00650CiD+sC7v29R|h zCwUZQq-)MGO2YO-ZU&Hi=~r$fC#*HbGpXWW@G%x1m+}XLm+~3zEwf>8q#`-B*|{+-G{JI)v+lmK$q8} zqyUz_qga$HzFsBD?S0iPH^kVCkCZH($8yqS`ah8O#>KR5_-0NTd zkJ%)YY`;$UPEGvJ6jvK<`5Rz9kin8lx5guseoVp+j;()`DV~-S&+z_~&;J%A=3>_R zO?;Y!1L@di9jK&Xag|*cF!gh*laAD8`9mqMOh5H&teLc|FdMrIp_w$Xo@fNmCCTAx zY}`jSf4tgu3=vu&YKMg;PEUdNNkEzX=zi{K&njE!{)5TJeV$kOJN38z3=4(tp4Q86 z(qC9t{6w?5fK^~-5H`;N*sMp?C+?AS$fS%AIP#e0+ex zJWxY3GOZqj_T@6*y&_swb-ZZ5Sh*Pze>iwW;PzGqaM=a8{8PzTN1f1skXcRFHK!mP)xG74L4!Fq`T1MhY0s0u?CD#6>wUer2bq zK4Ib9V7}VKnKc>7Kk;iCbH3@7NMbJsjMTr^t}apARx!9|1TLAPL`Hp(V}2bUfB$LJ zkV&|<%4mOCn3>kY81b;|vtH1(E=^$oM52If@)FU0{s5io6^$X=-VG@k7DIVzF!ciF zwP+|KYm?}y@eMB_(nAy&b1m7Orzh3kcQ+Rh>Q+T~QXdW+xEtBTw^E?zbzuC!MT z>ETd4>bZ;wsMb&QiOig3vv?X{`AZ4tqypdgUtaPGBQh)8PZJw23mK8^=M8@)6Dy)#4%!vN zC`&dIYG0lg>R{jD3zG8Af1;-fMRzy*y)oJGTaV#@h5ft+gI~4D?@AW(i$eq4+Z$?a zyXHmq<5f|e-vvj;!XG%`g14MaezVr{3)fj+FQW+!4*M^YE~<(Du{TnO)T5Pj%L|Mue~~Vmlth1&0pn5+ z=&7ZLEpKl5`<1#R|6Ykqjl&&TORAQK*=l-QLJ zgwGZit(tj{m(I9he|}HR_~8gx1ZX&F>}!?f?PnCh7JhspUbVadt)>c30SM*6m%cb> zn^4!;$j4#$s&*Dwt$U}`k)LC|WIYN{kYPct=KQjWh9lT&dXB}INLl^Pqdt14oKB54 zZsbjkrK<+{?O@*0=W!4$%^rcgEX|)eDd!9)i__K0#iAIQ(SqvL%o)5ZA&08NxM&rp)XTrhD8Ky zjZ`K#_ZD3V+@x4Jx<)%MH*ef3&GaWyL-}xebX@E9k|AkNuh>s`aR1Ikdm`kWTsr*O zDP795j?*$%0GMSFZ>^cd^@aqJ{l0Ly8NrW()3C|fe}ySZ5qF=Vfj*u@ox|R1J$44y zg>Ie-xy;RaN6gU9z!&KkjQVOhY{$+yRfTSl~n%VwXA^!MEq)31xDw zo|7x0jnGN4L)YXjVl(No^kYd69kE-#zI-INe?VFA^DIEi)y8eH&+lzXt|jZWF~p;l zBh%l@iZTu>xdMYac|o>(D?A%9qOQx3FQMqi;|e}qPVw)PS;v!S*zZ-Qo@oF_-6$DL z!Hf*fUasgc78LfW!ds?}rYNGyo09e#-m$s*R0E~C>nJJZ+Kbj zf4!@-T+&{O8|og|&^pZ3rn3WeTd9ehK4?G`tJRnUnJ$}M@BJ2aT8P0mf6V0oKpf@T zPbf3Bx{oc_l)qDq`MP_V+SER@)Jnulnyt=rD#p0lPojp;;1^_!e%g-qGbZK?ik@+2 zgD^7Z=sbcd;lVyIuktFIxiEo>4$P$#f4Q3r)nHy2dKFOtIQ9V!GubcnDqJL(T3Mm# zLWJ(D&)G47-o!CfsV%XO;EQS`em(!Yb_21?)2&xkVSe<8`7 z#mF`S=zoQ91tdYeAetv2(#6F}sp*?1vkLZ_DvlEAIgiO68{sM`m^ zIhIT#nL+x27Hi&D+I)R@9pV|%fAM3Htjm*F7`wLY5mA`jz$lWqk~A0rWkS8pcS6KT zX>){&6@0$Kf;NGq7dDMc1cJXAiMqZaK%=5-K@mhNlW|j55V9yA6)sR$I@pitBmr@N z<&^#OW}LPYt1p8*r7Z~bt`gzgd`jX$s|J;jjD;gNB}OxO!$hcao3De_e-$=UW!}rK zjPCgwAa-rcoxzA@PgjOR;rYiToI7O`%xBybB`knmW6zq2iLPPIZsaEUEib9%J^DIf zohQ-`S2a#X0nYFxpx%4!TrQ-CtvWQ*`Xg-bqh#DILFzTDsM~Er3vP9*hAExOeieo7 zC};u7J1`|883_}_>d?m?fBHrMMTgElXK8S_u;bb>4wJSfqO6t1`8YAnjBW5tv@Qy6 zvz?ABRa_e$Nu;I*I?;m4Z{vGv3LtH%;+f9v!o!<*D6-DrT-Jm?j;eK>i+L&Pqg!05 zgpk?nqC~-~;;1VtEOen`#qI_hQ?hPNZ4yR!3v;&{o^CYX=R@dKg@8b=!?Ni$U<+OPH%APkS)BI^?9qy2Qts4A^Hd?Bb8&v_0)ehT)5orIcf zb!IC_{G~9mrqQ(ll(k{OhxGSOa^VS_2EMCILy}-Rk6CzW9){TR`ogU-I6(XXmV=oo z8GVOjh?%BdKbL4R<0H6z+_3z!ooGqoOu~hl8D$5eW2BQef2ze;!(o?iugEM8xA+g~ z3oQaGId6N~9vw8aP|IvYA;Z>=?WaBxV3w52Q0eTZTlz-c#gI7T&iV&;!QyqGtZdAQ zjFo*8s!7bYhldr>NXi@1pL*{6ZMJJ<#C6}8DN{Y^Vz>8`2wd|rgAJe7 zr7eN#S|rg8e|{KOQijpt;c@?DcU8_W=~aYE%Zy^jhs}5A5nx2bhVO5R9tP(pN#J*@ z%N<&~J3l$F!9vkS?c>pa?G?%3_@di18%%OY~)4 zm}_y+0DOWmC}~EXxA1o$@0y#OxJmFmTgrK{!&D+^e?3CprRQTP8(@}TzmFvrNH%ll zeNPCIxmF9aU=?{x3C;2AkCy#Ua9r&l4~Ku42C^y`VULi2^hxxrg%Z>z2!N`dNO~Jz zn`+qWV0vsQ7dm5-h&dX;P4S?dsE5(&F-EG04X@?Fp6y0?MB0~h60H7=;hB*H>u_tu z8vY!(f90OrCO#VolRW*sr2h?Ryi6?{sur9N-p)2QUZS9VCqQZP?8Z~0*SP>6o`(Rtd{Q)RCEsEL)HF<+e z(eL3fu>?)_FGSTC_IM(yqke6Y%nOD?O$Ue>5I?8{f)wR&X45wBdv+JfeYFl%vg0NdtJv zZR|Eo5I-Xf`Xn*F;Zb_ch^Y`(tnZ>;^Eam>qdx!GJM zIf7O_MUGu0@b&4Ci>HNh6%zx`>C{7}X2@99A9Nmq&|K@3hy-%b*6ji9DYLw?e@pdq z$7IHqbbZmGUUOumB)?sKfZwKjp)*h6fD-!c%nzO8EgWJSc%@=TS`_UmEMA@d&Pn{j zIxRT7UoAJ5CqlK<$9km+Vf!+YV=*@VIA&49e}*%{GnVm=mMzd0hJAFKWyq*!(>mGf{(#+JtoFCq zaSIy3WAvAPh7Ztb0gL|yg>6ut{*=k2VrN=>PGYaNq-AEx=qux*pqT+#lZP$tW7d`p z*kWJ7_HOtQIlb)wwGIhA^jcAoq97Qed-N^4mqX?wa}6GI7-a0S54)%tf5|N#De2%t z83J+Y2%5c7WsNJPdTH4bAl1HCd-DD(MZ11ulHT&N;5v}uYBw>9_Rwu;NA zPR*;Dbugbs5+(nW?8blXt$rvK?zRyp;9?nPYAoc@(!$jjMQdu_xnEvme&2QkG~!e{_T59CYOmw@FdP zz99=>ms#o~v95vS?dlW?DwcosFSckw*A%VgL`^A1`UoO+Uc!)AR2Fc`lsbUF=pD8j zlvib6d@b5!p2HFkD3UAkb#gkVf?4r+dW5L`4V1(FhTYCTEW^Rm#kRlJhzZehA_G^x zItr}ac0nWbW(*S&e@Z3-DHUXG+Lq=6U*X*Os7S;dzSc(gg7!2` z{oaq;Qcwo=Dq#2HVG7w%~R&6y19jOa-pv z7YNt7tNO?uhG=`Co-Tu_3z^W~Ps2*n5_C9-oX0Rhe};_s;?<^c9wO0YjZQtq0yWF= z-~5_}b+XpgnkPK%ntTv>ds{#GNz@chwT+rc2!ql;))6HTdu*>-g!tdn`HBUPQ}aZ8_-3xa&PJ79c*=_$+ILf~w?N_(|+%-7zq-@`Kh#m{=PE z|L^ZN(4}wi_n&ad$nf(|%V6x`VT4Q9PT1c{U;XXui1tD^i%Ws`yHLyrpj(l@46>-y zzL8~-^k;DUlb4PeuHwCFqP6M|v%q9c^D;8be}urrKr6JQn&m32T`=|%7iCI9@23!X zR0?rs0sAh$l71>~?++TG1ZApo9KIIgtG2W|_n0+wp?(HDA(ss2$I;OeKX4Z2*G8nM ziL*h{a9q>=SQ_iqIiYe<8rFfGE7izZj!E5V4$D$#VfKxk0HWu5jG+p0D^CAo;zO?3 zf4rFu9UY`p{oZ}ALd7@9yJH_*CkrO+v=^<%ry8m}!iwJ>9Iz*kbg=vu#R4;}SUiB= z`3^RS#wyRGz&dl4=xS*qrZkuN6Rp$1@K_x!H0+L^HT@P;6DkQWZF09%un`?Pu_2Iu zS$JR=d^liB5cp&c>z8w~V|P=M0nAiSfAl>&jO}oq&TH!0UP**e_BoRLBDg%f8v2j@ zD7kD%=)ful6$fomBJF3*Sv@4}83U9RNf#P3eWfyVG7dxmgH}z1t1ioEHg7AMEMyWS zpf=K&Q?PNO`9)GHJlP-bGA#5x7IMuVW2DscbbwPSb{@SjRhv6D%SIkViX|y(e;}_A za#c^DYhh?56@AInonDya_RB?fr6j}#t6l+s8r#AEv9yqcaKB?xl^UmHABB`3U;zQj zXbHI!&i#TK7>2b<#GT?P^Ey#i7VTG7OQ5Hoc7CS(?XryHni!hN!%@8j+u9eIuk$WS z+ZIS2CqP$%U%gChZXUB*tQc}of6N)=#3m_7t!;Y3>VhmMYZZ>#sOALi^6+T_qhB4QHyT3DNFZ1oF4aRxcXX;NzE_&ne?^R&s$uRI z<;%|ow4}?G$DTMNlGRv_26UdfJK~vp$1uH!+?G%wQsk)MFkVWtPpEx6rTuC#JXR0j zAKBhj+_S2@HQv zsSGI@6P0y-qCmw$O=p*RD^D^YUS79b@Dl1+%gu~nG@axv=Yw`sSPeeVGRs;*p%$F- z-t1x5-YcPQ%$#8}ZqQSklJ{&aH8=NFi-s`ZZnTY+Ke6c*F~jMrf1V`GV8kqz-m6MM zkj*yYZz@;j_g89Z$!>LHiMKyjcvs5!)JJ95@biVBMA!K?c6&F~KtWx+|N%n(} z*QsZ7aw5j~b$Brn_4!WIAZl@&jD{VwrnILo=`=+6s4l3Lk2MNhf)PL^bKwk0bj{pa z3~1Z}QMKTMdZ~?ae_Z_oZIy)y=trSgYB%joy6bkb_6%o_&BT{t_0pJprpaA)rNKSA z-|bpY6l-x5$I9$ie5T~1ly8^xhCKUaSo6>|(xX6TT_sV3)IhGHTo&E^zz z*zm3oe~z-BRgcOdH-saPgr>C3 zBXWK%;gq)}0w=4Mr)5?54QuO<=f+LhYkD+8$Ovt-tm;uHR^@GEBK#c=r#zNSkP^wj zjiAWm$&4GcUY?cbQ6OCFEBWpyDFidF$)*Br)RKu@1>tQUH0<}MaxL#}lR!jm+?rcp zsgc_pO)-Q}f8_h}dFEAe84b&=?~42)P?|II$sV_8k&jH?KZGv_{D-OmAgh55eOgqg zRW5z#z{*S9o@X_BPBWR*)|5d@qWX6*s@+s@q~d{Hr7k=ehWTl2L5hq6>&SqXD;i|Q z{3JWPJGP3wE#3@e`Os=O7m1c8;|)80AIIjvc#xBTe>xRIy>DSr{<=D__b>a&Twqy+ z##{3AOPh+S$~E&*_j4Ph#Yhr`H3j5G9ODSgIB5S{2No|&3ThE^E}pj2j3V8zyYVL# zH7M!*r)2P@-)+>4K1D;hG@V)vrcB~BJMl`l?P_G1l$a3B-187#G>L7$)8SU-6X2LQ zcvgr7f4&S}m95|r@nVcu8dhCTrc;i8RaDiJoGl@HyN{oy3^9&-hT zI)Dgd@+9p-joBLBtXceKS}nLOjh8gl6ni@7#mr%;q78i(nuJs0sEZikSeIGCxYGM{ z1?L;9NFR)c{oz-wWl#^KB|$Vo<7#M`O_ms95>RFq<+J_g-r9a4`=_uh`6=%2V#pwi ze<=dcbAqyr+~1_^vq*iJ1pzru1GjJI$hw9n=;Yp3n(>4`yz&@YLa&)87RtgDL>6cc zt+b)3dyB{8k0(lfxcs9!3~k~1;3W701M}!jM~LwimWq2Wv`&nYu<(b+!RHKP#$2H_ z^MLY2b;56mOo^JM1CCV=)&{d(sc}hMf47C0`Gkzs8H?y<>a*V!51*dhu;xpXC{gLBuL7U{wq9>qlfMKz+tlb(c6`}v%9PVml6Rb-?hu}a;s1V-o^h>%eTgVVZT4~nOe@Q-9?v-JbSN?_)V3-Q#Es?jZN$t@RtAy@mc;(BYPYg5okhNTQ@lEYjAYp6_8)y-MSOk*wC zIEkTD2pr#{Lp(n;c~Fq9|KaPS=~2<@H;+DQW`W@kU&4^dDz}V11Z?ZG$!`pd$Al>p>5BdHl!xPKwia=s6m&Rf>fPJb)lyXt z_6JJ^sL*FncT;yGE!rRSHgSDJ#KmTr;^|SJgcGlWO+S4DjZdrm_n!id6iesaK`PUD z`U0@u9264pgc=+K_qSYye=!-fUr*2JLH zhlYzu5bW`OfvG%e<6K~J)IUm5P2=(Bdb%wxU=(9lshkWMyCHB#z}MKJ?;2=LX7?9a z9ZXY$0pZP3akG@~&9X3G_vN+^TA4#=rlZq>i-{t2;DV;`#V%=Pe?_WxJvoXCg1@UU zD5ThD);5oLy;;OV2djx@_?_Uki%FwvGz&vOTC(2h!Yx$A?<%@k5EEV!NW3*%z_M2v zWCO;ZNo@%t2#3WH)cU|)e72wa;*S&|3swfyUb|0hXT8re*)X`+$qFY{s$uF zZO|i_a)U$=KrcC-VN)xY=d*VD*nxmfloGW%Zgq)|8P2-$CFkCmXvxci&6HasJ#mq$x4O6N9NQIO!{tXQ;Hy3<|=^ky= zuRk?oq zm&bf(+h<>CGx=e9dylX3(}G~D9t(2YJyK&gaBO=DC`wB+^P^pL)W$yWx+QtKs3K&6SF8)vDbqrZ!3$;lX0 zX;>N#Jd*GiVoZV0XJc@Kk2j`7`nbHYpBbYE^?K0N!Foddm!@v#Me%Ir=Z|Pd(g>>B z;UQ)*lf-5IrGuBL9itY5?QIVvIk;~8va2ODd^b1>YyMnv%MbPVpj|;nF~1uhY5O1b zy)?lWf3Q`3-V5pki;B&Y#l^T(-t<>6RD;nS+=NP#7cI7`cDRT|B)z8JC4-)&Yd2ZO zk5SAXqY#(XuF--f5e*llb?mSsXU7l5=JX2JhOzM$*U)C+pRGW>eT=FUwDg088J87L zy`#pgs1mjM*Zn|rsAA`#@yHVKTEKl8wNln*fAka>GnT}k1YyN42RVT|mnC3;k6`Up zwDsW;K^jpA+mX`Tpzn8P{58?{bw7rk7k2EQj9_YwrSD0PH&w*+TQVBfvCKoLCpfewQ6cPR@|6X*<}VfG ze?W%L5?j88&hQekz>=&~9QTYCGX?`yDAdq&_H`BT`A*&4f$>eU&TJ%1(bj>4B})V? zK`d;XORsG>_`ZD(Xw^6|mGIGU#b(gV0MjHjtsM-zlcSfoX=>^Y5C;4hD^q=j>Tl15 zr8=;r?Ll;0o(;qsiv&k1T%0M`Y^u*Ue?-6-lLq7+-^;Am3^eJj?K?Dq_@GwVh9b}U zD=lR19F_IqzMQYCH7s#8TCn%w+piA3p|oR|L-f6mE@koXC4ppLam_Us-f}Qyt4#YS zrW1v>Wwr%j7~nag{Xnn(I( zoo;%Qn~Yfk@+boXM*^E$o05egw3929WUN#NGN+=%cGQ|0&lZB2$iSrTHE}V`eZ|T_KGyv@DiE4`Dx$6A?3`t;Q#r%;1nApvPfQ1Fy|r zH~^lM_glmK{^(|H-x>J^D(t7WfAEF9mAdbv zIgkdHq4sC)Wnn?C%|o_%c(YXz+0nP>^pkEC0=U0m$kuMirM1{bF+ZHP8iWZd^*tXV z=cv!6@c9k9?nlg8t&3{)0`LvFyR65Kctzq$7i52~z@6CWhofaXAdPUkJ}*W(orl)R zuQSvY#`l7V6#Ou4BiEDs*KP`nr`*e7j#C_#6;q|?x3^WQw6m4Al{M5gl`~DH zQx$ZmbgZI^l`*uoF_qEuJJ}86E2WdFjH{H1x}x`#^Pw`42!Fangenzjv8DBi3HwSn z!Bo~&nif=+`DkC+NNiQyaGJJ2^qi`+kF*0?$M5sD_Z1RAmQL>RaBKy4Y8q3D`ki@QBf*V8v|jaRRGYMp(O#84g@f9 zP^JmZMq>Ol5h2;=ZQE2S0Z|%nXtiw|bE4&zUSyusv*^(aHjwQK`vw=52 zZ@6I91`DZNVmWDn*O3Gz-FZ)MYFh4tqH&@^sFRL(O@H!Crc$9{QHW5`#DYLl!H`PG zC{(b{ZfM$BaLkRA9z1WHUJsGTI$o2A5wVKAEncJ@>6?CA7K|20M^-`bsOT9OUK&-{ z(A-I6I7BryF;_t_-8{f>TFLP42?op}kCeuSU zY1#6+Tca-2DSdK0H5Y`PdoGD%3z+vUt0%8vt$)nN8T~mOa^z+{-mppK^_Gq40g!0d zg+!Zw028uQ?Z1NwN5jyQtAl5WLxE2V&jOz%w)e!xG(CLcgA98GJ1KD}@ENj!67tf1 zD3lm=r@h@56Whha=zrLcT6R*%RpM6S)52lEu3C2TsQ82)KJJlhX2?!jvJYTY;@OHJ zWq-^Wh)YWq-4her^CPpGA6d1Q(F_HbmNAtEQ3_u=RS9TeG)qA53q;R(to~mDQ3~Gz zr2yh~;qNPO&l{|JkiZYn_MnE#a8YRc!DjDzW^W&6_JcvO30U=k35v7|XE-kv2a!(+9&js9S zF5tiK|Eq59GgUmBhHFtOIqfFZiWGyWfZf!nCV2o4()yq`3B1N_I#OENOt~-P(Ya0A znq{&!#?6SHYZ|KKeK99%F&3M}yGeQK@iMbbMVIqv(gobC0!O0>qMhSp1)siDL8VIKqYtJOIfxu#tj`-R}Gk-9*{xU?w=hmBuw;$S;G?O=ZblLOJL?XQ^YCWxr z(eOxOyNQWyB2dkroaXoFnXNm}3Lha)qv0knO{Kg7pTN`%(+shpXU}%6*-L^0M24+4 z(hg`u^WKyq)c8iMQEZV=Wi-skHHj5bv~AR!its_p3c${sOY9R?^IrM3s()dH_=e{K zwri~;o(>xEo*COlq)9A%@QGhgOdyj9Ou}U?TN<%!yQFzXaM8xliqT7J48|Q81vY@( zvc=?pJKFNCA=8Kr@2%e|jg97C5dkK*!Qsby zR^r`ljNq|Co7ZRB3m!#yi+{jUDLmxJ0$}rya`Nl0rv@)1ASEP(>QJk!U@IuJ+1>Fg z-SSpLkw25`kCZmkvVo#4a7C=)G2tM6K3clHRa)%B<)77GTY)H=+ehd8mLtXD<#Vb3 zTbJS{5-SI+j+2M%e`sX|L`C4pZLvw=77_xA^T3}&R|p)GL>EDEz<+d!!%egn;m{%g zVb)Wc5IK4%-Edrqx?uu|UEC))nZiaXQqfCrI3_^b(+*qE)TSt`;JzLwI8NU0I9>r+ zHm+Wq(dWSBB+yuPH+Hfp(KaB*k+mVazHaq{XPIP;Z4gh<%9?W4IM<@}kTz39D?G}! z@gVZIKU5-ze5 zZA#0X6Y@H} zpx|+a=9P5PbKofxtTLPH_g86E1E|Y9YxS2`BAtH?&y>8|Gk>jD+hg8x4kGOxFKLQF zIuEh8QGUT%_02CAWCPm<)9QZLe>-igrk$QLEmT`LtJ&qZ<`XH5M!7# z(sL7;olQ*CVt?Fdk8F;u)M=#HArWL8F=aJ9!?))_IOIx7=-Qazw*jXPSn<3UO9>i| zMGohjl2fWimaDGsHg&nWZL;$>ShJC4d2o9I64(!LYGPA>E*awxR$w1wKh5`Z)K&gYK#eg!ANfP@fVVyNm~b+(qz?9&)AR-sC7V}M z$-&g=H|vGRSTd>3ktv{(@s4Ntykg4ms-&PVc4U6vNNhks+)1R+=pvnTMSix*kN!?7 z>I{3dlq;N61%*o%*itYN24PSodPEh4`;CN@jrAEN)<%E!t^~i1jX_+HlbmmccrG}s zlgogJQ#I;EAtgCEBjRAS9AVFxt|oUebu=Rm5VotT4DPFtC5DtdL?hTN3yA#u4{89#K(Rz7^8B zCWjaS_4M z-Qtu~gk%DqI9aSlZW8%QC?@0!5tm?1KEb=PTKXL2 z+x-yCVvSIjR@Ss;vA2@iLt3FDt#Bz@&H{h@e1wv03PvO?+Zdl^oH`-jMBU1FsItbm zm~$EqZ$MhZyA;k@p#z$}mD=73^(N<~XLoH=+q3c}(tteP2xjb3Ht$F7q67!$Z-OF&& z@{zkKOJJCPqU04QDP&3R=%WpMI291FqAB_;o5ZpiaOk>Aa=aR-2ExtL{vq=$bNpXHi- z(};5b#uGtVBf#J;CE^Aa38}0JsIK@1!_4~$cNLn0S_CJoLz_^ulp`+SLsH+MrswKc z`Z6vQ%UPytRmdEqr(-B)Wi`fpMl-M8KHY!b`Td9Oo#&raLldW?1PmWJ!6+JK$o_In<+eZCrHaeXgJUu@?9rNV=Y<%{C>WPi| zQ+~r5MFdVpm;5&d|Ej-Ujt<7B4>$9`b zY%)DRoLpU;j=t4@jc;b-^TVqNBmRG)#1|6+KkD-DKE7uY`+M&{efU5&vGZ!kCX6PV zkdIMOmMu+!D(%uHd^CTBRVbb;t>THYbGrz7&@P_VTlIGRyna!?tbeLs)jRbs^=|!Z zy;two@9Gcrr+QR>tq-OIM}1fyj!$Q!dR&h$t|q6`b5)P&@u)tok4L=VkNUix*3+}` z@uEYz)sJOE@`T4Slz4}D@8-tP zHHXp|jv@aa3k2F`u+;wF^-T+#xDGaNo__p&_c>v+H{?XNnLAOF9)isxwE8rN%rl^{ zdoro_C&z?K5zK#Dp{G6=T~5#IgURK=_1V!W1*U^3;Z`3`XQKn=&yMxy_2{%7-yEEd z&g!GdU*r0Gaz3u7^mDO{S4FU@FHWz?t4=P*<9hb@w7wyyx}28Kre+;z-*3Nsy1&cN z`T?t(Bdd~m6l8hX0J1DL3)K^8t(g1fxA$*fZm~!Mj%0uQ+*m^MC?W;Fg0YCIq1hGm z+Jj)NQ2FY^$JZ}k5(N9d4W=TgdV)-Zzeg2S))GKA3?<@Z;k^FuO;!R+Vj_37z&wlJA_4oNu=rm46ZU7chrA~V82%72cg*O#!V zlW!L%Xcs}N|L1f__Kfh^LjcPAAUW>g8752VJp2F|3xe~Dhat+ zaRQ6|-mnGtPGi-q6_EFS*?s@)gD6`!&5*L)T-nsLl#MVo5Vck{)=O=Q zj>e*hW5CXKKFfH(o4ZJ;wSxES-+p@jX-|*{df@m~!LmcgN*NmniS$n*@d8EgTUdYi z2+n;%CdNYl-IjB$;J)>A@Aa!^B;YYZym_?d#r^==7X9s@`*A~Yv zto#BxODIwe%U5)XTr{1M!%Om*z!@zf`UQ8~pW^9TTx%_{dQSMXe zu~C1V9L`Rz`2Xm*)xGZG-Mw7v@OE9^%Cwlr1@qw7XWqGu>hKO--lomlF9nb5^X}Xg zb$F+q+_vPco2A@tecqkBm^SaEdc22NhxJ*v?*NmWbQf!zmYntaocpCwn>qgvI34afvnzYqM~TfNY^a}Ub~n_E7@_4oYH7n!J;H|iDPea*eWM;iC_I10hPu~8T?^_d z%&7sB4(1-*JJ&c}?&eO1iiLyQ|Bd^Y(tq$Ycj(Yn#x3atf9?E=zjuDk>HXqcASC* z`C9p34CKEO$X}%IytooQqWWffyde}8ylBn;0~xs6+n13#0~D7F&jVdjL^(D?LPR-1 zLpV4&H8(^uHaRpzGC4FbK{Q4+IXO5(J|H|qIW|K=L^(l2I5;^qH$*ZvIW$BvIW#aq zG)6T!IXFW;T?#KuWo~D5Xdp8(Fd&x!cmXJXCD2JPLtz-j@pJA~MbR2s^IVjo=9(2X z);uh&tR#j7TRSU>g;-ho2t*K{!BVX4B-pT)kn?o&%l~=ag+nl6yE!o>5@J%Uh-EP=mc)!07ZbuGG6>(c-LfjCg;!(}p-($Vifoa8 zMTA4P^NAdy>&wPGkxL{FZCn?Akx!&bY*!!x#MXz6MWT?{xw0`Riix9`jU^&PoV?jM zFUmwIarSPz4KXUpMTMvoW1>n_iyBcY>O{S05Mj|MnnbgRh!)W*qQv>8z1BwDIack& z&y!UL89cCxk;#3lPV)H1s*AiBu<9m2Z)w#-zU*4{lHWnAKJqvHpZn=}(%%-RvzLBj zfX?Nk)gWEGS`E>SUt0~+O`Teeh)uCY_dW``&jI`c!)`DMmnP8z9t$`)G&l++B}Gq0 E3ipdUKL7v# From 2d41b017347eb2aab544c70c8efc58ee6e4d5eea Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 20 Jul 2022 15:28:49 -0400 Subject: [PATCH 33/36] change python CI cores to 1 --- .github/scripts/python.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/scripts/python.sh b/.github/scripts/python.sh index 0855dbc21b..1c791e71b7 100644 --- a/.github/scripts/python.sh +++ b/.github/scripts/python.sh @@ -80,7 +80,7 @@ cmake $GITHUB_WORKSPACE -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} \ # Set to 2 cores so that Actions does not error out during resource provisioning. -make -j2 install +make -j1 install cd $GITHUB_WORKSPACE/build/python $PYTHON -m pip install --user . From 8a33a5bc53537e87ce23de8aae19032058f0d334 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 22 Jul 2022 14:29:36 -0400 Subject: [PATCH 34/36] Revert "change python CI cores to 1" This reverts commit 2d41b017347eb2aab544c70c8efc58ee6e4d5eea. --- .github/scripts/python.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/scripts/python.sh b/.github/scripts/python.sh index 1c791e71b7..0855dbc21b 100644 --- a/.github/scripts/python.sh +++ b/.github/scripts/python.sh @@ -80,7 +80,7 @@ cmake $GITHUB_WORKSPACE -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} \ # Set to 2 cores so that Actions does not error out during resource provisioning. -make -j1 install +make -j2 install cd $GITHUB_WORKSPACE/build/python $PYTHON -m pip install --user . From ac28b0e9690b82a298113c02aaa3091be70845b3 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 2 Aug 2022 14:14:13 -0400 Subject: [PATCH 35/36] fix setter and getter for biasAccOmegaInit --- gtsam/navigation/CombinedImuFactor.h | 4 ++-- gtsam/navigation/navigation.i | 4 ++-- gtsam/navigation/tests/testCombinedImuFactor.cpp | 7 ++++--- 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 28a3142472..7e45e5380e 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -93,11 +93,11 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; } void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; } - void setBiasAccOmegaInt(const Matrix6& cov) { biasAccOmegaInit=cov; } + void setBiasAccOmegaInit(const Matrix6& cov) { biasAccOmegaInit=cov; } const Matrix3& getBiasAccCovariance() const { return biasAccCovariance; } const Matrix3& getBiasOmegaCovariance() const { return biasOmegaCovariance; } - const Matrix6& getBiasAccOmegaInt() const { return biasAccOmegaInit; } + const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInit; } private: diff --git a/gtsam/navigation/navigation.i b/gtsam/navigation/navigation.i index 6ede1645f3..ab95d5a292 100644 --- a/gtsam/navigation/navigation.i +++ b/gtsam/navigation/navigation.i @@ -165,11 +165,11 @@ virtual class PreintegrationCombinedParams : gtsam::PreintegrationParams { void setBiasAccCovariance(Matrix cov); void setBiasOmegaCovariance(Matrix cov); - void setBiasAccOmegaInt(Matrix cov); + void setBiasAccOmegaInit(Matrix cov); Matrix getBiasAccCovariance() const ; Matrix getBiasOmegaCovariance() const ; - Matrix getBiasAccOmegaInt() const; + Matrix getBiasAccOmegaInit() const; }; diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index 48a89d7a05..de8a97ee1b 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -276,10 +276,11 @@ TEST(CombinedImuFactor, SameCovariance) { auto combined_params = PreintegrationCombinedParams::MakeSharedU(); combined_params->setAccelerometerCovariance(pow(0.01, 2) * I_3x3); combined_params->setGyroscopeCovariance(pow(1.75e-4, 2) * I_3x3); - combined_params->setIntegrationCovariance(pow(0, 2) * I_3x3); - combined_params->setOmegaCoriolis(Vector3::Zero()); // Set bias integration covariance explicitly to zero - combined_params->setBiasAccOmegaInt(Z_6x6); + combined_params->setIntegrationCovariance(Z_3x3); + combined_params->setOmegaCoriolis(Z_3x1); + // Set bias initial covariance explicitly to zero + combined_params->setBiasAccOmegaInit(Z_6x6); // The IMU preintegration object for CombinedImuFactor PreintegratedCombinedMeasurements cpim(combined_params, currentBias); From 103c78b0de0522ca838d444f00ab93b14aff388e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 10 Aug 2022 10:31:10 -0400 Subject: [PATCH 36/36] revert name change, save for another PR --- examples/CombinedImuFactorsExample.cpp | 2 +- examples/ImuFactorsExample.cpp | 2 +- gtsam/navigation/CombinedImuFactor.cpp | 6 +++--- gtsam/navigation/CombinedImuFactor.h | 12 ++++++------ gtsam/navigation/tests/testCombinedImuFactor.cpp | 2 +- .../examples/ISAM2_SmartFactorStereo_IMU.cpp | 2 +- tests/testImuPreintegration.cpp | 4 ++-- 7 files changed, 15 insertions(+), 15 deletions(-) diff --git a/examples/CombinedImuFactorsExample.cpp b/examples/CombinedImuFactorsExample.cpp index 35ed387c40..e0396ee818 100644 --- a/examples/CombinedImuFactorsExample.cpp +++ b/examples/CombinedImuFactorsExample.cpp @@ -123,7 +123,7 @@ boost::shared_ptr imuParams() { // PreintegrationCombinedMeasurements params: p->biasAccCovariance = bias_acc_cov; // acc bias in continuous p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous - p->biasAccOmegaInit = bias_acc_omega_init; + p->biasAccOmegaInt = bias_acc_omega_init; return p; } diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index 12167a19d1..c176318642 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -110,7 +110,7 @@ boost::shared_ptr imuParams() { // PreintegrationCombinedMeasurements params: p->biasAccCovariance = bias_acc_cov; // acc bias in continuous p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous - p->biasAccOmegaInit = bias_acc_omega_init; + p->biasAccOmegaInt = bias_acc_omega_init; return p; } diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 0813bbfd12..8d3a7dd315 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -39,7 +39,7 @@ void PreintegrationCombinedParams::print(const string& s) const { << endl; cout << "biasOmegaCovariance:\n[\n" << biasOmegaCovariance << "\n]" << endl; - cout << "biasAccOmegaInit:\n[\n" << biasAccOmegaInit << "\n]" + cout << "biasAccOmegaInt:\n[\n" << biasAccOmegaInt << "\n]" << endl; } @@ -52,7 +52,7 @@ bool PreintegrationCombinedParams::equals(const PreintegratedRotationParams& oth tol) && equal_with_abs_tol(biasOmegaCovariance, e->biasOmegaCovariance, tol) && - equal_with_abs_tol(biasAccOmegaInit, e->biasAccOmegaInit, tol); + equal_with_abs_tol(biasAccOmegaInt, e->biasAccOmegaInt, tol); } //------------------------------------------------------------------------------ @@ -135,7 +135,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement( const Matrix3& aCov = p().accelerometerCovariance; const Matrix3& wCov = p().gyroscopeCovariance; const Matrix3& iCov = p().integrationCovariance; - const Matrix6& bInitCov = p().biasAccOmegaInit; + const Matrix6& bInitCov = p().biasAccOmegaInt; // first order uncertainty propagation // Optimized matrix mult: (1/dt) * G * measurementCovariance * G.transpose() diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 7e45e5380e..b496181eda 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -62,19 +62,19 @@ typedef ManifoldPreintegration PreintegrationType; struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { Matrix3 biasAccCovariance; ///< continuous-time "Covariance" describing accelerometer bias random walk Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing gyroscope bias random walk - Matrix6 biasAccOmegaInit; ///< covariance of bias used as initial estimate. + Matrix6 biasAccOmegaInt; ///< covariance of bias used as initial estimate. /// Default constructor makes uninitialized params struct. /// Used for serialization. PreintegrationCombinedParams() : biasAccCovariance(I_3x3), biasOmegaCovariance(I_3x3), - biasAccOmegaInit(I_6x6) {} + biasAccOmegaInt(I_6x6) {} /// See two named constructors below for good values of n_gravity in body frame PreintegrationCombinedParams(const Vector3& n_gravity) : PreintegrationParams(n_gravity), biasAccCovariance(I_3x3), - biasOmegaCovariance(I_3x3), biasAccOmegaInit(I_6x6) { + biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) { } @@ -93,11 +93,11 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; } void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; } - void setBiasAccOmegaInit(const Matrix6& cov) { biasAccOmegaInit=cov; } + void setBiasAccOmegaInit(const Matrix6& cov) { biasAccOmegaInt=cov; } const Matrix3& getBiasAccCovariance() const { return biasAccCovariance; } const Matrix3& getBiasOmegaCovariance() const { return biasOmegaCovariance; } - const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInit; } + const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInt; } private: @@ -109,7 +109,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationParams); ar & BOOST_SERIALIZATION_NVP(biasAccCovariance); ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance); - ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInit); + ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt); } public: diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index de8a97ee1b..aacfff0f0d 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -43,7 +43,7 @@ static boost::shared_ptr Params() { p->integrationCovariance = 0.0001 * I_3x3; p->biasAccCovariance = Z_3x3; p->biasOmegaCovariance = Z_3x3; - p->biasAccOmegaInit = Z_6x6; + p->biasAccOmegaInt = Z_6x6; return p; } } // namespace testing diff --git a/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp b/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp index 27d87d217f..c0a102d111 100644 --- a/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp +++ b/gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp @@ -57,7 +57,7 @@ struct IMUHelper { p->biasAccCovariance = I_3x3 * pow(0.00002, 2.0); // acc bias in continuous p->biasOmegaCovariance = I_3x3 * pow(0.001, 2.0); // gyro bias in continuous - p->biasAccOmegaInit = Matrix::Identity(6, 6) * 1e-5; + p->biasAccOmegaInt = Matrix::Identity(6, 6) * 1e-5; // body to IMU rotation Rot3 iRb(0.036129, -0.998727, 0.035207, diff --git a/tests/testImuPreintegration.cpp b/tests/testImuPreintegration.cpp index 94e6fb89f2..1f584be0ed 100644 --- a/tests/testImuPreintegration.cpp +++ b/tests/testImuPreintegration.cpp @@ -43,7 +43,7 @@ TEST(TestImuPreintegration, LoadedSimulationData) { double gyrNoiseSigma = 0.000208; double gyrBiasRwSigma = 0.000004; double integrationCovariance = 1e-8; - double biasAccOmegaInit = 1e-5; + double biasAccOmegaInt = 1e-5; double gravity = 9.81; double rate = 400.0; // Hz @@ -76,7 +76,7 @@ TEST(TestImuPreintegration, LoadedSimulationData) { imuPreintegratedParams->gyroscopeCovariance = I_3x3 * pow(gyrNoiseSigma, 2); imuPreintegratedParams->biasOmegaCovariance = I_3x3 * pow(gyrBiasRwSigma, 2); imuPreintegratedParams->integrationCovariance = I_3x3 * integrationCovariance; - imuPreintegratedParams->biasAccOmegaInit = I_6x6 * biasAccOmegaInit; + imuPreintegratedParams->biasAccOmegaInt = I_6x6 * biasAccOmegaInt; // Initial state Pose3 priorPose;