From 93149ae5f2ae92f2d38cdbaed92d39bb20914f4c Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Thu, 9 May 2013 18:59:20 +0000 Subject: [PATCH 001/256] Updated Concurrent example, forcing a call to smoother.update() between each synchronization --- .../examples/ConcurrentFilteringAndSmoothingExample.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/gtsam_unstable/examples/ConcurrentFilteringAndSmoothingExample.cpp b/gtsam_unstable/examples/ConcurrentFilteringAndSmoothingExample.cpp index bdbb3835f..002d24ad4 100644 --- a/gtsam_unstable/examples/ConcurrentFilteringAndSmoothingExample.cpp +++ b/gtsam_unstable/examples/ConcurrentFilteringAndSmoothingExample.cpp @@ -132,6 +132,7 @@ int main(int argc, char** argv) { // Manually synchronize the Concurrent Filter and Smoother every 1.0 s if(fmod(time, 1.0) < 0.01) { // Synchronize the Filter and Smoother + concurrentSmoother.update(); synchronize(concurrentFilter, concurrentSmoother); } @@ -210,6 +211,7 @@ int main(int argc, char** argv) { // Manually synchronize the Concurrent Filter and Smoother every 1.0 s if(fmod(time, 1.0) < 0.01) { // Synchronize the Filter and Smoother + concurrentSmoother.update(); synchronize(concurrentFilter, concurrentSmoother); } @@ -282,6 +284,7 @@ int main(int argc, char** argv) { // Manually synchronize the Concurrent Filter and Smoother every 1.0 s if(fmod(time, 1.0) < 0.01) { // Synchronize the Filter and Smoother + concurrentSmoother.update(); synchronize(concurrentFilter, concurrentSmoother); cout << "******************************************************************" << endl; cout << "Syncing Concurrent Filter and Smoother." << endl; From 7d03d3c50205fb7fcb63990c0a8ea781a0ae88f7 Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Thu, 9 May 2013 18:59:22 +0000 Subject: [PATCH 002/256] Moved pre-sync code to the update() call for the cuncurrent smoother --- .../nonlinear/ConcurrentBatchSmoother.cpp | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp index 81705122e..1e9d4a2a9 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp @@ -87,6 +87,16 @@ ConcurrentBatchSmoother::Result ConcurrentBatchSmoother::update(const NonlinearF gttoc(optimize); } + // TODO: The following code does considerable work, much of which could be redundant given the previous optimization step + // Refactor this code to reduce computational burden + + // Calculate the marginal on the separator from the smoother factors + if(separatorValues_.size() > 0) { + gttic(presync); + updateSmootherSummarization(); + gttoc(presync); + } + gttoc(update); return result; @@ -97,15 +107,6 @@ void ConcurrentBatchSmoother::presync() { gttic(presync); - // TODO: Don't let the length of this code fool you. There is considerable work being done here. - // When we start multi-threading the filter and smoother, it would be ideal if the pre-sync stage - // could happen before the filter is stopped. - - // Calculate the marginal on the separator from the smoother factors - if(separatorValues_.size() > 0) { - updateSmootherSummarization(); - } - gttoc(presync); } From a5f28ac8f412215ff6a4865eeef1211bcc17e13c Mon Sep 17 00:00:00 2001 From: Vadim Indelman Date: Thu, 9 May 2013 23:17:18 +0000 Subject: [PATCH 003/256] Created a variation of an equivalent IMU factor without Bias. --- .../EquivInertialNavFactor_GlobalVel_NoBias.h | 587 ++++++++++++++++++ 1 file changed, 587 insertions(+) create mode 100644 gtsam/navigation/EquivInertialNavFactor_GlobalVel_NoBias.h diff --git a/gtsam/navigation/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam/navigation/EquivInertialNavFactor_GlobalVel_NoBias.h new file mode 100644 index 000000000..2858b091e --- /dev/null +++ b/gtsam/navigation/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -0,0 +1,587 @@ + +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file EquivInertialNavFactor_GlobalVel_NoBias.h + * @author Vadim Indelman, Stephen Williams + * @brief Equivalent inertial navigation factor (velocity in the global frame), without bias state. + * @date May 9, 2013 + **/ + +#pragma once + +#include +#include +#include +#include +#include + +// Using numerical derivative to calculate d(Pose3::Expmap)/dw +#include + +#include + +#include + +namespace gtsam { + +/* + * NOTES: + * ===== + * Concept: Based on [Lupton12tro] + * - Pre-integrate IMU measurements using the static function PreIntegrateIMUObservations. + * Pre-integrated quantities are expressed in the body system of t0 - the first time instant (in which pre-integration began). + * All sensor-to-body transformations are performed here. + * - If required, calculate inertial solution by calling the static functions: predictPose_inertial, predictVelocity_inertial. + * - When the time is right, incorporate pre-integrated IMU data by creating an EquivInertialNavFactor_GlobalVel_NoBias factor, which will + * relate between navigation variables at the two time instances (t0 and current time). + * + * Other notes: + * - The global frame (NED or ENU) is defined by the user by specifying the gravity vector in this frame. + * - The IMU frame is implicitly defined by the user via the rotation matrix between global and imu frames. + * - Camera and IMU frames are identical + * - The user should specify a continuous equivalent noise covariance, which can be calculated using + * the static function CalcEquivalentNoiseCov based on the IMU gyro and acc measurement noise covariance + * matrices and the process\modeling covariance matrix. The IneritalNavFactor converts this into a + * discrete form using the supplied delta_t between sub-sequential measurements. + * - Earth-rate correction: + * + Currently the user should supply R_ECEF_to_G, which is the rotation from ECEF to the global + * frame (Local-Level system: ENU or NED, see above). + * + R_ECEF_to_G can be calculated by approximated values of latitude and longitude of the system. + * + Currently it is assumed that a relatively small distance is traveled w.r.t. to initial pose, since R_ECEF_to_G is constant. + * Otherwise, R_ECEF_to_G should be updated each time using the current lat-lon. + * + * - Frame Notation: + * Quantities are written as {Frame of Representation/Destination Frame}_{Quantity Type}_{Quatity Description/Origination Frame} + * So, the rotational velocity of the sensor written in the body frame is: body_omega_sensor + * And the transformation from the body frame to the world frame would be: world_P_body + * This allows visual chaining. For example, converting the sensed angular velocity of the IMU + * (angular velocity of the sensor in the sensor frame) into the world frame can be performed as: + * world_R_body * body_R_sensor * sensor_omega_sensor = world_omega_sensor + * + * + * - Common Quantity Types + * P : pose/3d transformation + * R : rotation + * omega : angular velocity + * t : translation + * v : velocity + * a : acceleration + * + * - Common Frames + * sensor : the coordinate system attached to the sensor origin + * body : the coordinate system attached to body/inertial frame. + * Unless an optional frame transformation is provided, the + * sensor frame and the body frame will be identical + * world : the global/world coordinate frame. This is assumed to be + * a tangent plane to the earth's surface somewhere near the + * vehicle + */ + +template +class EquivInertialNavFactor_GlobalVel_NoBias : public NoiseModelFactor4 { + +private: + + typedef EquivInertialNavFactor_GlobalVel_NoBias This; + typedef NoiseModelFactor4 Base; + + Vector delta_pos_in_t0_; + Vector delta_vel_in_t0_; + Vector3 delta_angles_; + double dt12_; + + Vector world_g_; + Vector world_rho_; + Vector world_omega_earth_; + + Matrix Jacobian_wrt_t0_Overall_; + + boost::optional body_P_sensor_; // The pose of the sensor in the body frame + +public: + + // shorthand for a smart pointer to a factor + typedef typename boost::shared_ptr shared_ptr; + + /** default constructor - only use for serialization */ + EquivInertialNavFactor_GlobalVel_NoBias() {} + + /** Constructor */ + EquivInertialNavFactor_GlobalVel_NoBias(const Key& Pose1, const Key& Vel1, const Key& Pose2, const Key& Vel2, + const Vector& delta_pos_in_t0, const Vector& delta_vel_in_t0, const Vector3& delta_angles, + double dt12, const Vector world_g, const Vector world_rho, + const Vector& world_omega_earth, const noiseModel::Gaussian::shared_ptr& model_equivalent, + const Matrix& Jacobian_wrt_t0_Overall, + boost::optional body_P_sensor = boost::none) : + Base(model_equivalent, Pose1, Vel1, Pose2, Vel2), + delta_pos_in_t0_(delta_pos_in_t0), delta_vel_in_t0_(delta_vel_in_t0), delta_angles_(delta_angles), + dt12_(dt12), world_g_(world_g), world_rho_(world_rho), world_omega_earth_(world_omega_earth), Jacobian_wrt_t0_Overall_(Jacobian_wrt_t0_Overall), + body_P_sensor_(body_P_sensor) { } + + virtual ~EquivInertialNavFactor_GlobalVel_NoBias() {} + + /** implement functions needed for Testable */ + + /** print */ + virtual void print(const std::string& s = "EquivInertialNavFactor_GlobalVel_NoBias", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "(" + << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << "," + << keyFormatter(this->key3()) << "," + << keyFormatter(this->key4()) << "\n"; + std::cout << "delta_pos_in_t0: " << this->delta_pos_in_t0_.transpose() << std::endl; + std::cout << "delta_vel_in_t0: " << this->delta_vel_in_t0_.transpose() << std::endl; + std::cout << "delta_angles: " << this->delta_angles_ << std::endl; + std::cout << "dt12: " << this->dt12_ << std::endl; + std::cout << "gravity (in world frame): " << this->world_g_.transpose() << std::endl; + std::cout << "craft rate (in world frame): " << this->world_rho_.transpose() << std::endl; + std::cout << "earth's rotation (in world frame): " << this->world_omega_earth_.transpose() << std::endl; + if(this->body_P_sensor_) + this->body_P_sensor_->print(" sensor pose in body frame: "); + this->noiseModel_->print(" noise model"); + } + + /** equals */ + virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + const This *e = dynamic_cast (&expected); + return e != NULL && Base::equals(*e, tol) + && (delta_pos_in_t0_ - e->delta_pos_in_t0_).norm() < tol + && (delta_vel_in_t0_ - e->delta_vel_in_t0_).norm() < tol + && (delta_angles_ - e->delta_angles_).norm() < tol + && (dt12_ - e->dt12_) < tol + && (world_g_ - e->world_g_).norm() < tol + && (world_rho_ - e->world_rho_).norm() < tol + && (world_omega_earth_ - e->world_omega_earth_).norm() < tol + && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_))); + } + + + POSE predictPose(const POSE& Pose1, const VELOCITY& Vel1) const { + + /* Position term */ + Vector delta_pos_in_t0_corrected = delta_pos_in_t0_; + + /* Rotation term */ + Vector delta_angles_corrected = delta_angles_; + + return predictPose_inertial(Pose1, Vel1, + delta_pos_in_t0_corrected, delta_angles_corrected, + dt12_, world_g_, world_rho_, world_omega_earth_); + } + + static inline POSE predictPose_inertial(const POSE& Pose1, const VELOCITY& Vel1, + const Vector& delta_pos_in_t0, const Vector3& delta_angles, + const double dt12, const Vector& world_g, const Vector& world_rho, const Vector& world_omega_earth){ + + const POSE& world_P1_body = Pose1; + const VELOCITY& world_V1_body = Vel1; + + /* Position term */ + Vector body_deltaPos_body = delta_pos_in_t0; + + Vector world_deltaPos_pls_body = world_P1_body.rotation().matrix() * body_deltaPos_body; + Vector world_deltaPos_body = world_V1_body * dt12 + 0.5*world_g*dt12*dt12 + world_deltaPos_pls_body; + + // Incorporate earth-related terms. Note - these are assumed to be constant between t1 and t2. + world_deltaPos_body -= 2*skewSymmetric(world_rho + world_omega_earth)*world_V1_body * dt12*dt12; + + /* TODO: the term dt12*dt12 in 0.5*world_g*dt12*dt12 is not entirely correct: + * the gravity should be canceled from the accelerometer measurements, bust since position + * is added with a delta velocity from a previous term, the actual delta time is more complicated. + * Need to figure out this in the future - currently because of this issue we'll get some more error + * in Z axis. + */ + + /* Rotation term */ + Vector body_deltaAngles_body = delta_angles; + + // Convert earth-related terms into the body frame + Matrix body_R_world(world_P1_body.rotation().inverse().matrix()); + Vector body_rho = body_R_world * world_rho; + Vector body_omega_earth = body_R_world * world_omega_earth; + + // Incorporate earth-related terms. Note - these are assumed to be constant between t1 and t2. + body_deltaAngles_body -= (body_rho + body_omega_earth)*dt12; + + return POSE(Pose1.rotation() * POSE::Rotation::Expmap(body_deltaAngles_body), Pose1.translation() + typename POSE::Translation(world_deltaPos_body)); + + } + + VELOCITY predictVelocity(const POSE& Pose1, const VELOCITY& Vel1) const { + + + Vector delta_vel_in_t0_corrected = delta_vel_in_t0_; + + return predictVelocity_inertial(Pose1, Vel1, + delta_vel_in_t0_corrected, + dt12_, world_g_, world_rho_, world_omega_earth_); + } + + static inline VELOCITY predictVelocity_inertial(const POSE& Pose1, const VELOCITY& Vel1, + const Vector& delta_vel_in_t0, + const double dt12, const Vector& world_g, const Vector& world_rho, const Vector& world_omega_earth) { + + const POSE& world_P1_body = Pose1; + const VELOCITY& world_V1_body = Vel1; + + Vector body_deltaVel_body = delta_vel_in_t0; + Vector world_deltaVel_body = world_P1_body.rotation().matrix() * body_deltaVel_body; + + VELOCITY VelDelta( world_deltaVel_body + world_g * dt12 ); + + // Incorporate earth-related terms. Note - these are assumed to be constant between t1 and t2. + VelDelta -= 2*skewSymmetric(world_rho + world_omega_earth)*world_V1_body * dt12; + + // Predict + return Vel1.compose( VelDelta ); + + } + + void predict(const POSE& Pose1, const VELOCITY& Vel1, POSE& Pose2, VELOCITY& Vel2) const { + Pose2 = predictPose(Pose1, Vel1); + Vel2 = predictVelocity(Pose1, Vel1); + } + + POSE evaluatePoseError(const POSE& Pose1, const VELOCITY& Vel1, const POSE& Pose2, const VELOCITY& Vel2) const { + // Predict + POSE Pose2Pred = predictPose(Pose1, Vel1); + + // Calculate error + return Pose2.between(Pose2Pred); + } + + VELOCITY evaluateVelocityError(const POSE& Pose1, const VELOCITY& Vel1, const POSE& Pose2, const VELOCITY& Vel2) const { + // Predict + VELOCITY Vel2Pred = predictVelocity(Pose1, Vel1); + + // Calculate error + return Vel2.between(Vel2Pred); + } + + Vector evaluateError(const POSE& Pose1, const VELOCITY& Vel1, const POSE& Pose2, const VELOCITY& Vel2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none, + boost::optional H3 = boost::none, + boost::optional H4 = boost::none) const { + + // TODO: Write analytical derivative calculations + // Jacobian w.r.t. Pose1 + if (H1){ + Matrix H1_Pose = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, _1, Vel1, Pose2, Vel2), Pose1); + Matrix H1_Vel = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, _1, Vel1, Pose2, Vel2), Pose1); + *H1 = stack(2, &H1_Pose, &H1_Vel); + } + + // Jacobian w.r.t. Vel1 + if (H2){ + Matrix H2_Pose = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, _1, Pose2, Vel2), Vel1); + Matrix H2_Vel = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, _1, Pose2, Vel2), Vel1); + *H2 = stack(2, &H2_Pose, &H2_Vel); + } + + // Jacobian w.r.t. Pose2 + if (H3){ + Matrix H3_Pose = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, Vel1, _1, Vel2), Pose2); + Matrix H3_Vel = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, Vel1, _1, Vel2), Pose2); + *H3 = stack(2, &H3_Pose, &H3_Vel); + } + + // Jacobian w.r.t. Vel2 + if (H4){ + Matrix H4_Pose = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluatePoseError, this, Pose1, Vel1, Pose2, _1), Vel2); + Matrix H4_Vel = numericalDerivative11(boost::bind(&EquivInertialNavFactor_GlobalVel_NoBias::evaluateVelocityError, this, Pose1, Vel1, Pose2, _1), Vel2); + *H4 = stack(2, &H4_Pose, &H4_Vel); + } + + Vector ErrPoseVector(POSE::Logmap(evaluatePoseError(Pose1, Vel1, Pose2, Vel2))); + Vector ErrVelVector(VELOCITY::Logmap(evaluateVelocityError(Pose1, Vel1, Pose2, Vel2))); + + return concatVectors(2, &ErrPoseVector, &ErrVelVector); + } + + + + static inline POSE PredictPoseFromPreIntegration(const POSE& Pose1, const VELOCITY& Vel1, + const Vector& delta_pos_in_t0, const Vector3& delta_angles, + double dt12, const Vector world_g, const Vector world_rho, + const Vector& world_omega_earth, const Matrix& Jacobian_wrt_t0_Overall) { + + /* Position term */ + Vector delta_pos_in_t0_corrected = delta_pos_in_t0; + + /* Rotation term */ + Vector delta_angles_corrected = delta_angles; + // Another alternative: + // Vector delta_angles_corrected = Rot3::Logmap( Rot3::Expmap(delta_angles_)*Rot3::Expmap(J_angles_wrt_BiasGyro*delta_BiasGyro) ); + + return predictPose_inertial(Pose1, Vel1, delta_pos_in_t0_corrected, delta_angles_corrected, dt12, world_g, world_rho, world_omega_earth); + } + + static inline VELOCITY PredictVelocityFromPreIntegration(const POSE& Pose1, const VELOCITY& Vel1, + const Vector& delta_vel_in_t0, double dt12, const Vector world_g, const Vector world_rho, + const Vector& world_omega_earth, const Matrix& Jacobian_wrt_t0_Overall) { + + Vector delta_vel_in_t0_corrected = delta_vel_in_t0; + + return predictVelocity_inertial(Pose1, Vel1, delta_vel_in_t0_corrected, dt12, world_g, world_rho, world_omega_earth); + } + + static inline void PredictFromPreIntegration(const POSE& Pose1, const VELOCITY& Vel1, POSE& Pose2, VELOCITY& Vel2, + const Vector& delta_pos_in_t0, const Vector& delta_vel_in_t0, const Vector3& delta_angles, + double dt12, const Vector world_g, const Vector world_rho, + const Vector& world_omega_earth, const Matrix& Jacobian_wrt_t0_Overall) { + + Pose2 = PredictPoseFromPreIntegration(Pose1, Vel1, delta_pos_in_t0, delta_angles, dt12, world_g, world_rho, world_omega_earth, Jacobian_wrt_t0_Overall); + Vel2 = PredictVelocityFromPreIntegration(Pose1, Vel1, delta_vel_in_t0, dt12, world_g, world_rho, world_omega_earth, Jacobian_wrt_t0_Overall); + } + + + static inline void PreIntegrateIMUObservations(const Vector& msr_acc_t, const Vector& msr_gyro_t, const double msr_dt, + Vector& delta_pos_in_t0, Vector3& delta_angles, Vector& delta_vel_in_t0, double& delta_t, + const noiseModel::Gaussian::shared_ptr& model_continuous_overall, + Matrix& EquivCov_Overall, Matrix& Jacobian_wrt_t0_Overall, + boost::optional p_body_P_sensor = boost::none){ + // Note: all delta terms refer to an IMU\sensor system at t0 + // Note: Earth-related terms are not accounted here but are incorporated in predict functions. + + POSE body_P_sensor = POSE(); + bool flag_use_body_P_sensor = false; + if (p_body_P_sensor){ + body_P_sensor = *p_body_P_sensor; + flag_use_body_P_sensor = true; + } + + delta_pos_in_t0 = PreIntegrateIMUObservations_delta_pos(msr_dt, delta_pos_in_t0, delta_vel_in_t0); + delta_vel_in_t0 = PreIntegrateIMUObservations_delta_vel(msr_gyro_t, msr_acc_t, msr_dt, delta_angles, delta_vel_in_t0, flag_use_body_P_sensor, body_P_sensor); + delta_angles = PreIntegrateIMUObservations_delta_angles(msr_gyro_t, msr_dt, delta_angles, flag_use_body_P_sensor, body_P_sensor); + + delta_t += msr_dt; + + // Update EquivCov_Overall + Matrix Z_3x3 = zeros(3,3); + Matrix I_3x3 = eye(3,3); + + Matrix H_pos_pos = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, _1, delta_vel_in_t0), delta_pos_in_t0); + Matrix H_pos_vel = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_pos, msr_dt, delta_pos_in_t0, _1), delta_vel_in_t0); + Matrix H_pos_angles = Z_3x3; + + Matrix H_vel_vel = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, msr_acc_t, msr_dt, delta_angles, _1, flag_use_body_P_sensor, body_P_sensor), delta_vel_in_t0); + Matrix H_vel_angles = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_vel, msr_gyro_t, msr_acc_t, msr_dt, _1, delta_vel_in_t0, flag_use_body_P_sensor, body_P_sensor), delta_angles); + Matrix H_vel_pos = Z_3x3; + + Matrix H_angles_angles = numericalDerivative11(boost::bind(&PreIntegrateIMUObservations_delta_angles, msr_gyro_t, msr_dt, _1, flag_use_body_P_sensor, body_P_sensor), delta_angles); + Matrix H_angles_pos = Z_3x3; + Matrix H_angles_vel = Z_3x3; + + Matrix F_angles = collect(3, &H_angles_angles, &H_angles_pos, &H_angles_vel); + Matrix F_pos = collect(3, &H_pos_angles, &H_pos_pos, &H_pos_vel); + Matrix F_vel = collect(3, &H_vel_angles, &H_vel_pos, &H_vel_vel); + Matrix F = stack(3, &F_angles, &F_pos, &F_vel); + + noiseModel::Gaussian::shared_ptr model_discrete_curr = calc_descrete_noise_model(model_continuous_overall, msr_dt ); + Matrix Q_d = inverse(model_discrete_curr->R().transpose() * model_discrete_curr->R() ); + + EquivCov_Overall = F * EquivCov_Overall * F.transpose() + Q_d; + + // Update Jacobian_wrt_t0_Overall + Jacobian_wrt_t0_Overall = F * Jacobian_wrt_t0_Overall; + } + + static inline Vector PreIntegrateIMUObservations_delta_pos(const double msr_dt, + const Vector& delta_pos_in_t0, const Vector& delta_vel_in_t0){ + + // Note: all delta terms refer to an IMU\sensor system at t0 + // Note: delta_vel_in_t0 is already in body frame, so no need to use the body_P_sensor transformation here. + + return delta_pos_in_t0 + delta_vel_in_t0 * msr_dt; + } + + + + static inline Vector PreIntegrateIMUObservations_delta_vel(const Vector& msr_gyro_t, const Vector& msr_acc_t, const double msr_dt, + const Vector3& delta_angles, const Vector& delta_vel_in_t0, const bool flag_use_body_P_sensor, const POSE& body_P_sensor){ + + // Note: all delta terms refer to an IMU\sensor system at t0 + + // Calculate the corrected measurements using the Bias object + Vector AccCorrected = msr_acc_t; + Vector body_t_a_body; + if (flag_use_body_P_sensor){ + Matrix body_R_sensor = body_P_sensor.rotation().matrix(); + + Vector GyroCorrected(msr_gyro_t); + + Vector body_omega_body = body_R_sensor * GyroCorrected; + Matrix body_omega_body__cross = skewSymmetric(body_omega_body); + + body_t_a_body = body_R_sensor * AccCorrected - body_omega_body__cross * body_omega_body__cross * body_P_sensor.translation().vector(); + } else{ + body_t_a_body = AccCorrected; + } + + Rot3 R_t_to_t0 = Rot3::Expmap(delta_angles); + + return delta_vel_in_t0 + R_t_to_t0.matrix() * body_t_a_body * msr_dt; + } + + + static inline Vector PreIntegrateIMUObservations_delta_angles(const Vector& msr_gyro_t, const double msr_dt, + const Vector3& delta_angles, const bool flag_use_body_P_sensor, const POSE& body_P_sensor){ + + // Note: all delta terms refer to an IMU\sensor system at t0 + + // Calculate the corrected measurements using the Bias object + Vector GyroCorrected = msr_gyro_t; + + Vector body_t_omega_body; + if (flag_use_body_P_sensor){ + body_t_omega_body = body_P_sensor.rotation().matrix() * GyroCorrected; + } else { + body_t_omega_body = GyroCorrected; + } + + Rot3 R_t_to_t0 = Rot3::Expmap(delta_angles); + + R_t_to_t0 = R_t_to_t0 * Rot3::Expmap( body_t_omega_body*msr_dt ); + return Rot3::Logmap(R_t_to_t0); + } + + static inline noiseModel::Gaussian::shared_ptr CalcEquivalentNoiseCov(const noiseModel::Gaussian::shared_ptr& gaussian_acc, const noiseModel::Gaussian::shared_ptr& gaussian_gyro, + const noiseModel::Gaussian::shared_ptr& gaussian_process){ + + Matrix cov_acc = inverse( gaussian_acc->R().transpose() * gaussian_acc->R() ); + Matrix cov_gyro = inverse( gaussian_gyro->R().transpose() * gaussian_gyro->R() ); + Matrix cov_process = inverse( gaussian_process->R().transpose() * gaussian_process->R() ); + + cov_process.block(0,0, 3,3) += cov_gyro; + cov_process.block(6,6, 3,3) += cov_acc; + + return noiseModel::Gaussian::Covariance(cov_process); + } + + static inline void CalcEquivalentNoiseCov_DifferentParts(const noiseModel::Gaussian::shared_ptr& gaussian_acc, const noiseModel::Gaussian::shared_ptr& gaussian_gyro, + const noiseModel::Gaussian::shared_ptr& gaussian_process, + Matrix& cov_acc, Matrix& cov_gyro, Matrix& cov_process_without_acc_gyro){ + + cov_acc = inverse( gaussian_acc->R().transpose() * gaussian_acc->R() ); + cov_gyro = inverse( gaussian_gyro->R().transpose() * gaussian_gyro->R() ); + cov_process_without_acc_gyro = inverse( gaussian_process->R().transpose() * gaussian_process->R() ); + } + + static inline void Calc_g_rho_omega_earth_NED(const Vector& Pos_NED, const Vector& Vel_NED, const Vector& LatLonHeight_IC, const Vector& Pos_NED_Initial, + Vector& g_NED, Vector& rho_NED, Vector& omega_earth_NED) { + + Matrix ENU_to_NED = Matrix_(3, 3, + 0.0, 1.0, 0.0, + 1.0, 0.0, 0.0, + 0.0, 0.0, -1.0); + + Matrix NED_to_ENU = Matrix_(3, 3, + 0.0, 1.0, 0.0, + 1.0, 0.0, 0.0, + 0.0, 0.0, -1.0); + + // Convert incoming parameters to ENU + Vector Pos_ENU = NED_to_ENU * Pos_NED; + Vector Vel_ENU = NED_to_ENU * Vel_NED; + Vector Pos_ENU_Initial = NED_to_ENU * Pos_NED_Initial; + + // Call ENU version + Vector g_ENU; + Vector rho_ENU; + Vector omega_earth_ENU; + Calc_g_rho_omega_earth_ENU(Pos_ENU, Vel_ENU, LatLonHeight_IC, Pos_ENU_Initial, g_ENU, rho_ENU, omega_earth_ENU); + + // Convert output to NED + g_NED = ENU_to_NED * g_ENU; + rho_NED = ENU_to_NED * rho_ENU; + omega_earth_NED = ENU_to_NED * omega_earth_ENU; + } + + static inline void Calc_g_rho_omega_earth_ENU(const Vector& Pos_ENU, const Vector& Vel_ENU, const Vector& LatLonHeight_IC, const Vector& Pos_ENU_Initial, + Vector& g_ENU, Vector& rho_ENU, Vector& omega_earth_ENU){ + double R0 = 6.378388e6; + double e = 1/297; + double Re( R0*( 1-e*(sin( LatLonHeight_IC(0) ))*(sin( LatLonHeight_IC(0) )) ) ); + + // Calculate current lat, lon + Vector delta_Pos_ENU(Pos_ENU - Pos_ENU_Initial); + double delta_lat(delta_Pos_ENU(1)/Re); + double delta_lon(delta_Pos_ENU(0)/(Re*cos(LatLonHeight_IC(0)))); + double lat_new(LatLonHeight_IC(0) + delta_lat); + double lon_new(LatLonHeight_IC(1) + delta_lon); + + // Rotation of lon about z axis + Rot3 C1(cos(lon_new), sin(lon_new), 0.0, + -sin(lon_new), cos(lon_new), 0.0, + 0.0, 0.0, 1.0); + + // Rotation of lat about y axis + Rot3 C2(cos(lat_new), 0.0, sin(lat_new), + 0.0, 1.0, 0.0, + -sin(lat_new), 0.0, cos(lat_new)); + + Rot3 UEN_to_ENU(0, 1, 0, + 0, 0, 1, + 1, 0, 0); + + Rot3 R_ECEF_to_ENU( UEN_to_ENU * C2 * C1 ); + + Vector omega_earth_ECEF(Vector_(3, 0.0, 0.0, 7.292115e-5)); + omega_earth_ENU = R_ECEF_to_ENU.matrix() * omega_earth_ECEF; + + // Calculating g + double height(LatLonHeight_IC(2)); + double EQUA_RADIUS = 6378137.0; // equatorial radius of the earth; WGS-84 + double ECCENTRICITY = 0.0818191908426; // eccentricity of the earth ellipsoid + double e2( pow(ECCENTRICITY,2) ); + double den( 1-e2*pow(sin(lat_new),2) ); + double Rm( (EQUA_RADIUS*(1-e2))/( pow(den,(3/2)) ) ); + double Rp( EQUA_RADIUS/( sqrt(den) ) ); + double Ro( sqrt(Rp*Rm) ); // mean earth radius of curvature + double g0( 9.780318*( 1 + 5.3024e-3 * pow(sin(lat_new),2) - 5.9e-6 * pow(sin(2*lat_new),2) ) ); + double g_calc( g0/( pow(1 + height/Ro, 2) ) ); + g_ENU = Vector_(3, 0.0, 0.0, -g_calc); + + + // Calculate rho + double Ve( Vel_ENU(0) ); + double Vn( Vel_ENU(1) ); + double rho_E = -Vn/(Rm + height); + double rho_N = Ve/(Rp + height); + double rho_U = Ve*tan(lat_new)/(Rp + height); + rho_ENU = Vector_(3, rho_E, rho_N, rho_U); + } + + static inline noiseModel::Gaussian::shared_ptr calc_descrete_noise_model(const noiseModel::Gaussian::shared_ptr& model, double delta_t){ + /* Q_d (approx)= Q * delta_t */ + /* In practice, square root of the information matrix is represented, so that: + * R_d (approx)= R / sqrt(delta_t) + * */ + return noiseModel::Gaussian::SqrtInformation(model->R()/sqrt(delta_t)); + } +private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("NonlinearFactor2", + boost::serialization::base_object(*this)); + } + + + +}; // \class EquivInertialNavFactor_GlobalVel_NoBias + +} /// namespace gtsam From fcfb27440aeb4dd28c0691b2f5d0a0571800d86c Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Mon, 13 May 2013 17:55:06 +0000 Subject: [PATCH 004/256] Parallel compilation flags in package scripts --- package_scripts/compile_static_boost.sh | 2 +- package_scripts/toolbox_package_unix.sh | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/package_scripts/compile_static_boost.sh b/package_scripts/compile_static_boost.sh index 466283044..ca3b99e09 100644 --- a/package_scripts/compile_static_boost.sh +++ b/package_scripts/compile_static_boost.sh @@ -5,4 +5,4 @@ # on libicu, which is unneeded and would require then linking the mex # module with it as well. We just stage instead of install, then the # toolbox_package_unix.sh script uses the staged boost. -./b2 link=static threading=multi cxxflags=-fPIC cflags=-fPIC --disable-icu -a stage \ No newline at end of file +./b2 link=static threading=multi cxxflags=-fPIC cflags=-fPIC --disable-icu -a -j4 stage diff --git a/package_scripts/toolbox_package_unix.sh b/package_scripts/toolbox_package_unix.sh index 1887248e7..0fcbd3151 100755 --- a/package_scripts/toolbox_package_unix.sh +++ b/package_scripts/toolbox_package_unix.sh @@ -54,7 +54,7 @@ if [ ! $? ]; then fi # Compile -make -j8 install +make -j4 install # Create package tar czf gtsam-toolbox-2.3.0-$platform.tgz -C stage/borg toolbox From 50866b9a0ea7d16e7d63c5d6a22eac69d872e338 Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Mon, 13 May 2013 18:04:36 +0000 Subject: [PATCH 005/256] Partial fix for compiling statically on Windows --- gtsam/CMakeLists.txt | 9 +++++++-- gtsam_unstable/CMakeLists.txt | 7 ++++++- 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index c3c954716..d5a2fee90 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -101,7 +101,9 @@ if (GTSAM_BUILD_STATIC_LIBRARY) VERSION ${gtsam_version} SOVERSION ${gtsam_soversion}) if(WIN32) # Add 'lib' prefix to static library to avoid filename collision with shared library - set_target_properties(gtsam-static PROPERTIES PREFIX "lib") + set_target_properties(gtsam-static PROPERTIES + PREFIX "lib" + COMPILE_DEFINITIONS GTSAM_IMPORT_STATIC) endif() install(TARGETS gtsam-static EXPORT GTSAM-exports ARCHIVE DESTINATION lib) list(APPEND GTSAM_EXPORTED_TARGETS gtsam-static) @@ -149,7 +151,10 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX) set(GTSAM_LIB_DIR ${MEX_LIB_ROOT}/gtsam) # FIXME: is this used? # Generate, build and install toolbox - set(mexFlags ${GTSAM_BUILD_MEX_BINARY_FLAGS} -I${MEX_INCLUDE_ROOT} -I${Boost_INCLUDE_DIR} -I${CMAKE_BINARY_DIR}) + set(mexFlags ${GTSAM_BUILD_MEX_BINARY_FLAGS} -I${MEX_INCLUDE_ROOT} -I${Boost_INCLUDE_DIR} -I${CMAKE_BINARY_DIR}) + if("${gtsam-default}" STREQUAL "gtsam-static") + list(APPEND mexFlags -DGTSAM_IMPORT_STATIC) + endif() # Macro to handle details of setting up targets # FIXME: issue with dependency between wrap_gtsam and wrap_gtsam_build, only shows up on CMake 2.8.3 diff --git a/gtsam_unstable/CMakeLists.txt b/gtsam_unstable/CMakeLists.txt index d240ac4b8..74fae5bb9 100644 --- a/gtsam_unstable/CMakeLists.txt +++ b/gtsam_unstable/CMakeLists.txt @@ -58,7 +58,9 @@ if (GTSAM_BUILD_STATIC_LIBRARY) VERSION ${gtsam_unstable_version} SOVERSION ${gtsam_unstable_soversion}) if(WIN32) # Add 'lib' prefix to static library to avoid filename collision with shared library - set_target_properties(gtsam_unstable-static PROPERTIES PREFIX "lib") + set_target_properties(gtsam_unstable-static PROPERTIES + PREFIX "lib" + COMPILE_DEFINITIONS GTSAM_UNSTABLE_IMPORT_STATIC) endif() target_link_libraries(gtsam_unstable-static gtsam-static ${GTSAM_UNSTABLE_BOOST_LIBRARIES}) install(TARGETS gtsam_unstable-static EXPORT GTSAM-exports ARCHIVE DESTINATION lib) @@ -100,6 +102,9 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX) # Generate, build and install toolbox set(mexFlags -I${MEX_INCLUDE_ROOT} -I${Boost_INCLUDE_DIR} -I${CMAKE_BINARY_DIR}) + if("${gtsam-default}" STREQUAL "gtsam-static") + list(APPEND mexFlags -DGTSAM_IMPORT_STATIC) + endif() # Macro to handle details of setting up targets wrap_library(gtsam_unstable "${mexFlags}" "./" gtsam) From d4ec018d0f373f2ee3c4836ed6a50fa596c134cd Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Mon, 13 May 2013 20:48:09 +0000 Subject: [PATCH 006/256] Added constructors to Point2Vector --- gtsam_unstable/gtsam_unstable.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index 80774e862..fc2fc1fff 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -146,6 +146,10 @@ virtual class BearingS2 : gtsam::Value { // std::vector class Point2Vector { + // Constructors + Point2Vector(); + Point2Vector(const gtsam::Point2Vector& v); + //Capacity size_t size() const; size_t max_size() const; From 8f4c1278b945851a557361d5fbc39093dedb627a Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Thu, 16 May 2013 15:24:37 +0000 Subject: [PATCH 007/256] Updated BetweenFactor section of 'math' document --- doc/math.lyx | 205 ++++++++++++++++++++++++++++++++++++++++++++------- doc/math.pdf | Bin 127548 -> 173687 bytes 2 files changed, 178 insertions(+), 27 deletions(-) diff --git a/doc/math.lyx b/doc/math.lyx index 05eb355ad..8d56963cb 100644 --- a/doc/math.lyx +++ b/doc/math.lyx @@ -885,7 +885,39 @@ H_{a}=G_{f(a)}F_{a} \end_inset +where +\begin_inset Formula $G_{f(a)}$ +\end_inset + is the +\begin_inset Formula $m\times p$ +\end_inset + + Jacobian matrix of +\begin_inset Formula $g$ +\end_inset + + evaluated at +\begin_inset Formula $f(a)$ +\end_inset + +, and +\begin_inset Formula $F_{a}$ +\end_inset + + is the +\begin_inset Formula $p\times n$ +\end_inset + + Jacobian matrix of +\begin_inset Formula $f$ +\end_inset + + evaluated at +\begin_inset Formula $a$ +\end_inset + +. \end_layout \begin_layout Proof @@ -1521,7 +1553,7 @@ name "th:Action" \end_inset The Jacobian matrix of the group action -\begin_inset Formula $f(T,P)=Tp$ +\begin_inset Formula $f(T,p)=Tp$ \end_inset at @@ -2811,6 +2843,12 @@ B^{T} & I_{3}\end{array}\right] \end_layout \begin_layout Subsection +\begin_inset CommandInset label +LatexCommand label +name "sub:Pushforward-of-Between" + +\end_inset + Pushforward of Between \end_layout @@ -3378,27 +3416,14 @@ BetweenFactor \end_layout \begin_layout Standard -BetweenFactor is often used to summarize -\end_layout -\begin_layout Standard -Theorem -\begin_inset CommandInset ref -LatexCommand ref -reference "D-exp" - -\end_inset - - about the derivative of the exponential map -\begin_inset Formula $f:\xi\mapsto\exp\xihat$ -\end_inset - - being identity only at -\begin_inset Formula $\xi=0$ -\end_inset - - has implications for GTSAM. - Given two elements +\series bold +\emph on +BetweenFactor +\series default +\emph default + is a factor in GTSAM that is used ubiquitously to process measurements + indicating the relative pose between two unknown poses \begin_inset Formula $T_{1}$ \end_inset @@ -3406,15 +3431,104 @@ reference "D-exp" \begin_inset Formula $T_{2}$ \end_inset -, BetweenFactor evaluates +. + Let us assume the measured relative pose is +\begin_inset Formula $Z$ +\end_inset + +, then the code that calculates the error in +\series bold +\emph on +BetweenFactor +\series default +\emph default + first calculates the predicted relative pose +\begin_inset Formula $T_{12}$ +\end_inset + +, and then evaluates the error between the measured and predicted relative + pose: +\end_layout + +\begin_layout LyX-Code +T12 = between(T1, T2); +\end_layout + +\begin_layout LyX-Code +return localCoordinates(Z, T12); +\end_layout + +\begin_layout Standard +where we recall that the function +\series bold +\emph on +between +\series default +\emph default + is given in group theoretic notation as \begin_inset Formula \[ -g(T_{1},T_{2};Z)=f^{-1}\left(\mathop{between}(Z,\mathop{between}(T_{1},T_{2})\right)=f^{-1}\left(Z^{-1}\left(T_{1}^{-1}T_{2}\right)\right) +\varphi(g,h)=g^{-1}h \] \end_inset -but because it is assumed that +The function +\series bold +\emph on +localCoordinates +\series default +\emph default + itself also calls +\series bold +\emph on +between +\series default +\emph default +, and converts to canonical coordinates: +\end_layout + +\begin_layout LyX-Code +localCoordinates(Z,T12) = Logmap(between(Z, T12)); +\end_layout + +\begin_layout Standard +Hence, given two elements +\begin_inset Formula $T_{1}$ +\end_inset + + and +\begin_inset Formula $T_{2}$ +\end_inset + +, +\series bold +\emph on +BetweenFactor +\series default +\emph default + evaluates +\begin_inset Formula $g:G\times G\rightarrow\Reals n$ +\end_inset + +, +\begin_inset Formula +\[ +g(T_{1},T_{2};Z)=f^{-1}\left(\varphi(Z,\varphi(T_{1},T_{2})\right)=f^{-1}\left(Z^{-1}\left(T_{1}^{-1}T_{2}\right)\right) +\] + +\end_inset + +where +\begin_inset Formula $f^{-1}$ +\end_inset + + is the inverse of the map +\begin_inset Formula $f:\xi\mapsto\exp\xihat$ +\end_inset + +. + If we assume that the measurement has only small error, then \begin_inset Formula $Z\approx T_{1}^{-1}T_{2}$ \end_inset @@ -3422,12 +3536,49 @@ but because it is assumed that \begin_inset Formula $Z^{-1}T_{1}^{-1}T_{2}\approx e$ \end_inset - and the derivative should be good there. - Note that the derivative of +, and we can invoke Theorem +\begin_inset CommandInset ref +LatexCommand ref +reference "D-exp" + +\end_inset + +, which says that the derivative of the exponential map +\begin_inset Formula $f:\xi\mapsto\exp\xihat$ +\end_inset + + is identity at +\begin_inset Formula $\xi=0$ +\end_inset + +, as well as its inverse. +\end_layout + +\begin_layout Standard +Finally, because the derivative of +\series bold \emph on between +\series default \emph default - is identity in its second argument. + is identity in its second argument, the derivative of the +\series bold +\emph on +BetweenFactor +\series default +\emph default + error is identical to the derivative of pushforward of +\begin_inset Formula $\varphi(T_{1},T_{2})$ +\end_inset + +, derived in Section +\begin_inset CommandInset ref +LatexCommand ref +reference "sub:Pushforward-of-Between" + +\end_inset + +. \end_layout \begin_layout Section diff --git a/doc/math.pdf b/doc/math.pdf index eb429095ca9e3467baa95e577b53fde0516defea..9b1046f68c4dccaa64b02e2792dbae722fc233a2 100644 GIT binary patch literal 173687 zcma&sQ*$mryQu5fwr$(CZQHi(5!-e~Y}>YzH@2M-tZ&X*v-ZI}*z2Ub>-hm))mPu- zN@5c9%nYnBw1A3kblty1AGe+rxO}?&?XW;7cNVWWqB42I;!`B0gttVM;nNb6`b6hw>xi*&!^= zNSU_GSYiKN+z%p@vryMm*Kl`#^Yu~&D+<;5wwavb@1I(m4vzCPdbj-iclfb+*Vi>QUB*`c>IiM06rvc42m^ZP~Z>h$3Px_8CL9TiPP}MQ?sK-!S%;^ zi?fMmD`pAuPUkMI*I8Uz_uZ>V>=ak?zjcF&MILJp#HR+%f1tRvixN-PrELTfF0jp6 zl(2n!gkftXN$GNdjg}=ETiku!Bm1l8!7 zTu3f}5|1G(Ednn``nq3`eID9_8&$qCEPPHUnGHj2$Dm8TXYBkD7A)-i*e7f9`OFg1 zNe#y(rBW;d8^;?bBnPvsk^TV-6PnTv%+ZYTHwcM)SQPs!<_mi-l2oG2B{x>$HlzI4+Ei8Do z6?YvypWLel*YDx=7w7)sv(%-`|qAMqOM)3Vzp#IWy6)_4K#-ONw&rOm7 z3&_U;_Q2z>dvOw1yBSgq4>Fy*^b8iItQgjk2T~1bh0X|Q>v#Egh$wJiAM$&Bw2}(3 z3$U;|$NPrIy-n#M2v+zlYMIj9q^*Jbynv7+3~wT|rj?t%arL-21Lz&$p^u&nE0|+t zDx~Z^{+R9RiP4UbUHw8CYDCC>>Eik7c+u%Q%@1h!)sRJX(Bb*)i*pbqLUFQrmU1`o zy_`p{xKt=T_z#$PQ7h7AEyx)%-jVj~LGAKJ72nTSeUc)3ekB=o0kA~9%i4RYauo>X*=}`CY04%JBOGz63Z#Y}h+M0s&zU(qDuWk~;Z> z@TlC$!?xnX_~S|k-WiAL?nsC=Wfi3UaawxMXgoz9)`l7q0eLAz7bHbF3DU75MR9l) zFwh=ScHqPhbH5(2Fo-+Bb$|&NA1JkV!HaM(k~|u4MvSzXx-*738_J4*00~ZEi=u(z z!ouREA(_EduGW<)NRT~`e76^QZ^FXKB&F0q@_I_5b&+6I8!nh@CpwZZ{^`QE=o;?Z z1+TCo8hTAvMg7&%~LUz~b<2L~@Sh^LL5Z#t^*o*K*6Ox&|9O(%_LePLxo+j7* zHna<9KRd&un7N}oGB_(6VVQxa5FAxez`MmPcL*VPB}H}RV>wLMANqSXQpgi?YjlA?Uz$$1V&{XD2sfce!@->mFq3nox$`xsZE+elq|ul zPl_&lT6PJ!l0+q?w3+~Zgu8-T(2yYnL9j>8SDb=uWJ*TES^a`h!MPA+?V*Z!7l7QA z;Ji{?v-Dud4E!H<>u`{d)3o^lX(r7hw;A3$uLTH*WW{rUdPPvau~vCiU_U-m6jZh? zyyXeLnEFKngn{V}Rs^db)a0yp$}1nHeyT}K2cOGNzv-3D0afv)09-H!Ez{U_m%Y(Zi{9%VGzma1C^Gd93D&IGGA0Q zv>uk%xi=-#K&{=^V=bf|ufQsI03*q`Y%2_uc&itKOya6ux{?z=a>j zv#f1CwH1N|X^k)|&u$KdLwsICx54$TVD9R5F;!`Um&HtVJy%9xWZB!8&eg~1F>@|& zXs)SB4J+MtWQsz8r-qCee4tP0Kvvd>k>Yi!)G=VXYhs#wIwM-*4l7tfRu3zxyi|lC z0;h9j{X!nuRiYdQp~K{)Q=!Qt&ovI?NP+;;UsebVIA%n6Jv>Vv1RSP&t{L-c+)Ue( zmwghyz@2quCtm8{O&JC-P@F}PBkIu1R0 z3O>3F3_mJPC(NxPC?zls;gcS68Rl1okxRrF`Dl7i3Zuk1bN57k zEAmAm$#<8Y9{=T~yBg`ezT3IHCsj5x-UiotHUUk`!e|$MulW^ktsG}#taOoYy9Q!{ zs+6&sMJZE_7DcOiuEyHUX{(Ic&P)9fyicc>QPOl35aPi3gi1&MNyk3O(cmD zEX`sL+9r3cdyKq4)+f?mD>)(+8hy^?ix|~&vdS}iaJ}`lzd<&H4m*W-k%pq9u)jfI zF=1cxu0v`~rGLKMRQ(1@9QwqcG6w`SS9{1|N#e_Lkb3psP6XO?PsZIBE!vivc{ zHt>-hHBCrWR?>n0z#rifQx3D(2tm=w-@8SQKG^dpnyXTm;euVP%x-tCvHHXRWwT1) z1z!HcH>0nGrU3S_Hc_bd?}lc!O+;02dtglC`5)LKv4+iT_PL&-3l1;5O|;{FaLf&_ zl0g5D+>dTmfQ8FrlK;psWH9$)NLTe<5jUveLACb{`2_`E-)ZAvE7V%&0YTS}&I>+f zZz~NeQY}kkXpz_64w0n`dp}@+#SUQIaU=dOxywCw&*h`#Frfz<{Wa_5Te&u}sY~PM z&Bu39T;4U#X6`bbn~ztN-SgMFh{ool4My!sU<2}=kGJ);tE|_p;&Y|&kv;Honyf*D z%do@f7pog2JiSf+wHyx0MuUmu4+T|`MYvmq^mK?%RQ28!2gHGrm|!n&UwBlZOjxC5 z+31D9;Ff(vL|WnoQ1bM`0#x_C5yu_V_j6D#1gv|W8_ zc}Lq#MW4(mj!rMyWR??$)#rvPw#AOAf{{2qr0++BQ-n6%9{W3Kzx;O6*)Y!5Ii;AyODkNY$l= z-SA(%HN;!DzUTLZXOaEM6L8FT_mKg74y7=X1C-a0!(zkdvMrEB zDxNCqRXc~#ryFm=y}wW4ORwVWf}KfhXC-|1&!2`y6>9_ZuR-)Hs$?FgkA_>oyVL~~ z_G~_9QMZ`&8G%z0j+{YrKIJbQymWip2zV?GSs%gsh0nZoEW88Rc;<)y?7)71fjCnm z#MfV%NTI4gafHiz>u+CV))lP*nQ5VLS~Lmv8X4O{adG}9Rq&+jSspM{WiFG2RCRjc z`_$`Kfl%VPYW-xyrjsyl(DA3cwDFv~YSs^3Bo=!P|3ExFT$KzNjJ-~KZcwZ~D<+se zi4oNQeYVyME)%O0iMWuwkm^L{nQ9SCe1u>dGrY^Xzr;>^CSO}qxyz*O3-s_${7+ao zw}e9BsU`bcbUd4?+AANK-6dCp6=z8yWg%M;I;}b45fpxM;|(@|BwgbRj`O{Mkprlo zIB?eDVT}la<&N6DaL4{WwUKP2V)hYCv)@STCP)baL~GyjyygBlJWmmZr7&BWPiwvR z#Dx7tsc?Ca+wMJWEpZIhto*1^^Ml|Ci$cYn>*dJ1G|*U2Y@Qd}YWba1OYYnyWSR2a zh0ot*G?@H+DBl^J{uhmg93vUeZwy9u&i*^cWZ*LUr@uc39iV=!d-pgP6cNpW$^*=( z#V?@1Ubg=UMIG5lLm353%N2U)KpGFga0(09WO5A1Vn7B<0p82wynioOdus@A*q(Fd zt_;TSQiNdW_ex+9;<%^P&1Jh=`=;PSBz9_Yp!D&EYpYA zGBtlW2B8ZCq&PpHG?^8xw`Z^a;yqNWirP_}-yt5jt))tIr!da2 z9`0^fb;N34Si$RO7~Ly&fjaoO(}YM$O);F$?eu{=@zHU{q9v^fPxb z`@iq`|D68I0RHRc|6e;B6Dt?Y|DCaL{x2Y4;rf3P0)5#Oy!IrI^A_ev{u=^6+x>FS zUGg5ny?gO;JJrVc#N+7u!Pnq=;@Z_jG;y8Oz;BB~h4I<7!R%?J9S_xqNKa8 zpbrO1icZw`{>QtLoIi^FuiX{V%EL~n7I0ajUt=(VS zd-6*X^^CuL?I}@v88mgnY%YgR%!d#=_dqU>Iy6S>^7AYcac@=Uk}C?G~;Ub1C6nk z1PX;E-P|A+;67Y{F7WGK71X}U{fE`i3F())cy?ZXShVtba4f7f5j^OiT>rQ{$kO1W zK^p|3&9CHBqT*BupJ&*_$Tx z+UOjxe^!A5_MY?lEPtiZrr{-+0HpWsB^7g)YZu-6bu#?=JT4ML1`&H;!9o1Bw&-l3 zr%x5(MubW%I0=Heof3dR$={59fP>_CP_mDYc2CeCf0_;HPbm8DeKPnGCN1d~K2t>o zJ!U`#AhTd4<7EfiMaE@s#sN|&Y_>Byua=s^!dtOZ8e^@LW~_;=X^!+ zYUhH0VaK}c(hWb4fsULan5$!wbMoDt(_RAOov~2_rd>GZw~w8=B|>-=gF3STwd6bu zh(5cUZz6_jtm~>0DcG?EWK7C~S{j{+{*1SlB(`WxJxszC+~vV&&5g0f#Z!&kq7nQ> zUhuw+ot#c*WRq(X4eaBGhV|$awrY`UwPMu5`~7eAAN34DfGT8PaIPkR&0j{~f&Ldd z9R1R)_6{0TZVG2o_c zfl!q7>R2C5A$kMzlV`ZoX3%WnVU^OKy3kLXhj6|6JgYH59CCW4F zL8F!i6!AJ5V%^l`9dNNJRBG@zSep;`O{9&ONS(CTJ~u*$ZHq#pgSh3ED6girOcyJ7 zO?ur5oqUmSN!4qCm+1k|c6t<0Hql;i&2A%X9uY5t=UFTgJw$t=wlL$`2-0XG;({-?V&IWn_Xhpy^birYuBbS$omK)-f zN?o_S@ian8Q0Br)+c(6c6@<&1spPe`)fb8w!Gmbu4t;i`~*dzlteRgA)}1M7EQh=u?J3~ zHhR?qb-I%OdS_vwZCWU^Q#v)D=%A5oX&dbY#kR~Z%0+S<6Jd}R;Ew#KRq5q<*Yl-&yn9R?&1p_U@{_uf82t$rXZQ2T z6=f-ziB89OVYqm0z6n#B!v8*obMb_xyb`*zPnw0FJe?V-Y}?^!Zsei}D=^gebAQ-H zs1VFz6X=2CHE#izbg)!+TfqGzQLx+p{`^DeQE%Am?ecI@;PH64ynpoT|9avGDERm0 zA=v%?^>bVE60(#D8YUGRDr~Q;(i_he35%*fp+)IZ1h($wilApAgfYmtR|W)b5XX{b zeC-E4rU`lcd+q@VwIm-Ws{8!%w+yjhhI^EOGGSiAcG<_puOGe#$GJ};u&L^s`xrOQ zCRhkof&?@&$#4LrPqKN$IFmTt_dOiym*IdyBPl%+^@y8$M;&o*RRz%j_clBS2HPRb|@-Pd=F&m2T6R;{4~UEy752 zI*7zi#jls(VCKqm`$NH8Gh{%#(Jtv$E+0U$3r#Ow$^!+;EL=gV^kH=#PHjnq>s3}G zUj%$jT$%BPBqeQG0T1bbE&9^Bs@o~twz_^d2X7PV@~Ul&N5q41r8`D74mU_Qg+ng; zYZma!^_1uGxbceM>II=81+vblBCzl&WHP3Mn~=12PWT$#lS^vO&3mIl{#st8wpDEY zZ7_?BqD;kKf6td8`=d=xNvo5g9EoR2Z z4q_V7T0G9aez$(YLJG7Z^Yz|y25D?9;#;SKSoV2Rz9LZ&R?Pq|*V3Ye8ZQfd>Rc|J zG{c~MBT`elutOne>d-SGUvO|PYzAA0lga0{Gk5>&R;|4p(3jxq8#iX<8Y0u3)3Pv* zx*5C=#&8Ky70K?5kHO0Z5yq#(#L66G``M&n@_T^6Yfe^` z(AZT6FJvQWJK9cHL(qyYxoCn5{_-TF1xPbxX|#KHY@`S4CL=M1-quUkVTa>W`pdvg zN1c|V0E;GT4HGiDW{s;*TA@CvJ-g7_sJM7k`x3c$BnnC!LEc!*jOm^}0v@^%&PKN7 zGm}_xiDBuI8BoXUKQ8~C_#oU4O`0RQfO4ldt0Q8FClcl=O*pGJOIX7!Qg&2~Lor91-aMu|PpMthg74xU%M;dMYI?lmVVW5*$dbA~X zc%9ywe{SiOeH0LBZkaP(Wov%MP$2-mlvzNqKx7StN_xKrZr21zj|$B&N|AV*QAG;E z1EhAjC2q!K|D{?7@2L!J=ErdpJk2gMLp@Cm-maJaEHjdmD(D03EbAo7?dpR@f;f$7 z7Zwf9?UP$ol0d!ZGL6%*-Lg%xm_neVQIaG`zVBx(9r5S1yTvY%4`XHKQB~=WJUgWt zXEcJJM9aOaS_>XEpn2syC&qgqgNw1oM43iopN>hQXiFm*mGlsr66Lrb#52|N99J13 zpqCL>u@TP{vxx+K(WmiLjx0($ssUHyrobO;Qe#(rnFakml`1Ms79tO;pj~+I1SOSx zax{ZPO;N5z+n!$Q)B>jy!av&wK3nCqp~+G75K0gy4SxTKiwwFdd}*b)xLQ6YfOIhroi?ySigp`nAH`n-&p*IFO13b%`rWKU$w3H=di!dC%xs~(hC+6 zaIuomBx4tkM4)^p}^bV*0@l)Y?^ zZY`?MZZCKptTda#g+?>Z7g70b!C{-8nq2#2#21m*G+1f7rPyMH1fN7}aVJ7mfj zteVeiK!|;++(;@hA7-zCWUq+EP#&r0nIhAor4!Ct{y@g)y>R!>d)w2oh%;X<&5AMPB>>W1ygSh!tE zGGEhjVY!d?Pogfeio18GJ7e3BwM4#tw2gr~Ymb#7(PTM=M>h;8Jma~EiPt3vX-^*H z+dGAvv{tBIZBcyt_SD_LN*xV!;q@YgO6YB?#+)z_;QpF(lCSzg`|;r0Kwm*j{UxxL zIfM@JkyjV0p|?#?e_>X#zL8s&D&MRsFE&OSSE;CyNP4f+(;ZPPSt&?3d!x6&Ara#f z{<}xKU;0_}Rw5r`i^-VjLx245ASWW4=m=9T3{o49m%DE-%_+=x4RIuIh`*1wuq}p` zcS>MK$bCoD0~2H~3jMM6AD==MX3tqScN+vb`FN{THx3925n-?X^B;Z!c8_54xwGpP zXyFeO3hXO=!V8k7(R?(&hx6+0c5{O^gZZ|h9hHj2s_~@1G$RwiWc(D&*g7Hw#$pVa zWqc3WQwI3nIC_&Pu>IzX=*9yAucb%moVU zP{fXP<#4N0$($~kql)ec%+b>Q#BV|>+zpwQl>!;2o@D(#i7zK9(4m~$a(bKW9ppCJ z)HSZF8+Vi1Q9sT-C1(`nP9dpIbn;7RxVBr6y0^)nVGwN14Z;rKS+ZUCU6M-e!Rt`i z+p)4E4!~o^DFUClqy?^=vq8A1D4C5tm7eloW~cM{ZG1{ZOvvsmD)FT@@7nJ8Sit>1 z=Q|-U4qGJtB5Gnil0*ZWVZnp?=!j+j`=ciG^Q;xR z*2CTBMJ-ONk+)l!VSo`_U1T3Sd}x#3Js@sU&&=?$lFpgBx1%0NhYuNKqWyS7O)_S5vz14^-|*38h6$>k(sRX00iw};*gNJZ$V|QEQzAGftdha zT1tRnTd5(mHrzi`h~u-DJx5T9AXN9*W}&Y}UIRKh`Xu|EDcw3jsuvj5`a0<>q(AK< zxIM!Vcck1kCc&B6osY)ueGlhzV~Y^e=$3KI^>jw@=NznC@2nJ}W=W}9cip09%E_SG zPq*Vq;>ib_S}Jg?<|<9?Lj5kQk_%c-*pax84{H$e7|p~KkMIqs}!H6ekmuD4Yk{$c6)BT_*{Hwb}hw} zSK?>qZbZGgRk^y3pz7!mcxaU|?HNUEb|8Tb?-Clma}f4*t9gAgZ*#QQL{hr}kLV7h z;cF<~4kz^naQ?GT>Lv0OEIo|mfTGO$0rgyAF9)i!7u0*2y9llyt}uOSKCqI{R5-?w z>Ejz-mtgyZL9L(_ad6|7t9K4t-6fXvYlbK}!qbLY@bu7mq6VR^U$+ESs?JRGT;Op7 ztR6v7WULrsII5=8nm@mgqFF)|{|j9ITT=f^T-jN@XfW`Q69OnWbN@c$mYFg-qA%w(!n%4O8` z`RiNdxrS8h($!RG2n_|u0=MCN&mq1jfBo;DufG}f-rl>Li+ufFZ?d8UJwE0`D|RE# z76v>;o(Hiu^8|Th@x{-~&LH;l1o{7M-=6#wehNnxdKlgz7Qf9!HT<(-^aW=ezTNyG zYQ4^bk1OBuv4Vm3bL`pYm+EcV=U42fwe?hdgWQF*{=4O`?c=XH<|8p40z6~%pK43f zctO$^*f3-2)*vmSRPlo#b3#i@TsD zi5DK#dALC~&-H78;Bf=p3-Js5XvfmU)R|`c_)rCZiTKC($FWg1l&p!9mN#!vf28hp zc6fUIe}iwKFb$WWbbFt|ZfA(b7lHc+KsZ#^^+MkJw)@(azT}GA0p`X_f6v^xgd{DB zOVsrSq?u=jq6{8Ce*FzoL_PZu*Ju*>-5vECib7|Ri6_K{i~}1w7>C*fAaHF$Tz7+C zvQqSy6mUGDI$Wh{4J|RG<;@G_;pu|ezUf`&j7HLp_Zy5qT561w7*uS$s67d<-5JB4 zXBDNeP|~5raG#0PFTbr0^{yWuJ~q!R_dPhCIUK;`HauCtk}|2WzF>8}hW}aK?f67lWeX$Nlz#HsrXuvl zKKk(__$kc?$JvfsuP9^k*tU}-dP1R}|X_ztN z@zZEwNnM;)16(Q4s&?f)4u77X?dlUNzHj%JD=562J3Wn-!Za4Y%u6`FaneeF>NrAT zA%|-5qZ(SY=aBW;xW%g>1>W zrm_jf&9VPDJ~#&r)-{WqO?Gdhm=?sz&K#YQFBwQj*)>SV99ATs`|!ss7IvZm6Z_o> zdl1YQAsFLV;a85&SIn&m-c+S4wl8a%d#@Pv5*wbpc2SrI8<|n{)Fr$7a4GuUy zggOrfsmN`i1P~^<4TrQ8#J}Oea3Jh6?Gm*ODQ=M%l-7LWM1w4iJ^C3*Tijw3iQxK% zlTd{j)?Q?bS*+#H!mw~=VEWRGwt5rOZU-S?C|>3tU(r)c^riqiY?;pE`W5KWICA#s zr5tHO;yl67B)rd5H`JNu;q{#9wW91HFawtFK0%aQmcU$a0UDT)^N8bRGDRD5`_A&pvldHkR4k1n<`)Z{tNqJPE2HXS44a|Pq#qV zF zx26>ZYtL1FCSXs1TPhpO*hJmgp^zaSDcc3cvxk^@lpB1j47=ObQlV@_MP%JyH!TM3B<6}Zx zFvLfQac83VijU3aw2z?IGZsra=cPM?ksGo0 zV`=72Gtt#1)zNQ^P1r-#JWPncb~-BYFXYiW=4tP}e9VQQKbVw7)!6@P_Z9t>zx=%n`49 ztq|#pk;!shQv-gNs{^j@N(ZCNdJ>pEXtBiD;rNZ)iyJg1oUyfIQhw=q@NFuyI8(OEU_`SNt6CwL^6#n?9x}k!< zS%=tYX-=!j#Yu;5bZDVdl%Yj|q+CNTn*U%J|zdF<*iJBGeG{ z8m_2qsa4s0)-&oAW=ny@*iKw96hmBG2MW`@x-{norA=%50Zu6cFZlM$FmIA8o1va2 z-vMm0zBXml)vBnwB#P=`Ib<@IGy7g7fD!39@yN`?b2d0Ir>yvk#aZ-ON zquW_4f)ivj#jbu{#0>$uy})jor($G(+lSDYQC^bIk8p=(J~&gv?YPE!E zRbXpA5|z!lB!bB;CpxWdL9c$}8OE#DT8of$3Y*T>y3k}-kZzg#pHk!+Ah;FMC9153?Nm3fKkNCR7dzAZ?-h>Q2evPyJqO)_h}RChpPAKQkj&Rqx$V)!1kcQXa++{ zop^(UVX&AQXK_6t$F{ww0SF+?#e;u=e@z)Px`zbZaxD(&o*s&ns!WZehar}4rcm^b zR{G1BbxPu5Nab?%JCy`l+f=i{q#Ir~bBn-mXvM8N!`R;{%c_8N7SdRi`#r)e>00Zk zK$B35W|$Gf-yj5WL&)I14269z?KNrQk_oggWl_6 zDkH^m*alO|nu|gaf@hUf98OfQ@!jy%B+C6}{HrGUjc9LkaoAyW__GPm!#7?a4?%?W zj)C05XyLI;yIAH5<0%Zxr4D0WaME`RgRdV2Cwx4UDNnJWMlRfWb29moc6P5`ZZH4z zqt#M74tl2&0^7DzR)4j>!!iMZw~Ds_#-YD1?_Hx3k6UtD!U#B$WLFFO^s9tyZFbp> z+D_q5t8`co*n(kd!6evZCApoU$cJ_%bDT8H?0%}&w=72uv*UfHN|4ySHyefK@>*GE zxJcvR(SL#!PhW$;yl0#ZY%J10@;@*QO=XmMDWMn%6om)ok1&Q zt8_11nw_{l3ZZJYC7DoV&g5POprSqi;~|17i?6u0oXDTVKw)r`<3leppG$RJqCPvD&p)u9+C~GPj(4gKsR-5MH2r zI>ta<;4olD%l2fgCxcpt!W$o7xl>l59ms0L4-zZQNn`&|=4i~Ftx5veCZ)a{7@4Mz zPEH^32L3hD`RYzus;A6vPqqDfAN|ZqSx(p*RSkrdyqRGlpsbAFda#N6tlZThhO460 zL1~$hrhgp_wK^VVr0DA?#APdrq9eXpHY?GiO8uiadI(iH-Wck2 z*Fe~OV6>F`$r2w4Ta%RY53)($Zm2y?i*#v48`Th-Q$&ftdPAEn2~%lvj7B=Lj&Cgq zQ}-r>edf2${-ffzv<0)Hy8#QD6Pz0dozJzl&N|wJmtT3+&qXc+ei%X8fn}PhfW3w? z5DI+6eIiu#qL2%NwQf;8c6|R8{L*Q#5$~)b0IQP`0~_nc)dD(OLA>O;dlAQE$Mi>U zii3S^3wN|a0F`J!iKQ+igu8D&Cr z)ZdmYrST%!r-0crb#ytCw<>{<+m+MPjhKT+!N*wA)j}D}d?TES$6y&KaMnq5yk-lt zm`cn_UqDnxKXOIs?LjL)dYpUN=0|jZoja00gk(SxvD_!I5z57YN2E^2W)#D;MUvC` z@vAQA^Y!nct3gxLX^gGsPGsI_5{|&Mum~nzJ5S-?L6&-;l}S{xq8!K_Uvb5A=Hl2d}a@k=0Lnwc-LT76W6Fst}H-Xc_uJXE`?gdL^D(!}`LdtkpOlj@213 zo-bzpnv!_>n}n;4*6MU{{OKu02ZQmx)4q*HR0z-7V|l`X1C?BlakcNRhgVst2ERg> z9)eVHJsokjAGuVA?zTD@fm)1F_NjL}F79J-$91S{Ek)kM7Xz4lpDIioKXno{M2kUQ zxPC3IRAZZDx=Zd$Tk2Fv*ll-0mf4Od+rf#lLi-4U*f!t# zdYR0Y4k#mtU)(8D9f43pS|?b2r2HgiYfRRgyi?ZZ9HA*j+r1h_F2mWVl{p!0*5cuj z$U~>C^y#-rMpkaykZey{a{8D?mp=!P`Wf7em}fi_z(A=EtG&JGE&NuWA=`YDn^Xy; zI<6(HdUOA603>E?&U198jj3!zINmhw)}a^RXWrdS3&>zqfh*J&Ryw8}sGn6e1$SrZ zC2Y~*pcDs~f*(id6Onb>P&7wSR$3vL1z(%U{!PO>dno|dL{zY%>@2jW+bvW4Rg+;s zumot|E_Sb@0_w>n>&7a1u(LqpFRrvysT4iN7PAKYPlk3z> zQDS76DR$`n`2$FQ%ReY)@W!+VDExE-{B2REbTl1Rni@NN#eMvBz1aEVIz(h$c%d&` zdb9t|Vk0^*$?>$Z%I#^sB5p3n_(Ii?Eja2&&v_cZgv_US5>IbJcQa`u?R_vfIpL@k zlO*QqtxvEXX)z%^@kw*MCp>Y|5JuwFxZ{$>f13A1UZ)yP-jn}xvr~BDWaY=O6A;&M z`qUUi_(S}FtvkAF!5^P}2HpVkYIP95m~<~s>p#6SdL**iI2UfUU;`Dk=jYST(g#e5 zzaRAgwv*>5=FjN?qif?sU1PH?-fn^^Z;n|LLJ<7x3+dz~t?)WFRl$jQyQBZ{d}B@; zg*$k8F?QL<4E6F5)+}XJML>Azj+zl%Q(HrD^~CpPB)Rs6BB{J;3quD*0L-ng^I{jt|U zsQ5#%@H*Z=YI@<{M=_)oj$;r-#|KiaGSzT?3B9v;6(EP|ll z)Bu&G?BSy`%_k}E`%8d07hiz;%UMaEz$g}l<;}y}x=qYrrk7u!e{#z5;K$MQRZ3<^ zECa#*K|6=lP5i!IxAfNe%fq-WZ!}gO?;c=&a9B)GuV96&EDD9-@9_4WS+V7PWkh70 zU_eAk?808!n=!Mk_%dS~T@ zSqIAz1@Qb22BFhpCXjB5@uRX952p5Q&TX&D5(U>=#(4jj0vwB}_5rjOX#k9nrB-nknUchuEF2^>t8R`)<%(IJl6iQ+ks8b#W0IcYkQfnG-2f!n z+=IA)A+|Gcis!vkSu!kZ+G&F0mLy+ZAtfz4QxwSKNY)gWz>_3UjIAKy1z*(6Cjuc; zgS+ThhV(&Z{wm}0{QK(mh*blh_ZPT;M7Zu)w2`XDh!{IMK=Aq*@dx0yI1bakw}RhyubOow?e3;>s4(<*3I5i(2l~ z=`#NZrc4UNP^FxR@*{f*`hDSiLb)n`0w;QU&#-OZG61UF6!h!-1x)7rDn4SGb3PIy zxs8_4&?A@CP7+44-#>m|qA=_Fw^YY6Jw>Gfh#FE}Xs%hxB&{yvL%%RDKi*IB;|W)7 z0;K$>k>v-T^x&9z${7R20W+N~FV+CVFi=0mYb_q3?!v#Wr&I=l*$q&+nm--!3?I1O2 zWxheuOU{X=fr#;FvC?C>&)PR|7wYw-QALh}2RVx&3b_C0k;j#@5W(fx>@@!j*;yT9 z#*81Ecxg#VG6*9IpS7~ON?8~QnGrR|CLs8x&nBVIZYK{2-O1?u`YlJjGii&i)J%!V zjGz=hSK28;AZTCbU85Sl*A&!b7d|M3ppvGETCWTr)G4*3XSVULo0US%z_$led*}lg z8@8M`1{Y8~9Mb-SvcAYB&jbe~FcHK z1^KY`sVi=32lxi*P8XEwLyQjHJu)>?4lpS!=4jH(7p(wzmMU^-hu7_eWXe$6&R0PHUO-q3H5oi34S^5RDkMm9ge4WEu?d5tt8r>q!w)-ZOJPgIykCX{uSE7o@4Exk3S zTycFggs?$bX{Ehy1hiM2ll}Kg+!Sd~Tx9tQ2;MfWuslcq88fzx>2v-3NyfNH$~mJZ-(=DLZy|DWvONEp1v$$b+k7=W zV}4J$)pS0vdodMqXO0CRUoFXYXg$*z4QPm>H?ws>m=!9B^NPEV^iWtsFU;>aolao# zpC+q{ggedGxn3D$G~!f@M!>DfIoTj=%c5fWusq8r{0^9x8B00ttI?QUf&_;sw;}+tKcrCu~B%OO2hm)&Vj=J=-A{gd9j_zIl-dx_$(6(JB#hNUIeGK?P@6 zI2zqEGIVR1w#_#_m1^wOcD#wBgI$DE(`lt-m!=xgtC}&8XDivwWb+zm>OA#4N|-73 zX_gyy2^@h>%My->pFLR~aPVC_|W)j2O0;c|?9WQhV#07aN1xpu@T3THBCR270 zX0Z2(zjQfR82->nH<)Y$MhKiPV#Y|&AKvy(dB>a=$TO&OmiwSC7L#n5y3Z{#fe2&{ z#Fk%C*Yb}6(M=h`fL|ZAHS%)?Bk(=?JhOA1<}H@ z@4iH80ox%4dB|+Mn;q#c?Ek~qJGEB=ZHu|_>{cJLX4v37kSKD6f z&~oUyk8Nytse4G-LJ($;M=87n8+rwNj2lY(iGtA#5TF>^cC3&F1Wvyp7JyI;qjRZgYO%5c*9dKFX@0Sx>v^OL~sjf;7*H=9_`*{3`hEF3f4y8TXm%) zQs&Q`v00p0$&(EKLXu{m&N$Uo3Jw4I22-}*Yq%}}fN||4n2?T}^#plT?!-p4o;c;o zP_xId9)i!8xA&$rPry=5=BOG`6(CE^H!s4e28x-`IeUU~2#J&L*;&(X4rHLlxu~_; zn_*=f`;}oUL2G^;mLWkVNxLE9?(lruKW+E8K|dPo%z|N$VYp?0{tiZMJ88>~$USg{2`>)p{J?))0!1LI9ItbV) zf^8S{!O=3IHQK~ZgW^e&Ov8SkX#)xSF=fTMOY|~)NV|VR`m38gag{vq{;iE8op=>vGLh?e)Rm(+sjZoE;h;5o-;x>P3 z4l;hX4IRe-aRm}ku%z~yBGYKA1{xM7lF(7Vv$|7ft#DmlN%5jkbqz^v(O6<$EAVdH z-JAvuZd)q|PgmZeYBzQtrhI&^jxkoDcT=J z2X4Bi(PDVrp#6wkXShz;#zdM6tC?`B&Pc%qH6V~m)eKs+#F}W~ute}j(+bUdRT?ov zRM;kU0g)8Khg5=QM===kVj2XDTQdp-9tY9+#CZIEhwImCs}Pa`){bk?V(^*3<#y!U zJ9e8N5yv<+uE27+w>%d+JE$mIiM@g^reT6E(2SiQHu<+N%mJ!2)84P-7Qyb=5UCDS z%oHmGGsZZ<{h$`tg3<|ix++kw{C(5T_U|LlAiiswEAyLX&NWSFC%{nZ&KDK0sx>_d zc#RWgEabtb!kCi)S%?2#FE6~IAtldFI1!)AnpYd`xl5QpH(^ zbwU$9ggRe8GQ9#Lekx=rYg!^2)dVY|_Jef23^uvP=u~!)n?9Nnm7(G|n z3pK7Sehosci{tH%r=tN`95^->anXD4SWpj8Xk8M{|4pz9H&7lF_T2FPzmvRMsY=|$E%#@RfhGJ`WD`HcmrgXj;<)WIQaza zxJk7z_OHGYBhM4_qR#LL;@$m0efy=v{aDl7+f&0nGAVP50J$W;#BUzA=p@_ZC9fTE zd`Zr&GHb4-@(bW89z10?&GN(N#IiYHELfT-omr&7jak8XU@Vq%a17c|G%dZH>)$>a zdtnv!%im~#{5sK^r0y*f;*PgnvR!qNn*m4IWiH+|io|(5mm$FUK^^Rcc2~zns%?+g zImc(LF3}vVsd|12?ytY;*`0DmA*s-prk#Q58S2KPFMk&W3l00HLDodnIB`pB1kimG zJwXD>3(lj7J%n!{$Vc8}f(DLOCvnwJHNa){A6Wr0bALk5=lMpNWD)tqBf- zY_wFdRlvH|j`|3m)!WKaVwp%Kk{bX*QDnOkYb`n7@_KD`&EwlKI&deb)j)f2=v;N4 zBloYG8zn#r8JgQgzDBVst{RlzR!f45?d)Edm(I*1bK00za1qCZobT;Nnm601fCOZM1Mt{%}O@9uN*vO>|NY$AW{VI84jf~ z8r4hW&AXa zFnyX4hH4<4efIO6v>lA4z7Zh?TqRC1wlx}sBlE<`ot#B~(ufz+qh&zkcwcxrEKJRK z)1F-o=W98#a{jU&5E%&vvE;p%m?eAESU@=ax*Y7SLS#|H`SaJf!)OH>cFl#{R6N0i zmm)61SgO-=JSM^R_pBjfdqLD)e6yorfzQ|bwa+YSjh)!~*?=N;qpeKHE(||4xmC}& z-4q*#>1#lb_#H}0*hA-m#0#&i0%S3pHM`+mK60;y5BOg+UPBfjq7|{74*VV+Z=zoZ&IGPA;JA? z^CF$v@to4y{zs0LvA@nHfBpr#m=x)cV0h)R^OU}L@Np4!_*_-W53iwGNeO(J*I%1g zS`7{}tnfH=uwt9bTP)fxkDq&jr79fS0a+T4WLxbt52BW5D^1da12UgV1|Ry_{jXoo z5)HzibD}zdZ;#JD zh3`ksySd_s2m?L8_p`eZ?owv+axKLrjt4q8+1aQxa4;drvqizHpj^$#1jCnQ!yh^O@b`GOS|Mk3RxS|%l_htAmy+6 zIGG?|MV=Q)-q@aq;VDQCB2Z18j?k=keDFo;SU@|Wjx9y<8Z3GjgM55^87ltePc6pG z4pYTF@2n(Q`4;;)a3FNnVwJPe^b@{o72><-%!=I`V-M6xw8+hk@=KWK%_jD_`d0&^ zmyaa!sQGS2?E|*B%F-0?r`hkOwjvBH-|0M#^bRfWx+ah~20d+(-vBcdszursTVDf@ ziEhL+aA$$e^+usS0?NJuRe1I4{#0-n?w2Rug-YwN_{XL`Bk=s#R0Kw^PjQn*iGb>Xh#-*J zf?u|)KlzPp^+Frqx6iA~k{5FoBcAy+87o0wG_Y2K55I~Ykm-Q&5DBjMChO2f>3$P# z;UUFdpm2}29`5Zzyj$|YB&#nSKsx0m3`LWd&0IG;e(&`Yj`qVW zUD|eac>R4N+Ra%@7Wn9VGKOvW$+<=w)bwi&EILmcRyn8iJ3QI9%m-7sZb z+a^hd|4Fk(m$o$TWy4l>xT}oqEpytJv`97ey@9f+*Xd!+Kn*X?kU4zmqs87WbZzRE z8cpkEH8Kz>*cr6tMr1D~BhW`nwf~iQyXESG0Ua-ma#yf{CMnMktoc&VS7K`z&xeq5 zl4>iZn-qtYd45n5xx%BQAcGRUyU;jwc!R#?;OG=otdcGlq|Q{QA=KY>xvA3Ir!4rh zfZMUJdCYR`&{L0$}MdF(p)>mbYbiz@)SFZ&s{>N;9oi-0?0(8 zwiK7pUlzA^g7x9wEJnjnsASEUCs|v%0kJSB_XZKV?``$w*yf{ddl^~z0m4`HI{F`U z{lC=wzjh}V7x(|8>;GAv|Ig$9Z+EhB|8MB}wVq4@SzFSowS(US!K-?&T8&!eQTDP( zpd`Tt&OkW59jH&DpXHoP>uKr22jQCqZ?G&yNYZrm^u@)35EGoIw3aLeHgfFS!N6Ia zyC0=H|F^^2>;5C)RnViW+`!2374>R?7asLoWm$K&1uHg8rHRjd#ec^5O<6!&O<-@%L zqj=rCFk3MCp6*GFT1nxv54Yjrd7b#)WagGr?sgCS?)PFLW>@h zbAW^H(oj26x%ZTRC2Vbk0^|7yOe<#f+thQp5N;nT(|G1D9BSSgkolumjkTZ0k#C&c z?OcwJZepQ%yGNbzYH^^=A;)_-SNrDgj)QoKB_U>(c z&rPOxuUPyq&So*_G5g+2IC2Hb(VDl*G664q>UI`g;P=Ot;EQ2i5^CQq<;|}|QQUv+ zb#om1{ZgN%pfCOhSaM_YoDRYtU@kL+S- z{YU(39(N&U%{4qew?bhnwa*gHs2C-2AVR6L#6gF)KuYUT2@F&q%1auKx_O{z>j+0lIgzfhcPBuDoC$IFl$#i2{hWsqDMe z>X{&Z)dwD_KREbuXk^^h`~D*0|F;~E>a<^{JkSwSQ=E^(5p^9b5U|6 z)qkp0!xkC&JbFv{oO_E$NwIfTzW9?#j;P4DmIEP#Boiy5l>}%%RzzoJ7DQ6pkdkaUNky!Y(k~={|4LAi|ylEEnisY)fy?)+WDSL7{|uS1^uoda$BL ze8L^7g~k20sJv(%24G~GVRudK_orvKh{e6 zc(n#O)Ql=7_YPiOhYu*arAq3R#M`)4V4Rl3aHwInJ+vol7vz5F7974!SREr0mH*~Q|KNPBUDG3C$8rpagJa-<1Fz*p@0v)`Wz zkl@}EO}f);gcP?8vU^wMz&}dT1Mxs>y}3kPg~AlI?wn!~Xf#*Ja;gpqPK13oV=GOf zVfHg@M$qmL0mNlySs%4RUwEVJ<8&S*BtXiF-N*TMd=%@EAla zA6O8Ru@R!12>cfco_~f|RD*4_E4l5-Yh6;zEo%K*vGjzdMe4h(n|>ysO)r<2JjY0d zGg{!vC@a&oH0AV1yw!j2;hC(k1c=bz3L*zsR_qBQe6=7ZrSKzF0%>57?}0tt<3T6Y zJ7wp(=}JlwaSE9z?h%lCMADgFvEpj{;<4pIbSnwZ0tap7nLbe^BW)|6)*=*(V%x-6 zr>@iGs!wq-ma)mw@Vg~2^tNenkWjlW$T2U{Tp8q_$DUAecrh393EcZ7;)gRz2%3RB zyQ3JGE}O^7>UgjAXu`|(-dtSs>}!RiHO?KUXF+U`3Xeh|uh~Do9nXJz%jMc4 zD`s-@DNzomf5NMzbDKAZUq8(b?6VLMY-;-@IdMT#EkbV;UFJZRMD~|eW$hdOD?e>% zSg$c9?OLx5eP&*2F|mO*Li+qQWQO!cQzwy#^;eCpWs4C~Ujg~G4Y&1YGil}Sx~7m4 zp!-)%&$N-4EW!w}50n~M!$QWs05Zf3@OneUPh?S{t8lGkg&ylF6}n62qIDY%7R!$H z_m8|qM8k>8L^YF_XV!EljOgrY6jR?CiQO=sRXPyF=}9;c%heg2m0Ce7rxakU+Z(yk z45TU=N$|F_xJ!0f)=3yE zUz(HP524+?ko$8DJj|lWc-cInDaH?8z_oV|w9xV$1w_?P&gEH_oKu>Ggx=g?Chu7m zSsKQtfUZyGN_7k6o&M%44;{y-_WgKwC0|=Qlk{hJSD1*WHlObJ z8Q64*b{$0vTIxQhDo{}A6@mogBr(_k2!>SEeYpXv4QI~^NNGjCd8#Qr!wpS8NFvDP z95Z<`gB4zKUPc*=eNy#s*bo@8DiY4-0Pr)6k6pK20VBEwy3A2790wuZ2ii;8j12=M zgd~PwHiOn;_;oCgJ0H@hx8_`#vyLrJB?ylX?062&GaHztZ*&h%eiX{(4ZQsMT1ND} zT|CHYI0)@`YZ7>{%Cz6D3>lGH(cV~J+EVn+5b;U9U*$P7tCjfcgW}5!7SZsB zLSSI`J}@+N1cZe8gw8OPv?YRacz$ZVxsBEZhyBERsdB_GRblu5fWDXS$30usQnPz! zgo+?Ry|&Z}u;r2zrsl*s|51Tj{Z#AL&{Tth*?anfw%v@cG`ZrllS9@|-kQZyROKka z({BQXVYaA!k5*WDFVXAx=n8GKJ}?B&v)tJ3zi;msO@KOg;W6)b0;$veJy7rdl!SJ? zZ@;(Ci(*KPTfw)Xo9wk+fnM*QACH5JFNM1wf%m0+F65m(JMy!p&S(xJYX)!AXdx4 z&NtT(vpNdzFDZCNfr>-{;Kp$FE9y^S)?@qGG=B(2V4lWX`h5s4_cdHmgs{954w_;7 zwO|<1_t*5q1b$D|SJz%@6HuJDl#t}inZbfGUi{_^mD+b46roaDD=Z_JSAX7&N{*G& z2S5DNdXd3NApdMzA^+;`TE|kbA2u{7WJee?eCgb-Fgc>5Ts7Yf#Z^R| zj9AQ!hXQFuJj3!)jN(O{nKEn=ne~}Wq7^tDD8&C=rAmU4+;Y#}Rgmt7x{;l_c*7fT zX##Et>{{*Ysk-JO=N%?PRHt{B6Kip6N4LA_3{HZfGLy2}MrAX9eD_pSC<>vyWCiZk z{mn3GqRG@yBUuAKtF9sFtAHTm&gu$y0HRuTWs_aROO;W>UdG{=IZ|{Oqu97&-@8<9 zT*2qRa~7ud)oR}L(`!>J*X=-`cWH9|k{wbwTRx3p!mDvN*6v~6SIvp!!LUwmpBU)~;N{Tnp4cMpfXp%K18N+RqHpB)- z80$LEyFhm2(jMe8PurW$e(zD;t_ZOXZqcl- zB9B5$Yg=@rqr%*Lh};(dMaxo!X4icGpfV_IGx-JW(;BPxsk9XAk^n0hyh=5LY(J`r zLtXDH-DLguqi<1H7eih4tYAz>vQ%5RE?D|(3!a_XY4M_{d36J>XfVG|NAFpCmVl)*K<*((l7Ny$2gUo2sFb^D=b$PuxFDzEnnb3JILIZk94#Y&wc{0#Z zmQvFm2cZE(ta9Zq;U zN-?V4{v4kTbazANXQ#Js#Y_jMRuF2Iw z8ab4Uz@ptm3F+s8^K3d|mrwOhDWFk}fBM$w>3KgYpv8PG-*itr#Zp-X!T)eiE)AEx zL)S0wNEDJf|CcQ;M5|9mI<6lBkW;2HPPECRF~$6%n5@JWOibdY#_Hh`biq$pIipYN zO6l}#k49TPd-1fXS-jp$qin(XbjPLfyDDk_9YerwG$P&$aZ+X@(I4YNWdNjev~*-{ z!JXNci8npT@m%?#hy8QXF$2ujFb&4}*%d#f&?D zSI?QLNq#nRy8nzF*8+8Rg7YuHRm<6@WvXSP4RvxqZi_k^X}8qctML(aaP^zJW(!Xh zn7g%wKhnHh)|meI7)GrM)1CT~tII8}2@D(8XrA=^%j2tCoxN%MjXJ~a9M1((>nF{3AxEBtF&~gMD;D*TVNr>D3V(y=n=b{S+zG00xXhC z%<&Nm%QM73tvn*K#K}rL*7o(x174D5ROkZ1>eAS(4V~TD`-EJMK{^X|AUeGyt;$HE zb0DJf*p5gZnPu&$=1PT~0GVa5etJ-g*u*5`_&PIAgq~(g%;D|#YFz_SlI*oO1F;fM z$B9FYSmmSZT8^00c8hYl^9)g1sh3sYLXc2)Q%T?jvDJnBfYNh8+-eLB>jW|K8EPFH z+M4R9NG5v2e6%s4n&JdU_z)8s3giCInCrw!kTifCWHdjqOgiFe(^LLN}?@ zk-a$XlESxHd@`@CjG+f&qrxA8|DA_Q+hohlmqGPR!)|e!>fP`XTS|8TXjry+fGjxKiFzo5h0XGLPhKS&;iNUe$H^3C`j(hFa_I>c=w$evGg&2wVtz0jyT27EXS6&*1LFP?Bg5{NL={_BF zI4YcjMTwc8V@o4T)j1`BYFX4biL@j%E{shjp(B_2kfD*LR2Al}lP<21yk%9&gyxn% z@;g8292rw;D$^z-?qV38{Z6<;vz&Q|`&)r`#2T^TeAQq2y|ypRU4~CkAg0N84%pxe z0%rZHQsn3a>1S`xkTR$>J|{q&p#?d}o=-i9`d{%se89WCY)16g&_6sQ;&eQ#9w`4F z0_$wu4;10+TcwzH)GM}Ef-M z{9h!^!Nu`^ku*E&|3K30Z2wCnokBK}ByqM%dF|v-s*~nUGvO&|X@^)~R65X15wuwX zI%TvI8)X!}5V%KpW>M$E$MT1iw5hQZ0I5zf6w6RWLQ2Z_dHSo<90kA|`c0HUhZpZk_z18NH$GLlx@Il+hGvH19{ADTU1cKVof04Os({ z`1+4n_r2qtKvr!c1*dyc+5as!Ih~d1g%xeaVB#o~g zDeYjKw zjgri%7Z@A7FpZGVHktVvzZaxdpQE2H$s#M*(Q?iPiFDkr;JwLyMDlCCgfE5V!(!xZ zuNlL$^)*~fAE3>CZs~ftpOK9^C3qvOsEX-lcwTEGNzcM~ylli9ekPV#9O5aZ6v+P8 z5y*!l66dh%ODfQ=e*tBk#0`rr{0*aEeo*vZvky4>z}E9RiYH+nC_{k*G%#Q_3)!M< zHetE*72ROTTFg+xFk!!0LLH?&R)FhKkW-^P^<)lS^6}7cAP8ZgDx@9QRJ-`C)9l$4 z5Kq--Aavc*<#__B<~djJkoDgE8f5=4iMPP}6retFn50h|@4z)gBRE0+vKgZbCa)NT z6iovqcAi#8k-6{8bY3Xk-Rk6SY$ZTLq7)-oqxd0zk-duB#}SC?dDON``>-xZKhkIJ zV64i;GY>)sTFm!wn(#GkHpePuX~vs|LA=1u_tO zktMH3K20meA4Lky&kTdJ$0A~mdD(fkNJks)wnwAa>58}1S4p?RnDK(etl5sgZr-OS z$8wm^!?Fz$kX(oIWUYdf7dc5eWc%)6FN62Z=*uQV#+{Dzqh-#U5Ditu_i7KtcE#^@ z4}Yt(Z5(jJwfhq1*l--rY)-&7E%Ej}IHd(IS+g->@h?(sBa^m5IsnP5#bG8GUKm%btc0Guzw=IjnxbHbD-EH(E39hv=f>YuF+!Z-#4*&fH{pzg^_SP` zvpMR&E)ZzgaD-Y2UxM+IC>s~fbJj1{cT#!cpl7|`A~G<}6Jr*ToS;pyA8FXCP)n75 znp%;Yn-ONDUzW4{WK3LtcXHza(|o-)rb80J6txslvci_Hr=(chUZyED}ju$SSa!r&igud9vK$y(XvV& zS)7}_*lY$gk(U2~l`?@4Ptb=$Kvo*vmVye-ov-OBTj}-K?W2?Q<$X{#LAgjrDklFd zAwPlVEO5=p_U^evn@cnZ0QfOyhI%quc!HH{WJrHJdd&-LDSPTXEg=1^1E{}YRs`W| zEefH0z654-dj3d6wc2r$BukgF5qd;{FJ!G*314E#ePz%xHghYximX+2&PkYwiy0WA z?>C?S!CJ{WYdb3R53VHXJNmWRA97tH!6rWTU^xJpcs3%S>A}d zx>Lq)WAN)GtYBsdCV8pHE01GfVMqHYQ{PFI({yO2(O=a)5hQZRkCQ@JMAEav#f<*v z7d!l>Tn+*s7L&5y;!zz2?-8w%Hq&b(c3xMPgrq3#~4Yn`{ zRHrhbJ0=+bJe1p3+l4c)R^WSf=b`WdMEcCKk^P0P!jbis3Yk?>{#~;{*|g%6f6=Hp zY}AhO_NT$uPGW|SV!*uf4u>wJ(Lll@;|M0&BkQ_TSv*fN z<(dT;Z)}jrR2Ai1!DN10O1&cQz z5}*e=Sq{lIC%QVR2o044O2pqF)20kKGcg~NNTn+&{eAlzSaH%_n;{X@Qt$Eg}$vj*~&;S(Io6DocfNhC+RYhyw=Hcc`YXUArJS!vEh|eDEnUGgd z`VSzgFwVKYsxs{o&W~@UrTEROI#HWCh6YriFfGX}Si8A-)msF_#Fx7Lo>X?HJ(mpZ z-LY!aPbZ{M3-FkO6?JcSow6K%+;>xAeb!Xj>&*Jz^J_z~JfAd1u?F87z;U!#)J8+X z9AC!kWpw(S{M6Ff*P5Kc?qK*;hSIsF{NZMgknZghLg=nFR&osQ%`FQbnYS@@uZ8OJ zRr%t)j%@f5f9=XYk*OyezGuMzD@oU}(azykU1dEYybQs*X&ks3+xiE<%wGr!4vfHj)A!eWA)<|zmAE0o!jJP7ES z-)(nr(YCrFVK@Ao1gx~|5;?X|RN?EJZS-SU(`JAF)nNlrpNUsT`SwU`shi4(2u-`d zkKGVFDj#-JPgiff6o~02q#r}DT_T`+M#Z3rleGJ&2gzDa-V!hG)!fl=xHC>yxPsNS zy9V-&IlV#SMp@0@c!+TSGCn#sV4a~nTXZz4N;G;L#us&_LK+tLs#WrW<9GP96U~uP zj9=w!c}UQh&#Hf6EnE~xC=dFcu$lvcw4Mo}v;n?}Az*^jant(>0-~~(%hbkZ<07AS zQn}u@YsPGYmN~T0nmf|on!-_DIq{6pBX;jfEfJRcTL#Q#k&L%WMjA1ps!pD{rRkSN zpU_EV=ajN%_8}J5Gf`dn?hYWo%hnndWM{nm(Oui!Xpkg-)mV57w1{7TJS{NeXeq3U zKccK}^0LV}FxBf9xi$jRhUQ`fF-LzJ+hF2zW?a^LMS~APj3b;?P}bU6P}e=Z+Um%5 zw$R^r{w2Yo|+&bUQh`qHBJ957O*fs6yjD9z+#%+1K%U*`>D8ro&9KKt8 zpL;?+n17>>w44wOQ4}1?A^Ari-e)A6Tk}9qdgYRGkE`;#>EAz5-;2TEc3gVr9&4TM z*C6buHgXwHNAM{Jw?Hc{fcb`rCN|A2BHsti$QEw-_3EN#v*vissOcuGkvz=0og;oT z=N%qzG~rSmZQtHRrZ6sbPvUTM4sF@=1$##Ndj8a@ls&n?bWFmd4{Xz@rs_KF)x;73 zQDBB!!-a2p{i#Gc8vQg5trV5Ah@S6Ie>v?M$^Nj5xO@TNEt)Mno4p7E$zuD zC8_Bkjuf2GVp%K#&jJMEtr_yrO5G>solEj#zqq8K$E{Us$&OMqJ9NngC?x zUR*omLN%D4a(SEt@^ z^C)20AKE=mn@RP9y2Vo0f1{W+U?!m4xnatUukuf|bJ$_NgUnRgjq_`<%Sbf@nniji zIVWP$UX5wbHHpg^GuN0mzEq^OG`FZ}sSxWbuA=C;nc8&-k(6z(!IGJ){Tm=+t(lVg zD4p2V`SF)l+MBjGh_*vmm5?Z5VC0nZEGSDSfE6z^^^HbiRYP7IOqQp}t~K;jf)EmW z@R+6mWX~j}&9z>Xr2K_9RADo%5kS(-dMp068Smth58x-0TjT1R%%3RX@=j-%A4PSx zDe&2e3KaF!w4ojz{Mx6&cg&9si|B-JTf7v~0xp6h8m;fAe16pzsX9nyh~1}V32S4S zJO)sEK@tF#U!zwT8(~GHM`MmBCXLtG_sou>^2_5IZHc_#IdnA(?Qz>?_~u7nvSVcE z^oyC(?$g6kC<1-jiR$@_uQAZsG^)V}yXNG+)b}RnO7t7NDMP8CZQvo=x6i|LYBBO( zF^BD9ov~{EbjJxX=3_pa6!2Q3Tr9=ob)@bc(j4!}pSTc{K_t}3K94+E0Y$m8tWuvo z1(VsJ!e*$=qP&wCX7gwRa#me^7lV~ejQvr@%XHbEdy})#c20UfourOY(1x>XT}^h;a~l~+rEA5h48v%3F*+Ww2s z{@YgI;{1Qtl-U2L{mK5nvOj0|CgSnN(!%5YuwoNjXm_h1s#LFHfCm!kM2m<)8|C^V z7Vxxf-BSn}rP!rnK0yOocVnK#O-;?!I3rk*3gpej#U#4@;_^Lg4|v0WO8XS_^?mO# zySltw2HZI@1r6@*4jI0@9-LpFO|XD|j@(gn0o#X{Fw5n|8nYn9}v6Jo|UhCVI$qa0To{chsOGyUsFR$^3uE(uXPtN z=L=AIeH5`ff+6T+Idaio`3R0|ly;BXYi?Q(zg|3bc6a)Fgds^kx`^1+3FPk9wG6nnS^~Rb^MCB85WtXUa1mI1V z`jzWoluJecCt3U#B5a~)O7)#{wkav3l2~PAgKv`yo;k~({ph~{tyMrF= zNDPU0rpQZyu)NH(z*JtZ8D5H;U5_~k#q}x(iq_}EwfBks$xKfuguui&`Uh)ZPz26d zTklx?g<3ZrwrH_rA(wf-5WdP{W(r#(Dcoo|`G#&zyJqQpHetgs3VZ%7id zD}Gro>~hV5#sOw{J}(=OF>{1*%#om->+i0I0kQs_%U@UbJWv(>yX^z&$45Zw9xYYlO_?|t#7S92mlce>~ieooWcPjU?X_vPM zAQVzIih6slLXs5xzOp%Ga0xLG^4&9yRQ0KeMDd~5ZysS!a0x6`#QZsJa^7>7oQjQ5 z&_aq&*IVvFC@NvU4Vs0HfUx9FU5$l-mYjc!1wwI%X-Cq@W2MpM0}qMMJ%R{anC*FK z5(;DoRm-JQ{bCfWPm&Y?7o#btg4`6{|6CFZMLriZb19u+VWHw+)=E6sm0U4uE+U*! z3~JzfmO&S)Ge6MGJfQ<~>=Si?E+OdlQ^la-Es(KOR{}6S6kj54eN` zg$xR#$Q&7P#IqKmSjDL8=pz)1Qt^~sAlArswvE`nAsmQFdCSo{j7Q{)zvP+1)8V*eAI&i`yN%e zv2jK@Q=&7kP^BcFG>6fGYN$vqtA1@d;F?G(bw){>c~p@*o->uC*elIP<~nrCx=Ot& zhiuorxFI%-f2DjC3$(I}gdB<2A|i(Ow!*eFE3)mOlMc>~;XM`1Xk5#wsoPd%?WR<4 zS`>rRAU_PltQp0mo$3f8{{#Oy^&INN8d-d?>hg&skj83t&$!YH@>bjzsA@0Ik;*xsN&kRdZZ>;w0vOGKkINfTh$tAqj>~@Xr(L8KmJtqlj=AT zY=&}l+?yFQiisHo0@^>+T7Ue3!nZoxWQI~o`S^-D}Vtt`RO&A7R9jc6{4cl%$h-Ufm_ag$= zSuUEFGoM*RLPNV69-XCbgb#amq0fl%dH4)M=mE)I#tA~|kznWL!&reNo(zW%ol!QJ zHiGOikM=k3fOUg)^>YOhW~UYfdaSDTs{m&JA(rQDdO;z+0kuuT`w_%~Z~_T;SXN{C ziMJ3ih?MHQyKW|LhUL~KrsL$zW91a)f~QBK{^UElHCYxb#wQzT8+)M9Jvc>&qET{Q zny5A^M9trH3*FAWf-t87?Xeg_(R&7&aDhe@A1nabiw{))K|*PanKP$?WpDN+gfL@P z-6}9R%hFR^oRXqtf0~X!SyRn$#%R19wnK&eqKkyQ870udUe)Q*Q!K>mSX*Ux#JXyi zCK-10BZN0_NRR!qx(NcazxovK61cVqqTmwih_y~8Z>ZnbVmYDj(^cBQaO=!4y6Ryf z=ySw}iuyYz?(LH_kb%MuM9l5>V_&8P4|+y%GZHIjW<}cP=@+DJ4>GZ8dLj6V?Ehix z9hyV|wyoQ;ZQHi(UAA`Fwr$(CZQHhO+pce)8}V-EG~R9IAIQixa;`aesO_5&cM!{D zWMOa55(Bs$YvCj;nKp`9EW%J}Of<~qm@wz$BK*8nif^><%fJ;|<)0E1LrWQn9 zU0=jP|0xa8`Kyo>pt=yM!FA3fCx%2WmWD(qKoIVS&2E90aOVP%0d|?tHTBYs|?lUkZ@`zb#{_VOKJ#u zyJ8?EO*iO^iQ~`ujb9xhFwokf4YUL{Nm3V$&w-9NQQfhTK0XSA%x-D31W%-xPot-= zU?0s$7TiliL_31KZDpea!;~_Wxv9(p<2N|gb%A{?{3^~3rP6l;<_P^O$$C9Oyaq#s z5o43?D7LqZ1k+uaQ7ZrD53;va3>B2yDe!WIH)aP5<{`BrfxvVfFR)1hA~2epn;=eD1s5->#HIM-!(l<9b;Zr< z0(}O+kFlCi&PWgjuqoE0tGWKYor!O-_TWT|qhw@hHTRkh*z3+D=%A@9oOy**(IaG|7JlGy zU$;Io$5`ZHQ(}W&gc;wcwuM}T!jQIF@$H7nJ$q^8#zH4Rjee(jBVBo6P%0{ zl3K{jQIjJkA2te8pj%WzAN~_#L|BGGw4k#yI3je!mgxg86jL~)9Vta!*OP8>Qkre#84q*I&c%EboY!Dmv<%Xm?AiX18LpCHloercIS*&_4rL951KtbR*`X{+ z{t-tQpFYf$zX=<=AbrwJH_U@0%4O#mvqJHm$U1P*uf{k9t!WJ?^b4DUzX5Rt-dK`yzxHt^w9K|f61{tKB=#Ki1pEL z=$`BRMVa2!Sfx^i88MD`S?N^%7ruUg(Nx7_GBk#iK{hp71J54FVHd+U%Q$Hw*l*CE z97h8EI@ub3ktD6HP1c%tRifUiIvMJFte8}=(y{UpIXq*^ zt?F|sMYp+(^?LpwvU(ppj~f}4c>*v=)$ce}R1+=RxzW~{I~x`P5qhE`Xlv8mku-wZ z@vfeqra=khG(%XdIlTUip3W@ER2<|&=M%OVsMUVa>kvADJyxAEGwC> zTrwR;5O+v^Aj+FZ zI}PGjSDJS$&8*fhf4!fqk|A7HqYl^-Rghu|y_xTi!ph7D>>WfW)Z zb!}$~;@fE9m-Yy?t&(-ALlB%($p^RN6dG)10}Id!+92UPqr|WZac4*P&>-dW6g@o( zvQ11enE|75W{cL`%jv97oroQYyIQ=hJ%nbG-xm$ox2kjITD<)>Y|zOFb+Wq6aeHAa zXMyjC~FXcy{GNE>OlJ+x(f@IL*VL9Ecj^r>oo~g*cnfNz`wKT$A3a!bJ=& zV?CLzV6w8Om48)D>Yg)|SUnhT_^{fP)3gai@0KccaC6#XC`dZ`kiEXT^&IEh;aZ$`s1<}>Og36|u80}sRl9j#FC z&SophOYtYf6%e2q(^oYC#tXGb!LTuLlbm&EtpDheR5J6K%4j1_%@pC<`tQSwFcWET z$-=J#g{ho{%1~7Dr!K%%=AAW)!U0?&7(2Jx=u73z#92tgsXlW{l=U)DX zFw}#>_-R8rLEw^{Pck+aZHXdlt`x|V!lnVQcOv`cspI^K|Mci~yusJa>;5z{cVC(= z?gJ49w{bDSuyI>9&mPh@x2x;zV}2Mt_NU3y^Y!L@7~OaCK9as?@Ynl$@OFQ;(AK55 z<881Ix5h|R3qmc(Su4&E-x7CUxOJcN@`>D$kk>sHw|a|RqtO1S=g*C?YAf_S$G-!= zA4bBAL$yR0EogDl#5^&Kgcg3#&}CxAC&;Y@NUhi?U1;xVC8$hepEJ};I$J`DYe0r# zBcv{0L}tSNjbQP7)Z7uAh{GTKuQG7XG&!Pi#f~78{O6DT=36 z0;l47YcY)hg|utng}xa=%{I4jG>0gqpPy8#drPI8-y4rmG`4M}4*><^`=Unz@i zurQEz=FDk1h>t5Hu9UC#J0s0Z&?iAw{&@38t(4QV(YV&1cy)&%H~x*4ah>ch44`d_$2B`dVwLPQz(lKtm(RB2#}@OS)p;F#>y=(89>v4hi+6Ao>vuSC8hSu#0E zzHG)VF4{J79&OSad8QXik+&&wCP1~il&(-;?U0VWvUNC2TN;Tk?KJt$trc+f>?v1a zrvf9Uba4cw1@vb>I?AX#6K}bqv#SKL`hJ5@bfMLGep0j_SI1`S)$M2|xKoLA5G8U< z0!tjt!TBl*^a!9nyC+wGuhOyHC5y6sq20+*;Avq}0gJkz{j!1n%L@JGBeo-WG}}sBLq!5V zJs7EKhs}bTtS)Li*1)*g{QI{1GN7V)9;cbPTMOSM6}WvUWo&T4*1!uLV%nsc_SPW( z$G)6Izuhy-@y`u=TAeF0sY4GnQCO4)>fgj_B_H*rKQ*xCGa*V*x6js+MK$V-))zGD zI)u|LO-l_IBLS?WBiaqxz7C3Og&Tv@Y;QFyfT-GCDcVvCXBOCeaQb!px?j-jzc?!Y zO@jY7bjix{zdZnK{~fwy`@e-QwWJbph7m__Ue%&(nc+&xUjrfVhX&Py>H%$o;QRCu zs{o{^jE#NXtA5;xx!MumcJE&27b9JJ z?=nZ}>4r}3hiB25zS}T=csx4Xf04lY_=~R!nk^jNz2|3>uxr_Lf~JobBk5aHxfeBz z12%nn7qypk(yv{)m(7t4xA-=%jnTW3?LWOrl}(*6d|CBBomy8VU9fzdzXc8lS~jmi zkrqxaC*|y5BWn87W&4TfdV@`WyQMp5@qI0Pyj1ym)~@wQWj`P+*DDdYYOh{MX-bgm zEMU3E4QnSxne^1v)+Cnykn+?(r{H9x{_!$U+hrKrQ-gh0g#(ZwXK}wN({? zT^KKTp1-S#Y#vFKX2;nWO^=R=pa;ee>J8!%a+exnfdArA4tg|MDx{P^3rYxS9J&;3 z{luvS@hl6uu4G=f1{4mOc|npf(D?stQz+{X1`=Vswx3`M8qa%n;zIFqDj3x70I8A@?l7=YKZOF z5h9l)))kNP3N}2N5~reU4@$W}QLIzJl-|(rN*EiOPPxTIL60~QNp${ep%c+ObeX)! zc@@znIhu^oL~3N$JWPBc;41OmID`Swz!OH#UL=IP9U*`cS%&w4ULJHmUn;|MqVXaL zpab*`a1v@oGw4VwyTN>S)x&11HqjGO`~c#v<2(ZLD$(sx8eF))pfA2uUTZ7k76<5q z(%Tc5YDN&C3bZ15?AbU7*oTlt#*sMq~m&FCWHC*};vPyj#~YsI(~e`TzDV2XgEJUk0g7Upf#rZl zU5)?N;v50UN|~bjPhtFT5UG-9IL&)LsKOEjN>e#u)Fcf7Gyp0F@gAC$E({PuMKGHT zv}*aVHpdljncpMOvjc1>Fj2l^zT*i5Tx?r1=a&UT5p9mTyjBDElF3M9A0;%`+b(w; zMrp&ot5;QV#JX@GRL!}9k)B&6)(9IIK*EzN#wP$NK#1lAE6aOXVvp@hIx*@m&}*=k zzIL~$O*zRf@hP+GBoBd+4yOc80;;C<^^h|tzL2%^J64PlMwHX*2tZUY$-sp8F0$7e zJ@eahCf7o8yJ}~)0=c~I(T^GcjB|ZlVtTlme=7K1{{JlCXT$7KMp1Hu#c4DLyi|og*t1wnC#J1tR9>UHv??VKt z!{NBjBuv9NtZ(9&G@@Nh~8vJay z)fxf{ej5YJ3d))VPs(!=#0WVZPpa`3=7a|`>0qxR^WE@{XEYFDTNjs6qqM=lYLib4jiE+T>5@4dn}+( zfYyz!*FZrT|tT>K3y{9~#j*1*5WeAYNh071SpENKtpngJ2`r zmQl$#r5YoF|_N zt<_@ktXNqykRKxowxMWCPP)NR4uXt}LUujJ<>tLozV=z31KfiF&nmry4vX}2Wq{vg z66-~qZNO}(RznyX5(?6T6!+IHfDIXd0_4GzcxlL)Slr^mGGm?)bqk;v<1o^?F5LQwj8XR>P&7oUdmj5SaZY& zFe`&@D3Mud-y9OJ=Pn7&5tpJeS|7JW!F5zEWV1gJxBI0c0u4iYbr2CUD9C-lH}qqm zKvD97UE%{+^k$Ktfl$%t1P&$SX`M*C&U-~n8GjDGV{T{DCGhfd$ z0aL(NwCEIy$;1I+zsCm;@VYkqm%>`M-)Yx?#9{|r5BDCY37SJnXTq&a%I5Y|7 z_>~Oo)4=;Znz#;1`|M%Z>jS-bq=m(D`Vy1%(*0UU3JnfG>q8!<><~^a)^XYC0pYfcj6d+G`AMtt%q zW~vhxqK*d`$4v_nJQ!A>UHs5k`6o#F(@8B3NZT}A_Sz3NxOMn{k{at1RM}Q1g3elFmWa-Wnl`Wzto} zIuoR5$&Cr6xe-S61Th)PH1L|vA?vi+PTd%VF6}pFs2LA7`!ul!x-j*BT%YOEXpXcg zXhZ;zXQ_}pA+F*%1$LgBKTw(M;RTY74e%5d5dfFf`2TrSbm*6&`}E8X_O>VOYpCu>?0-?AdGNJ$ynOB*7hG9_J?)6MM=a8j z1j#sp^?wRW(Qo;?++O!fGgD`6dpq4;@v+_SZ*uQ_Z+%|?zue#UPpTth@oeG})OZPt z%<9qdk#NJ8bGR4pG5Bi>m2PQ7w8kO1|8C-%R86k?$2tVAQD=x2j{C$P{m};k4@}L& zkzp~lWwY|0WVIOw*K45tmhs)_PZvX1*3Mi-%%YZRbi{vwW0fF<%q2e`r%K340zgAL zO8j7>uO4JrNP8Al%}r4hiy?(d1CO%VM5gqx4RxC7j|D1N?_FNL!}{ReKN@1znn*oE z)^-+Kbo}NOP8z%ye6L8|gJV4(O%|=~TG}xjFHChm2ahC5(0FB5ZzVEtMDs+eW0rc3 zc%OvJY$|w~cEmqqjSZD7Ew&*oHQQ)H1!ATJv6A9S z#E5T4tLM?HzlH7$(bz?oEMMaEj_pR8eM~JzEmVhI31?(0)NYM}&7k0*YFGY?k+~d0 zwGI8(p^T;$8Ue!SN}5yO82h@s7}O3Rv6MKGph{9dD9GCApaW$@Bo!z0Kxfgs^GF-e zE`W5Ltu8=3n$%x7yz+v03oNCG*kspTteaM#*Mo4pNNC}x2_8Lx1}y<5tMANU$CR*~ zzl~x8iGv)g@6I#4^kO+Ec-X0HV7v3O4|483KY2lKc2wsz=MVpQ428+)`ySh8_4>78 z(4zxXN*-4zr@~c#z+$+@slB2vB+1jXSlEK9HUDrfX%*5Qif^=RfN!j$@GgnJKKC1W z@Sfaq8^(lftbjz;t7aQxMBnL(a+h6;fJ3f@YudDe-?$g>GEp5RCC5?Xn@3877eO?;X1IOi!Swho)7 z!qz=pOHaQG7xyCTu8lDi-0jAk`>k>0uB?$&c6RNzHP`xa=tX>#Z?C8$7Dz zF3$SzvAis2&>QXb)ST;tw<)5P19364xQ31i9)ro50Jm4OenXX_1}aq@=@^O}U8n4C zlhMuK7L9>v(u)v#S&O$km7v~A-8@~r)u42Kmo8dck`gx*0Vec%%K<&Ifq@mTfHL2F zH&X)Gw`P`;3wQ#yAy55bA8u$)@A;RL4n%aX}6(mY>WVK!+3c)!Oovqwcy3fwSCV1;VC;tVKyOpAg z1RC%j)nuM{X(CR`(FvoC%awQ)?l%XZIW3Mu#}baq(6M7!e2cfVnU?7C7?Ve;ycpw0 zd6=fCQ^oN2BC=Cjs(-Qn2#2F$UUW7ysVvZbq@o8E>+7V)ocNvyrQVIXWQmYr!tiGU0&$prP z94W_RME>FQSwB5egY6OBNdF|}5pAjqnLt6?jTF?|WL&i#JQo8zCX_LMQ+a}oS|bMz zm#xKSyV`Y!F`(!r)qoqBi)`vfCL{iR10KoOarRwevc%qXx*vpyOqMxGPo|omF13RSqqw`y?ko6c^;(*sLtOMBFyP7@?`D@pz50@hCF^#M3r@N4_cc{8)6~ue0wh zAJ^yGt&ijTfwUFfY)2j+U#w%&Tg}R!XWoAF0oyT(iYuYk;1^#6)W9q7ML(u8{MmylK2gb)^A2{%&two zHOg&u{lS-UhD%4ct#^Xz-JYHD5lsB;mx7Pa?rj~7%|56z5cs{n!1Rur{LizAx%k&F z9gHjI*NZ;RN2fOVs*~5>PbCy0Z$Dp?F&quyD`W>0%NV%+RJz&OzdxJT?=vi_>2a^8 z$^MWib4(*?x_ZVz&!yzTKg%Fm35o)ehAsKHW_nV%?%izLm#E&|fw4?td$aGndXw4N zR$WRP#n=D#m5lv;+Q=$-yDV!({8lANG<}3M0q1-@4c~4UzuoDHc}S*TNRedvR9UQI z;UpS0!~X&p4C@)4pu)Lne!nrun20t#S*L!F+H~p@s}LvOwQ1*x*lmod7WkJVwdC|F zq2<6}qgxqjQ~=I8RkAoRnFs#0FJAayyt%Mx(34H;$#9G z=s)aX_d!#t*fob2n;DzW4>7dizjJHRUn#AYiqaxDbxTUPB^L5{`0rkb`J46NU?}Z3 zgeQg1x^A$;HNXAyhQ(K_4UTqdOz9K|^n1{Ho(XpP5wL0tPVqf+f7OHS51W|QA({@h!FS_0 z`_hZ>6Uj@yD=XFAp^;g3*cKJC&Pu%_D`}rUZP$`X|7T$4;nWnxG;*>lo(7=&c%m60#|cZu(XenxGyip`tJ|i=b%*oC)bX` zP5tiIh!(xLr=%Xf{ldj?++f$G1QPNV*Tb_Hu!aSUpCrLob>jfl=8wOozwf_}8(M#> zATq8};72K}Wh^`=Shq}_wtZNngF3O%E9Q1o1w3s%W=u zQx6g$EKenMmrq4K5>yCSFp!cU>!wBTBq6snTdHG;g1XpfIVW{evHgk`;!Xw$idaYe zgi+I82}DV{DLAZ2Yj9KF7rdzKUP=*yJGCK}1gXAXhaO$msuZj;_tvGwW3&m{sDP_e z9n1kHj{pX&DGQx@0>lUoXf@P0V+^XBv zau-Lz%-bZhY%x3CJf4y#Pf|^J(&)F2WlZ>SiPR|!(SE*%`~I0&0$#F-Jq)L)?iC+a zX&FVThkJg~f|M>f|1x)ic!4f*Q$LWv^eF&ih&tQW?s?+$Sx>k4BL#OV^zpA**FBm* zuv<5cX?*1HWbob(Ax+(jAAz;k>)RO@v72>>wIhne3S zA>wK!djN?|PC`nb$U(mnRYgf2945(zUXLFS#wo}vf9Iw?b-eeY!RjtDY{Ey~8+oU` za2C`)!g>&weZpRHXu>0M2=!5)RdA;B&C=z1qrUANOZ4y3)aCe~uQ9#QIQ5{r^3i;} zl*n_;C=xK4jx&s_bIV9`PP%=J2zN$$eU;lh(l?YR8;Fqo&>4^WJUV4Y+&Nq63=lJA z@G{sY@f`?NC4k!D><8o** zeMGi2i?|@Zp1B?_^^;B`=h+iF;B-`JF!+N3L}@Tj9NB?mPN4xhBoI#=!d*Kd2f>MP zMDnA~)QaxbxJO9X7_j*M1P*?hLM1c*a7#oEXMwf0;ZfqX{U&qH%vfEY{*wgL6|vh$ zTDz6&=sp>sZ|B>y(`N4QeoyhMcmb>ytDe1B`RVNBiVoortCThcf9Y^E6N5%w?Dv|f ztAr!}(o)cFVcraLIsWeDFsvvk?1~WN12qST-Wg52;Bk2uV&>-xp6gDHE?4v=PWf6er=!mZK34ER#;P(bmjte;E>kJERRS*rVu9nZy-8V_YENe zONq)(t`;~A$~%aeI&toFC4w&AQI6{AcYL%|h*S4aoiXw#z;j5VBIuv;h^m$tNh5?8 zj6&-Cu})zWav*Td%7-RmtYQqXn_}RNO$X=UbxV~1?ef@1&JfuGP8V9`?nxko-if>N z8a(ypM(-*-Vc2>Mge84GCfC4qJ+n`qI4mQgnK#PaSla&Gw$^3g zArk)$5^9h=ln+B~<$_X&rCn7(^}v0oub* zt?;U`K9;rm>&ydrtXM%3fD<5%)3-+28OqrdX?cwxn zVJrs_w0aQ?cvDw4k{7uy?C*QHDQw(yo#E?wT%Ddgt-Z;9;R)yd7 zO4*$7>V66-nyrGN^!-CLzPUT3hcM^2LEHW5Dxke{&1sg*p z+NgmC3wS=*aMoLwX5j8aYg=r~+kPS1Dc~}&{02Gx!so1%f+g(jVqSJqR$nga>^jGs zRn~Z%WqTLKz%OT*Vzt#aFwt@gF(^u1pgtnbdViFJ5O}rsMYGJEH^WLVaagZE~i2YPbKFd)mHLZTVd=J$U&Vr z_tMy_M0F&z0Gg0`YEG>&lEj2ec{^=nZ8mPmR7L!*8ZYFp)hW6Q$S$1;pV?WdcHJq4 z(Y)9$;RUaxtPfeK7s!CSVq`;!e>U2M>2uGyh;n5MJpb$6%&>nISjSE!H!hgVD1fN0 zEf7AfXb#>@ouibL67`7>k5$m&{b&UHK`24Vf@~<6%Dbv8$-8PnoGrBnG8>v*LWWP7 z|CGp})jVaWABd$#NBw5tE_i3YWn=_qMnpTGep3x4I~z-U)E0(o;+do<)iTlS)_&-k zKXvm@s1-T2k1@%R<4ZMV>sUa2K8}F`)Q#MWf zIqK66OV=*6^De;r)Rmb%=&Xs}!)6|*v%{_*tfzb=x|G_B_X7S3{9N-E4HuV2lI)o= z?+d_s^~GWpD9Ae^JO!hjp<*g<3lecP3XW`~6AMEA1*pHSGS$^A_^=vQk1&s^EPM5| zokjTu$>2)cD=le#n#vt5sa+(dZIk=U*f^^YVPbG|6rCvL&EMNcwd4Me2y%#y+q{~S z4#yOhkQVNfLw9Ujd801p3|wkhcA>1-o@m_Yeo~c+DoM!}+OCqWYy<8M-EYjaf_)!7K z>*_JIV%NHs(pC^BA4uq(XS-9isY($`d8wcSmOqUg4b&|f#c{!Bf;1PuGE#sI8V#pS zbagAomuD#=w@SvW;BB!mCg_ck z>`Y3yYJ00oO~9u75zD_X2!`{pGpL{Fgw*gs|GK2lO-Ci|QDVQcH$sHUwziePeR-?t z7@gpD7h-q56hN;Z{o1N3uUxsWqKs*r|ys?g{a04|AyryzkK1Ak8=(%(@*Zx-*I|l@PpPmu>X5#I7Q{( z=|QgVey$w4+*nS33ImSH;U&W8pIN02$s@+AfqpSd4d>>c6*jOjC{cu_UP4ek!cXE0 z$2YZ0QZirF2(G3>syeoEUW0@^Ii68D6d?v{8l<#Ul2cKuVlcQ7ks!sc;=uXTTw{$n zzo~*tTz*KI)n*7nLJ`7n6HNgpH3m5mumjO@?qt~9p(rK76-cK^)KOBc)FKk~qX7P6 zD+zIBo%)`4fx?=1{zIeQj)R9RH7ST28A>)Oc+bRo9ho5C)eg&YX-WzCT;DzZIY~Rj7JY?Z7iq#_fOeCh>AMw4>g`;%z7Uwm2mE-{3Qh%T97QQmoj{Oz{7h( z4^f~kcJv$JhE=wCePpKfecL7Wh}v>G)=HnRcX3HL-PO%T!;j5@T3KuHfn-HN*a;^FddF6lwnZ`ACx$IbxkpJde#>()6ugpm42Kd4rkF%xF&x6e` zX}Dgglu|%GBs>AF z0Izz;(kf$@?Qv<`Pf)aLqJq43nDoSL;E*LwN(7=&{^*Yq?QJYZcF_lmT4uzHV%3l2 zCt?L3AL||POZ$!jZP-qVYU9aTwpwF~*MZUakx^$F|4Dp{4DtJnoDRz-nS7&YBMz-g zi#5(x;EziU4HKz!bj@zoH+}>e&+~sly8nT1{{!hbng6$?j-BGNbI!kP<{0eM3=1v#u1PPflmw7ccEiOZ)~jlg#U{C`plwCE=rQrX6Bs& zOS41hUs9DSSH{a_Qqtguu{r`C{4MDfPpvf7UEhB?j({z##8>6{;*j=@p$mnF(*yWQ ztW=;P4hc+D$r=Zz2AkZnvupn_sb>Gn$3-2j6Prnk-OVDq*1T=i-CD?C@EseC5#6v; zrE5*{byKCGYt!POtV!L?w^KK-PMxl?8zMg1tetE7b{6e=S@`g;pu)L+9m?9DvHb@K z3_zx4S!5Tx$ESV0B3`O^>Vt;CmSvHGiPa-N8f4!{NX_`@o`uO_6x2A@le0q~x??F|e18wr?1n^s zeyS8RWQL)T1xBZy<1P0xj}f?JuCP|@P(Z}|$^4{3iVJz025I{6BD=lc-yGwdD6@=# z-z*Lsd2!|^deXAgszlNx&j4wkU4dQpX|0JE+H*s-X?NF8-+sRX$1#cNGE(g!$L-rp zkdQ~#9lTUMUrR02V`)0QQt74^lcsIJ~l^rs_mFjMDx)-+Ak#~TPu4W1zq3`}NDNIc<9aQ<&s9khte0|2(JR9X@ zoiaYt+ry+p-dHAf)8M}jbXur(gq87$$7tYh@xodzNqxt4f|w@Z zTQt)D{vHYu5E77hD#H#X)>t5Sp&Xv2pLdYL3vqshOfbK7lyHhn(ZQ_ zz*{)2^CtbVf@#3FiNGWLgcHV@aBRE5e0Xqh2M)p9Y?EIYs@XbpgFZaq2e6~i^j>9~ z+O(`QKkd$n%}KV(uG@i@H>%qOd%=2)|1q;{K=pvcqcEW*@ldF>hU$_pEaA@+R`EXWhR%F&;kD_ijm71LJ-_l;YQfiP8MIt7t1(*n8mUI|HSt_dET6|Hyd#sF^5`$nXBfqvn<-Up5k&Rvd=u2Z-NjRAq@ir zf{Vf)cqKT8qMTMXT=V9fgg2b%JyHR2*ZHgp|1gS&zCcc{+LY<4c6jD&=a|znmkX}r zz(Eocv+4WpfoFPF^`$d!r{hGRC+g7o)6N-z~c|*d95E1eLM2 z59L1lL_@dqM4`1RjCMUVcIaMC4nFs)bu3U5?jzT}I|%g>K@Pv^e1uPYf+^Tr(4^OfyeFMQ7%!Vk}{nVaeJ{p0@RcJnpw5Uhit1wfJiy=T~F z{;=wziBS0=5Ptv&>dKaOj6c87IR>SOT8zL<=$WCVSwIIy*#wf5mb~FKxkx$dZJ4Nm zvuR{bAROm;XUuqp-)t!5VuLRXVE6;mqxi@N5GJ&O4%IABL1b$d&6V{y%f&XXTW_QK zk-nh8x07XWH!mO+J9eg)vaptEL?o0Qs?#*N(|pZe$mKmNYs3Ou420MO98*Py@wI zBFPUooI8YpcW!cU4t|f_QQyFleaxk$AUN_}nf_AO;=oAYP0t#5`5+bq*Qx=k=1L}D zoO=qgQ;RYYm6ApDh8;CG^wSBI87&}^HAYk!46z7{eg;&5Y%pfTz1h`9Wu>>A9KA6O$PVa}Ch%TV3oTbFIdFD`rWM z#uc+rN=Dy{4{Np{l#?#5-k9imLe>1EyY1{ui3fbw8z+(+f6qub*YsvX9LnQ|p+qHZ zR)-&L+4W0^(OK7w2LZPABIwaL8{0c_$PCkMxuD@53Se0T*uW-l?rQN^zS7pYtZF^S zi@ljq)EeLrngsSj)a7^R^k#sjTu1Ya6f7sP^;iM1swDICi<$!) zw4^>BOZ}~)3VT0$8m5+x$ zX_71Xi(FIdo4Wm4x6vMl(Gmof<7K+Z4yUL^z67Nu1M6@ntvf(-uFtLKI2q5Wwh!j$ zYV>pG5r=RGVKb&)Q`jBC3^>4N+bLB#rNUtaSw9RGuY)#`I@6OB$J}R*);sN>3<4cpiLc26W(=_b#@G^~Z zVu4J{qGxNEcTY8Pdv~+B1yk3mT-?}C^2$a6$(UQUTyMtBZOiQ9q!r_A?Ln=;nnqf_ zwtxiYtw0B8%f1kBMsP%g2$v9w{n3T2L69UyqpWDu->SMC>jQsZ&wHs~?F6z+$qObY~EovsXWPA!zL(SB5rrTj$c+ zs#(-@-PL=gkh9a6Z6dh&7yo0CMTG0cJnG|oa+iNnNO=CN)g(VQwZ0nsS4hlMg~w;^ zOw#R}K{RD2mt56|uxkrW>ouDf1|PrQY1xHk8^6p+^zzLNjFz)RFz`-{XzbQL&~F#z zI1?fd`NktRD#p=e7CU-M&Y-Pft$6-@>45S^-|18-k}UthVM+3aG@ATRnE-o=+Dd90ql4;|UWXEa zU_shCGvF<(aa<8uIYFNGGn%js{NquL$CPyyt$EEqVRF2BU`l38zcv9)#m!m8B)Qc< zk1=b|s3h!Bid7}XNNl}FQf-_hW;%hG3h&IGQpgI=kk9OeCZ+2NbQR7?kSXKmpc48z z)H|up?sH;an0Kr!kVcSQ{-=HY1t8OCgH%ovTV|l|^izRJ&afsTEA z%0e(oRKOvQ+>HUJks$&3bQ&u%>tGW-7M~nEx$)MxG{rwFz@0I1r1kc+8E%RK`n9T; z-Q%5cp|UaM!=v`Qdkr2@{2|lLGng}ddq4EVQ9e7awQ*03C2WEDuyc1~zzxZF277{a zJ#evK+S~JHjV7rYpBGj0Fqy{j#!V?1K5Y0@YUM8wVrYHNe~)|r8RPyl?lH5lv;2Rh z7H$+{ z@Th9r*N3BGT-0#jhw>*$QKa41nPX!7e9x@LPqnf&Nn-kh3`Q6`9}s1b>AQVzLc%M-4^dRziOrrwA9X7 zQ(977eFeW3?^j6^W2Pi~TaM%J65an}?47ye26^A_92^WDZR zoKqB?h_-rQd@q-Uhph_|C42JnD9YrJ+~DIX*rb1-t;XEt5e(cYYSTYNBQIFAMai?Q0u@BI}AvvstNlA&?14-F4L-svvz-Xh~#Fu5h;9z z^6NS3ZTxhed@jlMvzpyL`z0TKpW`av$yhW3N+^}LdsvGbWhPQWSa*^DEhIk1gMc3B z*2yr}&TZ9H#}mK@fFHuAp9#UiAb~<^u^7(lJXvat*p>60F zW=1rR$B-y*H01epy~#!Gi3fYH16m`c3947o#X)1kQ$(AH2^w1a7N#5jur@7FHVZVr zZY>pfwx`45t^7}FEYVs%dhHt{HCG@TD})hseh5(O^2aUmvW&3 zzR!EW>Qay%dSt!{3mFX37AuNfTMp6YI_HRED8ie^kq&$4kTgcgLOu=Xl%}6hmdcb+0 zLY>YGZ7!IR-TeFZnBP2@8+}l^Dj-I%F~I4H2-CtkrAr2uQvzdY8O0#W+p@jahqqi4 zf49n4kMf{VB?vO(EzNMz$;HBf<0FAM_`gqiXKe$p)12jjS0T-ky|0c_ys@szp=`GE z;Bhf!q~a$zaRB|RV!zZqb_v!aLHt;{G(zD(I)uq5IA)Aw>W4Bjf?fe04GZhcqsg|u z?e}}*l2dGg@EB${LX1I~ zEgkyqYVS{cb-rJi&;kxH7eWGNql7X|5da?hgd#40WTF_r4HA^y%IWRJG9ATjOY^Z! zK(DqruKMSdh9xCJr`3o^a9kW2oTYM4aIb9oLM;aDbsYqK|S?SW3-dp_{vX9#FRjSVa2uennI}y zFP#jYtZGW6)F5RRDqTnq-1gLsSXlRX&-@LZtN1dk@G5y491bZqzC;cc&Z zm0TCd=tz?zGx%L|yS^5xk8YM^D8}G+)$Xzi5aYIvTxhR=#1g;05>l5y$nlGd-2nCx zp0sK}$n!X0Zt-Ou3WR3p@8ve^aNifij&U(++M||prFs-OW|Bb~eOJ~?nK_P=065rwh$~mX8inxYy915OM7bU` zjIosReu?c>lTk+NR4biD-t3lDF)38JA5Z0gq-`t|0w}t6OG(>~vIck>QBiNOGr8*1 z^+3GxUBX%Ief%#!Pfn!)6ipTa)Y%I7wfmwBq!|8EyjT*-b9C;k$rqMnlQ6IWZfHwc z@&Xn^%qC`DQuaokp(pqFhJ3uzf|xN;(ykJbZ=qs**sFd$1|`$b<# z?WVkQNxH7S&e=c&-M_behj8ULD^><#K2t~|PGVK0kszr#?=?h1g~gJ(aO`hC!e)ly zKiaV0ws=-(pyYb8t|?Xtxrfm7+p>iqZ2I@-E*P z*~6TL`Ys=x(`?lw!b}Y^uaLlyOW|hu^z5#1IFDi* z!IvAs`paDpZw@ZWD1(`Z+K=grLgdmc_KXAh`fy3k9_DesY=znpYBHhdb(DXMI z{emQ8QJLblKe7{JC1+iROEYV=`W3qbh=?ZyER$7c#iE`@VAC5mAz?iWP$w!gT{+k`E0^iIVtwAMiy8y4aq z{_O?5ePEgmagC?jdjUEtl!tQmfCI9lC zS{?-e+Ye8RY2DHAq10wHaC1TcH{ z4}d}EzKp_oH_Q1g<|32;5w0g!BcpC`uLz&DA5B1k!6-B;lMoHbo{Q2X_fei>xc(Qu z+bG3hMP7Asx8+Un5v|!^?le47+Qu=Khn}8kY*%+=Zf4^3q_K=Q2Y+>d81$5~xyq5; z)9>7P=KV`VcvQ3Q9EM|YB6G1Q<_d@Hjw>-8ynxZJMt>)frO!0&m*dUCj@1RWTOmT% zi=T2`%OO{+uvp2B*1Bn{ra>iyaj_!EQX45f_6r7~ZjUh`x_d=|hspw)NRDH6Ex;vn z95b>WsBV&QI$mC~-RoXffH+YD-o=Ds9djmfKiwjuyOr#|l_oDM0?KKBL!AZ{-fW}X z$gclW1HCiB)Ws_=WE=6jHE@#sSwF7(W!WL9 zCz2l(EV95E)`h#EJs_oOL;v9slC#Q}gve#Hh)X3%Ioca12tJ0(ebPp1i?IlOGCb9* zRVPke@6H`rvoR((%NKc#>%e>VUF7-gyy>vcbHY^5PkyO5r8iZdRK^nz_C~y}N&BFR znTjYg!$PE%JTi+912<>)Y+r_H4y&6DS0KwtX4w)ZAu-W=S5KpBV;);*4)pQMFkC$v zX8ZZ|4Ov3YPGy&XBK_-H*dZ<-yc&_55uu1TaV|BBe=_X<>zjXbHk8aqjJ0{XZS|lW zsEyv(>Wy`M2JGx+`9p-5Q7$j&02j8pH*rCPt(#-O*7_HuHhsIj{_u>NF`{d_KEG2V zG~)mjKmFC|5JG(RYSVN!pI>%S@0gpUpebPR~>a0wI#ff!v`p5DbFK*kS{DNgg|fgOxaWR$Mnkcg@MzE($3^3{1(0XW0QX%=%Rc3Ppg^0XZ12V> z1(aH%`HGM7ZnkvEuqYO$*r}_&r9-L3CqW(K?Hp%jGQ?b4d+35L4aI-9rGp2F2YW7Y zb4!tO$#=-!Q40VOO|6|Zz{Kat?^OM%ZdlQeAEo)Iepy^_`3*&;D1PK|1FvQcanmGjp=`-HTM6M z*8Yo2{{Jhjjp%H};j|&LK5&eS%j}u~$wt3Q!|;prP9^|S>-7g5@{D&;TVAKQwPrs?u~_ZVH8SE*Cu z`RT;_%js9+XA1zo$=iVsv}on==#J$2*p6&6wefj2e7v4))nGNVs@de)xcfM$IrnsI z+zj_~KKeLA$1lQezRw8T5Tu||@q2yeCD$GD2*Ivu#yvvtbByiZFI*hma)9DvD3irN z?{uT!m<5y5maJ!|rnS9||5>zhZa}>|iY@BP8xuDa&0ekH#P41OGEcE#u$%;Mr!L42 zqys{`=-Jb;b4Ln)a&m4twnLb{o6%m+Jqb>P!{0D4EYR8)8EhZWfQ5zyrfBPk14{*N$sew zNhN^k<19k%*T_6~^aynV0X3*E)Nixf--OV|$|-qQW9yS3{@b3PlbC@_WbH-rbXg}ExT61!o$jRNsp>14;|$mc@#4!6TuZDMXY5>a6WxC z#k>L$N65wOc(Y!L0}Ffv459$|_dY92ay6NCK={^&$3gD$U>PuUH2RJNm~a1i#g1Psl=QV691 z-Kc$QaZQ>488ee%%fHMPB_$C6=u7p4I6DGx%&A&adCgKq6IYE zL4c6HTtM-hFF-M?4Ux>4;D6`f`g_2Bxs}C!TJ^bC_kQuC{#FOR=LhAF=hymU@%%pY zeE3fA8{zzf*FA)V!(9Cp5&UO5Ah_aV4^X^P{*-3buzn|iS3_%+-xT*X7O?o~;qeK$Uy1{Vk^~!18TC-?24-*tfUZg(te4h8dtcsre{S#ow$O39i5m)eyGQo7wv! zZ$2lY9neU=K%*I9(7Kx(!rl-}zKh}fvD+7ENH~C4;0ia_4_gP*QTh^W!UcwRHU3^2 z6>jj!Ia4gl<3nO8W=VyKIHd_GCWN{Wx9simgY555g=$gbo1nrmYakDM$;B2?dLeK^ z1lYiQhI%0VqwdcVfS9~$XM~INq>;jAq~~hachi(35Q2r&=?p6mQ+jlzC&j!;{Ot=; zS<|hrYr1`M0|Fkyz$=|rHbg#i@;!P8u7a;f{_Dcan`Dp+(Wu!~*~Bk=$kH%!B=qbo zJv$HQT>5rQ;+lj1sz-8~y&`?UQmSzj;mqONFqW*!f|1#F$Sl{PmI49l(+8yMZVb{G zc&fsvtj96&&ugN$rS8jZ30K7rNF1VZb_kKPia2S1!3EjRbS>bpEJ3qNFsspt#3RP@ zF5%KjXarbS)^QP*XlZ_dV?d}kEz`I#XycAYD}FxV{sUV*rV;bRu*@n%5J+kuViM3d z0NeyzczRkg0P#o5T#E+)2p|!R9VwnI&MPuHxF-D!5p1^O+!NFAuDMZ}*w9?^5AX&Y zTueqW;8Tw@mMHD#XpD61R)Xkg|cTBGDpb+6a zQbcA-iM$&DWJ>Z*LvV($b9yIjE^x2d)p*G**M`2V>~=J1SxT!EmRz=4HnJp2HeyMH z$cNqQ0lOo4N=*0gPK7aDzk0&6NnU=yh!dQL_zVX^o%>jn zKXBK!P0N;^Ou!^lKfd~8I5LXs%zs@xb&(%j`+t9n5>1BrR#4!(QF5oS7NZOK*q?((|0wREiXU?6C3 z>>zV!Iy3l%j!a*Av_vj!v_3&iP~pQw4gcREg|CeSiRO;8=u&IHPALp|S#h_UeQ*LN&1q zBn(8=dY>yHP730cRoeY(bbm1lW0PA1ga*_5Jy`DE&&*A?%WfHu=7czy72KbRMo_5O zCaGF~vfJ3Er0Lq(mNjEy9Lj=ZZ}%$r@|;I>z2%BJ`X}vZv|Z(=MDS=V1}J>Y6Azz# z-nGn%{7r7bbM_K#gw3_WdU!%k?AdlYNYthe+IE=WmwLJ@cDX^@L)d@s=(l?jx6MS3 zCi6g)T_$bD0~k%%6to-cf4iOF9i~Bt3rPbL zz6{6KgWAq9B4bb{3-_!|P=<#(P-!pH0IkURLkKO;v*KAXL1L?qMsyKfGauY|(8-{v zR;Efw9#^ShC|x6;lAF=U)Ok>y{p?mznN)tdMOzs45cDNe9xsCI+wi=Paxf1uv3;RZ zCBe=Kb(N6_S@02q=@=0P911_siv0&hhkA@Z93Bci1X62B*&S{ z(O9otA|h6mYCOV_iAc+=Lv3mS%>lT!_HJq`lOBd-*-gVx6@j_K1gfYv%09G0D(-{D z-i$Q7R;*_$RutykWh6-Bsqc^cb(g42r(lF*hg5R_menEHIj_bvo(|{Rb9NpyBC>Q=*-uP060?qy3i^ zC=v^N{uPc=00S@>G~l3{uOqbcS%i>z9B!J8m9Q|RBeJW?-al|>_0yuzG$6dY87{rr z8ZOj+M+cR)w(k;ys6hyy1Yw1W{nvL&AuNUOQ3TDz01I7gx4Y0MI==y#GsOJ{H1;|0 zEkTUSE04(>pZWF!rO!(E4z_YUN4Zjq@3tEj;Ksu-jE1Cvhej_rB545c2L@@G5{ z?hSXM8X7`WO?-i~2>aIcI6eW6_0xbdXbe*X6QD(c&dV_k2cCBSdhIk8 zb`SA0#Z(B3SezbXQ}INv+ofgkL%|X1CK-QXT!v-_f%b~Sv%at`B1fYMKtAuss=f{_ zy`D*Ubx!v9YO>V7AFyT@hekx;Jjb`Z1_+sO+R{QmZ~gL#fYNFP?#dplO+$@+czQ4O z$%(QiikL#Uii+w`oD*0cC1r0fyEm6wF+4JK9&iR%1JTvG@CQBU93#&t;|`I~fk@!S z4w=oaLY0>Ft0cZyViUY56CqO2m$=6tV(p(1g+S0JRBw}a|6oI}gaks)!hK}|YUW=K zHubK#_wo|5?#;!4YU4jp4&t2JnDIMu*CMTXbQ7GsCBDg!+Vyn`X>c19N^|+GtAku0 zhkEaQmI+6@qFE_l=**|V*egBipoXS%(|}t_g5uJxO`Kh`VRwV*Af0i`MmdY`qFHyM z8J7LD*Y^xsOx?ZuRxStQYGe{kJe#^hWahR)Qm}oqlsT*GUQ+$}kRd{1oPrc4PoFX~ zhFhgRXH(UE50S&8CMa8Gomf{|;X5X!@9LTO#W7$6@2(b1t?lK5s-nt0baw(=OdJ2> zK;jLw-#sMN0H6eV;V{Pe#8*znqBZod;l7EmOh|Km_&imM^$c+{HQcD+%rh3C% z{RWufeFykiXhq1nsgEr64Jc?DWAv$LiW<~sCv?YEiGzP)G>H%k)M|Zavq_za#FI($ zq3Pw3_<0hlE3dwAgyQ*3q=M4cH&cq@$-hn?I^p0D9y(#`wg8*X>BmFA%H54GM@MFz zRKCyYlm6=Q>@VSjJpG@-!T$`Eu`sYP{Eu+J`Jb5_&i`8`M|-ChyA9FJw}O3q=S7aH zkd^bxJ~6se77Lvgp$rIUc_!4^$EJ+;r_H)cexCf|(KW0~+Nph6ii^u`b1)!2pVU13 z@pA^|xe~eO3gjF6SC2<~=Y7>xez#iW)#TZV^l-@T%lW>#t7{0fH@OjhRG`hf8;fmn zR`4|B)@@D=epTPTwXls41om2NItucO^I4`cZCKnQgnh%__boeKJwD%mehlHUf$WFISr&p=@FMKFw^=S#9gX|&|l z7Uiq`CGFgncF;}hrE7q*CwI3l129?-^|mi|GZCrV7OTsk8;^h{d~TJ@Den5rxCYkrBGhzvR?bHy?ZO@+EtrJNqP6bv&S-Ql0To9p#uIDx)+odt_Y6XMRB{;J(4292MXH#K(cK z3oj|1{Y*W7Vcg(*BxxmR*nFcEZ*AJbPpJU3+>R-u{diUEX%-6-b|L>$i!k|t8dQ~R zamXM%=EHmH( zvN=prCJ#h0eTJI=bW9@!ylc^gUi_upcJs3tZGxW380{44i=EZvA zgnzKc7uDt6jjP+#b@6>9PAi-N&zd;ip>+BC5h}jzkA;^L>wgIg_;-EUJD)$AaVEB9z;ocw+WmlF+=O53J(hb z8_8HCPNIIZSzI3oQ}P|^9mdW21SGX1OT|l!TI_=K_N2|2H9^%pZG;X%mm{xg7*A0r4&q$hOT=qyvdCze8sG}9Ss1@X|FOdv?BC5nm z0NR!&(>Eox5jdp8KO}C9qD`SJPN`i~%x0{snPwdsR^!R(usws1PH znTqCEvVOGAO~uPJ5sC*NUUV1<7yM(DQIaZ_OwOQa)pSdU`ADuFdBe9l`F^Y#{v4O` zvs!8(3H`mE1$}628_ovo6JzRCdsZ)KUk+6uFKnNzl{-DoG-Cy7&uXT*iRD`%8;P4k z^H$iV?O3d;h5v)Pau2q})*CGr;Lm5bXeA=S*dGT$xn3Bo0n*=xipGt>LzIup8%}V= z12F2|%aP9ir(Q*;R#;EdwLL+7LAkgMm`@j|XUP!(M~~#|)5WUplc|N&@?;nZAG@0I z733vbhN8ieh0+*ZfTF;~p(Od%6yJf!{-A1jdx-idj_o#*DX5Wi#| zn&Fd}yTvd>1v)XOm`TiL18cm&AtN;f5{)!I=^!wNlQU0^NNK=`NK;c9Y=k@9v1Dn4 z!I`htM$k$YRTxTr`&bbkB52O}eH_=_Gjx}r=SYII7iO79K?Deyc`y|+4_g>ko=OIF zB7Cq;&whL_#mxBESM~EjF}ddB8KVkM45REL}Y{2b3wXYENBA zn$w0fo+nG(E0>}m0@UFuW-W4*xtyRc^nubpR(O2(@8=wX(HPo{-_IuWmbK=^h;E2f z1hb{v`ZqY>-YiL7fq|Luy;M3?=V1SI1GR$>NHCu!Auf6Cs{y7f+f+u>JFrE&Olo3ek9h-2o2|XL zrjcwXUI}920}+PH9iKy1uhHNt3g9l{(F9-EPNqBxUiL7ILCZ!%4iYK_v29BvXkk#g zGP2UxQ~=TPL0P*`mw;nhF84ln3z|LD@Y>J4;=}Ka$A9TH`0R#b#k%b`>~Z#wtWn@I z#4fpJ9k)7r)-8_PqWsDs)RVE?(yE1uj45H!X8Kj$T+fI!D53+Aj9T~QAGy>G&23N+ zw{YRhQUk2hPC-XLj_+gtfwH2RkAH+T)n#v>py)4K!jTQL6p$BNp3q@jDGRzOU11M7 zZYDKtad;rqUJrZoTjNGFI{oTV(n}0+M=)=%we|MYNi_G=Vwrz4p?@m`!KeW9`h9QF0)j0C+ zygdh}R2bWPFW9*R5oVg|C*>2c}#t;RhA+)gjQP8x9g+F2=i(3WoCjzMo})FB1f zxiQb&63VWt-_@!Cg3CndqVAriSCcXQ;Rw~YYstP^Z3l!!mB|yzB7%g7YF)AB5K_M) zQuJM%#2aN1%NZ^A+ANeBNhVDPmF}-x8r4=*0aIY+O?tCC1YIelo8wk`glC>Yjc+%0 z@l7P2_OZCsW)I)Yz%1XSHsO(Gx-#N`l@jLE+S$|#A=tvKXk&?@UCl#UObr~DEeN3k zdksSAqUV{e-TMR;Z-E}w+)n2O0IZBwW+(Y$sNhTEviRk6naEJw4!qS^OgWinAWyi< z6h2v+>I!0Bc^YB!f-HECjq2j+o-B5PQPL0dC8K@zN;cbm62i993yHROc8Bq5!Htb) z%>rpI^_6kCV&o+AS6j+|OjlIsEt;n(wC@F=4S3#P&$WhwaVlli{`wO%Ap~TzSKWd zp%-R0*7~i_l~JZfv+*gvZ-U1=y{XJgBlkP$I|U>N9}V1;5&oUVR!dbT*!Nt<0ej_) z1w$E!L#QVs37p=n(a78qih`w*@W_`b%oo^;+Pk%o-adv%%l}}1T(%<#LkwkL9cGSBK;ma(nam#F)duzM{2o1Y@*Zc%+bLcrhnd@1!=Ibs#1V|< z!y;Wm#rx((0>N2REiM@!lxGOEZ-EY1dGY` zL1`6szc}g0yhS}(-~@bYO7@pGBUzx9H`)MPDjbj?QT*kxEHu+gevCC*7OKh>(x(2A~}`q3am6u;-r&M_xKzSNMl zX1XZCuC=SXuXxW}R{hor!!c%xdlp;(EY`|EnKX&{_FXt#Ik)49JyIA;BA&hhfGWF`YRcr>hk6mE&MFjBW>z zM*Ciy-r?AXy7+?chVe=>8ihjuE_GP+v;y)i!+Ug=34bli=H){u?ZrS&dypXI4G`iI zS3c3I54wsZk6}P8Dt*P3y81a4Cpo=LxhiH2LXrrqg_RN#iXa2vvf*qQEiky^1)nbF@m7_*H$l>Dn^5F>oX|hDC<%x(^zj&Hjm^kKn7k;X9|yI z@K3tmag+>O47TE{4yhXX8VzYcR-*rNBWqPaDsIy*%az% z*o+@M^Gcfh@>CLN9-o}BH2}dztwn=vKUh^jd58XQ2VeExnF}FL^ zna8fd-_%uc4gM+wBJO7O8gv+?uPloO?{)M-N%#mNZXT617&x?qSU@W=3dy%tEaN(0 zjAh%CGo+a=bn%iIJT||)09q#*xl?{;Unjqd4oJI#dJhKySwD?iLiZOsrO0Y}magYq zC>jtp!uZs~io3Le!ytT^wyb8wOD9~2kTrg?Un@p}#sw1Kpri}cTdfI9aY{7aI~y(+ zAc#olhU{StB?Vgt(HyPcQO8OGEYQdtREh$e7b8)iMm-!|8|80cvR7`(VQ9eDg>|Co zpaLd=s#knDee99_^a)mtRdNd4j$V-FY4m_YkCP^vo^-}fo-&xnM|Md$O2mcZJ0U?+B z(0ernc{|Pm9i$;fm^(ax)YT7SO_gXN>cwABLIfO3ecj#OtXx zrQ3aKyh%|47XFJ%Z$O^6w89_SzpwM_1T>Z2-xoBmAua36ZAGoJ{Lh?s7B_|2osmSx zQv2Hiya~w>sz3$MPuGKI4VsW&MZ(Htc7rw*!dfD@HJ9eTQh?Q}so+|=Mr8M3jxqB@ zP?Nz>7bya#)F0)|KX%4|20y<$##h^R^ljpehQPPeyW8Yu(T_;AyG1QRY}o9bt~9$0 z)e-m>R7mP2w=No=Q0CE_m-d!_s_8I{iV=a!0}KK0JyjaT>OFFH7nLZdO&73yjlvEo z^qMrAFz&`NheG1E?c!nfo@*^!q0;;Ei!N#KK^s+Ez19bOCYnO`O1J^pI}l58@hbtw zeB2~Qgv+!IOuOh6jmC+0a8uog!io;79NXy^6YLc3QAUc_JR?0piHLRusp{o2`>k+{ zwmwqj3P=e{bJu5t0f!{Om%np-Ml|-+5kzM=~Y&E8D=j&|;B~4&D^!=z2GI6a%iM<`{9XZ#RH@D`VCI52qEM}g4jC6kX zX2o*Sj`0PgD0;l{@)8!7iQb9+JrvTT&Js)3iPn5NpFC@>+~r~3P6Kd&QP zB{Ulqh{~~lh_`83JIp1z69?Vxv1KX8WGf@YpPG&S)dN(iXe|Y+ul#>fy|hY(Ypt2C z&7Mb{#8<9{`ZF6KRPw*zn9&Ko)xufXIjH{S^S2d^Yq{K2)VtOf3XT?vi4SEv$chD= z@qMO&PwgX&#KmvPu1qV<;&Whew6O_m4h`g)XZk!bNCBsCT+5WV@&_*F1L15oUG9yb z;Q|9+&j63ocD!jb71XLzJ1hNpEx2Ri%R#JZ`f58Ki^RU#-U$SrP$28@Wiyx|-BOq( z5*jWlc_2Afz45-r#L27X)YK20<&ay~3&Mabf$Fe2lwtnsPT}+D^m=nYF1=mHmsZS!?ZJ;d9Jy5sY z$t=AnBN#(T!%Itz!~QUtAI`X<9Jb+853;B-Q6aR~xv`9eeDF{SO<=EBu3E5_?-Icd z-~}WtIiphfEkbrm^T(b#05o?beNYdsxqo^FLPl4e*~%)g^nzT;%*xWpN)?&@LNE|d zF`E0Eet2|1YsJF4V~mz5&MwQpaFvoT7O!8Le;`?f2=?13M$h5bG1QEow;y+0XZjn66r=)3F&*+Vozzt|-Q%VY+c_7A+QI%5Qzi zg234r2_lU2> z53%b;+yquL=;}c>F5(pQjVK~?nB$d?N>Z5E@>|v!zl3tEj9SkK*I=2~%Dh|OPx9xF zBZz!D*!_Z_cly8#rmYCETc)+Ug(0~cf7!ums>QeB=o((*ygrT^^SI6`9o4BUQMCYBZOstNR{{feudZH9Lmw0r zKOG8qY;pslhrfUvu=!wPc^&3x7{vzp$g{veoVW-U@4C|Zm=PHs3*n4*gn>Mkqdo*+ zs%qtF7n9f-H@zhXSYJ{0S}%3TUg9Gb;Z(ycbTOiro*(QfDJ<2!ZFkzRH?E?0ovBO1 zocGLE6&h@1Km04F--cCCWwS9`B^DmX@5Y5ckAqk1e_s9n<8S_(f%xC6pON7|4NgXe z|C7Ucts~up(}LjhDyEfB27g z^mclXyz_a=0Pr($P0+5^^(b!cNVcch&@_ELo0sj|dm2uRpS_}UD1N(R@MkyrzGBzk zfdk4E?DY7D&j+X5B<%Lrm!omO@f3HDf7W=cZ1?RORBkEQ(8u4e-fDjO{To^*z}as2 zM=-m%dQbnaIB}25=j~mQidy-1Q7}WW$=$gnrWBfo6UU^W<*AL<6h!YY9={d2jOg?d zQ~qZo{p>GWZb}fi*uJJD8^rlR!jGTZPnnO*qQ!?}zx#jb1@}+;)q$;#0;P(hSABdE z82bm~y+PqvXrY$qM}*iht~%Q5*nZ6p-2z+qP}nW`=Fswli$owryJ(W`=IoU*p}^sA}BK8M}3wXPmM2 znsXgA1mbg}|K{eh;CzU_=}c#Hhr>i=gfmDh6F_t7lg{xAN;(c*&WoEiNaoO^{R8;T zFWxw^kGnIadK}}<;mw#1mn=r+W+)?gfc$tTufQ;blh0FbZDVMJk09H2LO2@h@`BhdKYSlGMazT0+cip|*?4xWaI}E1a0H7@LP(>i+3*;W_ z80>59TlHSbfh*uXNh$g7C=w@BV2~mEWsdtkng{FyAkA5@;sVQt|}5JVZpWi`u_U+$dQXZ9?FUIirb3PN5`SHz+j5|h)Q7kAz!{m&9I|jQM+6WsLsTrjX}`$1S0d|g=*4(CEjHQ! zqv27XWx)8Tmk_BW<8TBgE8$JH82Cz|T)lDuW?>h~iX~@@77O53b_E#l6r^pjK)v*v z=9h=6ZZJ7+C`51wSHRVU-JQQ6DJC=Ldva1kV z`T_N{QO<2mYzD|!FwWTU;JJVR!o2E0{+}`kt1Gun3sWu5Pz?xF-qDX+g|adtL-dty z25n+kxGvLv6iA9i@jdF9{PM%+*XQRuSfk|Qm^W=sc1 zye^4KQf1}R3L8w}m5@B_gjK@VaKSWfaF45l98JtX-6#h%jtk&*Rcw&ss&6T0U!+P8 zU5tSpad&9M+8h50yOGzHyI|q)?h_H`bXDFaF?;&MjV&tw+?hMIl10xslaE1&kADUh zq?C!%Kuzh1k%?Mioo`mmS5~Sc-{`_?O~etFm`2?;KqQb$(q`KUnxe(4XhZ!B^DKL) zLl;3wp&Wp#HBw4{5#j@&I@q`v1TEx^DdC6%tq!}`4p!8OVhZnH4)NLSls0lPO`cGu zql}q|V9DzwVRGjCkE8Z2;sU^zrDM6?O@RkQsLeGz=rv6xY*F>e4O=%TDZ|*&KAA-z zL}G&EHa8>A#^K0_acU+XzuV8H(^(CffWOcRhv?3%vD%ZUw6zCZ?qKEUGr@UeIJ@5H z|2op{0TNdr3G+lxB^04`-zmX_f{&2A>p&xo8L|V&c&CY2M%%fE_iTgQV297FNG(gs zdgdcf=Npbs4Z9kvH^i5SAS+kH5ykRP+Z;XFKX5$G=#1IIU}0(BP69$151+gwW3d=v zT~>?R7fU7CLhH63=+?mJz?Ty!MOB*L?>?`Wn$CEjdgVjD0)v7}+8pTZAm&k)x-`3d ze|9%^ya{f5{qKh~ez^;5-8Xd+9Q^G59M|2Q?Lu_%{36)h^5r&I+d=llZ04A(AX@S9 z7g~xW3~CD;hYcr9s0r|4f;^OvoSruyhp~^#pdXWbDuV6bI>+GX6gBLXPyv4$%|AoM1f`5e3F(9m6kg5{Hvst-D{RH?Z{OS$OWnwbx-3QF~=$Z6JSM=!|{iw<5#Xs8}xBU{gJ8c7g zrL66@>(7j+F1sdweqeL^;Ho|d-l--cxd>s6R1`U7}5i>dKkDF4rdq+AAm2 zP6^HqsMCb#W$w(Ze-VJZBWrm*K2CwAM8S<=_A6~%u7NKBPI&mR@9N<{KJwo*k8SOa z-+_S@URorWcPUNKAp8cWH4E5|VhlXUI?Ck>FdNUV?vx$x$}3U3qJ}7>H>Z<}FgXd4 zfwa-nnHQWh6g?!TuOFAA>$V=uXb)rC@j_Pz0KMa^ua|1bf`OlreGg3O;|YIFJr+=E z@iQn-7KlQ{)E<*o4-87-3*aL#2E1hI%7+YaHvMqbFH-HCsj6T_?J=YRXY->ss`lmI zs}!BXt*2(8X4dBYUWU!So(C99_hm<)lX%6X5g`^luA-zY$|0w$R?rKs=M+?9YoW8G zNRVO|A^~R@l#b^6H3Ta}<2iexBB97$hq%&tov>GF0~f*pVS`rG7b`=X6>1!upCz~V zW2#t2Qe86sfuAG*9h84fjIIPp>D;<^;g}g9G8C;4)EGe*m>DP#ELNb{73ODVopTMX z<(Fuh3cv3<-On<1=W2mai^qHsTIDm1)pN|(PjW}5nE*1{0yO;HSe{|W4AJl1T%m34 z;*MstWml}_(53)axUmHlYAZIcU){#^&~BlLQir4-9lh!396;)c#kfQJ?QA<`}d7vEA`Kox849GHE9lz1)iZDRQlF;}mmU{g}4LL#^OhVG)pWQMurP$+S zBhLRO@FQl=Tn7tReA<3>`^YdM@Ypjt7NnTnRg=hw%2ahMM#72coCt2kG80vCzx_p8 zWJ$EO{~A0WbG>RZG;b`ryz-dO-dI_f1Qxrns`GnzAl0faY1DYN zwniZFtt#dB{5bm12Pnqk!QTvOYvd7+)oLu8!y(?^Hno^@_FaLibMGIG^CNHaG#^Bs z1|f{2zk6UrlQb!|!LlqvyH@q`msYF0)>^>`R*#@0`y;8M%B|g48Xzz^J&1kJ`S_{c zB3c1H{1@SROB?w?ZN*ImXolIdf61IzK`~5H>o@K2%wtM~&14zDO)3yE5AS44P}U#b zv#dk&`w%mYcKKQ;ZEDblzN|A;gI1gI8nZ-f;qM|Uwzi8whD6D(Q64!v351yD9_&7tnZ(a zR5I7&Q?#~~t?n zuVk3~bF1<0_8NTiis4z};0*%VmP4<06X_p=(7~ZxR?@Em$PQZf;P-nt2nTxeF!^Nm z|7fS>x)I6B#5s~q#X0(ohdXqI+PY1`ehhEX!4Rj^gcKZH*GJ{3^V53udY>1?kSpQOe1RDch?`KQJ9ZDn{0LW#8#J^Nn{j4YSn8Byt$)KAMDVq1Is~9c5wQzL#2b zQzrqHnWvqQT_PiLq%V{4Kq!IhI!z!t?8e;0!tv>ISMryGz~{JDyvwik%UiI;Oa0X$ z1S=#e7lk`}iNgVb_gdLVNM$KCiTyM>tcO_eyuBJ${CC>JF2smS%-UvS7=Z1>x{z>g zHN`fGx)S6-6LMJD-%;l_)kQE{F?<8{e0;x0%JuHkfi<9lcW?JQS|AA+6J}+?l|g1k zuR~B&xNPUn_x@g4rMr9qB8g43B{i>?J_NhbnCH_sDwa?!q^i*6a0U&vUtiMTb)MEu z3?I$Sk!8a=6B&QEc@Z=69Hz|RYp{RZRs?!L<03qbGS#87RFyXyM)d15s+qce;exmB z&zn_N9Om~i)V>7)4xDAn;>XR1edhH2`f%?&&W)FQYnwHD04b+spnFWEE{aD~?JC(y zEAAHHqT6y9c+%!y>SEmBfhwhSONa^1ni)uu8IXF9ThlMY+ccPj3TJGhqRd(!@31Dw z7@YO&rNRn)`*huofVbfqcFHP3rG+YmnxTTs>W8S&V3eIBq57QdfWPhx_H;y-fQ5AB zjc{G!u+nX97DKI5F?Q8z79P#yIQg0IxZdby9o5w*mMl?r1#?8d^bA&KA+KzR;Ln*i z5B-(}hL4Ma3tq0vgv|nc+o`v|m_JCFcH7@lW{`_`y=+{MFd9~X!dYNBF7f1yHh@qr zwIuu@`bM*4?iLxW!C^JF+~MNlLZ<|0b-QpL0fR^OoH83t*Ncn^7G~LWBaN1I@m<%Y zx09ODWNI(zUILA`p`oEatT3sz+2tYb6C!}q+(s{GGp8~YmPglTW9XofBV}{K)$@YR zkmzWG-TSqtB|QW7cVyaAT}6Hodgl^1gTpHk zK@*+uxBFXo-|1z}Kp@XA@xt^eXFcCT_RrD?l?D_09X#p4+2j!%Nr9@uxom(%&cJYhaXN@k6v+0F}%7j@4ofHhaClT%1E*4nLK^oUWk-{q30S#l3nOm;3(z$cY zo|=krc#2ak4MCw@qBaSY-hggeywy|#U0qgCdjWqL^c9&5y&cNcftv9@fj!pM%x4%d zOfHoDZe(2???8x zxae(Oz93(DkAe3`9Xz;eNMba+1D^aT^!$WFDy=gG~)bhZ@U@j4*=dMSonTPyJ;w}8zY(d8tW=p8)Y_YwSPEz#KZ9#pxgTHUg~Lk3zP`EZx_q?0ToE)TiRkkCgSi*0>W3HdYy&66D{5Q1A09H)MVtT zDNZ>69Bwma*sYu=l=CW$z{`BjPiw~72Cg-Y1~CiclX?zuAs9AS*p6odIByaR0&C>7 znUjL~2&Z79>?^|$0c=Zw$R%~P*7N<47f3WXN~f}a8A2?#RY~NV{sdXxo#a2g5Kz*v zz$)K67M7w2J&6Z)k464$5dV8?N^H-R{+5wsuo!V|OQXE?P1-8!xO^J8f>yXUMfHd0 zFYi)T2|sc2T~YG5rW%tJXM4j|2gYdTceQW+3Bu~3)M8?fn>E#7nI#C5L2(Zv5Qs5( zQ+0m9QR`o3i^N+zaK8}84l4-S&-eG4&ODCGK%W=FIJ9m*`+b>?;>(@&`yR+|9!BxS zQjbY~ebQ_DsBM*{7!;K%k@q6R>&lqorQ?Q0WVx0=LY|EaySJ>O%9;lMsfpqBNm944 z%(#TuZ>x62kkzt2k@h4Y#M-uEqb74NQ3t1w5B`ZkH&U$bsJ}$R`>yB^Dtd2ObX>MH;vM9cN`K znipEVK2&g1a{XeMZ91URT*&Zv^k_qK^H8=C#QHonzxMkkOrkS^&?fKec+u68?JC9TH%TnDFevFgN%UGu261h~Y|q z9`EnP<|)X1`-+l?Pzz`9eD@z${ENWE9wwPatR%;Url*vu`Z@NH-m=iF};madPPSQ{0(Jds+{;dqfEiZU+N|W z*)=-qPy6CPm%-yq7qz6&eKc-<(}dhoj*C;8=Q!!PrE zW7<+rM!%mdMjQs*st}QI5=f6L*wb~SMGG1xam6Mt=%P0Bftw2uHMVjBNas;1-cMgQ zc`UYuhN~H@gRK}0@KzxS(lXAqdi?Szn|HcnB+DWcx|@d0Q|xr&#{SIt{Nlt@2W6iv zLokKl25L{XeAF4^i+7< z`};QI0wSye3*2ut3n~RWxQ~?<;@bPRIfo|Kc94)YEEZ_Y5~(zt!t5?jP=+a%_Jy5M z5Sjl(k~9396U>AZf@yJR8V}wcVoUJI0+|6Fa9!C70 z=VBldx|^s0r5n^W_@CWvyWZ};4)>qioi2`B0{a`^y@r_{`#XPw??;Bavu}+ZitM^u z_q~~4c5C&^0kk||X%w4}dyEHR2^W&r=FJ$;7(KCZE?8BHl8GXHB1(`;U&A=llD7{^ zhL$B#sO{(9MIf0_&NAGUjBTTYsa~}^+eESlLkPaiJF7U&rT6N*oe$PvJg&kk8cGxVm&Sp}ISY5rMy1yVRO6@5fd zg;m{U+=MoLt#OcKq9H-{X80WUjxd(f2z)U+ja0cp2D+2Y1wD2iQ~}|E3NHD z3;it&0$^eP8cZ2FvCW&>dKJ;ql;*2JI|?uEm#y6NJTJJF3d~L^+55O9N{d#rf5Q3M zZ2+3(V>u!<*!Nqgv`Pl{sP#gT_LCDqSnK@hG!cZU4@EcH?GFTkjbk)8R$w~hz+9em zV@os)hgBXApM$YkDA$rBE@bwsVDi=iG4Cgp(0S$2jvjGgHttD8Sc7rZ<`@({hz2X1 z?cvCDjGkWPn>;t#KP4>JAQK@#>s7Z{0HMvSW-tSXs2OjvWLp?JyL@(a6`d+xMHIAA zYKqq!LLvK|F zTn8f=%j!YS(f3_wBK{^xQO1lES^_3%x)`mBpGN&FNFv5bbP{+^lwc<>%WJN`EnHXL z&Wq(C{Srtfh2&sC-K^s&!~D%oQ7XToksqqd5Dh_ehP8Y=hIZ03HsjE)aUw@y|7TU_;SN#GBY;$ zFRS(*zefqen@vQ-rh?;b?7i-w{o`!t*T0B>gFT%P7BRO5q_N#quqUiZVwr&LhTM0c zOI}8D_F9T{s;flNh!cZcDY{!cBC$@GF4uN~aMqp27RZDG*jqObtvZ53o0&_#drHz4 z7lH_aF`~1gUUA)#zUR>BFT=0|XxLO6&3R6j*UApjussh8>5nd%7F`YfLWOC%2W^~V zJ5Y!ks4-9VejnZ>Z`AJe3@6V&yp;s=Odc(!)Ip?IM`^4IzJS3biOqeV`^^SNslb#fJ6270h%q6zrz+4m zq1Mh-tkKBe9lpQm6kK0^xEjyw*_CdT+JRvg8->qo0O4Zk0XedK-g3Dd9D(@FfC)Bl z#H{GsHLRC3`iWA2eBB8vfd}240odvOek}vMVMgV-(#(DngAHD{B16>|0eGlE)|Yi% z#%sl{fq3(&TFUisxk>k*{?B76QLaZKROl@oM@X_weG9v1Iz=6dt?s%G+iIg*hh=G6 z?O?Bwbo79UA~v1{A4O8HV_`l@wYB(1*T9_6PxX2GW2cbTy)A}Md|h8Q^Y%v%Xn%m( z%H|?z9Z(P4zct_<)Uh1lt=#B_J~$>k3k}(~jl^nM|4MAw1otvh`wV94>NLa|fvK)f zM-($o#Hxde6u{=&9dRk|ZO}+9>Y~2%gB_Pnf%ta5G;gfw`exq$k|d~ezx5s--?7mJ zkO@bCi|ZA=G<~_l`+fgCAAT#VmFxYsDou&sONOL(dS`~D_jWhq)D3?m7~b>f+^Yjb z;nN2K#+HTzFwDjP-%@LYg(hcA0@&De!v;h`Wp>dMyA2{N;kCUJ>!N9f+0FjDZQA3; z9B8$NRU<5yGNB|c_1&q8Q*lyfE95BHX0_IMfj^x|Hr|!9*wv72X4pY;U}N$3QNmje zy09ylZ4@AO2}NhtR4Eg!IhZw$7A&$nFq~+_!>F4pNONytxurJbn^{P@YxP9SsXr-` zz4{<#f}}V+(hPAOWRKm=BLZHb6`V({%RNX(jbXDglh(kwCN*{Aw78X*y6}p3 zl;YJyYaH4sX8qet15{@IdM#^Smm3#5F~?Fun<4(xpgkWH%r)+$-~UBG;o1l8C2CZ> zK)`lnd5_^y8FS`(9=3Lo^z_C8{hgM~$a!*dOh5^jySSVHMZ)ODB&5jq3D zCyW_7GrqB%?O`9*H>H8n0X_Q%$4m0+{(IMNZ&YGrH9lM&UZR`$+3EA+IO$u&kq912 zz-)X6pI@m(JMQBa;_|7YI|=Du}0+ z%$tmjihdtmynjmH-`TJ@=QLS1GuWs&Kh=U};SXwu$e4Lc?hlBPXqb8XqV0m! zkivfG8lJb&GOp*z+~=woR3*0!XQ@l0wN~l%0IdFhZo6iF04NdD1^-JH@c(sCSQ(lA z|15y%f9aqw{l9fk^tO_4N07h-ZZ!UdiZ#!p-Fn)cV zE^IWhAo*{{_|p^E^Ye#8>E3dj#n0W?j@U79-=?tXXz{ys z`R;+4^|FrV7hAeFTc8A7?RJSp>e(6M!w(k0(_q)jbx1A!jlDYf# zXKC@u*}^UtW7O8*#`ISUjGOnsx1Yc(=#Gp@=Wb+YRrp;^*xKeFjJFa<^~~i|Nb?U9 zo7*5vfdj$5y-50Yd~Jb=K7MMwxJN~GALnnb>fAj@kKK%R7iBkXFwLgE-?={*yD#=U zKz#iV#Y|X8hHr(=>Ruep7>zfAA@YNVzxTq~ekhs)4ZJiL7#s`q_N+<9)YF<5b6M^- z8xHzfyLv7SIaExorhzTbPldDI=e-aEd@xe33(6F^M7s#`Ky;7C>k5S8ABxa%e0T*>{q&KG77 z%4)t4Gjw-Y<^rN#wqCr+c0=vVBb{CVJ*$-Z23j7{B3b7Gx7aw+xVX@%4;gS%&vNV( z*HmYe)Bfoi`m0l+lgb9|kJxPit8Y47&{OooIA zl_CIRgVglrw^E^ye=JZAAoN_0;IN64t*libm7z!$2a1r>s=IM(jPsf>Rt>2h@M)?D zgSkiiiEem(1`xM%5r$-VJ3B028St8Io;-F2pW=; zSrq_;&e@wy(d9P`PipEooQGHcPu^V9uT0}Xb+hvea-Q9TPJI12Ykb{ocdK!V@&!7C za~W7)$jc8IqGc^#8M{^19sHhye()?fN0Kd~9G(c)KI%915mPuy0!t32aL_*8V#54Hq|xL0f7D(Nm>Mjx^itW`FZbCzTT;Q?*t$U9 zXHH?DLXf)4gH-&;&#|_--M+7p)3P%G0Z#9qtJr@Jme0QUzQ3T~+uv8GxlIc8_BYeX zpJ-Di-ikZ1VjzV}4*;xZ#sw0(Rt+R(G)i5=|L`;DVQ5iudjZID)yPGhp!yLTk2{Cq0=2!pM#E$5dm#gm`LfU_f>1^zb#o+g-(fB) zQ%pZ_8Vvrq@KTH1Mmx4E~JmmjUxM3BE|tBH4>mE4e}3yzVmk@Vr$QbDnlF_ z2lo?1Zi_ZGWrS87mze&xEkRTcHx5^8)EUZr$WeRkVPchy@gcYLf`P2td^1EWj zz>jy5F)~BpM(o|TOln?Aa7+o>{=YrAyfgV~BUqEc3d%Zh;`zB(EUVS#z%>k-TxPLN zOx(%cU#%3adxMAT9N?hxhH{gN9K zu+&;S9GljQhpru=dr9LeveZObTu*AnU>p7OSxThXEC)i{w95cU+tPDZ+!IFMgabl} zcLypMN3TUw1o-j;mgH#+tc8k;@^B)c-x%;i@-*ib{f5dr*U$Az1`Jm7S-0GD)I#6L z2m;XWGG{FOc@$k{L6yPQDZXBK#1lVkf(BqLFn^cU`GeoF&G!ty5214-0$-wVR7V79 zVwGk*BwYvextca;L@$-x;MLI2m9-o=)4C5aA?9qG5RqiYYQ>QKyy-6o8t}6wLg@%!pMGdMF7mqJpryou!cfMSe-Si7r5l^s`BHl+NPi8^*-S6nX@vCKy-Gd7u! zzHIV(;*t|ZbWNHS+0)8ZR)e6OPv=5uD=ZJ@5aFP?-2ZsO8q4km4dhVi>E9u>Ouf;Kjrj6x??`3MYT%GKYPI#>E7Y;nzyoE$;7qnf5YFd&);w zpLdA4t&X__)hi3PJoGXuGlK3x^Z`#^*_9SBkbC4EUKfkzKZ|4y@iWBs)w@>lIEzZC zk%(?zkS<8>Evy6+gjH>|b1$zp>sT%$D$QahVWhnSTc?A#i~)kI_h8#Rn$*Fo8QESP zhywWEZ_)Uux+=eQ?wi8K@5A#{^CFqR{8DYPZ9!$0he4AdtltNUmV$zjhE@cH0WR;B zdcj~if}%Nss6KB~7F(SNE}ZCr-sIDe3KrGdHCYHDJS0OfTXf7r*^Ut4z0jZ@;EMjQ+m ztBa}B3l*VAC1(qs%B>zM2;Rpm+W=6*bUu1*F%@XAr4ZS;y8{;bQGK>$GpHr;>b5fc zi5z9D3@>EJ)p3#`vu-_iEtbkfK&<^^lo;_)6`t8DRR8{QNG?^VR$x{VOL!e?M6DO3 zpi0Dg>55CP;>Yi=w#rJ+ z_y}VPoN~$`%4`0e7HMY3wvXA)l(heEaY6~Xun^cm%#BmZQBRiP0x7VG$x2;&r;3&(}zUQ!uoJe|E zLG~zc*9fTrv=IK>i*gpUS15PQvQYn9dP^(wcm1SpyR^~=1d9C8NKE5n z%RCxQ$0pF5iK|1U*7G6cs>m*&oHB9Xo-JEW>KG9TD}T8?jh`q;b_3-vQwm?KYX-`6 z%|iUyI0BZn3$1J6u5vVuXcRyL7B+2_DNiy=_g9#c@8Ub@6tz~?ow`a|TINh6vos8j z`U|_Wf*Z+LxMi*ZQ`vqqohSq{RfXv%@rOppg{k~A<709p@_xDr32)qJ$qfxB3KI{k zDm_w~86kQQW|Q^it@_*{avo&OyHhUTg|D8uMdm_r=LS|B0Oo2M3Du|oP+9^xJW5}x ziG$PSMO+t3j3~3K9J0prX%I*Z+l?vPFxmaqje36v?kNm^y6#Q%nqIX7ieptIt#Z*Y z^|5>`zTZh147x4kN3;{Dj@;I?>NB{>m=JRkoFIr8iyx%-gkU@}!vnd=iSJQ_he1o(IiUI zFio123}cgfF4UZos2M*}th#T@47Ko}kP0FPub*C3mfFy-i11)J@SH&dCM`nCerix0 ze+mj!VS!%EYt~|)VqJ^HqCn*sQy&jp9Z0xdD3h!-X{{#lbMY$}0|mmbXz)|}cRJ#6 z?XpN9qs&T&umV&%pa0=sK(jfF<%pI)2RmgN5V68F;m23QFi_M$kE!+r72VPZCDay$ zfc!h`Ga|L0Kr;%2*jSG+Ynbm9GDH>*j0eV?e05eT$kSyV5!VP@C3ESO1?$mgK#h{yJ!Az&kdNuL}8Au9tXjyiAysnJ%C(>%P zyukN-ODL+e_L}}ER9oc2i~2XFjBcH~DKk3zSn)Rfi`uzcp&>66JB8^o*uB8Rn-gRT zZ623)$|&xNdSkhoc}bKU!#Gs&Pv>>ulh<*h_cg@Mh3B1HL@`)jC^r04u=VZzt@WV2 zhg>sqkN7NZi#$QUJ#lof4h3&r+H#Hca?<=&acXgl-~Cgh+=*xLMAp4-kJ*u>P`|?G zItWN11cdUi^j~FL?fZ0127%SLi<9Zbc(%00MuoM6#3S7wjTt9hnE+&^g+ZZeX| zY=J3NZPuI;QsavO=Or-A=$ITwne!a{>|d3|fJ-tf1T9$l1xMPpybIC(Hziq&V)ksm zgzax^6cL?!ncRD`!y;GQkDg?OKb5_1rcNHc>A6fq=BBo8-1hCRZbnz~0(~PjDnW>y zQt4hmcB_=jN)9Syc5zLB;tA|09%wuCFct_7(mGeC_Dq6#-0cMPt7fCZ)ISZRAKE}? zD?&BR!OE9@JD^R<^16W>JOk>W*1T{cgvNMz`ZMy^Gl!N{m#WOqI6>GGdE8NxHF#w* zC&f}l+qUwad^K8_Fm-DzWe#?6-fLi4yo8fJDwOa(IJwV?E4Ua^by`uUBhvP;;aNWU zpXenIs%+Z{c`vRGFO(b#=NT;khTE1-Pk>ZA$j}KvUzaBbR=h8aUNW>kD}q4&pnI zM(jX#`0CCER9LT_`yt}P(|%e1)r;4{p_Ow*&{Z)EJovcBXH41Nu77YpRYjG*N|cYW z{NEqB#G&W)`xps{zpX}Oj@hmuTb+d#{Vx^Ze~yJf(ZDNs!<^Ypia27)XBKiQCnk2f z&=!gh)r~Tv~MiA zmy5CbG@mZ0x7;;ryKgRCC*=GoWZxB%s*uf7w-H4l+O@q?tR1+fD)bes^;-9PFhhw@u@% z&EoL_z2(pl`>*s8Lf;iUI!Wje1(fx*@cVGvy?h6#Za#omj^@Nw+#(pl_uQ8-t-NzN z3EI6u@R9oW-i)zccj$R1S`pObd%B=p@OuaWecIZX}ShQ*7!;pC{cfNs-6*88*V6o>%=y zC%;_wUHJOB6v-1JxExl>zVDb%rl@)G6;HkzZU~2!U7nJ2#G37KeGs%(#y|bf%`4764{@vr{ zdOyVzeO>E^~g$!~UM zuQLPP>l>5!6H*c2sR!;N@UnB#N2W{VVFY?8-6$l9Ao=(2;R6OqRxy@ia6E|LkjzoY z2+}S{El}$e;J@H416)$ryMV^BJLRE5#y?rzrojzy)-c{f5-{gr^ISN^fS4~2#$YGy z%x&r9PD!ohV1rHF-%lP zD9v=og%4^OsS0~~L{FQ5@Ve0Ux;o7VJY3y$a9U2jdlVdR6H7R4CWB$#*ISG zfa(CzLWRUPFAo+rT0Mc~DBo$o-Z8{kFk1N*@r>5#hvV!G5F<@uM0E$1i8S6+g?R9k z;Vn>`L3$_4WDTA2*gjRV>f#w3P;u1IC<^h&O;vw>qtEl6hg>@$L&61(qrgLYWTmeY zr)-BabWju}6p6!yL;-rAN(vaTH|6fr<9&mdN8(!O14eeH*VR^gkpArFkWJAwx)T6> z;!&L9!{m$~ygX+arz5RRw5?QfIqLssRW?G5B>hy3F#jN0-u@@CfV#RefO|`0B@9 zI#a?sj`>9mx&I0$O#^P2A85o7l*jJI$z28kALNor5fVCw6t*vmu$ZON?^O%~);eMc zMl>!1HCoJ$I*igiX|(OjNbQrX2@EIFaoQdegAodze3&w?IU1Z2VAsYodH+apUD+mv z?spC;NQ_Exs;&rq{HF|>8AKmQdz_hB!GIO`?jIj(PLk~jF_t310S>DG@22TDRst04 zSk{9n>LSPg-%M48TrDibBl>QFR#oUDaULJ$lBkt#Y^M=xh}z?LcK3b zFyVKndVqxvrxab>+Quy0tURMZ4p8zQoC9$PgTWU+@|35%02}tQO5@?U4Y5bhZk~`; zN6Trp7IylWD^|=kcScX>wC@kL#=?+O6m@Wn;&EBr z`)tG-elO&r+Hcz-s#wfg1U=Y!P$!ss35<(KVawE_m?>>Jy>s?)AbzA@Yu6|M9+FVt@gyW&7-<<3d6W=Y7k7z_Scy-W)KKy_HLjdq{-~+YtSFo zFvt~fTLvu6k(Fkhs*hC+mgTYta6)&hU>0`odUytw_+@;7*a!Ldt%^k zA3?`akDntfM|Np?=G!iGXt95NpT-yT9s7Pm?udOd%p%;|D9`A>(E29_0_L6zEXH8_ zFcNDw;A_~!#R&0_<~<=GBpKDb@U;*l*Ou`^U%cCJ;qah$_k~Lh3qJ;PB7*_hTL(m7 zr)C=X6!^kT$!m}N0tXaeX_~IzHh)TfoE#6duYWRRE9i@uL|g2zYy-RA2yt$-$^T7V zguJ#VCRBw;L`ta^Ck0wdklk-U(J~*7)-Lnx$?^9ITUhM6dI_1A6Eotk1#PduNMN9# zzliZofQ7oHwBI4kh78KZrMzw;e5OPwMLJUm!Lg-2U(MwrI|1NW_}tyV`7XAp3V?7K z`SGH@8E?mImY%q1&1WkS&6i9@cof=AruM@e3*A^r$BTQq~?@*eg_!s=hvEib;}I-)!&O? z$Vp-!L8N4=5er;nak+299LNAuJ4N2%KbvwpBo_?|cYsGk4LG#?JeT)PE@~VlUNk-# zpJs|_6Cr2XhwARjCkj93Ws=i3dL&HFY2F{g;frDqd4hrp(TvUF>l;(!qQu=1f>BWC zN14h@8Bt9v(MOx({$Y~;XHAUQ6)#E z&{@u-XjL^0(Kxfw8|dl#IN!U4izh&C0bd*<;-H`OETTKxYF@pZ97QwW|Jc2L?}V3O z7$EmHPoMN2#aKVC3^ch~v#hM@xL6kz)idejlCGaO8`f@K z2?c;|WmM%wbx7x%zfOpXt zw=nX-i68P!IU=J{hHk=r+cpHRQE@$6HC5|pBXYtCGL&d`KYa7!{wsEmELl(U9y~b> z7Lw=oIq|-!(A*q*oxUZzO;X)`(Y4uD{v>+Fh@l+=eW!{Pa|)uP2gX8osi&L`Z#V+w zD&BeWy#A>V{B766Le~)6S@U?QGDyA}uL-cVP~FF=~NbaWrJc2$ei^oNZzw zW2U@+(YR5#n00}u$&h^+H)qvbl`%m&Yq%qvuqxNQ;9Rb5P@6gp!(oJS=YOE9Y=$UB z-Emof>lzEH2g2QOVIZlLIi)l!d&E$U(p=OquhBp-BPCQBp9P$5YXq#iXB8d^*nrz) z1s7pA#vE00S0-s1w){X$2D!|?JKTuFG2W%rTw|;rWs4BLKE3n zg_sPhWoCR}36JK92CGR`<9nxw^p_dBmkt=xwcJ9l7}68jFHt$RV}~863R@;AEDHT= zM4Ya*q1ev^VxfIXw<5w#e1O83!4t#V0#blfoMMpAHfFF8MgP2Qb^@`eJk^fb1KPU0$r2!i=Hga|!vHS;m>w#9g?RMu+37ICTZ zNrWl*Rj=3gOH8dYx@$J50*8C_PwEBrKdau2G&jI~KP#IJT~P$0W*|eXo4Yq#4Z&l-ii?gK};!0 zhCTImQ-E_Xx1qjvpv+4{NJbv2_ZQkGV}w%RhCV8dJf=2zD18>--~L^_w-UbfUh770 z!~JNGXkuM-_D9O!GT^JX{xut64dg2dQR=h?=_I!xyEX*@T{f?FdKa$&eM3+WnV!Yq z<1A+Du3XFf*AH`4 z#*z(onKp+Owt#GOia%AxuR(#Q7j@#coXxP7>hfj(H{(s3yRPgv49 zVQKpO+B0sQWO&c)Y3I+A8L$cV7!&o0gIj3;k{e`XD$(Drf8t=U6He;MSfK}6AFC}j zA`wp*da3hal;r??J1jt#l)$>$IQVdbu03)#yF_36=1{vvZbx@RU^7;;&1&C2%LjK~ z(}lnxg&teu9IJBS$^3&==yIm8KkM*^LdCyvvblz=Vj^KW5vR#?Q+AjfA6e5%o&qc# zH-Tjvf$a}7(ilcO`m!lW?Qm`Ra3+RZ;CO>1LstknZGScg*sW|pA81H&Z>Jt!A+%Kn zuXxjH!*j8FoWo+laG|Xmx)s_=_$g{hYh7r%@TNT9z zQQykJLoIDR7=_3=g}-}p?1I9$25nvQuL8zIRPkJ=WpoI0+Nw^XGK+C=YMWcJ22^;_ z-6&iVTRt`{)uvYD1yu_S9;>PPBgGAB8-Vwmj78v633o8K-E;b}QL_LGqq543!aw{W z^vU7%@;gFIrIDZ;omOQTmRZpm6DBV$xpj#R<_>+@vd$*m3%n60n?oW_(&16AiafPw zl?U3t`orlhtc4h?+=N4*oXO@O?p+_xBTp|%rJt&E$br#+%hvOgNU2O!p~fT*6?(M0 z)e&6zL2YKK-%QPD*+GZD{&ZXAOetp>h_pYTx@nJi5GQ-j(+1&DN zk21CK!Z~^zeuwdwqf^(TIt{eDszeGo4?dK-M8Mrk#m!V$xJCSy3skC08I?LpK#izY zs!y<^@nWm~$$R&*WT@6i5?irnE~ieseqvk}O%V!kEvJXJ1Z}nnv_YxECq2$99h;AR zQ!u_wA*QG)Dk|cj+$zs!*G216G~d)dNK*Zs@x|cRG>;LJUlOe7hVn(m4p(KqG~WDP zCc(lRfa@H!z?jy{dZCu}$MdTzG~XsuYe+K^xU6Bn5LxRzKWIGymFI zBEd1JZwXQ^!6RkVSN5UB1_YEJa-eY+n0x64WJAHG811MKIo`MrYP-g2Cf9sZUPB+Z z#X6FnHOq@g6pebte*suReS-JR4w7q@V;g zDzJrY#|FRDabW?wsn80qRMv}DYWc{A?YZWY<@1me!y%iLY?gFbk3z`s_}?9A1cBoy zU!3ng^WGR6E2ZitV|u$8cy~Y-CmQKRKWu#SO4D9Y@ib8xUZ0a|Zq>Irsg~>=A^5qt)|NVP#{kL6ra`FBmlxue&|q`C{|2H%3~`+20bbelz+ zqfHyK<%E|ZL=wb#^xr9g4Estb=50y}MxHShYRw)Mob_}nBD#DH^=G#3sr#}20v5^gsHGR0M}uLT8vUWkkl#*Bn_o_R zxc%XvnY2eR)A_Pb^AEjt0@ z4-lo%S%)Y+NOs1s!d*l0qhQ9Lp02%Ec@QK$WIa9f(nW})vx^aSNw>ftco#xC_7MMq zVtavD^rxCROkjM!f2CC=f897#r5wH71AjU}pl}m%Wc}oW3&ei|`^(b>q~k|0+=Cpb z_nVQZ&`03~fMYq@PX^a(8nYFcgqZVXOdU*C)OUp%#Qdp6hVi1Zlbk-JxMD@2v$@r< z_8E$xozP_lsoM?vdnqc?Y*gISiwD7&Tb+csa!Xog-HKH^%;0S)^ylvz0y|NoS#*5T z-*R7+5S(fwIh|bG)yT-nerioVXGMwBM-%tI3-}+@#Hz2U&OnU2GORI`VzF*2u5azq zb&s5=o~aMM8TTB5x^5qQ+a9Hg1}4WMf%dezRc;WWCAT-OP<1~Op(k`DT8+%wzvJ!0 zbXkDnfaw;lss2VLv(J@wWk3{nx4rVSFZ#Xxm*wyO1SVNong1`ei|M}vCYk zcv5EwnS%C)CNBOE$)6`Ytc#pzv9N9W5+Wy!^jw=PW{?nlyRrbZ31yK$l6M$Ouz*`sTJ?!MvnpK@*`#DUaEu z95u6^AIq<^-~ig(WFEg`?=Of#CT|QJ@4GdeJ=)1e@G}-A%P-ny<>8`|anH8yUO7Wo z(W}>QWWK`&2L$j**@e=1-+3_WVl@P3RjxdMsY&b8Ma3-2bAI(s;q~h+&Y$rB2zNY5 z=B(qnNh_MI3a-yBJTr{0!)^g1m0(eDr zNG^5;QFmEQ-Nl@n`C@8LoUT)rGYwqm;jo!NRnjPTPFNPYWVKXE9NM{%Vwx86jb|Dy z0EcpauV!QM281K{FWsM2EyL5FN(<~F{M4X_PG;CV168_snp8AN^w)}L=W-^Fg$9~- zw>AMxeqwcOH(wwWbp5CIHw9pG53$!-1!3Vi+N8%ZQfz4#RvtL#z;@et=Zqy387)oT zf%z7oNlgaH7v{_^=h3bi;eRtratN5)cJn+Hr}ROYKKs{lGAN9 zra6-Ow|Nad{_a9!Tdfhu@)+$kR%{qE;7&sSU)OKReWcc^CNuWyfUj-b&$z?1lG zoCO>bq5{Y>&J~5T6(blBUoYfts68BXO<&qTD9D9lBxydF608oix2~xRMi+`stQYmJ z0+;q;zyeOP0*J%AFE0&b;*)oDGnhu9dZgn;O#Xqs3CBTb1!}KVU|a5h&k-_aMi@iy zXYEe-)S5fzm`tF`Y9E!?paj&~qZmmS{rx<(zA+KrZM!~1ZSw33GR=|%F^Y3v>R_$D z5MoKTyq2)+g;8p-)86DL26`o~sh}KOl+V&xZQtB)O+|G@3!lhHVW-sztptY-5%vv% zn_kK^v)G;_f0uq#8 zF|$#`8^{afiAvr7&>*UABo+%MQzCq2hT5su0%F&mILR+sckIVZr-R=CpE& zf3!1$2kD&y5fop@&_PwOcdSLa-7vo3*3Ddt@F3s~#lfn5LP2fxQF#hAZ^Zp@42J^^ zOQaWT&+Qi*$P5 zpuz?`x%myn^ka9)Qf-^S%sniwbOv{&1_pi`1^i{)^cvzD`t-%fW#)!V1eYKppoR3O zlh;^JQt9&$(B@5%C68?Hyj)hvhx$%0)exDB*x;B2R$}DXdDa|}?pxh3Dk3Vj1PM2F zpsA`E*aF4#2`cwCL6&Bu*B@=->*5ggz}5*S1j)(RTkDh}Tw@o-Q#31Np05)IZegC+ zi6YDK7i3LTNS*4%=OLR}`yqy`vq2@)#+J1Q9W z19Qte+8^TBa5ae+)-03&UEHf&CqrHM*2nyvKt4f+$ky}o`0PFszW%X1%*;u;BxKrt zLRk|Q4RomAILScVP)Ja2dPa#m5J6mjBFyoh!0b=F!uq}ajmi^GTn{NQzZd=NSwTA` zJ10P#tpsL>k+h7xu7wiOioO|brpyVl3_mGKR%d3EX+N_w2i*BXxp2M-!@iJWl5 z>44qEH-nfwE;ptXRC@mJmW@z2@W=rQ9mRfUDg5@51Lk-J^{e@B*FFF{=pSkHs zCk{)E5zqLXBK$6NU%sqPH5MZPS~GiK<1&gMV6pstA3KIs-_<>&)V*rUg~tnFQdWd0QHsR-2>nG+_|@EjpirO*5F!Y+y-$y)+p+V$gqae;?anT3-q(*oHAKDvAKuUXnA?-Fg0q07 z1ImSkua~2Vd(m39T@1ZMsNUc|@Z8wo%*rKff>}c7a%Y>+3T78_wUqUCF zU#iCrnxP^w5?OAKOQ7&3L#Zo58P=?UE6s`%{w%UcJMqcJrrLAsmLtF2tRrUz(Qwq7 zh-~kRDi?lPP6;kYf`w2ZnbFvN+%VF#3L$XgSsJ>aETftJJyyPZo99TeaIl}D8YFce zGJ$|p=><-THkwZ(gyw-^xg+?%4YXP9@%E>b;?Me3Gx^6}$?LIy~6+|!XJg(pPQ=6MKUel7U(jdv{WkEd3h0$CykZiMl(!s)Zyj(SG!`b=s z^WXwD*{wo*2KZU)bIGfiTMwF*`jkyyEw^7402b?9ps8-eu9OQ^#$wV}In}>wU>Bxe z#canjcB-!rctwILVsL&RjUT>LorO2Z^UtO*if>3LB&5T+SICh%dHWJEkCJpIHGVkE zVirD)_{dpSxtunE)zV@2hC7p0cR95v(?Gz|3Vi6;@qpLsGx^~Vq7`W-w)nc_{I>DL#NXBKhHm>6AUebqM6oez5bH3(zeO!Aw0=Hzs^YL_sdMlb# zChRiak^&UG{K~Av@2sj+3ov z0W@8dYRjVR$&2~;u13OX$7QyccW#~|QBl-`LAJEkIN~o!+)%@Vp7M_xlcDyV#ef#r zmVz-2-Rf-wkj_MD5*xi6VmbJR3Vsf#28-VXLtxMf;tuQ4YE0#tW3MJ<{A4-7@pkNz z)FjjjJcP~gE2v1e!k><(Us;;uk{K;u+=|B zC{SaN#`dpP{?ATjKokFtncIc<&iY1OevSmR7-y&6X;<*@Xb7P61X+d&yw}PYEh5-P^wyeks%(qk!kiu5Wo`|3PPo>XwK*@cktYVe(!`B#^dQS&wR- zS2@^Nha17IqNs%Ser|T3kOVbD%S({R1}$|xq_{WZMqPP_kz;iHMPcMtg8D%qaO_69 z`WY9An@~ZrFOlxJ>g=YiZwYd$zd?t+s5<{&G5H^f_@CY3w2k`Y%Z$rvFuv z=tyfU8gB$S$^Ejxn$WqzsO3uPxEpIWhz(e=)*u0=7cvbp91q|xnO-QS{oR{Wg{h%s z>guYpBJ;1b1t}NX^#te6&^?Z^26tLy;H>BS2VN4seoQ#_3OWuC6yu0!TXfWXWWok8Ow2eF$!} zI*hG^7ou9R8$ zM6*49o06_SNZHGRlfUqnpXd_eN+anLgzRArh1V3{-ey=WfQ&0USS*ux0RbWw_9}$Q z_TBPaI+m>f53vPNxO0C=ZX%v(_gX8^5N^TN4w_C+3e0J1N|bd+q%g!_NiqyWRWe30 znfqQ9_=U~i_$iOF9;4A6+s%to83tA$-7(q(VLvFZXxf@29@j^S54(sjf=XKq_GY z;}8sn7kF$TDKaI$ftwKHLwwV(_EV$t3B_;7%Yr-}SlS+q-u8L}w!2}_|oqwnOr}kg-a^W<6jXgL5;8OI41L<@VBAni44Kb@*ZTSJ9YIiC|k(5v2IECbU< z__c*ofBcAmZ_6{ELD^*5xi3{*(SyxbiJh)AsUX)QANw=6w`}F$OVnYkds8T@ z@VyB3*2*fLQ1`ShP=h%?`*8LF#v(r+FWT1IaJFK=oJP|vo)x8GTES_SH(}x#a=)dF zKw~8^w+M(a0AZFYZH?=v{p5M3)lX`8y{6@P*!?|35 zTrzXUByfM28>tcoq?c4XN(v&Vtp?I>f`Q~)ME1F7**wQ+5=T8Wzum!T2ssSw)}Y-s z8%Km|tPZtlG5Y*8H8KxQE`8P*azyNGq+vfkB0M^31U7VexZ7ecd(nx6u2n0XsP<$T zcj&%8!W&i}#Po>ONid7Im*rIOxX?i~O)fb&RNW+FZ(A<1E!gA?yt@{~Q+;qR@DR(W zNvKLGOOgtah7hzZ`E9?x1ky+3gG`%75KfEp2in10K)ngY&A1$pSBJr|KszaxVYS2?h=UG(27=N zk6y-)fm2@mb!^EIq@ zZ=k6c`LeCA@1@VdR0^F#=yrn`Yz3*bFZu;+2>4)X`Kw0!qhEhs2J!YKjm;*5h~B3ldQvp?;Tmrk;8SlN8v z_$l*jEcPhk>oSw=x6)5G8pXy7ZdW;lSSK60i{=mlpVqC)$hVC}khB?H?8fk*sKo2R0t%tF6j)9f@(BXQVR}!K6czvVd z7Fyae>5Z=SwVmz(*efl9-5I7eS*b!*Q@9qdcU_y4ozutmPDTYgzmBc#PX%(uhTh!I z_2&cqtHVvrlvzf{OZvw}I(F=t5Qpa2osGma(;tykb-d@q;(HJ9I`VyD;gmEo&S8(w zpM65aihpA}ACao%#Y&AtLOXP~#7>g7Vtn##(7f3L-`WB6Wnl?{dw1tKu%Zk04Dwt3 zMN&qu`SRLm^{@;<_yk|am{aNY?(dvR9mT4!1YZ}l$FxfP4IoN*1h)CZ`AsMHx700B zZ{%TH-xyepA|2?i16{>P@|k9kI@lU2&zkMR;{v^|kdy8UA~uRua6`oTM{TU`oi~y3 zS!J?v>VYM~3To5EqJswNsa;ie{W9DvM^g4%| z->Tk?1c6wS#zn||xD*1R7#9+8z^Wd|!wg+|n2AFu&JgXsIhiLl1;6~9q~4QO3e0$? zr5)O>*lrSIy7Fq6Lj&@D)$|VLpZ4Ot&oIv=LLp1#->1 zP@O;hYL{Fw1k%VZ{E(`!{b+(=iw|Tf(ASgBWWggxPuVY<@H7pz9~kYiq5H1IYw~T< z?4_|Gn_SG4nnfB^4WJmTKUot*HOx80nH3pvBAGR}=TLfpiP&Re+F;eqOSdHqPx0g> zYPbU^yv~ZYHlj>t(eu(N9O&ep1Wh-fE%g=IhiRv#z+;&~r+CwFrFco3@NIG?#bOBX z71Y8^pI0Q&Gbe^MaE?GUjX~p~E*8&GLR&5hf?QFPF1ut(T@=_*KG=?8Oyn+i@e*J! zLj163Jl6Zf3$CBGL`82knBB{-Qe4kFWU2^Wk!`|!kG(&^sNTvqy#F@RjHFm2{Q}5b zh^ZQBzM*V=Fs+ftI6Uo4rjzlcTx!I9n9neXHwz_?Pht>|jnyFci~H2-vFie3^_Z=Z z>zA`SY{phnW&N=V0*km+wiGK4y6#FQ!7i^7*Te9eP!pe06CN?}yq(!EiCS9f8gWN* zt3%`0kpZLfF3)r8x@|WdSUu;1nEJvXu~ft%XkEOG27F>`J=Of9)suP9&3m+gmz~yg ze}D}wQ%Asp7 zZ8p~n&UjhmOT4kbbnRi(*xE{+b@|s6#rv{LvZvK{ho-jsY8e;tPE=N+!|qaD$&NbX zC+GjAaWMZEbBXzXWiAbA zYsBESAhUgP^cWJD8Nv^JC?FBVA&LZ}5^D4c81q-Ux^TpH*3+&zdaHZum9H8%jGDeY zMq;3Vh+OFs3>o6<;q&%bbE0ZR|49GncCBuHP21#rx9@F~WazPxd^==(w|Ufc`2d6d zBXJl3u)4b3>ak73s}i(EzMl7oj`!p)5&hlG0@u#Ih{0wm*|^iT)3?k%0v40sa$WWM zNKu!i+CD6Nb|)kB2d>TVER$OP5r(iPbXLDAye9&YRIjrUCM>aT4Sf`3aBnJrE$VVV zuUYwU=&RPgU_cYi#!t5pJNBB6ZC_ZY8w9O-I%uS|U0>XEp}r0H>Fy4OQhLdH(Eb0R z^X?@yk7+|jYS=J+JX$+?>rgoMTxaI{m&L=o%n&%9-00Khi37JPx_rw38u!jh$DJUC zZu%0hr0pm&?3=p|=m)`&4IlUxO~mHp_xI_MU<6}Ce)_OxQ$AnVY9ZjQLmhsQM3V5A zcx>-(HR=j-mhbU!J~to8u)aVaEp2*cqP%oQSYHz#{sRf`M= zX)bl<3wLZUPFqH}WIu#v_tl&iNchJvR%yQWFY+1;IXeOCQH8|z^Vg(B_hFUW_RQ{0 zm*Yp5c2~1lP875y_c(NP$lPKGB%Yq*<@nF@QZ0exM=C22f;Omv?EYEI(dd5+jI-*Z zGLh0zSv4?w(Jf>@qkW{*dhN)R`)0#Nz1@b^FRgFVoR7yXE8A5uEV$J+f~2YM-&L*# z)`nIZ?svv^D>*XW3f;{egeMosL7;8UB!N74CHah{NP>)@&0pU&7-d(k**#~&zvG9;NhcETyU33xcFlXzP}UO1k1@!*y^Jne7%Cn(>!+!u09 zrY8D=*XJC>$>P7xq|aL$*a>y)O<2NUhpERk&t>SXAPMaPH|c<(0$@w*ve8Bv(*H`< zG~b**%w<{};voAwq{qKh@=~^f3H4>%OZ@F;)`l_WF;|u$dvED7>sQByiK$KxD1dE0 zb6{mm;9gm)p(lj{WqK@0_CpcLu7^J zRS866G#2Avl_)lJOqNomF$PTRGtnTiCK&tqNmY~8WvLyYY9vgiSq_*WI%%8LUc}5V z!yHS9vMkqhXqkzgGOC!*L}n!fhF3t=4#iuYeFRvf2 zO3u%dlqcm9zd^amK0_g3v8bbR7hs6Hh=OMy3lD6^55Y_lp}nwz;=?odh{kqt1=(Xi zu>Tg?OHd>4RELEm2BK5Et0aV&i)hqRI#2ApAXNbQr`_3#?9N&H5x~w~SMY|1!2uH~ zvQe<>%n_WOYH2uzPGmdCQa;%q=OuRr70JDtoG3lucCC;1^U$PqAc;vX8$Ihzm(1zK*wtm>Psc}vI3#{uH$*yE(}Y9V$RZ)eNcmHp zce6D#`yAN0ZH&U4g|sIt;n+vO-BNucI#_8WJ1-v5pK(uVRkP26@KkLuo=1}hnuiQo zfSBO6Y!|;+XGZB#2;rHx`2HEiX!I_&+5pR-cL^@wc0mrGrc2D}2W@6f0f)Lvfzm@E z9*^wcU)T>W(%1@A$riX9?PNptWNg>2kPO$$69xP&B|P_Lg5M5XG*LmPS&pR5iWy7f z=kqh=V~xzSKeg7&1>vNtK=@sJ(Q5UYGEgipNa!mi;6wKEYGMHS%er$FR7-q4{2?a{ zRPTxv%KvsrMVW_Czrj>493qD$_S+)wr5>*omlZWx=NSMx@z*(A*8npR^HMt5qa!k~ zRln$y@pY)T>b$7l{V~Gj$~>KMY%}&KF4TT3Eb)!Zy8UwZm1X0Z5yFjePzznZ2hXKR z3&g2$--+|MT@rBEu93T~bbqRPa_+Tcd%#y&xOHsRg#?dnv0|dTuqxTQEHW|##2N;` zDV~Pd*^0+rm!wlW{HV{kz~m+(E>S}i6S(^28R*$D zz+!XTZ0yK|#K zf0lE<4)3b9zk6y*NxTL7x_7CIAVmxro~s;(Sx zgePT?WJU?7gxZ-2oiMBy*IYN2CT9dXU5v#q0wKyDR9}grVeCe6scaNMi4iV|-sRAV zuL!2oSXfH55B6IMwjtMiqBMsD{EQq3_qOo*DQC?sklK#u0^FH+|WXByp2 zvH#flvI>7k6bLtDjYP@T6n=ohdTp=bZ%lwgI;2UD25s+)%xp1L0pX#{X&X;b{H3^X zoQSjB`BWy4H50YY>qm=R%`7!et z=t0DG&E5hISY*s5232bZq`VwxCLq@pxzZC3qdxW#&Th@YLjo5DH96c%aj@S8=+1mG zsZjNc`!cy6PA!Yxxlti0FbNe;2UGK0VeuCOs-&Kt z6hjyu*RQiOSgs72u`#YRrOumy9;p`jbk<@ht(9hUn8`&L%rf;!DX*KE^BK6)*m3?D51iw7j_(z&Uv0v=&o#{qolFe;u+Dc z=@@DqA_o!xRFv~;1)e4(4x}OKZigf21`z{$?S_nH)h#Q2-ekHh?StYP%P_E^-HqVT z>J(I1Q0==guUR%xLH(6is`h2M0v*Y%E$M`)s-KSBUc~y8cYt#zGRt45?t5ksJdoim zo#uXv+SiE8QfVHUp|IH?t1ZTevI`Gux%q1l07Q^9$T*w-&2XUD#Wtu}yWf7VUl^d? z?{GJd!Uq2VNbYkJSONeFwPi=}1n~)OGxkTcAbi&9Z+zE)EP1^W+GY$74i!{hTH%$E z^efocV%rqTn@Q3Jm^e;A(J&CIiZ|dKS)`2QRpGBW|G2JMnP1t`QZXdl0vKE7#Z>#0 zka1NRXZkV4gr3uE9MjkZZjmEOq<^`0e*4P%Y7k|i{#%-~lH6wD)DU7R@;aWL6 z#o(l&y~a|4sO6IPr*iQnk+w4ynA7gpC!!N2xn<=-E9uHA*jtA23jmdpS@M)qrrg9; zXyqw${VC$s*Oi9Byf5Pm4B}nSl*S@%F0si}cs*(cvM_bM$k}uUx@f4_foWJq^xPM3 z=qx9nR_RlTLB^|5)-d-g-&};xV{V!ehoNcCQ}_9lH@8Z?qi48i_0cH8!hQ;7sH+j* zQa$}Cpx<7Rp;Y1_c#eSzA$ZWZJm&&U=6U24-U>f<=}EDC{7XAtAV~F#M&n z&@H|@eJW-)C;m2OY4Ix@w(G33g^&=%@hq;AN(t%S z?rT5$7u%GQtsKpQ_+qJ|^C)U(^4^`vP7+4Ii$KQ>s`q&)nE0NVjRkPHH1z1em@L zC%zyvIuO6>yuQw-4yLwlS`3|DZeD#}dfw2!-EY^P3#LvGn|G#v@FqRtq;y0i}F3{uA*{ zk99Ae7#M;g;M0|JI$lVMW0Bl?s+l~dDz*heZ?$inzBI!ME>A~^NCj_wNkbi<4nm+| zBP!o4B8M?NeA}ebnJZnoRl7$2V2aTY4pX6}pQiBM`0<1mpfuRPAj!w@vyjid@@}-= zfcODK09CmUB4zkNOU4hVClY<>|0}=$BdY&n$8oST{vSJz`M=n4%>OGpZc1CL<{u1G z?9j$%sM~~{;p+OFn+k9#5Lh4rb112~>}&Ck!*+7En91@@ph zaCd%2EQclzD?YJxcmB3lu~5LwP}ccULO7G9KW(`uFF%cMt}i#b@aJs9&Z6|#1FI~O zTW92Ke6I$dYNXMrWaUJTDLNv0!NQzvSMuAY=d_|he;KMwZYL+mM7#Iwq`_W>;};~2 zN}VekLWl(@-=&{Z;#~=*MNCO!gIWK%cl)s}yW~QNPl+9=D3NUUa?k$vbcD$J)9s$i z``t&QA{)2Ebw))`z8l!#J@9mz5VQ`jVBaSL9a0EJJj*05-6X^FRolU&TS>UrM1w!b zzMX5i1i!h(Kq;fUT&X%ms76| z3&_71*HN`R*jzzuP<85C%nEg#_AoWhd9(YmCOnkBMj8x-e3@l~M5FAr6LBsgRjYo} zBz=WnBd!Dl7Ex)?gI@Ttz3@%%Iu{g175eH^-S^;Ef8Q>h$-f~geGIog#)TaKVlF&O z@2R(PDY6t~ViLBs41>&kJ0gQ06`TAjmRHubaF^8v_Qs*f`2&X+@>wq+BR+cv{XWnk zrPlKOC=qs_{%tf3qU@x;Ng?shJL2e0_~+0PNI5HZ_uB zJV-00Pr2Op0tZnTZcbn>z2V(-hSQM$$rhQ!2tMkGNq0jq~K;`P0??;$m6dm?p`YFGiJQ zHRcrGicl7#`06WIBu-7^e2E&AALK0ojV^T~sf@4fG6=MmIp&O)Vsg127OJ`*9FOWo z4@Jm|z%o5L&#qBiD#d`@#l(O8lzJA%K2>H}w0DyD<({bO!{wd!!y{u+wSdARF%hqF z-ozxh1)oBiXA6wlQ+lNM1VJMcHl{iOI@$;qocr-x1HDmgo*g}t`XY)SWQc3n4&a)k zHM`Q}`HM;gjzjE;yomMR-5knqXSK;R5g3(Z*%Mu7wzVbd0gW8`Q{hKS=wh?j?-9Jt zn6xum+IJI9wO=0WyN2pZ)9s}g%ZhC^dnePgg6ppGFBbmQsST0c`qQ6mES1H@@+aJ( zILklt%k_?0i}kr%^-X_5HlMf-dEFYFWCyhCCy*>8d6%(FAd<$9t&NofqJ?I(^ zaAJdT;EZuQ5u%mQMK{DhWC>Eox^z**KwHeOWT?!u!UE^Ssrjf2J>+d4F&pD32HDeh zn)_om{2;tJ21@Q~ggx$9%>tGY4(ylY>d!KE5);epi=26rG^6y3e!fMe&oVVJFNp!r z0$>&nBU2#3IFGiZpawbT%Q8g)Io(!hDw zktOhEN^DRHeTnU?KqhM<3lD$)#vZV;AP#X)Lo3xkyDR^dmDizW)|*sFL*=f7XCF=? zErt*=JrJAig$-Fwgz?^)Dq-Y6)X{}tN$az&@Op{NO$(iBi-WFVNwB43hbz(r& z2`V6=L!%L z0EWBo2kA2huX^PvAU?R>qH1v9KDt{Rm;LyUkYdaJ9|3RfS9mWSqj48X*-<2-75qv^ z?RIswZP#y-rdQx_k@+P?7icfQbf8S>Pi5Ts^CIm!;XO@hM&di7#`0~lfV)A4<=lyB zQ67^5<4wG%Sp-^Rxi>DVbA#r#;=Q6GgI&Y^Pk1PdOLu4Zb*Py_d0x8u2(#AW{e5sQ zKD&q@tr-16xRZOX*V?KV#Br7$!%P_mwT>Hj(}BNxeZf#Ct`5V6@&oYVCVYYQnjEYT zzrlG%DIj^9Hb5%Ry0z4@q;Dr37T0beS{uuj8FzT4mVzVB#3Q_enP+b=!%nvDHD71~ zVBB(#MMG6wH+cgvCmp*#epp6p_Yr43VboX5p^xMG{WMpxSA{-ENqeLEJ0MOEjcFd8 z=0XeI85Gi$nu_+CWrfIw@O+=h=NT#1hw5JB(5NaRU7Ej17abi@2?IDw5 z4^!Uf5l9;DJ@S+q4ViNJQr_d4j}cNvnrT}?20~e7i9c8wEB30U_H0%#Sj;q{OwU89 zS?(FSnP%2wOz;{6G*(EXQsX^v$A0gn37$bZ1sg^ z2-ri!`tSuU*b)THxw*urpnRj z?#HeWjXdp)uIuw`u*47j3Q>)1&lQs+2u=kccy`)_)t5 zk|!h=?Gk=-e{N29@oQNTTRpjm_Nl?c4;QHJZn0W-hMH7_!^|MEIafg8-<0}R)u0~= zUDwkTkp@MtO^H4ZHBFrGZQY^-xY{4U4#hy=ZTaMv9Gy*2{8E_|*lJxdVE`7bnb72h zDGgq29+f(u)mV&Isq7Ptqwh{4^o-nJO%fwQCiI=YEdey8t1L|{@0o~Bmvg&Y#3$Ux+g~t!OBtxk}JuM0CRQ7Sl zt`gH|YyD!INP5yiR=zTShafl3=$CLpO&L)|Ldm+YRKU{LX6rc0#4JLxmKkVuEE|;W zQ@dDw?mU#~id&2LRayqGE?^FdVUEA;{wqkJSB5va-p;K{l90h3lV16B+}stUVx0ac zsbD?g5(>T4PL|d7UXwqnaS?30eVmz5&1K~L*7QV&D$z+oZHhA8jHgJGDs;+y+A z-ktb~o;!@CJad98jLHn6C;nZ@Eiipn^~Z+V0EQ>3BlVe{9O7Bo_!`7+=zWa*Zn+Y} z#EEX}ukNFgo#=;ed9L8lFKuG8q#soS2?q1LdaNq3OO?JL0{KPolp%yjB4JMYf%3FU zH+uRCzO&-iquGy6(RoL~`6F@$uLV~|GoO`B5W9EFGu7=v@tFp=vk%DYKw|v#p4AlIILc_R=cq(a{i`FOCa>`97v6FK{_m%E`0`W z!J4kQTwLUro2eTtAR$4CUbGy-Z$xBAc)kCkC;!LJWoBjL_&<7*<-gduEdMJz_ey)i z@t>XRa^I>~7t;~u8u&r3;$3U4CR(j+9pXS>%&$O3&K)PAh4yR~gE8HyhfdY2|ck^RC@qMI%mIR0Z;>$#q2fBc1F+|g&z;UVWRB~8FK$W;=Tf`immIP zMj9#Ul14Zj8l_9=Zlt?gIwTZDkP=Z^xdk}`g?m<2U?-p(IjJ7@& z`KygfB_SNQF`Wh`CRg}N%u{%&-}R^Rv9+Qp*Hx4lQtREjap#Fmb}PIk+&ymZP5#@s zu{W_R4!T{5YlHlE_ByYQ$=((+rcvI{yB8|uEBm(*0PXiZ;;)ep5D^jZ2I);bePq&W z#dFnuq@%B?_Cg!pG;^+~J>S(YEB%FR5sEVGEV1uiG?J}Tj7$~=k!ok&zSlD|rx;<6 zML{Mw;jP6JK;?1A^}T!o!9(CTjEN2f`r#ESm+!6i!VAQc20U*>X1%C!!-|5JVRI{& z{w11lueN{#krofdI0to+!Gh1-6{K+Ll}ikT&lGvg^6STWZ3|ynFh;<86y3Pl`au#& zmyDv~QLS$&(=dXd;Q2OZL(#}9>J4M}vGVLMh8bX!CQbTxp=2UnDwC-taK0!>b!RTY zS+R^O5Y9Mv^GMk;2iiI5mL)3&%Qk0)M&*eD&-4ISF`Owm5zFiLV78@ffjlwx8#CF_k~KX(;{J`sRbcRq_ar$FbCV zDTzexD2F;?GG4lrN0X1K(W}(L6MAuVkSRmZ(vJ4oMhNXgK-X_xUBDJhP9OFjq{r=i zJktZ}nAI8HMT;4d&+{1Q-MvZIS%YJQjQHZNCJLrL0%2{;QIwKqYSBx*$HZR)7lR_? zT6+1dZ5zz5L_DArG7$1TXx(1X;=53AD?o2^sCjDkh|=#X&B5m0lWm`ZD5?^X$M-UA z3b;^IIk1%LhB?A-zmK!x8Mp`kFygfy2E!L!iTlXDQFp&waEbu4>GzN$_P-?^21(yi z6`)G5+1b3Fq_kqlI%NtsL;FQ&3NeOr)+g7`!QN}7o}T^yJK>AmR+&(MoaQv@dAQrz zG1P$!s4EYHBrdZ*S?(95eS3|}>JSIfj_D3Zp>IFOpIzFvn7PQcLxO z=KK+P7EPzOPiD+D+qGtjM($^yBBvK3W8iqDY~xxVRu`tOYcwEDh2@V|vZ_>eHs^-Dr7K&-ZYFv7?Aa}ZCkD9Q1f9JHT3v@4vdFLf z>SEOsYM18?vVw#g$R3Vr?r@3CWzapea&QSTsL4lWx~y=Cc?nfr?Tv}qL*i653d0L< zx(MBhHhHa%Z>}6jGmS0qIn>*E73sgtv8ph*<~cO~4TU4`^^9=_jmpz=#dvhN_iQ2) z+DUcst8h8x1g@noa7`k7P*xla-@5EkFuNduHzqDh+;GWnA9Jdycs~n{ySG1T@$2aP zW&UPsEHuD@R?kr+>ee{Lu#P1(Pe+qJXoiWUVi-U50P|ycSX%Gb{yi$x%wl}k-Qoqo z?AJnwcVgTK@MKHLnxz-l{S>=Bn)UjNB@?b-Hx`&MzE*YEUFBC1mS7e*ia%D8!B=)*JqkgMml7*aRj(-RWes{~(LDq1U;(?F= zYT!sfX@6B-f%DDOa$dfEL55z{7p3tJz*$oF8Id>UF2!?dqu*!wM%UNihV#%UMtg=b z(JCJskztV}5|QD2%S%>{#Flm1w0xhY^>ZEmDh-n3EKJrH@1Lt*snbLHq~om9((YzO zuPumqPT>yLHH0<0go~t06X|mwUZR%KH+*8((}hcSCD;B+j@#7QCBzY;HA!2mI_!!$ zKP7b8x;oCpbG~nb#k8+6WN*&J&^PAh9-iGQ)=VGfxIM0+$ILYKOSk7M)Gs?L$X}6- zEcY$k7bZ5wfLBGwb(HBu5+-{1wP%jV`>uFXK>BzQ_JRJrB0uHyE7y%)NZez%3#Y#P zO@JW{&j*nO%rc~UfRu88fJ1+f79ta|_)Y?s+}mY$l|YuK_Wsky6G>`IaZa>CHSyem zQE~A`9D5rnS(_oj&lD)D?O!fxBxsVxTjX+6IfSA(loivt6|BfMmDO(0OVXg~KQ*WS z%n|0+o?F7KOM<#gnH|HCS*$Lj%yWw~Og$A>JjKH&+M2OX+|y?u=9(e~^E#ol`83AN zK}A!pbEPF+%^lnu>47;MJf%I$nHg;f5-yZ9AIcxS($6j6xOwXhB{lL$ProN~M`%vj zYKz^gX5tLGUJn`Zly8<+(_!banP>>%>aSdpz+Zen%tC&HDsfB%fiNQPTYJo54tAe~ z+WwJ<rFMt;P=#rnhq}oJLAGjOHQXe`RqYueSO@X zwgGWvv_D8wVN-m*;;g% z;A>5vX7z${XFD}7zpX_MNrTUIH;rlUIh3C*(Bs8<%9y%2&)>=G=1SsbWB_f>o%dnqcGHIq_r>Jc5oxtbg|o&ozi78hFH7yeC-IW& z_HKKZDtkcKV=)2`Z-T~=`oL%p{po7Es|Ho$v^{xp!6#L^coS(n_vp0cQ6i_B*zWtB zU#-(TDOfkfR;&mfJa1mQ(~;PR!{#aua(O5{so6>LR*bed+S9_G=FY28N1f+UF~J%y zX)(M?LIOI=IxiCu-9f(5l&LFg6pd`*9JCO4g~O3%)kQZfg`@iMWhzG@jlA{wCs9e7 z#b4#e1G1{$Oj_%HaltEpJGtpV<09IX>Hfjrk;FlewdC5P2Mp?ji=-i>nl#rt{U;rC z8nnIIYbuo5QqT957ej?Bxc7FkuIqV#8R)5J4rfbF?;4YYpEH%H)Dc-$hSC*Rb_RU zSuK{QdGqnXq_f7RV&FX3llj1+9tb zopEM<(2I9_CcYhPOCry+c@5$-W5j#p>6LRAi{NbBWXb~A=Fn&;Vn3#|T}RB8Z9M-a zc`N6c*z9#4xwL*9u?9GBOo7nbFU9(b8hTulE$0%JUOMnyDd3F&xtFjnmJiAbt`?4X zxbzI@D650SDUdJZ=a7A2f0Fg|K>I_=i`DQkMClSA*J>Wgha!xxGfI%&l7LBCY-w;h z7A+UwU?$K@1n@A1;@?^=z)x;B4$kG=yQ{WU`LS*p^Z8-8 zgFTb;dT4~=&%ZjAwrH~LM8CI)oO}P!I@{!2v{Er~%p9jfki=C@%zNolN7wG%l4vm@ zdVnvh5a>l0#Umm6k+R$62DzF}?iIYtTj?%0Q_oZLM1=w(D8-P42hzrUwS+6Q8*#xvMH(j%BslsDRGmmCI)tE$RDY$8V6S}}eQYV^7Qt6B8Z8>OEn4oZ}+G!;EPX2zr zYH)8^@n-{!3m>>Do~b?R!;!*yYnRGSqkjEUj!o8AB#e*z!`I+wyopzy3Xk0UvU{0E z_M%Wn)ZUl4yBi8|pCy=vA1@X#8eS(k|9sfo;UP8>n7>V3h)N`C<9x4m9I_u=16ILj z_z4$furaq^ZD8-9cFy%ZT||y4vUmd*ILQQfO;7v-?`48kH~8#GMG2*VT@v2u9(abO zz;xlLSB>J1O^e+b8Wbx+?h<%O8{Vj) zVyP?EZdAPt_%?NqzvwGf(fPZi1d-YsHsmtE1{KDJl*s_(d5p%_D$ zDc8Uf2)8omge!GI)9#QF;A1mj^h_)I7*);9FuS$!*3yEtb@UL9!*c&l)KW>2th6rX zI++>S45)Q|ou1kAjkO}44|5zk{Nojr4|Hmyt<4i+`|phpGuq{YeD$^{KDk}2;Go{M zdmqdU{n*>uohi`903Jf{6i-go%{>8f=O<=3HNXaaYWj+i_maSqEmSHUW*leO2KduaEH{9 zE?mp=sSfARyY?1NifMD;eQqIT=b<&d3Pa~%Lg)jL3deW_wK$Ey^E^dXQWgB%B6S5y zD}{Wh0-iY)61`ox@$Sf&aLz|H{>wU)W2WbsJE<`Q@JY!(D(~pTWqi537UgSmQ|euH zeUZ|eKoXRYtRAC+cDSmfJms}1j~v4b>bM8;bZ9E?1*;Ig%IiG8!*s4zB)z4zFDzEMOLb8 z+d8k?^)Nhfg+{VkGygK@f_{#gOK`y474@U_@Ukhu4@{>9VkLU z%i^?)ZbuFI&iDOqas)ZWd(|v2Tquy_LfB5$@9&knl!JdU+2VO-`Q>27cph1Cb1}J6 zfj)&R3EXii!8p#*QpTdhcBT6wgXRL9c%k9S{%_|?SThJ-J9_6&7ki5vY5+@#RINVt z%0NP{;rdr)EY;C1x`i*qSkmXQ-*(hCV``g9n~L8c8E+%9;Y`UOF%ixIzod}rQW>YrHgIh8x55vH?IbXIK-2n!F|xr<_oB;K3H(viF~=4>r~gX zhUte&Ou$rH%8BRsxIt0Ao~7b_W~XeosP794ldvvY+pDwL3<(Q@@3DrW{J2@3N+B*B zaNw<-!?90q3d}}EU{6L;RVsTYDS7B}XvTj1yd?5Bg{apzIy5KJ1}^kqUOX4d_zt@^ z$D6~;OsMZs21zl07FPZx?N$c)yr<{7KGaf)yB0@IZ<0lHiO%$U*3mZmONFudy}hh( zl@Qs=rC}v5LMFAwa4cK0bqM&DXY$(Db*!(GX&GioSM{IXzW73&&+M`fFHX+mwrXGU ztHXiemsv^*W}_7OJsC=GY@|Q4k9(m1V#5nhD~(5C3Ash$n*JNNIst2PJR>m|b>IVD z*6SsGG=!QC#_bC$jj2z{oLBG)>6>z|yu6Qk5y6KR$HKKeT%Kgph~a~N_mbeqYcs|7 z;e7b+s`8fb4tc|B@atX&V_{BGKKN)p;#`UOQPJh+JWNmI%>~Adl*?nC&0Hs+ z1&mCid}}TW55zC_m7vyo3b$~7!H_R6=ALq(EfQ@o$y0ticf;Z5y@gKiLBnyS^D?bR z3*z0OH}}r#Id2;1mkmkr-HsTFqUK})Px5Mva!g(gtc;~i$yn&3b+C8Qizjt8UK4G9 zUNA(xzBx3W@52qR6uq2?V6af@2)|HC1tz8vvWuXTrrUqL1_Hf&x#ygdB>S8sX!=$% zf+0@0?Y(X7$2I=IM>S&a_M{wG-`M@I+SOut^gQ-Ls$b~Q{>)SWMnKAe!|t1wwbYL< z4cIkY#U9BHty4_bBo9qH)|451Q(;c;oki=+%9(bMUny+6ohs|VAUDWo`#_el{s> z^{O8;-V1piI(_}aRbNk6xHiB0!?C+JOxFT6)P!j-Kd)zVd=vB5omYn`J}^kupj#wL zPKaX4w&b&%OR1PZ#QlwZ0)ad5RFPz06XUE==~|-5+7hxa2v5=bNp5|)b@1qB+y*-? z-OG?_F7HOokBg=p@vn_g0^~8SN4m@!@79%DETx}Id60We{MG?Eh8Q)A={;LJNgb?4*HJb>7i>{N^=@G~&82eL$?c_Q~4>HUt zdw124MBdVVa(rDn7Jt)d$)yoqw8;@&yQX;CzFT^ou4v1&=E6WZ&)N&gS7>A!2j|EL zqV|h@U*qAnXfkQLdj}YSG}#LHQmGj73*T2rLb5uOIAnFOpg&_o{`&W8J3QVFo%l#7h`%=}uCY{rpQjRw6Xsr##Dg^V0AX$#Z% zO}FkZ#i7ORq!MzoFIr0Y=M%D0dp6*)yRvXRHxvjATJinVl0S{{`!yq5x}4YT?4{=7#CczTXJaLy2`T9Ls;^<2LsxBf zHoVf)5QldSlMjSQhCe-deaD98PM$31kV{YAhQ+E!?!GF{q9nZ1g^TvSe(|q#Jz8ax z)u?VMuFR6Z+eQ!a|Dc)uxf>~An{Z8DvB;Q=;s(|B>@^U}`6ks6%o1B=?TN=JB0Cw_ z*c|VdWOZnCw)BI0so}qf?l0ny<4s zm9}Q}A)gUO+HHe#J)~L;3%J}Px^}5`O{p~QH}IWP#Cc{PzN-BceVzpV0zP&3#JM#O zZ>kU0D3sHUc10A|oRQmWpQWkPh+^L;#E8nnY@lac9e9ibUw=2g-bJKHbY0AHP9-XO)5C>VOz&UG8MdF-uYO;carpI=bnub7J@LYQ*6Lrd7(D)dGCFJWYUJyi24tJ=Rpiv#U3F63 zm})Xs8<{+Qm#^6Frg<{44WdX!FQ|IOFlNM&A^c$P0(s77szbdoBS)R&JttcqTlh zV=ObJlpesFObHLXg)Tr$K$fxsUsE>Fz(!!yW%EXRXqR}cLEOmGVmmvLgM!DG`C&ER zcAkAfPqnb8D~eat1huG=_!jH@=4|1^yAp4r;I$@aIGk2qxktU7t9X?_jomNH?9(lT zgb)+wqUf1Z%jYyqX{xE8hVPKsHTzOmC@HPLV_}> z*==u*3%iHfTa3vMyk3K8yarg&Jf54%8%D2JR)K1BX_i;Mx~AkTiOhfaR>j%??1wdD z>mBhz?rmM?e4fw9a%;0d*2=f-mMWogOeY`ewBo85&e1qM;rZk%hw8zo7YP-#ch}Hq z?tar=*>y~0A-<@+X+W!Owzr*T=n#O|4Q;@euYMI%qk&qBMI9oFk6_5Cn0ac;)BKUyQsXC|fu$ym5~WPd{>odc${l z(D2>`%EU3lB6?mwBr|a5jF4_X<%6Zy=gm2sWPJAsDB{(K3?j`tKNjD>@^hWM9$_rn zd8>OEC(H8fq4w(@6HI?yubL}&laj2hCn{`gWtZzO%GhyCa0)ykVUT0^z*HnOCv5S~ z1vA>B0(IiC39nU?dS{g>Esw$*O=U~Hz^cmO97DI}one)gOk*|OuenHH;tHuAhF-Q` z4N7663}=(vT6wjzoz`q|Ggd%>N_mmqA~4RqN%C6J3$#EkCTlziHbbr6kRq3leMSvY zmleYfqh}DVy;}*f!dKDu=|8;2O?3r%MEaX%R}^8p)~3WxYL-Pb1uLkR8NEw1x< z+a&pdMH8OA%ZxAm)zsRH6Le*lI42#|BG~2#z@w@8tf`H0eFzV<5?vaf6O5b_XY{Xl zInVh(&(Q=Q{#kN?HCme)&EP)1o=$0b4#``obYKr$o2H2SW6YiGz_9_-E834Trt-#~ zmXQ~~YctVVi%yihovmg!?Y-?w*$;9OG3Uj0h`PyXu)j?T7s=JbOs$=9=yov>RDNm|?0lpCWcA+qjk=sRy`F155&bCOxsP6DM~_%UL*~1x~`RIg*owvI;|?tSQyQhWQ9#(rRxc1e<`N{QHUjHMvEK@JfHOb zh!R|kX3~cYC1t7Z$1U;`Zi~%*6-H|fqe9h<45oQ%)e{S04lEd5PtojXmCV}HQ1jkJ zR*pXSn!uH?yt9kCgi2#xa?ns*z}#%}W&3uWxy^RJ`D8|DU0D-*;&h9JBsy;U?Ps61 zie)yQzDuk0HY9LJ6#VuM9)T1yQq6xvuHx2K!?e;x{r)Tdu>}p@`5!I4ZBydtlw=TI z+#uv|DUWD)(=Ad;J@DKx?g`Zhuao5)&%S!r;}2 zm!S7nC4{j!ROf{ z(=z#w2)5~qn*QBTOnANF zPLN>-Z9oMfVuJ-I8Xj*@0M)8A5g~P;+)+rIY+ag6f&yDhf9yrQU75IKCItED{afq^ zbOJ0|HFniWx(Yf^ZalJEABml#-FRB`wy*Y96PYj19?m7{&j$2-2~97q5>a1z-e@^Y ze@&4O6}6oNYnRVA^TUO1p29)is`6JGXfojOm_j*p`~olJKyaQ7d#!EV)yW|>&2MJ+ zqTT@eY|OaG^xEmx0-lDyu`k8Ejq^rtO%fvj_htUBh~0DnUOUeX5P$erxC28M9}&4X zb2e*D)-;EuHJ@kW&t+ygZ zMaD|ZJbHG0q3(S*m#*7-`8gwZcf|xe6w(G>_x>g?CyYsZ%!;17+-WuM<4yP=% zgtVW)AF3NznWyU-7WK<&cwP4*$=`NxS4rh7BI>)Av#iCfE-S5J$Ww&JOFSE8i4lwmf3}ik^(ld!ChtpE6!r5gZOT zzP+P~?5I&_$jv6nocV0~sWfv#mpt1eOKB*ZzP*fyNsI9D;) zaXHu;n5kCytS-^LvRZ!ZU}avhEky3k7NJ7SfUBuD+v<0|3m+-WkOF0{T6LDNwj51v3XYZ)%I!24t#}wU#C)hm#-}{QrGH?8q0o5&H( z(U|u`?4nbN-)u1Ne0kXUxxT^?_f_%+b_BlNsK#p_z8-hW((4=)6bZ7*dgmwZcL{Iy zAt_X`1ri#W44F(AgI}9%+s#e-7iw!tV1Bl^6cL?8_4GaW{V|*KrKBlb59G0jQ=f&HW-=GmSy8Ka`=$0@}4rgyZllYL$pdgt9tvHe0b%Kwm$u96QacDa_ zkGLN&z^jSf^|x@kDp1S3yy5JQt{Or;B)ZsYDoRYY?u`&m%b@WMfAfW7M2_>EfU)e? zVs%vleK@x9CJodF`o_~00=X)Z7J0;<4P1&gJaJH0o>O=Fl3`AZwT#60T!ee$pYkoi zA>z|I`<@H(+>7^Bx%L<>E4f`W$`%5f>kXERIJpq2)sFT0-@lz3evbycr4{+KaXD?w)S6?cBP&z(1Uuf3m^{HGr zxUiIShq8Q^(d_)1Lxz;nqy0BoQsk{;54zv3kl>#qEU1j7c<1>AEXQILJQ^(#+NVN9 zI83$8%4+BRg7Q*nvHReI;Fo0O_&#MHUxl%mw);MVle2kMYu|>v;~pMvIR2K+$20EJ z;}501{sj?MxBOCtvuTH!*)Lj}&d=|*k-Q1SH;UR)y^d8{TsSVDhk1qQ);hAE%x+v# z{y74T5Nkw-Y?Yy#8s_Qp_BkqnevB^z$_DrftELzvVj^a@7m_)2AJI%&nx3=N=);it z^f&<|@U`25Ic1Ln%uczO)6wF+r2}4(tADQ(RKoeOnYa#fhnXehC4FXWJxi_kQTrh% zaRhGY{P0Xg9VPajo6F`!hETe1jPvnypQ5CVpDk=}5%S;PvQIexI|jr&V#isfvFY~# z&&=jm-fquQUhKcj>0fQ|EiB*&(VnPU?N@0Fm7$P$4VY7a`*b5DH#G+};L8^{!#%|`+96%`-a|btSs89xOo4Y!? zyO^500*xrUIGU=NyXk?HC8eoB>gJwqKs_l>x2tNX7#$=5 zq=6P)sn2c!^h4<4KqCxmhxQ~d*>(BB7DMF;MkP|5`%{eKV2 zKT`?~uANdU@GGQT5C~x@<%W#vzd$MX@!%d0KKB__-v^%?{4=F6!NmWC>G?-Yc_0X# zPE(#Us$eKR2L1c!!x}CBr;h9KXR8%<(g@V2*zYSun>B z(1L#hEtumMY{CB)w%{MI1^*6Pz%KsLumXesEo{L*V9WVCY{9=^%lU6%`@<>#{JUiU z82T+YSfdsEZ>_zw0kB^ruXJz!thh z_!o37nCk~@p$n5=sQqQ$LYE2u2DRKj$b^&S44_?Mu!X)?_ye}kh0ec1?GMHYJYJEfO&qvl;?MH7P_{A#S~)b9@7Y{+ySozHPmh4N)3{;Hgl!cLqBd3 zDlk;hPgvk&Zb7%Fs-mAX30(`RqC*!N!08w;sEMqK4z)jl6GWt|qC+hw;B=fiR{5&v z$I28qL)8@Ie3B0ptw8#OhGTI6q)*o3;FFau_+%9fK3QX4rv|2yJJdA-vts*6lmKOn z-Hh!VEl(f&% z{a7P{RKc9Ub3s4>sd93n9}8;Wk^}u%?EnQh0AP*_@S{VQPryB1^kZy*OMY}P^zQer z&VKU=@F4w42vnr~h7c|=I#kR8guv1yfPO5oe<1I_pb0|bX|KP40~K7SxiH}T@6rSn zIj6n;LKCc{QT=Gfgm7+W#F* zQ2)mtX@WXLPILdy#t!P~IPLY9`2=-+oaX*5O~0E&!1t7Rp%VS?1OU{LaoW`{gg`wT zr@4Pi2V!W-&_IPLWpnxKA()7-zO>9=F|JDmRU)PnjRP6_yxy#EZc@8tb{ zM9+rtpOXhMI{rxBu?ONb`#*v2Z|M7LE;#lqoOb&QXveOG)9n94s{R@)sL}C%PZiWI zI_>sXte~!g)9n8UtAA`!{k4JyL!ASs6#Pmc)NDJ={*MU!EHmLwR&f9ItoXs${f}nFKjxLcVP@!h`Og6TVEMwVihi96-&bE?*zlFK zwVj)}3rN}yi1bUEn>w1AgXGN}EZwZAIl1|SgN>N%M<{f&uFyz;t?R#4; zd;e=&apTrxx(G>3ig^P0yB3O>G1msYMsv%qf*fp(-!OH($Q5ccF%Hh3TDV z)`v76%G%bjnT@sR(V_6sqi{|*l+xVBJ1JK+8}1lLULlaxc8fx27<`I{-aF8+tOAF1 zU@`Cnj>Bn0o(b;bj#RquQ%>h#eqyGga;k*}a@dib-ouDC{* zOvd@l$vekZWhte{YJ`l^dc5!u+urhW5 z_FBjrpIm~$oFFZ0GdC+&J-}?_qviw-$e9NkrGPBBIiTs|E69IH4sf7$&vROE~pd=B2W!tKpKO@CuL3kxPtjz-9b%r6RA#+Md{HB* zsXm6HDx6tZ?~1j?OdEcsh{Yq&;#zUXtTC-$M@ofyyxx1>r@;t0>|BUAqC6&abH2|KM(*Bj_k3H_NJkJLi zf`7pC96V<{&kbylfF6J&jT`Dr`;o=Cpk6fK9y$*Yql6rMfV&ZL@Br}%$nj%&XzFhn zk{@7t$N^#d-yQt?{M5fYAatD8{Y}58wEUrez@Z8O=sSr#fMWYWKyd>u1K{{k5FEQD z|0oC`+5clf-~`$GW@m2UW@2p#f+nDB3Q3u`7@OLfyPam9Bu}#euPMj_*boQNA%NVn zGY34P#|=O#i2u;qS?Z*%pL+VatF!cJUzSj*aZ0J16AYn10*21-DQMO2NodD_z&d`U z<95%IkW6#WA2LspfPk`aJ81=wh=BY$O~5pGoMCd@9JGeLwHdUv;~XG`&ddEB8=xc% z&~AV;9^~!-h(0rGS0_7TFLVKZkd?994Qs$wIXSxkl92n9K1k0HKw+N+NW)4*n3-|L z(drs%^5XKWiq`ff?yjni_KJ=I@@%T+mhLiu_x%^G4t2u+UWaqS=y1+69S*C~PN(|! z^B?%)jFW!Jhj9O?1mFbBRLC{t46FUmYM+%nWiVcV-Jl2H5#$40`lo5gHROP_#tpU2 zd4Nr3fC2_&0kkAKq~vK0sJ#K?pQa&uM3MX0&Nj;4QZK^kN@mG%z-(+iGD;4 zkLE6R$<5eGqw<@m6L}mwBf9b8njC`Lq7&oj4aQV+5q(q-w7HAkzA6YSBa*rYq|rv1 zZ_09QIIsu6gs*i_Y4#suuPITFV4CfIDYlI1S?-V1sJzunrh8NR&Lc*=BGv1*_Kdf? zQr(cGefS^OuqxZkeiVr(@1pO19B3QyDvz5@!3Dl`%ZFj_zFMi6FFYt!4f?9ekIMjH zf}W|Cv$0lEzb37q&Z?j$uJG$vbDju{@5=xvQhykIei#`d@LhyJ7~_nw&aOBCZvAm8 zK%o(eGWkpFfn07RXNUYOB`buFF2qM#zKAR)`@;%edg8(99rF5>0;&H?}+Cu>qUlH>{U{ljHk*0=yGEP!9#59!{=L&gih|<8k<1 z$>VxJ{>kh*Edx7pXZOx#;MpC3~OoabT zI!P(X$jkoD>ie0$A&$a7NNezSIR)syv*9?Mkg(wWaD4{g4|k7&gZu~be_%>z3UcT4 z?vIAw>4g8gGlY>K$8oO!!vX!AG586?Ll_;xU{IC@*c#d^z+}fJ9zSq(k^^PK)7p?4 zrv@VA9z-adv<SKQRX(H2=W*K>CzUNFL-GB6Lok?YmhBK?9%$l7IT# zke*MkA#I+a`wQNuIR0D$QtOAB-`hB2jk7widB8Q$Cd||X#LY1y|4HXSv;T+U1`IL- z-qbRMxTye>6rD=|Vdif|G)&iyf9n< z7C7Sqi1C8B;0Z;)mGXGR) zKs_%%qoyJyrmQLtnDxNsr=JDI@y6TVFAZTOw*c1}MqGeX1#$qq0@W2z1pWe-lTv?C z;;&jbUOxc;{|hwEegqQOxpgK(H5Fv8N~^OFq23!IeV=7#0ve>`J;r)N|(lyu}IS%KFg9n1h{ zt(up;{4W#dFH{UK%yN*E6NbB>Tl4s!Zzz3#0_fGrGw?v)wSe5=gKqHoq0|`~+|X?k z5G1&vOL%}+IgU-q)YJb*3i!aV zqYp^(>e- z*a2+i6acxp1C=3R1sFX6yMqC`K7<6RzDKm6(^k>g-uyRlFLB^4V&ElWHUVJwn*bmy z_<)5NB(`YjO3jT95_5&9D9BA<3$?M+HFJo9I!;2GhvY$OqJtp1$J$g3;xq;36iCg@ z++LF!*hGsCQm}S~I8&i(L5Nxa8Un&*z#GU+un`rQaLNy%8kktgNoWQpbaNVP`5{zu z5@X9-M;x{`WXmsgcx$uDJt)@dFPI$SYVbLB-awtyoT)1 zi>vkvj|rE|qtzfQ|HFH!wVQ{x0`@wl4*Sfj_(vNL;U9b4n4(-gY`#S`o?~xoFI4FF zs;xBG&pUP}bCS1#c$-&{!%FG#J_^ZWwHGf;8!Vm*4))JD@w<6H(Xh1GudlRB9R^#G z^$K@slXyH7C=s&Z9j(aOl9qlEss3!zJ@FpVi+jeEj9m*P!-ITnJ0!$+8y$x9%G`Us z;Zu3jEOnlmV(Exh|CWunja$1euKp%mPlNMhsnKx;1^Gmk22JRa-cYY4uei&)! z_Urd|go+DO-BY>+d~L%Ntv!FYQDsOTp5U$`N50PCOOrt~@<@b-ecVkQr3)Avu^_W` z%!vHsK790$+(7x$Sq5W=L$Ve-*6dRbn4}xfict z_&WAInw!XYaO4v;E55P2k?HvB{uQWKZ=in)^LY>U&SEZ*ZNwfy;%gj63N2>-Y(hBR zBSvU*E!|OdvF4`KU6#QZQN8zJ&Lc97E9liD+>w`6xW)qA$a$H-op0s(dC9wau}Es^ z-1DpH5>z82+!+=ZXeoHmPf?I_>ta`f#W z!T4RXi69PQV{5vA+?USQg%5H=v+k8IJ341{FS6AoErdQ9N5f68CAt4FaRvkYHNO66 zhN$q!nt^CO=-jJtE6?Q?61TTlC?4__w0$a~&IZ$1j7kTKV1+(y%DvCXHZ56B#g;W` zjR{eoibSu=)Trt+wji$G$WNlaO^v2X(@4*57(8n6j2OXK)Jveg=kdAhVA3U8gbpbr z^22ke41+H-MXn>>&&pz59KW0w*7(rkOTLNS9;>Q`yB{HWKj}Arrr5~?(2hG3rxTg_ zWY86OWIe(ok2GH7?jh{KkTI1juY^7hHdGz0KV#`t42-)`>qHj%L`Qqi>OE?8G{%sl z5s^$!zHE>g^&HM9t=r<_le*RhwX}sw%i^Ru@113^=n|zszloBQI14Y?z$-^Tw=Zn# zu1?MC!wv7gIqn|eDW|ee9u%N>&6$I!u)hTF9NEV92t$_3GQ3CaCzN)fxg=7G-o1)mB@P{m9a#be)QCasBBjx(G*Z4$Zz_mdjt_ z*)EOhE3o%mc2W?^w%+UP7yHOO_{q`d|@Cd07e zm%>oSKhfR}fHxI$U;9ni9L7ifmuAGTp>(Jj!Nx<)#>vGa0K|cTO;CJ5?Dtnof{*hD zO9GNSvm_vO|71$=@c*SL0f`(!uuhhvycC~Y!D z*UO`C3;Ty_-&mWFQJq6@=ks|=?31|OJxgM!7dKSo8^O4R0)9fx(uFsyo7&j$ih^Q6Mj`cD_)=}Wa zy;yc1VTO)vPAl{7*8M0MsxL9)7m2wqTW#c5Y?0p`jWZjPS4v7x#HXlZlI6Ow^U{G@6gGuTYe8kL0>mtV^i(=9ThI$SBcFf8rIB9I+{&yu?=xh(vm{T?0)E1EOCtk+)iZC`@{0CAL*Q3KmIu;dD5YC3mg2 z`g8h$wnIj>PU=Iml!o)D=@DA&s$wi};8msaWw7$--7{0T?@RYfJ|bDrl_B$bT!GKG zM4dcGEg*>N>;WT4Vn7 z%ycu2$hkaB0SXt1G8JcOXT3M9d`!DcQ<^(W^?1A;^TsJhvMCAUF*Ax+qGN*==6mR( zG&4D=gM#KzOM;QTM(%>sdTd#*D1RuwLeZ_yGDkQdex;J{L+<;a8$Ir8Z@YodNcj`4 zDsMB5SKPV05}Mwth9I6wK(W1V%}a6_(wXL#Tf3?#i)jV zbMDPI@?H~q=9}&(xl+ft(?0czIqV>NOZLuH~(5^yC&Ud*p&iR4edHRMtl(^N5EN^~QLdXAZs9NRW>Kt-om*rKkc%x5@yyIw~+ z8ef}S=7Emiv--PpaVUznw>-#*rxkh!-(F6xxK|~Rv~R;THY+@G(6FAkit#m+x|Ip% zO43q3AHfp#)v&P_k}}SnI^*z~aU5jLeCa7ORza)#3G-8O{Hut*+_5c@EMu7-Uc-}d zjt$RT{N35i8_?b9x%m>r?6u)?=3Bc%?p*cxUHZj1T3Dw+gf-kt)-0*KC29-W*~d4&wjU7AF~cVna%f;@{&I@(=D_}gYmV*>mv0AuzUTh( z6IwEMj#PX>!*!-ht(62hXp_*hVXfZ!CRCSS`^>WuD4s4R{AB!h9J9y+`E$Vbx={q;kcOkCrjB7U?7guI0> zA4r7uGP8A#y4r@58rZFe$^(qQT%!1fN@uc z@I9QJY<=bS*#D>=cmt`M8`Rz#pSL>=5!Bx-l z=Q`Snmb<$%s)SeqI!#C{>bHy;kf~ZjByW@YhNy(M!}V5RR-nAWr>`Ne3{_-tV`8yM zs+6!)c^p}?rh_Qf2Jf0pAe&2$GnA;g=t5pb22XCJ!~k}ZT?;Zn zLMhs3${J(r4;0{}UbU;&#nc=WWT;&;yuG|4Ls~8_+WQ@CKfbJO_AP%=&-<2m2R$#U z#QUtV=yY}Yj*a1?OO7QrERj0*bnhe*T*Q8_`7oqo8J)ev>WR4dJsj3A)V9h|bb=pg zl>3?`knyFgmc$U>Axhv>F(KGp>U>QL&zM02ubZjzu8bZY^W)7UJyNE%Sn=1Dv73G= zN?-SaR)a^K^WvZS1|(bltN zydm%H+mXAY8NB;nbzi6 zVAt;X3VZmXrqm7>U#cGE#)*%JRKiz>jd+rtx|1p`MP1+?u@)voPnk@+p`cZvMGPV` z`o`#)>@9VNf}u95&(nih`jSE6z-UMPi>p`)>|^7FH+$YU1#F6_{7nT#qf3@7f5U(z*C-YAZz`x%zcWlZ3KhEAcI?{ei z{|-7<$F^CqZKq?~X2@!DYt_1U?R|f* z&vk8v4;wx$<3}J2`-ioYm7VGDNuKTF{O&&v1wVfK=P1wmvAg+?QJ((4O!Bl0Z2x&I z$nal}1wT|#Xn@*(oGvmm|Gq`|`;1TkAP5iw2m?d_q5v^~I6wj*36KWJ0AvAjfG+@f zzy}rpPy#3eQ~+uK4S+tt0ATpRI$7D;{DXJ`7y*m{CLbCbz!YExFmtmrGqwSk11tcR z04snszy@Fo_z(2*_t5*tSo=3OWe;!wI0BpiUjfbl7l13k4dDLIgX>>n;s0T9W&b_6 z{-Hbk`-3YhI|uupr-H67TAHf$xA9O@U$fEhso zpoGAGR_j{^hM9n3ZCH=nj1Elu;Gu69a{lCpct4rhe1ZbvDO z2X{ylpzfhwl5d78_!X*YQBcH;ZP_A0K2&=G^QlrG zT_oCwuhv_I0h(GQ78u9_ep&x?T(gp1822O#bkOF9UH z91b>rFMYwoe@Bov{n1A>JJ`}kEcbfPVYm@CvPC1ACN&& zL;w8lwQ*nldJZk|xwo}X1XJoq;*SOZwK|BtUjA*^U^rDPQm5fsj}d} zZO2htfkEqiRoAXRJTSepegg93Q1ZEX>a&$gI{`K#G5T^?_B=|ohR4j8^w>n#BX8oV z@ulqW#J2eP4)jdCb>>Sd>&?qV4NY85Rz{_Yx-aZO=@TQIJ0h)7LHAG)nFnkDM8wY`^-v~*fu@92w*@GB za(e}O=(yv4y&0Q1JWq6PJaUtng-aSfOmiBulY)#LmW%it6ZbdwBeKM3=*kuciPnfr z6yO>yy+k70!SglB*tBypqA`!aPF=^PB^#AIHoUnuE1**n!ZbR8{l>$@W6H_{*u0xT z&#!QsiX_)l))gAYF)BIZ2tSy$!0-4}kP zVTO|tsF_Ti2cPa}y3<*HglV-@eddK|82ZJUo-s0;SRGNjlTW+I=Jv}%=M2ry2teTS zqxsjW#p_kC%vx7hkG0rEwNQ=n>rCWot>r~@E+H?e-fbuDP@YpwznL-+(}ahlR||E` zE10jaU|fVVAyhIHlyGMfpO3>$Vujn$5l4j;O)3IAh4~on;I~NJV8e5-VJ`12$q|+d zTK0GyzmVw2ioCtv_)DlzJ+d3mwC+|eaT$G<3E&H$2CfrZ1rS>L-K_m9L``mW&K?D$ zg}mwWubbV*q8MDWS$7;FCo5T&aA}~HgxhP}XF#p@dvwU)C&0h|)Dm^WFx|wK zwC%!*S1R0rL|q=ewolf{QG`Ak*s&LCB5usq*OK?pQ$X^xIDncnrtbfau`O&7{eno2 zbzs^#xq*M`0^!r>h8F=6MY72){0>&Ok?qW>75gI^5$eY8dLy@7$epOdjn);EfC!nV z+QIlJ2rTdys6%3PHRVZ3r1s9HC$RvW=RPb;efr!(pMaT6Hd(d|4GRx?oJymm-@Nu2 zUGR0G<_W3Osq7eo2s4aoRJe|iK4a}y~dr{Yw5%<9=0MKi_>K`b(zkF2g5!@Y1Vly|>1ksV7pN8q6}UTM$kVJ_?Hs`G}7uoOr& z2<%Ta&$M!q?+L=2WT0;|v)>g>Uz9CG8@g~pXf7FcB6vDyFciWsZTVV-&(=0jAOA2m zC~FKzj894{9-lh)sZw4U+}DKE7WnAnBi4q`X)1{Q zd!;qjld@$zD#~j#CaYShxrvtj$A`vbN%1FZf`jmfV}KB4%YgcMF$9D_Cu+6WC@?OW zM!2FaYM<2!*TYLlfkER%J+%=BHU(`le)6Wi8~RsQR|7592=r2wB)D| z6RvTS;55h3Md9a}4g2>z{t6PY!>+=0RbVQCa2^}tBqAxVQN%RY_pL>)wmdNxoed~( z=F`lilhTr7&eeox6EHSOQ(olY)*Z&?rco;ZD4O04h1bJarttBkv{tp@ITzSh4}^ki zc$3~M0mP=3O1)nulUe61S}UN%coqjhr_4BD5PH^AU-~DQ6Y8~Sm9eFO1|V;A-1Ib^ zZ0TX{W$>25oQW=n=XOE4TniX^k@$dgzadzj<8c79Rp$6l7MJX*L0YhcQK>Gd!*k-w z6Mq42s#9xMYoF1dJKlBh^JdctsoO!5_S=@@-y67hdj(BQsqib=NNu!MttI(#w5+(T z7wLZ*gnW^K%k271qgO-R_Hpr4;xi)o#>G-8eB$Ep*pOO7StkjDW@#soR_CE}RKtOk zeCYI!1G_YiVipJfPYJiQ{6{s@5f|0Q=FYo1tZ;BU={dc4Y{%rpd(s!8M_!&TQ2U27 zeKmhlz|Sb|%q-nXCDNVjQMwv&=PWm?87V%P22oj-Ssj{vVfok~hACPRgp7v_;mse6 zte@b3C!j&jGRf`WI2S4t+p#d2HBpyl(Z)k&$}SVZ1Yip7o_PcY^LI`b0yEz|`yi1s zhA=XJUP1+*cQ>5n(K8iFpMckw&n1`xnO8kizXHv84?bh0%j!tW3DwXhYfFinyobRp zGeMIb$)H9%Y;<*bfxeGyN=)ynPtl|@iUKYg1z9_$O}h{1mr2O<>D(jAG)xddP?J=1 zPMY2JXrzN-Z4h;9K;mLX!@9AQm-&TWf{$11FG7QZfI`cOCFNi+ULHm)d6cu@+0&Og z%bPxnd%B_QhhGk~zA{j67b+>Iy5n*c4#<+u%Ezk5pAm>Y2z<#ZPuH%>hL(ZA9x{j| zop@NSxM=EdY>{Qv2IDajlW@$^DxsczxMjhzQ9EY>C0?k5CZ*M+q0-absF|B?*8I@{ zI?BqbXP<;iwQQ2p$yu%a{28%8y`zVWI!gEu`74~+fokb2R0MU+$XFkRv05kVPMkS| zm?Ye$2|k6(vm2pkPN@!&$}mhl{LU)-EdIIqKC4Ub^YPh>G{XW5x_xOEqH=_yBeJ{1 zs~vaXB66PrW1tXdKL7zd71Mt z8vrX4i@a&eI*wEmZ1nqGw*j~wKoB<0o>U^-c&0az4Rr9hO{LW7vz4=+(@`4nAZHb^ z>{x_c$Z9YqejfdE5f1y0yjcxvG{-D)Q)b{Pt6PYz;LT-FJH%g_n|H2)XaJA4zD@cQ z`g@ewQ(VL>bu+k+qY2wN54H%W?tzXS$~C70UlhaqLdo^1d9~+{15Ktdv~C1-h}2t! zC3rmBo|~z;BaGeKZ#WeCLk7AHjHEk4y>+Xil zs1d_%hu=)2f_`CfcWLd*ATmg*=mwjzt(nO7;`OANNS2^65DqoHd$_lD=LQR?LeVUh zK?-W;oUiZ% z5M;q?R4y8+Xo+Ly`Z=aSX+zFICpMb|cP%g*3hev+cd_R*>&bzlwA<-H=6-wL5A|aM zYbL`r?S^Ff@WqC>=4%bc%HVuoaRI884JgY3(e>4v2FnP+wwDoWr{_HI-q(CSU0%!_ zeh2yMO3&{DLU9@Pz~xF0*NH!1?glv?k7$ldd_6Uhte_w6o-N$Iuf2v(*nt&3x{eh* z#SqQFlvc8Bl=q5~5pe{e^{JeTs0Z}D{;EMo1rQRdymY<%ZW z78lw&mYTY7ciV7?HEVmdi!$7yssixob@f1pm&>|%usF2+b4VHHffd} zj)*YpW$Qty@8Uc5gt%TTRx8q&v6EDAuepXDz`wXmTIPx!mTen&{z}<8TFiwB4@aWKjH``FCX{c+ei8~i?mbb2 zO~FaYnP~~UGnBLH_0>390k1|^K3_43J_3%rV%880e#)rQg5+sq(`$uiKYlY@-}Td5 zXSpyBETREPzsw15grZzOxiDVm*98xXBC8d*!(&)77J~4-FUDUXaOR=JE|WXTo_A1I zzUw#lMVa>1lqB1aW7_#DWIC#kFy84IGvlj>I93+&1@2`lFou`saV~puf3b8XGh*C z4o8S?WCi=abTTpVYq?uA3gSk#O(dEE%&v|7g&lkM%bn3pauBax#q{h>=0K3HAQ0%61o_<6nUDwaq*u?tv{tR38^ca%EPh2a$EimAw!Yg>Kcf=XWr2%Z;x$a3I^= z?C}pC-?@9WI&`$)JPdIvm)0uf#6Y$5igh$!+S;8Go&{gz7>VaRbHyME*akYf+ZY7n z!7tLlCr;~cFUrW4)-*OS-@?_g-10QhE;sBCy6oA*IHI&b7sS>aBFIU(du;fzV(mV0 zK*@Fs&ALg|LB;7sP|co-M#6VIw)8oRVpMQ=K^TNF*`D5skEmL^oepfi_SO!JAW%VM#dhm`1Rgc~jyRgI=r zx}JHQGD1hGzb3rOyc}fuaVtcD?#jJA^fezPB1?Q-`WX;w2V$*kSgKXtf8^n3+(+`!+zXmsQfotf%8tv}A-6JT-IaVKyyg}_$NjKn3ZCxf14>ew>*7yjuxsL^?1v;r*2@>M z)-bCL-W)-I#G!CCg6b=IIjZdYYq%zNSZc)hn?6OsIO{y^J|o*5<*hS3E?1$!;XN&Q z0KOyXVW+e!*mknc89@b7Wvdz#xRtHXuYo)d@!C6%9~qZSgw{0L!PYJAEfka%guPP zxum>d?oSEwUN~}8R{O@j24uTWtagnfVi_(&D0vXG{MQd0JmK_v@8h(1a7P%od^V5|26iDcz z*_Vv5fpx2 z7kW}<%tE-3j2sx}k)_~h%J{3IktDeYU4dknZC!_|O3Or|XlwPrBy}4z7>8GDVACU5 zAtd^??PSYfCyr`*Tt8=W9l+b6;t|FeM8GjCsq|JIhcBc^56q0sIhUG*K_KW|DKB<$ ztY7ST8W#8OZ47Vv&wDI=o#M16-5_P{zwuuyV$-Y2ImujD1HZ@@hr+6l*2NN^m=O#ox57c((oMkB1LwkQ_Q}WD(EY zQM0q)AL_C}?X~hOJlASJ0tSU8= zQX*;-fML(etYzA-sIRQo^!h9tM0t7%48Y5nGs_O^w+I!evVJZ#Ze{deE1cUlS?H^O zRQL)aMOBX!wtc1%s(GlS+1spr#~9pY?wq_3!ci*TF2e`E&ar~HI$hgN7CBv2FS-c* z#II=h{)!03Df~(-`}{mFA@sJ+T-PJNS<0xY25QU?!AuG`RcyNq)|4O0OL59 z7g{+pD#hi!&CiAN%sX@O5vkI7TGE18)}GFO*~fJ8JU84s`F$;`s-z)v>_kxbV9wXd z;i-X|Ky==eZL>CK<(Hl zQtYcSCRqyllafu#FxAeb{5e?X!sGrL)lzd5S{*pk%T{M#6n3txhf=54wKy`wIh0nD zSVn+dLNYnlb^RIRsPBU9NQWGD?ibgg{t%T<;L=!%z*sG4hpte~9+ci!Gh@i}a(LEY zM#h6?l^nOMsJ6rkDGsNSdOIj8mdW4|&TE`Kw_q`sCpNwkU*KZNQUfF&7y}<4EBLB~ zW02(Kb8_o)?0qy_a*Lt{UN+V@bk&H8ax?8ZYH2SWgLCBr%#T8|`1;I)`NY3fWagE& zX56TD>H_0TL+i4G$8z$XVKlmHqw5=9-<$OpkM2v&Va@q9bZIJw9;qswhleyH!|_yu zp!h`1{8-cP8X&YkYV#JiY*P6OwgR$0b{?;-q&x3?{w8d0h_Cip9f%CH7bUxC`9Y)v zhH1V6Gy3Y})y|wx825=iZcdK>SGyePIeSQVWiQ)f6nF^ASTg_Mh{Kf`fi5RcA6-z+uByuK8 z21CfLcOa9*^{anXKmSYu{9n1nf6aFI+y3y|m-*YH_J{p}m4$`*|5rQzR|~{n`sIIX zfna6*U$Mo%QW^f18vjaW_-AqPFaOH_L0shcEiV4yZu$4cMP>%(KeR_+X`kFQ zKS7DgY{4il4n^(oI59Etm~;>Aco#iy+5Cti&NRV@;!_@40a|=sK1Jj1emunk>0Uk+ zKTZKeR_e7QjHHx8D2nH`qC)5u1_s8@vN9`73|Gtt%ug6<7?|p&+A;RovvgyI#6krcH0;lBnkAm#3$v$0nzzm5+aJX2g@OPfV;X zu69i_W_fkjF0-{e4g<>^z70QIP+#9ifo4 z&bYilu;0U9<1-W{A3ZobKim8{$DEgymzPr~bawyj({BBB^>kG`22L?Kf9xQI*)$tR z_plp(d^&&ZA-yH))MbnLPFX9lX}3{rbpP6pE@`l*rxOT>Mk_tq{AC>ao7622=e--=x*#o5TH@E8W zPgnjwc9H$RU-_)`A6NdLLEiuVmCwRX|HqY2DmNsDtdH}WkDEWOa2zx0$6o9BMO|=# zo1ph+W;6ydSpu`htzMuXYkgcTXiqJTG4kbrl92{!Uv&s@Y_dG)5ir6}R|fF6PsEe{ z?_1LMCJ-euxlXE zx(gK6_tC!PO*@DCf!HAz1Bz?#iO|SlUHE|HD}EA;Ds<0}LaBZpv36vq)agrzw5Oc+ ziA&Uvt)~4_uE8Ed8r>iT$ zDd)b>Mg`4Q(S%}}P{1?7R(c@N(u43Mcfa*>*f>9R)q-QHsW4fP{XjH-bofzbgwt9# zv!LB0lTq}^wv6H0iSa#rdx+prk&GNzR5G7{H&IDIhQrMr(!lZuAduvqo{mgp z5!CE%6#DfT3~bZuLbZ)1z=f4K9{G&b@ z31~mU;ush|{C;c<9Df(+N2B`9-u&&=WB4F%{wUJlPya5`k5~T>W%}VX{4b5_!xjGr zh9mTW+$j8Wh5nVE@_(pMhTj$X$2;-wS11EB)1S?WN72$s(HO&KH80p2er0N+s!16H zBv$(S7Dgh0Yyl!7@U|XBi<5RsndPbZd^x)N;@k+wIY)suK+}cq)W+&~rOzHy2pHJk zo|seKfPgIElQ8L3&yEw0kLz%l+ncBE+P%lxy;u7E_BB$*=H;U&aB+16ikAt$rLjYq zYmHIpLyqKk$(M3Tjf#pH$;q-UYY`DH=-y`(=*wxGaEy41+(KCm?Mj7ewY(V#d6_av z%5ni^xUC?ps@&*M%U)&hOW>mVYEe=T$x%dWbo}!8LF!41%QuZY;qmQDq#p=4dzY*i z(5@A{X#t6YE~F%+WhQ6&0CeWSq>k>>xS~T`iBj7y{zZw&1J*; zyccA`qdUv28%HQF?+`ix2mlRnc!c`R$mw z*Vwojnb){h`F8O^p~b(ENFa##L0mTSj2Fu#*9|z7z$sH%Yv*LELs1m^C)@O#d?($; zS^Ff}PSY`R>z%*tWE7N+6)qfX+H6Vy?Y$EGcrtzUw(V=iZ!QoH z$62?O$(rqq;xw_tcDDeP>dP)p0EthTP4SJSQ4{S8`}b%_eN?1R0{uOmc|-v~cBL$U zdb+zvJCtVHxCk>ezq{P(s`f4aw2U)z_8HgS7yFSu{0^Nb^UI|^>}zx&37=|$9MIY% z8*8od>FKAi(a$yciiN=b14!Kzt#C`9BRl=w>;VM+^36VjC{~O|nlyLZI2yR@HVo`C zdIAh1h zyi&2v?jc_N9;sF7yc`c-UwSkpua4!^h6SME?T}<6Q*C~3=O)9+!KUM;B;%zEyrm@e zQnGcK1F;j-8?iOouY?aD8^wT=TsN!8Tk_X138@qSc8Fh;=mG3pt~Q=$z{IWHMk}TP z($F;$DCiDg7>8sctk9t~8|o)`ccdw8eI^a2r*w;o)joiE7R|xEYK{|DOV*&+xI_zt z2{)da9@BwwdSZsG5cR&+hYltT%-~SFSaFk15k22c_Jlqg{p$sVgkR;xY*oh#Wn2qm zRu!*xj@wV+fxfLStu9MqPZU1szYse?d|}g$j^WNw3NI7Ol3b@UO>9CN-vi^GAOyZ-@r&s>({OSyHxYIH0CDxaK((dE>G_f*NT$r( zu%MZOE7~&T7W4eoxiVI^q6O~W-r3<-CL8+%Q^?DUi)$${bdUOmKWi!6b<68`y{v6w z!-xwnBOe1J6XP@k)b{7Pu!A1Dis|heSy5r7R@T6}P`k)jCr8UJV75h>F%u7SC*6Hn zS8V976^R}4+Mc;DzOB-#;HYvgqka!mWJ-zpC}cv&HzYjHKk#0+j#gak5F;I%DA0f6 z5V1wra|N+~`qJdlP(7S!qfp|c0cye22{kcMPO(P#O~Tz~tNWy`Z$wJ5LGFF31*k!< z%R!?H+SzKk@;DF`cSUxz50PQ0F-ns6uzm|IRWbY+SHcz+pepFVPMVsW5~H?|QBQS} zB<+zf@Ql9Uv%2%Ijqk63f`6y+{qNab|7e0AZl4b_m6d?wBl>`q<3GpLkIwctnEJ6i z`;QLD%JEMgGy4Cr1+sp0%71dJ|1*}#_Gdr*-?7wxK&dMK1CIKaiT)o@s)@Pt2cG(| zoBJ<3^*5LL4=UBh+{X9=O||`a{CDtFM`Py?tku!n^#fFOGIKCC1~|Fc{)wyt+>IS< z|G9nt_WCLOAKEwL@AmzNQSjey->eKQe`W}#xw@&vs=l3LN4MI}YLI$?3CGSf>($ZC z&gI#BEus#QTwMf#A_*WN0q#x+z~#2mCzt<5;#&=s?OWK_mg77#*F5T!v}9gVmS$ey zy!SlS^U8DI`i0B!{Np?CuUD8sj#S6?5z|Le{%|}Is81mBnT)atdJ9G2Ff(+^ckaI2 zl0!Z(So`D~`C(i6?kBy~y1Mu)TSMOmSvd0 zmZD3{PU&gDob=(jwdhhSN&&A%wYT^~7g_DdbijSVM9u{xvC&-{xHoH~0 z9mJm!FC&vQSF&IUa+`92oq{Y9Adggv@rg+x+U4}tFIOU;AE1N-ziLr3j}kp5W)^je zn<FG&k4kNIE*acD=!Ax^de$6N55K+*TN`%}j} zcQ>a1UP)Ru*o+a=-Sta}cj6<+G}$!nmyV@P?T+;dW~?2HzSih&NeN?OW(5VULsm-N z)quu#$IbQKr*~=s5qavh$K>9WZ6OrQD6$wo?j$E}21$XF{)2P1w-rA*HjA_`8E z0*6E@wKlG^v4#X1?fMm;yTYbxG#XFCNrNBBqSggEdEW{TXW%Ws>td57PP0wqyW;q6 z@mNxpWZFbev-ZAt6xGe}THxMt)@5kOjpe|9!7hB9X_*1BAg+sA61L7qlh-Wln^8HE zq4L!b1XGBmupJJ*$|F_XT1t`Pmfppvk*Hr73 zUjQ5LD(hCK7jytv+f83UAhM0L7B7Q`LB+h34!W?Sa9%bOpu*?zWQ4CuO8uCmLxM0i zhMeaD&BN3U;jtB_ZyN%25YAHeTNhMI>bEX98&)}tK!xM`E)1&;EYDiOQv9RXUp2Y7 zgEzB6KU3hT7*w)El@!m)JIweFL7}?u;%6r*fJu{?44@sNAHTQ*=L84eeBo7FJSR9O zPu=H8Z}HVioi8&>oac%1#UNSB<_*~-QfnO{I2kJ+uVl$k-QmQr{i|us#&}u~w$X2a^dq2>jqGTlF9n;F z53}b5{%neEM4)O=<*%v8cZxKQosuDY;dG<(FC47-lUrVmLe&kvKF6HE)a^@ks z#3Qao)6?82zNlqt{j!F_i(p%Ilzh1*d47wWU@qoDeNOW-@hE*t>E0qFPi2ba>;l`p znY^se?Y_1wm2l%nu`cVXZOe2vOWG}Hv;vN?YhiH8K{)g_0@8&|`EranH6t5AyXZ}r zWjd!M@3xn(&2a5L;Ud85Nt!fa2dQ|ebey?FH6UM^R<@blcgx#&j+VRz(dCl)!i}7c z{5c2?&h4BsVzltmvL?u>5Ro(AqGpyVZga3#WvU=Zh+h}G1)lAE+IMNM_S*@=Ih^Du ziXU~|9p##DabspNcwwSDCljssnTRmhaoc4Iv93v_v#XJhG6z2b-@VW;ZQa~;Rq8} z4`QJS^(`3}fk;rZnD`3rJn>;)v))BrEK=U$Oyj9RWJn7iBPY!U^BS)Af8J@9f#}=j z;I}#RdBIcod{2o#C6iU?$eznwyU!;$)f1JHt{bBjPR9@>`<|1jC@-~k9%OslZA26H zJt^>EKlB@?CDpo*CoO5dh^LZnUdd{Iqc}?Y;pxg0tH5+5f%g%x+{Q1OQSnU2DF+8y z3J7DAyoBQ7FjA-x^-2!Cp*=-HzCbCP0hVKV8e~*-{AR-3^Ah1IG=L*a$&s}&Y9UHI zy3!ttI-Oby;`M3x@wz9@?6!|a_2tjG@TH`B6Bkv(SeDDeM&2T-MZEqn{8FYmxTjhu zPJK|=PLRkh?gNuc#kLFi^3@+}hWV2oEKn)+A~Uyzz50pB_=Fe(zAxY(H;bl_j2?YF zSKzzv*h!4vMw47QDZIh`N{;hC2{SiqDtmRLVj@J+;P+IteQP1O^exE^s_2nyqrVs% zoS^LrvjO7EZMYF$Ynt_XxmGmrQjXzf;X!<~C<|^OwY%g>{=`4{ZopUD2=-3GlMZU@ zX2%*Mk}8<sWt z>tkhd#CF?5OGDO9(2YiT$c~U?(8V>;!0OiuHL>%Xw7k>=G%e+wL00X9I_i6LRD!#K zyMbXa=-3BAo|^5nHHDQv2}0o87aSR)gfx4(U)y$fY5UrDPB^Unvup%DR&;ID@Fca2 zX1CPcJ$oK`Pflm-a!pI@!)j-ON5i8<$ME+XcAq1>(Bn}`*) zH*|L~Ve1OMSp#*ACm)IqMmXEVKQsO8yr*nTNL>9B^$68mUi~|oaevXvQLl%DOLdAo zn1fP+Git193f#?5Yq!wX6l=1KaM!v`6B93IZJV-+J7P=fV#4L&6sbYhHb0wD+9C5L z*f$|VPc6ZpkZf;$wyvy@`n+sClj=HaYDdqScN%Rg0W1Ul7;=F{0lJNiDORGQ-rjFn zT01G}+M7}Qw6BS?=ohXhP44GdNm4$=EsL`{DT;>nAxzZQ5)MgECSt*AH#-(NbYH3y z`VDjL$tiC(?E}Pmk~-feQdGy;f9WErp7L052D^U=%{fLPeu6r0>OPv0Km#?{LP}|_ zNauYu=c(uz9HJ#AWocTNnL3F%p*lez%gE>~DeqFBRX95CriOLu%eoTkE8P6z1}`aO zj!C(+kebS@s9_+ho=)3Aa_8iUFeLi5tn9QwgKcloA71Ga1>EVOd6uLmRH z;*B8r3)!0W=k%e{K@unKo6_XB>s_X5JY#Z=fnZSUh>vo16u~=53cbKC`7$#5X3$^rQS-crBwrX=R!Q0YKEzy<>mFOaw}^q zQR3+bU}f_J(E$jDD%$3JD%!e$a$7rR7f*a`5M+R>=tTDStZQL+@ypz--!EVdsA(k(puXOPl&jU=crvd(R{WM zknwbEnp~6_-{x?YN=NlrEzte598x8l@APqU`SA`8hpBQ z>f`z$f@dBG3hsJY+b&{pf|C;2X~XMNXsO+xSy~Q_Sru`c2kfY@B!k;;t*{a{RL;Im z#Y*Wjl%SgQn~)Ze^#>J=+7gQr2PoMjm~MZTG2J##4;Q?@4~LJ!>)s>u!RH~zvPm9+ zf?N4Hl4}h)_ad?U8A--}z~oLkyyeDy@zy~wo3L*W%iu>-3;P`Z`f%AG86Bi;UeB*y z4#AMtFb%RkCX#Gc?p?ok0QwTn{&U|WekBDtai4)KBbml`yR$hTAR@h#a&2o%hCxfW z7zt;z3-v4axskHt-S1q1wsU4}6W`$r(pHCH&CP0=XuW9Vo+WJDl|>wIGpdpTTAH+l z3b<36!~~u4^7ncqV_MaCyZ|k9h-Ic1%E=Y`+6!w?p_-poq<;>Io~e=t=TPKw#4JRw zB+n+e1p6uIkLyl78MY{q3#E3EgnXBJxs>Lv|Z_l9mixiZrgPLqI~bUPr=9)q!=-pd=4L6Q^wIl{CD2Zx9w z*Fb+p=7nex3DH+fA8Q)8S10(}6ZqyOI*D-5_q60C7zm9|_{gMhKRsgmBF#{2>H>C< zq8b_x;6xHEZU{je+K;qhw-2T6a&X0pt7+XH7dbGuMr*mLhxKN{gYIM-TCO!FibzxL zFuI+#0)ARyy2mbJlHu4Z3*q)Ezlz7XbMW<^fN^P=bX8QgHQo=J(zf~VBVg+7y+y;4 zKeT_D5hLL&U`4go3leVt{}~Ivx04eFLd}=zwVSW1gmnA_MZ7eU7iq(;wR$I_iIHEg zzH=#BMJN&9hIc6$Vq6x`H{dn<=?Er?R%gsd8(6Um;swR$4$Vzoi-;|}&6j*K`W*2GNZEl;tuY8{07*_JLkoH zFtDjfNCV`$ER`kinrE%%luIFgll7^r?xdKKu3=9ROsssvZex9tI!kQ|s+U3A!q04I zsEB)Al&J|#U6t7t0>rVb_C3bMH_pdaxBLTth!{EU$MW(T-7C+n9k<)@kdX^tigsmx zHyzp$K}M6plXp%#JZpk!GK04kd#2_EtNnqo?oE5g1|stTyvvI?#w||)@gKFQDjuPD z@Ig(BMn?6eg6kdlDhE{z0QHMhxOq0c+-I;E^(?ehtnx@1*`qpMA+9|M`jI~P zdmdgu*F#2PkXul~mvJ(T6C>22R=o$Nrh#e_YU*^H`7;Wk%^?vs8*hC<1HHll^+oO; z%ggQ_ak!hFl2D#x4L?(L+Irh}I@N3^6~=qb)k8vaYPM^t6+-;#(8%Lr2V?fPR3-kELy;9z!PeoTSYh6II#2a1;;o zC42GaF|`D%VZY;de5!aRyl<$NyeO4Ra3OD;R9`5y?(tMY4v&w=NWTcnk3(nW^O(D`ZR>p^^$6v5Mc46q7(LHi|gbs)BCgRkxC@-Dc~sUTi{}{22;A)VO_d$J)BCmU2JQ4u>KG!dQ6D3 zqv_6g)?@HAJ{lpY9`aeF>=}n)=8Q;>o+WucV%SANJLVeRR*GfA}6Y5-TOAJU<4}Yp;+`%X#5E zceT+AgN?C7y=y>^EJX^kSClpJDkTz+j0r>^#<(V&vQOpF;tkiB1VEF2orR* zb7N(6wp>K5nlmPE-(p!O;{-A=wXcYyXkG0n3T|)C=QZ?Y%ca-5WHfU;9?vFTs-4{T z2bo(o`@iFn1lju-Cf)>S2_`1JA(KA=8iLBXe;O+VA|mi&GtofKH5*KFjgrNmv~?c9 z=;{_*9JZ6~Wo&(#fq0)KF$-uSk%QsZ7^M+UYgqMZzKaY-e-GsE?c}=dLYBJh4SaK@ z!n+mcBok4p^t3AD|k1}S}e>3G(oVi@0B zUbf;pN31Pi-q?{d^-k3 z5IhTV`PJTUc1R7~(9V0~%74loP(VNtr5y>ZpbLVfrMg))2 zE5MD+nqb-|bwP?HqA@o4E3hC0QjV=hCJWstXm5aE50&sKFSln+$+0%;M;K7HZbS=> zc`*Dg{&3=s22AN-cP}fM(^r-zu5zoB&YZb3$q1DYV&Z9dv{r$zK2+&ZHP@h9J$Me@ zNE}^@G68alkUoxaBefl{Yg>=d?urc=8v2IucSIh8v%#l^bH$>&?;^K^1BM=w)`b&f zXo2Wx=vhP^#aGfbT9{QP2ola!Njqj+KB_qF=E)FVDPVN2{(5_G2oz+4OW#<7hvxdg z$y*~57}f4@s|?yZc}a6*A#pszF&I=lJ;b}RGfU%>I7`S_RzrSznX0&-c z#xZ?OFKH#FmKGjZns`6I@N5v{)#s^gV9KeYB%-6EvnV%@SbW|tmt?2FG%&BFq3nDA zY`D?id;lgw>1>eGsQFUp-4sBSuxBw)3VqqDjH`sh7Cd((NZ zTY{%&vF?|9fMKts6r<1*WR6y^b#B!j;x3u<>Pj&P7|BDy-esaEs&OIYBa9k-2k>c7*n21UL3hoLiB3EgJlmH_Dzt1y3&d~%(eqs;3-0$mTrMcW_PhgF4PbBgx zCuJhV^RHsjzvS!xPgy4a-9C>0;FvxXBF2yP0v~%USUFh!<|LRtbfEu~h*gs>J4%1Yo%~jR{;_HDLj(Ft{rMeN@~^tj@1&Uji|)hpTle`RX6E15eV7?IIQ}53 z>QtfZly(!^33t}8ogJ)^t@d>`co4xneY>eyp+c)eJ~Pt*qt^rZeTq4|aqu|5iIII@ zm9RbZlHw!`$Rr4*0q^BU_Vc|UfhC}#%ZXTy^S^4iR%E$$A@Hp@l9?TynUVRb{Iu5o z&awVD?$RDBaC0j30WcbMJQ?V327KQhD0s(ALb{XSNjDd{io3s0tnT!crq8t9x)fU* z^+Off%z#+O61*82{LIT^>Y?70Tdl_YvU`gCLu5G!{c5+5Q6B1T@BHlZCkBh6*|*p~*ld=x6x1|W-G*n(nMC%TzMJ=!2oqL? zsmYd-m>`Sv;uzpCB)a;!M*kEWB}e-V^If8Mq}PBb(KYNdQY11>w9E}LIFf%zSMO&7 zifAGF-dJ|FZ$vA-_n5|Bg}lw90!gP{1GlRgx15WSSfVV`9JQn#!u2(}I`8tY%Mf9> z8(4N;8=C%P2=2BQQC&}6eDLbbM(xhZbV!Kg9QdDkd*uG8x9ZE{(d6 z!-bi3(y6~alDIBUqS;!Td2zL)PvB;4DdQ-h%O4K7RnSFybK^O&taxY%>wNJFXAE77 zvRNBl3-3z}$RJ~i+1Kl7l2%L8AmRW2IC~4Ax|(!t6nA%*;O-jS-CcvbySr}OU4y$@ zaCg_>PJ&AyY~+%e^Ur*9=Rb4LJw*Yl_hM1auIiV!pMC_KgQ*aKIY}ZjA1UH>-5c%K zo&P<4yZGSL88bYhu`;6yOyHmnG=b|QFh9Wm;8nV*lqs9pZ6e#yfOXrahA|V4g6)@^ zS!te(K8CHm4}UA(9Ivze!~QaUdToF<3-lCdWOuN6KMT}`=-a(4*OU}>?n~7Lx`yJR zDQ`suS^j6W=&gV7I&i){;o^(5jFXbE^%>q@(bDw_<7$FIW4kP+! zmRnaobxtHzR1K<9yx8*Cf)+^!J!cUnEg zL>@_QpP3stFP=M>ShE3c8=L`o(Bv@`BX40%-4~0p54+#rM0;_?h~zGwI(sX@`-n4a z^qbgwYYlH>b6%tNKhP80^2mKaniE!iAw zN;^aTs1{&6QzOJPw_bo4DuBSDliROstYj6<%;dV|cwt@3^hk<%c9gX4<`+z_j6v&A z-09;FT@|Eq;q4^JAAx`4;E+OT8oh85BJLPbJZWB{hSw>DqK?mdIm%9tC%U2h)#R>Q z(~Y$R+PmN|BJ>0ObM^GVm(DvAJq9zxiY*x-S*fTotkF$qH-f3MzP7L}>P2yfPk_>F z!^%jS1H?orQHJuC6=z2lZ;fk$VS>E(Z|)DJUj50{v0!CA)}E`&$D4LLh^NrG850T{ zraW>46NOq|N}4-qQw_)%(ok$IPeq{exyF9U_JHaf6*J#XMxt{D}#e3+8W8I5HPKqMy z(n_C=m@PGdD{GvhJaMBp>=bW-m4kqN^0;kb* zZaTB=QjcV@jubF#RaBwo^nHbyXxUOppa_NK8~#HW`w40M%BA%AcC0ch7}<0=tzRe9 zFZ3x9Mf%zi4#U*wgd181$j>2a)CjC4*oyGYc&|Qn^6kz)0E*hsnbkb42=tITRamE| z@)(Ofjt^7Xiz{1v4!$IfWW2lerceY3>F{4<>xw9Rd%_LV2IcM*E$3V!g~-u1iJ*ag zPs%Qm_$SpKkb!lSMNZ=l++a}(%Gw%5v`}n)Q*7$1R=N>=erM2En4htp|&= z$Hg4%8w)2pD)z%WQsYK1b4IiX@I(;tOA~GFY!bC*+`Cn)qR&Bt62?p5bz~LO@p^EA7b`|*(S zJ{>&tII3wH_Va`GQZx{%)}K15kha>Vhgack5#c*J2?~V>6=B@$XMCkWjpuTnS`Mui z9%9{D)~euaJSL}!i#wUo7@UggY?`z)C$ zRPf0c5?BWMvrXqNkpe*o)qQBS+1W9vvJc((03%6oR`Ov*28%Z6wq<*x;{-o1j;MAM z?uoIkcT~tAKYK-Bd=~v;+_I*HS7NP*M{z7c*C~`0hzj(~`mG$^g)n=A^XM1c|s?YDw z`_~fnkhZEC8VlWY2z=gf3X0}Ar{PX9iUCilAi!DgE@)yfU>|}IG*X5-R5GlZ(|$$~ zDQXO-fxnX^XcjYpyb$_4Sxq?#zTW;%2h!h*@V%e1mJ`DYq`nz}Ur4+{FjfL5x-9Ct z1rLThCM^`QJ1&b|Xj{|3+^o`#+?LyGYJGw%6%VL)Q3<55V>~QM>$TBO^9{m@MArk; zFnNOQ%kbMfBn0$mRK|yA15~`Q6rSN`!pU~)RkQ-lNsZ6N#034ExTnm!O`*Bd*4pA% z`scw4DwaVI`8`&$#M$7P3{1AvwssWs+u;PD>|~80-BoqIcxR*GKX80l36c9Enjf+H z6!LTEDp~Kffum0ARY#_Gx0D%K$Tl^%gqr=*q1OPQ=>PD!dK>h(Vfb>UKi^nVv3l8y zVb(wDoS9o+qM)Qs&!Atokd?X|2we$6DUZMoN!H_6Gkvj(z_V)KAFjX5$=OEw^W*KE)08yGUsuTaQt z-qHGPRdk7&i5WK}$iN2g(?1leUl4@@Re@*T&{B+uP@(qf3^2Jd7 znCM#8`&;cLXY&{87@Zh$1J-@|O=*eOhs3@uiZNN%-x9^sByvEOrU%dmX3-2^%Lwg9 zKsC@L@s61GR^L=bm6`tAFgaVLL{X!%B`{wpQ@J7q1hVG7O4ODCx2+3Lzi_SpG-yqD zY(UftDDe4uy=OM}?Ya3dY{_3;95`gPallzP;?m5i&qP)HzU-seBy}Z0)P3n!|M+>vd zZw&2wKdGTu1N{>Yu}NpX2>aOP*ug6-Io7dn?{w5yW_63Lw9A8Xs*_$vQ3a|Hy$O}AJBefri4Ju8{S~)r9bNX{yec+kVwPa0_E5_p$Hek3xC34WlZoA3^*{{g z9AQ2QNDQ$l(&Kb66j{n$34sz~Nnwd)dkll$d`T{bwITPa=mfek!@gJ@o_j%>71=#y z^|C8EFyjP9V@Xzt(!azF$&M)4b768w(t4J33)^(i1PnO7-CI8uwrUH1oDV z8l#MS2NQfM75aBr=`U)?|ELlD&+(#v$CtQ10<&0IxJh`}K7!b}x&IHq^cM;;_XmXZ zPZ16$*T=1Yh;Tlh{BQ6jmj4fDT+R9d;`t6>vwFI$_2zK{;*Vv!N$kLvl?ml`9bU@zc*u2s0xc#>? zzP*9MutiwrT*T7v%QJpQk`YnJ77EqAiErm67AF|>I$FimQDNIe(A!$gr!{se+A<=h zo}nTyzp^-NhDd4lcQl6>(Y#DObDrE@B$LP`XaT81G-;9i6le{fL_Q$_ViF_UEePQKf$)MM|cOG|79FB%qD`j8+kuGBTbX z*)}%ZZ`>h=h8HE6L@i3eYQD$NAeV%KPm_MoJDlk3OrsSv0zlOvE_!gTrY3VL5k`VDvYiqgmhA zce4bNNI%{ER+-n<@fZF5HmdW4E46bOUoI;T=X%y54hq-0A7cXJZ_I6uk1+94v($B# zS2+1=;8hdb+OJ$E95$;*^wj!mO=pN2ea&rP*i72Le%)fy!R})k3*OM~NmNrDqhAj3 z?sE);c;;S{W1$!fi40_WhFp_wlOv%3U<{4v_9Sh|u+ZN^;Tu9>NLoKIO2Q#lW2zg@ z27s2rH`!_ucXYZa{vq0dRL_Vt*=ovPs53*8VyrCLj^w4NV8%#$Vp9~&5aMEJv#7ix za(s$k(SJs18ACNB)>9dfo1-B?#Ak?KN4?_Qg%XmIUN)*|W0%!ruZ$Y>uhbXjE?wpm z2+oLKl3sq0;k|-%3qmX}&9EzAT2nZwJz$&6)D_&&J&JE;A0fNny~{U{861d5ByT zc-DEQooSsrkM3VL*Ij@oZ+x>>+Y4S@CvH{6Y~c%#;>X0)4e1O+`hmGwWL(Mic{x9 z5b?%3aF&FlVlA{u>BD+cuZa^0>S(URmN$fFc!*1hfN9oD#IL&!i9BPMsRy&bl_nTM z=YB`SDc)#OeF~hSzgCP|@+yHlr%D5>YE1XvtZL>Jno-SoaAhF3xZAGI^Za0jQ;$n( zr}EZ^Wx0~|W7VwiMC^;x?Cp#LcO~o`G!-K*sJW3ORG^G?OtQ^VyQ&m2ttauVX$<5{ za!WiMk(zY{;#y%=3ud2og66Av6XnB3lgAX(2q3`myWX}m77z?trQLeS<0B?g^L#ADIY7VE?1Q%n&q(Z7Yhh! zN=zr)kO@xper>ePnTFSJ_6jOR+bk(ShQ%KEDx1%_oJ((PT#Z{8K=fsgyom~CBO)Iu znOj;jP4gk z)nulz(mhOagZeN%H;^8^VuyW^NV0>k{2}v0>T(5BF?dPNBU`0vx@ZVEFm!7wrGpxt zkv86n26H8uZ^ms6G;sOj4bvPT%mRO~{y>hVB$IL!Dsy2|`nIah3^*jLB;`7>q3iR( z@XbDtvz|i+g%fzEXb!3CPj3zQRcfIW?2&LvWJP_g5IyHz0dYM&{nF~fU)(mzNeb8S z%H{C+bbgVtxs3F*Sn$kbo~r=f@TfvjMj?d?!io2Q>*9YVOR3|Zuyz4DY)yNoY@6(%G+(qvB-+8!5dS;F!c9@=Ilo1?UefT zP>iRRyW0*rY;QsEouFBhE1%pgFTw`zIX+(#{&X%)X@N0%*-^*iVZMvQHq8_yfsQ0R zFFns4A4g0f2%*`CY6G7+t{HwiiUN^EX6mvc%M~@zc-dxAfaoB4#{BRUm`(g5_ySK=I5+dYa*7&K6yr5EZZle758SI& zBR{b`Mg{=NBBYUL3$T~(1QX~}7Vrb!9Q`WSS8W(18r&1sT8YSg+dH$(3x311-<9p~ zkL0G8tOJu7d4TR8&K#*8*o0G(7Y0dBKn@bOaW4H)sM9}1$_w3J`F(@47ohNe zUXryY<_&UTryXg6RW{IbNQJ^l@1|#VP$6<<%fWXvePDJcG#OIv2>F(bG?NROFjefB zQ0N7C^vevn(yda}XnHT=hDq9x0#SQ9TqS*Z0*KYu3jt5K!jnd{#Gi#qYh;z{21|QK zG7P3N1Rj~>dLPTqzDw^`n}8IC=4v>bB#t21t1u(=NcbaEE~nZ!sl(j6S#f$t$?Kjt z-m>c5?b&YYUgLe6m<@N~;kCE7_ck{$;6%X*>=DwGyQ!2#M+fZZuJ}CJ-<`ww5s=`; z|4^t+3&9aqYF^@E9Z@U8pyViBwV73|u*{6Ip=YA)o8Rk519h?IudT2am348CUF?1w z733qm+T0-%83HcQx{+C8AvCwefArhB9UjYYG(C5|<8VZZp#ctl|Ek_N;-|*X1s?8# z)&XS}O$mD{Y;6>MlR!~_j}mt%yt$24FzCSUAaFw2*?FJ~n*)^x!rkOkkR2>c-mYYY z$5eW5)b)nJ-#yq5(KKg(@HASF(Z;a-uu3}2FiXb{!?uWcmgya}x)-=)8~v!2ZZ$TQ z1@3(70`Eez{jhk7;NkXt58lKNv5YrtBl;^ussJj?z|!l_GJk3s#bVVE$cwhcLB6j(2z}~?=*2f$4HbkzOSww?*uDJSaCwuSfasVznQygd z6TLMrI@uglm2U<1GaY==nrPCQR(6Y3l}mjGRrO)kfErsnhuI}V)0r|V=VNG+?@Nqx zLk%8&_x4E9fzx@S)bzzz!)XxOsmsIqb6EMp4TqLF^GSvGP2RDI5PNbVb7OKm7bd(Xqb(={cBEAdY!Nq(Ky!vZ1;Ga zYVz)8X%=9ZO8AGo>))ySojBCWB|t$aLCdR{iP((ULY7P&+)HMT?bPs6DQG5@0uMwi zXBcN0ppU?mbhS6sLp?53k{>!so_P&VLwlU6V;GiG0*#fdD{Tk#QqG}s*8Y1s~H?y7a2&HBVF#vvk|2n4|k=1qT=xdH~(Eqpbr04*6~kB=mQ znyskTa1%A2HLAidz;d|pP+v>>iEnM^Chj%tC82DuZ9v1UGEL|PZZhq(J>W;K)2Ny1 zq?MFW9R;C`F}vzUe!4LB<)T7XB=1bfNq(U~6}z>!3z?~~qeGJNHHwKlmzfYpBzWxhvl6h_*7Ia*l(@)1;#Di{6bgRiZ5V0DF4n&1F1KQtX!xug*k{PKWjZ60D8HD3 z%9Ox!j~R~pWthpB$UMrUO|4SrB0hDoha;*#>{3M=2n`gCn-H*Je+Jz+<*}oGCOjQd zq*(yssZB1@s)FRmDpWkAew=!Yp=MWqRX(3kYEr?i8baO)B|KQGlV;ZT5_U zsv{x8Yl>O;B;X9YU!XZx{h4mB*~PEbM8Al?-EbplYKpy^k%C8<7@FFmE`Aq~z~&CT zJZlIMkUN=QU&svPVFuM@8NlGFIaqukZ`azk;mDkv7Wb3Wl~+yj<2kmK?UYx=Li(k0 z>f)TFNXKKDob(xC3Ktx@V!WGt_OT9(GyO30)Q{U#Zl!Lp9ZBj}{b^ePo8Xtly>|XS za02_-&-n}K>zO`L!RhU|n)fxZgbn;bEzp6)+!>#u_;5bCfZ8}pIn)Lpa(OTc8B0Z8 z4z@jEK6ZIC1<4i&TkA-(_%%no3G!Dn(t~k|Fyg=23}nXh&FfV&f@6Eoe?DNu^LRZU zE8~XtcVxsE>?7VM^3liWFfiO|f{EC$$A~Gt7t6nKFhrPx@00H$`z_=hOe*I3P zgA>O<<&%sbN5PMp4|iB$dEn#o7}$aMjWF(>*Uxf}dE|L@#?;}&Wl<=h=&gbo- z{Z(^$zLYmVpmt#;df%TgN?D)zp@@RXUP?EAe4}(E&Y>Z;Z(o~tf%OFmXZLGdnM+J% z0I<+jc6_tmL|~nG2sjNycrBf>NUiTtnx3O#3Rh^f;l#@>Ts#W7+i|@UHEpEq6(Y^~ zfp)S7ho7?rQ~V6j)nXtXSn`=>u;q<*KYVl`PrkWMwUwiHOG%xKW@%zrZ?wy_X*vv{ zPGqGJHyewNUZe~$O;F3^%s6)z!h#&2&IbzbYcXM+4$YU5 z6e6gB>RNcXSZU|6)S+m($a_%~U?XU4WPjGB-`a(+oUUATRiburM(Sm|BOAmi=s8^q z?{eS`=BC@!mHZJ~T8Lg`{Dk=~BKv6RlT6zxqlK=F3lpc5=Y$#r45{;-j2w>A4k$7m zAgtLXv)}7XZ0R*%dr*r<+I%ax0#r0GqfCe0u>|G`Q=i7Ra$x_00fu}|au|#E;xW)g zwjct#2?Zp$a`3ZnocKG; zuFLNCl`CjTXvw(cIPf3qO<{|;D>agi#89)}uXW$%EOp%k3l!MH9k59Q(9V}^wh(8x z8NN*-mhAFEf{z)7%vQU>r(Gdq4BVM&7@6vbgj-Y!ji4wf`+rD;tlQZS>MdFE6v@L~ z9}!;sV!~XR<~8@P%JLXb^Kqs4{oq;xDg&k`XC;TLZr=U3^pV^9JjI)U`GP z_7gy+vTyHj-itvm)goMBVn5S@ef*tzO8Sxvksuz-XmjSUrR!;^gwt*3Y*^Wa5bq__ z?PR)3=`oY-qiI>Zg`A)ix*V~4KJC9Aer`Cc3l3I?e0@cM$7^usP(XPZCqVmFyvV~w z?}Z`z^HXe8;!25y)EJ~2&4VT0avw)uY|gl>9{9$X)h?%yMmOfhYmlJ@{7=$6N2)d7 z96DRtW$ju-6nVsM1d$QQR2~+V|-#gB0C05t>`Jp_J}l{IU~e2!MacQRh==ev6P6@ zqQByr*)sJ>qydwTikL&@%ymRrsNMq;&qp*bt1#K&t`x+4HPzl)aj^0=v5K-FQ0yBNbuLg1TO2% z@KvfGW@k!rR3#Bia@d5Y4}Ke0mW0QqoIA)xrlpNDDd8|0?#T3remF#RHG6BQxu^40 zHKMtr-B3%zBN3s9v9q4#v(*g_yQfjo4D^R{PcA5E-n6u>Ca%4NT9VR-uou%Z_Wt2Y zBzHzb|5dW56Hl-73(Gp^rZyW~`5gzV1u7g>kfcPo59Ky_OTrCg1LOwY98(}Ex$oQ9 zaO`Ez&E@t$%3b30HVKRr$4u=KA!}2gCT_)@3jF!|*)2WNyQ}$r;PToyJpnYX6zkB> z5=+YG1yr7aIv2p=&s#Xivlb}2auCFaBZ~~~wUoo(-)`?~-EwURhRgA%%gQWPOclFD zRx)F$;BV6OD7;uFlNP#gycOM93Ux&4Lg=Vgo#;15=k&J0w68NB)Wp}%ZYw|=(*@oG zA*lpR2R+W>pXSnaA*12oV*T=YO7WMapR379gwPm`N%_-kyht!?Rft(gq`L5Pv)nOlc~gtC2eLyx^_#Qm#)O-A|?5~ zd$4xSB@ExgAPp}gwqMWh?%m&(XNuGN#D9p1y%)lCd}8fXSl2b4nq@-8g9jNK#Z)#P zi%bjmiij!@{@uGa{j?_XJ+`s4Cs;hc$tpf-Is^XUa-yaua_uy{9b_7mE?W};_yC!k zXgD%)RzkJ2E9|tg5|4_Tl0xHz$uTJInM1z&T^<8Y`1OT~s&$WD{&S-P5bmmOZy~va zffG>PTG?IgQ>kjYcBpCgGsWPs6CjO*v`GFQvA89=i}&F8eHb#b#eKDLYo*;V9nLGC z)L7nlYKF%_U=5bX@wpq>zXzKq+}xK@E_1fmt$>ukQ>6=;aHD(Nwt+EnHch<{H8eMN*^C-V~>>okQCMY2qYnQupQxHuvs6z>O%Izzfho=Ew{x0A9!?0 z@q`wrfT7ofArSF&8g^7iMr9h{!azQQq>h+}6<)9$$spk{ta=TWvm0`F?yBFZMpTLj zy;K_b`8w=Q9or^bY`JwLT0`jd^^~^RAXGO2snJNlv}sq5HEgO z2ZK&z?6TK?kQmptqPLH4%>4hY7xm^{xv#uhf3veLKj{W%jW%zR~QW(c(LT0)Jiuo~^ zUcOp*;n(J-k`uW)n2DNqz*Y?Yon7^T;@UNLkGZUnt*=(W6tT?x<`V$v9OXw-IEf zP5QAfal~be9L(Phej;AOxV3%{rMkL)r;ij20pZ#-^VlOH@4JqIr{>#(UDqy&MtQZN zz%8C1fyrck{xnicdnNVSNiuk=NG&667eQ$2a`Uxwm$80E@Z3iBr zYT(l*KSg8?7IKv{Iayi4AENHO5(Tt%YHY-4$D=bZ_0RB=Cy8|Ut{dA24N=rwu|4ROwFkZ`ETv! z&j`U!0ksU@Y5twuz{&Z~Q|SN5ZjjJclGakBQ?Rl#c5_j2uv2j0kzcb!HPiF5Q>5J>1MBab(G~@VR9^`ZUImrL>@c-|F zd{%ZguD@toa@Bp*&^7V$VM2Kr_GMzo_svU@4S#-6mx*<4YSf#93nImDFvmi)lQK!! zU}4EYlZ4RhL4&Tbj4@EqNJxTrs}_c9X7z0@Hte_TY}zjJ+}pl4eQ)yMUd-EqJ+JVY zd24&$>ge_9-FbZV-|>(P6`K_i`=q>YFOqL!`b*_`YbiV>wZa;+AzA&$r#V(e=^=)k z;aB$P204aY8NeQf6HFuk%xV4tJ|6^Db#^LOr2`S4bC(C}MG)pKD~q(5yhlqbV~ICJYL@WipfAQh?*y@QQHITV=NR|?3rTi`5ca!6df6s0gF&FeGg!t zLS@Qu(#APZ*a7e{XLWY@i$~NU zM1Q7W1!=;F<42xh#2^S;6F1fMAzIfg6f9I^p0%T@6Rk$PYc9)Vt!S5CsVtWHA5v*a z)GStK-C$u)sVBAXGUWwJB5?k=i5wNXeBY1P2fq7?p_nrMrfpfS&oz<{o5;~i&6*>X z!n;LCisJ*AlE^0bNm1THC53&9wiP!JZ6*DlxSFU&E^J9kj(3J~f$`fy+TzT@4_zJS z!T%mGZ(+hYi~u+RNSa`e@ETtY{_wo49Gso@VghyVTkj2Zib_&!_st-mmT&nU4f2D& z&c?F*^RhrtSRu89bDP~aqx1V<0OVE#yN(TL$=q>fCZViDe@LT#t6_?{r!uem*TxF4 z3}LHr(%|^w^hp_{E(9|?j2SG$K;40Od%k-QXz&XVJ8MRUJI~xaR$Jm;7KvMFC-?E~ zV8|>+_rq1P*MN?XWMv&hkxk?`2&nyQO~)g+c5>xg2C*{Jh5FSKJLliDKh6svQaWN8 z!HM7fN~^i6*0S{D@OH)MHzA7!L+=EZkQgopiCiIcp}dvG^L==~N6a!jc^{bhw*+5d z$X*VlzKkw>-rjZ&Q0`k014CRJ{Ca3*l~qp+S-!D}Q(kqe&SjGHlR3&o7JmTofi%$I zC#m~6tJw+Gmrjv^mf?^Q7a||zN0In3@cdAo>v3xCu_LM96nry+v%UBG4k|sNle;4A zc=pe>C(|4mAt}F_@mt1uKWt$*W8{{Ty+D?;6_Ne8VX%=m`#MK_6kyqdLDH%SE+f{# zi%|41Ia-XY0cuRGxP**!j$k$|4^Iupq7OVEN4Ns1f&-e@RfVUx?U&oReW&Cr_?9-v zxvS8o&q!iKX(v|e5#FFl&;7UrGuCKJtXtnZHyg(9T*<; zBG9g~S##Ia!ajCdn-DwD&9d`|H^i__d37^UP&N-L*LQ3_5&M!8xek<-*>Qw3H$0D- zE^l}iLSa{LTlUac?$!pHFGKLr1IyalP{_e`%_>HHOGPL#%&(4Cp5TFKjJ|G{KgFc6 zUQ$$Lq@60(4_d&W9o4jdD2;1{^c(1BG&{WqO=mJ3=E|?lCAx#*D0K&oTgb=08H*d0 z-KDq$*QViy^;}@BvU4nRh49XuTGeu2oI3(RpKof$cVclr?3zZFOwveT3JQ~{L=W^g z9_*s+9pv~B;K(B4$x{ZNV(TfDEeHJ>RXf#vu^6Mr(Jk!x67G_Srn}Ixr#^>v)SIOe z(&!ZMsxsfsIPUCRQO7V0y@7S&jOETecmDbXG{T7|6rAVw-RGt407^RXrQ1KcjQgYd zdJ0y`Uo*q_=IH>VUPewpkv0q37Y>iHCpw3ez$^^gpMOaXt|}-5qPhwZFC?;;FjY3? zQmZv%5i)_Bk;KnvPe^tdY5e9`l!TVmdVEfj(w#vO3-$mrH0z#pu+mnarmN%}hX|gS z_%=b-Xn%89*79&7$o=lqQCCx0+Vg-RNNzizmhk{H(LZWQyq;XgRB&t8(yEbMG^}TX z{dE64Xp=t^kw0d6!|SiilG(5Ze$r{*kblhWiuuznQMl>%^kci%8w7d|c=8vyqM<3f z2sEo1fvOgqg4$>uLyN(&vxqf*tqI8v`m;E?k>t_9oczJ}n4QtOb-pY&;Pcb2X0ler zgb6sO+Cudi1vHZ$H_%drbbSA@@8?2b+cKDCg2FY+4^v)U#YGSX=6txG<;OOcE0bRM<^ABE6oGWgHkFIss z1Dx#>o7=a}(8tv7>A`4fJ67lL9uGNP-ky$B?-=j&y?O7yH?k}8^NH<#o@u&5Zty}e zDq{cI=KSyty1Jzj!p5MGNpsFNDoPPBE~o*ip{}cWfFwc`f`uw>H?wLDsijch@ndbR zYMI)n=Boe6EbAQe^*6i8uS99zZv{S-@0%+Pud5Dm5s+KCc=4E8%Hv4tfrOpxocHVB z;i4jTkm{ttQ)?)NK#!CSB)%#^OM}BA^f{MW7kGbqGJA5jWF`3VAdt4porBC3fD5@3 zrYMVSR~92940ezi)mnLsC-@8by`=BxCP--%1xKik0PzZ|(l5<$)IrOG?r1(Fs%ht2 z@hC~J4xP-_=~P0vQIZr2FAdxeh+MlcNZJ)sOv+hx zO+(%9A9kL8pu}crwshas7|To~zvobvjs9R9_;vkTp)wfEz2jJ}zrzD6WT(4|d!n0R zdhzU5jsLm7@XOWi7k{M?`KHLq-E-XFP1j_a+eOTQwx!3mZ(;r7IqzXb=eL@AA}=Fc zHesV!7g(mP-&No}zUV%ok4#hefRL@avkh{E2k&gD4`Dxd$O-ZtVtWXJ9^{?Z#sWkW z0>H8N);s^bIcDMdXJ_{xn`32hVI>tgI#GEQ7UqBU!hg8FAL%e$A9ln4nhx_<(|wMQ z{EL5f!hZ{k`9~-G->1W{Fn=(C|HX3nU&Ar}Te|Mw<>QV<&Sv(1Bgg*j>hH{0M_V_S zf9;C@><#`m^j6M4UGZNw7XNd4D<=!vUz%e11br!0C!CRY3yaU$F82P8Bo%filo_05 zlt$rr9n3K2qIAL6#?#5VE%L_=Y}00OBPrPNmKE~0qxxy?s1XJBou_w{W8Y6jI!}ul z?RVJTKQV}3A0PR7?s{!Mj-nI?F(VBA?&`$He{+a<2#N6@EBLHkAR|owRql&PzqxO% zgXaD;+_~HCk@EnnoGbHDJR-vA;47*0HH1y*NLreConv!hp*S}t>cQR@5?WWtuL(G? zQsPd!r%{lDMeOvRI-*JJjzv8NX=a8btfzos;CGvE!31d{B5mB%BUh1rA{O+tuqR-s z%4;3dZEUX%V|@waBVn~#`8e@tBJG@t(=BA(q3u$z4M`ftWEVqvzR@_+RO9FqYHWUT zGWqq`d0$$>1!BE4%T3_@Uq+aYh1Ag#TpeDIlVB5$24DaFcx7;MQbOk%+^{IZg z{)8@X{I*`q8X#ETu0VWU(6=;(R?|13>xo*ARDS^JUI0!<#MFmDowgp6MC8CHTE*C2 zt1^gVR*1WCY_+ay{VYbfGdmMxX0DUDg&pewSZ7k++xzK9-xXSVcgp?Ci-7)2j*=fV zxx?s@c-ChFLJh+E7K&ef((0(2B_kA8)|;1&?ePF!!_T!_co3|y-oD{LwbC-%AXd0) zWM8!MTIZtFL$rA2LfHj%;>OIkWX~pbULLP%bq^+yH^Q@Am zV-y?^Eh{3TPMYp^K}XAg#eu29=LW^q+T9}T>inzl+oj>a>5E)m@hbMzY_&}ZV^xE8 zOX?xSq6p#Dzc2caET?~L=l#Aq?@Q?Vg8RsEk z=ivC@`2S-I{8tkR?*G^J_hb0aMbG>(`oAXP{3#p%zUH;0{>H5*VdwrU$N!H#gu|b` z?jKX{e_hpoirW8XRdfAW)qkmo|MOMN!|~UxE@&gT{0k@u1Q-Y?C@A#b-@ZSW6i@h| zPXu63gy0T9vnSo(;*bCYZ~y{C&GRR;M|0FiUF1hK6cBJwP&c1IQ3pq_zf~;~Y7-ig z51R-sdJvO2oPIPWYA_Xez5ANNTeq}hlR(-ZP2OZN8JtZ zM;-^vjjENF#g6Q`#CgC1pdqS0vOzsf=c_@5ijlI3f~7xAI1m)TT4q&eQ)>tF@h{FG z(WK6O5Jkvo=O)9x|i)*cA}k|i+fD20aw`iB8vke(FnrqU-Lk*DugKxbDT z8CJm`)gB`;!=u6gAGe)D$Eu3}_4#?kCC>e>ixDU5IAPgN-mdqFl;wFdjFX;}5|;^p`C95BXcH;y8WjzQi6-Xlcgu86b_U?e0}SOY z%~OJLs>({UD*!EkUc(yep2~r*{l)2R@$G;Pz}M)Ks1omN?<}{Zk156g&6b}EHbGa{ zAC)%1vw_%{Y5ui&{f2WU3jo|?Kz4k3{K!z>M9-xCBN|R*MpPys6Yz){@`zM19+rqB zYGRUNl3`VZt7fBatzjM{9WDis0$9ab##$}1;ux43nj6@{JZ?OCVy5Y3ivZkU^qmZK zRka$Mjfuwlrh8{PVSrGon9fBGmA>T>?a>{8c0gNfcXm^k+r0m9NT^Vh06_3#lDRuPc-K&0`!w#?o!BeDDPSmaC}PMc!#LNvLfcYC z-`XkW5ex?~kT|uo=ADKU4fw2VV&}4o6A+ca8^Z(O#RUM7B7jJtK%@a?oUIl0wS-5T zulWt-l>ppoK)H8`XS{kMAHV@X77yf?)cKf5G*G7cak1vnz8CcI_yqhh`q3P7sdBml zun9A(+8`^ZYi43ZlpR=qk7yqS8`ZN4z!DRga{{F88^S@C={R1QvGqZIyVp6m-voK;( zvb17SwX(1?Vlw^Ps}@FfAJ-0lyZ6x~xmp?7np&BgGdX_z+{Y&ilcN=r%g2${M{W5K z9DP)okKg2J^{Z(8RhluBgQslFFCRTTnBn z9Km5{i4y(gB+6_QC^c8m&hF}_dT*f4kR3>ZcH|BY#|Yz2X2(UwZlh(2U(8a3K1@ML zIpWlqLBLiVH-q4{e3HncYL_(rk|XF=dFl5EyzJVk@qyKrN{Atetf&ay_^RxZwd8AJ z+{bK~BOmD!JjBx<$P>^LpjiH7nSn46OiKUNeMYqG)5~2MuuK6xz*CHqKTt_%ElSup zg9Fg;URwAxCTQT;oahdTrNF*~1y0$I?1B z$CiWf#I9-UUyUGFZ1=GjWW99c@31HVslgfF=ts~Thvu-t*&6wnx){-#>`5#9%3nuS*y8GKN% z4^izX9XS8)V$(8gJQjdrT>RMdp_La-B^>s998bF7{$iv8Mkq#r48G)DZ(d=0Y~>IhMI3d2y}+(^ zV17oQvsk)n2C?Kf0&xve+$^}$Rg7p~tnqv$8pbz!{e4xCVRr!?rz$KTtSiNLI23+# zl==Usuw##_DO<~<8Aoc2l1G^{M5i>_@3VIgLwcYwDWy^obyBy->7Js8*ASsDB@&V% zO(kR~dg$@rJk=FG&N`mE088%4uqj6#*5(x2+MM1H(h-Z4!3SXPw20bAj&3e%sI z|7NzqRzAG4J^GPz=DW`gG`?yL4Dnp;n>u8)Ye|)Mn zNT+9t9P}hhs1cg zYdskE(T0_qUjCSLrz$hjSwZv)1?>eMtKhi=F6jwM5kTs9?&~f(zT^?-o=CoH`8}bn0?`W zzB&G+8h06RkS2mOv#1M6dDD422Cql ztu=DwsDp*cFYRBv8E7?4V&8Q&Zzzkh(5%_NYPeqKP36D3#<#?;Ox{;mAJSYs<$SM+ zS@}PTjni9vR4%fWYhBo*?~Ii6eN9OYiEXHMKbFu61H za^;(0lWMBUThl+m&@y`+S3=7*JouQ}`t9I!oEVr%BQDs`f{aNu5M zd(5zdaq@XzzKonQ_-v!3Gr8U?@_}__`AGY`#L~59=>~^EfE=uBFzc=^eMNwBL@B6wFxte4r`0*QWfa^*Y%K zt-N=c^QC(GPxbT!_u4<3u+O@7RsNiuz3((ldaXMXUhLSNadPG4*1mBGLyH=gW}BT> zo^>Bo?3{hIfx8=@cvvquy0U36Jz}rs+Os=~$Ao-yr7=Hr?u)7CZk31pyJ=C==|@@% z5(Z}9@c(L6Kfic>)}gV9o?bhj=GD0kcT>EkvPw1%-VyrLA>P90ePzdc~H~9@S zjFsnjM9ewa7;@mfRq42mYGX+ zb$<2xZBmQfseWfy)r$CE#vC2JaCh*C?Uyd!cbl+}_poW(^1(u<_GbTZ-Gsw%&)}MY zv*L|j&(g?^E^EqO>^_klx~K43eSJ*yg!-H=w>xQu8b3c%l{s0hf9^hF5k0p|vwmg( zlTfW=QZxGAFTUg}e|wt)^ZM-W|90KTqb?N^rAwrJajw$EdZ z_XXCWIO9=HOuU-`+j*+65gMdl--%r;4Oq4 zV|po_(8T8UxT8O7{5zb(GiE4G;QmIh8-M z*v4h8pDRoBG5T)97R9L#gR0t-wD6+zFHNQvsFeOI{S+#h!-DUm4uQ&u$Ou1GP^)jd?1I+=0$&49_ zFn_W7i&iNDB!raY2?_DXBZbDDG%F2|euR-CyYPKQ@sWo855@^{3ij%1Fp}ZraJZok zBUk|$C;kq7Le<6*1OpA{)L|lBu^p%Q{6UwZIXLoEhp{vRN1*C3isGOhn>vi42nwMK z9ZLxTwix2`2MxGO0N>|ShmisdL|_yv2q@1KgX@K3I5|F-;!zkUC*Wp-I$er_$q0-g zCbH!=h6ZV2BD4*I-L=pfWhY?ka2_@)t|UV(12NO92|*o7!8W#1UQ`)pFefV zv(O+`9VXf2gr5HFzLSP&VT>udn$#UR*>T>}m-UCs?2bw}{L!`?hIwdF$w_TEz z^N3!+-+0W=!4qhNXAvJN8$rVx15{pU^iCtZ01Yr0Ob(7fX^8iEkZ}af$zc*(9_n_$(Enq|zV-o>p z0Jqdoo(0rbL05P@AmM-o)fM1lP}|@*@Hmu)90CFkV=)*dh^If|^Z)ov06uIzqGKjAdfR9Cd6|xM8$_DrtEKdUrmjhTv=!*DIJwsq3@R$SX z4VQ!agd7ZNYa%{0b`m_qaeO`GSk8kmgz^Wv;xNDDSy)VUof2SbXlw^v@u-ahOhA1f zXkhj%;*%rs1u`gu+A|5oAr=z>hOZkV7NBZ&AmT%H4=I_!^~^&?SDy=XNgnefhD7BR z@xePWHM%7H1>eF_he0cOJlFCxUUx!1N9O`2Y%W0ySnUWLQ|MfP;p@gg)r#;(Kw*dE zJV@LmkJ%{?#R@VPM&Wsokz;WUq(E~mWZF;o0x!qvT@uQBR5r*cSRA5w9-~1+F@@L$ zm?U0r(C{t~m6st{0)tTuR_`(bcoL!)7HkrUIgpZ}nnK2LP@AFa!NJxA8wW0p$^m-8 z_5q~8qPYUnJ~$FWmm*lq)}Vey{RpZOD4@}~Km^GZBt_8}&lC;O6P?S@*!n`HBK(EF zNY%0+co!+LvXa7^i&%xYNt8}^Q7R*)FiPqoojx}#Kq&=nNL}CsiLKPj3aSYx9_(m4 yg0~R_j~5GDe?P)U0%*@Qp%3k3tNo{p*NvNq0P zN=Ls6F%Iw9B+@wFzVLW*$?<9%^ZvveR}~nEHyM={Eg>l%yQw9RG#b6j}Y`O>;Iq(ek;i+DEMB8~sV3nb_PVA2>sE7;oD3 z?xMBM8+dQrR3^>VY?LXRwJ(*B?|A!Rdz7A)L%#W}qb&PXyN9_HssKeNZdMY7vQE`Yv|Ho|2MZVYBde=D2Ia$E^n|<4LSKq>u8_w!^AN1WGn4%vb zi7VK)*cB$BR4Sp=Q8_7aR4R5vrrAg^kV8?*Ssu)j2EVvN=I5xE-^>+9X2c12W}19B zXQ)Q$tOqtZsVnqTVtSaU38e1RhTVkFPGr0yXS-8IJZ^T`)thsiD!n*m?``p&`&St! zkA(Od5^i1-|Dtl)+?BV)$r3#NKql@O@<9F!RjBU_rP%}617@Or?&Uu{J{(3^^^ZlC!A6o}6o4p2{E*IdRwwqHl6R3dblLe$ zx8WZRKwY~@wboo7T*bj*iD}fYUIU?C(BLkw8uojgy$3lhE!Af^yn4oeRuz`?5Kl_+ zL{P`7&)#;&A9s7Eu!j@nw_+%s7@8%sV3C%$TGM;iF7m>=R&N*=K@dG6^uICqQQkON#JcC>w`l&a;PNtIk8ICq$F* zNV5>dQnp{gS)SW?mp0v3TAyn<8cu-gjTBUF`mEmx!M|N*zE;ru`k)uzIH|N_Mxn~% z-`draZ^1!BAtluYfk_5K%h~$45e22}Zz>&PkLrp@+gRrg?pbinFU7?h06qmpsKRRs z+^i7k!GD(~NI!{eE_J)x>Bj1SegP`{`20S9P@0H*eL2?HnK!Qr?-mIH1LnufXtkTj zgknW-QPi@zv21N|z7pf=g|3}6&`V8@fo?sdkOH3tTWd>-4!aO^0tQ1isoc(u$ku7wW1#xk251uLSz$=ulY@gPr!u$5ksLRFL(7ic^~qTqoRZH@u!#4nXBYAMKQnZ zQUz9wvP9Vv z39BXysDS~^fA;t|UQ}B03#okYkK*`)#S?+d(`^(qAa}V+%&u=3&4I)8E&&lQbBRZV zoJN8fHMZ%cs9VV$6y*f(FJ%6s@KvD%amfeyAeONX5hsCgxM%|=v-I)nY!2&9^JJRA z56Fjvd|N?0{B8_ApJ`L*jfC3lk5Ubpwt(+??Pe;xEqAsl_Wkn6?zGvZ3LOq5L_g*m z!WDHvP5X6A!Uvj+F%^ijpBOVeZQ5*u##7xxD56{}98NaQ&InJaXP}F)+z-K2Jed%@ znEH?D8iN6|YcKCkLJeGGsqHL1Y)WsiJvg$Bef`3xGXw{RH*856M>;hvUrfp3(ej=FC+?; zpOV+b2CYjweYmJ{rXIj)P12vKPz$fX z|8$~E@{y2KT9Zo*jG7$*$yORma{5t0rDIk$vPgYgWmXmrf~U8jyiZ@-6>c?8>fc!f zck2A{u4}bw>-2c$$w^zwBA zSUj4O(D`+?6&|pGgqC}~NaXUfS|zsEf3fU7*d&qvuB?~iT0hRD`?Z#)IyBp3gIj~r z1o2tNATS8bKQ0Aa#KsM^=hwrc;m0fN-Lrb6lB#+8^%FA(l_f^xp-+^XPv;d!K<5XK z&_~ShCs>JTYw9GP{8bonkTVapqg2NVB-Y!5Gn=#i^~aLOWymO>_4&jd;?v!7jOA6r zu6cD$B;?Lusr|JbDxhhwl8tUTg>czI9OrShN9Q{itarZ%!5aXyc9;EV8))Ξ%<8 zGXYJJnwROr0r)V-gYg5S-BI*=Ea+<>=7z_PZ{i@FM%&kCUr0<3+>B&Qo@}}Py7qpS zQEgg(ER(>=V!r5ltNsdyiNG;HqU85#sK{=w_wJ5{)1i4N`gN7V>s?xePqValt2eZ- z-afbZa|3R|Fh`$k&U(E|C^E+30Quwmj9iXnEtMq30VKVj^*!) z_3y3h1b}~UDyX&;Y}@9OObh5d{o&3VFKiG zzLk-ah#2=o)uuHr34cI*rk$}CGk~%bn&nFrZ>P0Nmr}j?7Jdawz^AlRoxjXx@1)j! zOxelh=2f_P@6Yl|>uo)0%9_&F^iOWR*>r$3^Yfyeo2u0Lp376(IYyljS4CQNLQ}-* zsx#XU_nAt>E7uw|8J`w+NFgRH1tdB}tOT~eS3>Blg@xX>^Gcjroc8sQN24Ikp&=9l zVW!6qHU%oO47@S=jNvgI??IFE@g5$C#)s8qX&mglVewxm)VkcbN1J}WCnMeNcm=@} z+Jvjo`dV8eNEW57#LvCVw#|qjYBrg0YwrgDhL(rLffwV&N`Bdo(}4{gAD)Z8glFS* z_nFhdn_lDFXCmZU39P#GZiodbMxWl+ zz7&!cHA8TC_Ps;wLw+)fW4l>~QqYW~vGSUW&mU3TA$a$cifaQSfFN5D_Wg}MbHfk)z{3;V}+49q&q9%lZ$xQ%Q>gcTwLD~(rZlr zChh2MzO%5RZ5+?inxdvqD;24l1$F*j$dJNM?$FyhtnIfUGy00ZX);h@6RMBN)iOWp zL`CFyND4*|muH(c{xe~&1?^!lG43`91>0oi0fRiS0#ZFb0gWgX zOzu;<>HvCoiiqv(qnPD{!+r`RrnDO(5wkc9OY(6{wR+TSk(nW3j;_v9?*J3Qj1%B| z@9>)M((vT*DrMnpLkf?&YVV5gM+$+Ky1(EUQ6@2@@|frGHzf|lf>rKFxrQrDXr*dS ziiZO8yLDlw^r-4=)%(z15a6^>c31(h$Dvmg(-VBqYuWA!UxaHCY$oZwXex)XJOUokSPXx<6bP>PPoG4OLwoH1ka)e>it6R}9rFr%QKs z(HbLvZy5w-m94h?!WmgiXzw?r!h&|FgUF5zPx>>yKeMT}H~`8?0EsZ$!svFu<$$*G z!?;ni@zy&nhygKBZ-(F)FIcTEWBk6Cv_n?y?P~@sgRNPm|`PS z+K{j(upl59ZT(UWwA5GI`0k}Hzx4suUF(FC4BAmXbq13}ZseGQTc3#daVp}Bh4+MC zVAseWYdj)UNn)Pe`W#!U3BTm@gh}hM#g?|4iWQ3mYfUx zC&%Z#`o&ip0;~}}41_g6Z4c_k+3&aqLy;oa$+1g(P%2#*F030h-=;4VY*hd}%^6ad zsT%>5Y3DnJ2Byjq(bY_)I$q6FLI@&KuwxOo8+0s495=e6g4axzq|mdVXMzXQ6?(&I zTeb+IS8{h_z`s^QV%o+_xy^)Ve4Nz?G}3^9vjX-E5#6++M-8!zy%`u^tj6|U8+10D z8@Xt#qko2c-Pl(TbiF6}rG6*FpoFsTtDF;QKL(wOP}?b9ZO_1HpMVBv_b`vVJ@ztP zR{Hi}(hCgD5z+&KN;>{*3baO0s7mRCy^o%{AIYUU8#bt6e4V&CMy5e@R8~K1Apawn z(9*d?wZ!Nsb#hcm5AccEOLqvTcJqPBdj)$`h%}Aa%!U6JNs{3qr!zUF<6SK5 zaqqsSU}oO5wVs#H)8F*gZZrnhQ;EjHv2!mbM*YLU&D!1F`c`ureni2}nPI(45Uchv zo#z(wV?n1WW8g(Ly_?MKOl;&~bk=P*)Vu^!xx&w}wp>BX6VAGObUkSG+`iGe3ra0r zxo|kY38-Ru_}!8Z2x^1WHE;a7R}M7q%i>zEG&2iQqwKT7%07|iH%%(}u0ZGy2b||& zOW|=W+GIXeAuvI*PF(&RWxwiiNMjH;zqL}Ofz*Bw`zLOB1YHIiu?%=`(r(r`iR2J; zQAH`ysbe06R?U3BrJ}|qwe6O2_{05l>S8ZbUimc#t8bWU53u9kMl5Ktk<)6~vNbq+ zD|klB-Q+Yb4GWF{BVqa0CYfA4|)6ZLCf-&I|@w3PLUhe{0v`5 z`f(B}>R6OBV8uj(cWO=`bOy82dI@8{*^(IXih$S7J_yX_B63GQEdOhdM5b!%7(`oL zYJZ{hZ3ySZlM!6S0&?Ln;m7oW@E0qgFqX$Vg={5AE}P4XE^1&&O=J~4++?7!>b9Q+ zp`yE;M?0vxmzu@L>&wAvN`TG$NpTD7c@mJ3Ixw^E1GQArf#+dCMP==`)sQlMCnU1?eL(^6Sz>nkleH4geD&1`;9ykQOwZw+pjCDw6$89_z0WHe`XxA=-eVq2nM zSIw8kqb|A=YB7k`=NvhYkvuFByalKa0oPjm_9+4Ap3TG?eY)416B(=3`?(@LtR}2r zXfv%6A*RLZ#uI#5X$n|B)$dh(ih5%IgIoyZ|fDuAaFJ#4L#H#M(evh^C3X{Jc&gJ-P@MS zD=|+2TkI)3wqO362TZ$6lT9S&s9Y3(WP)wpGh-fa{UKS*}u|6ThP4*`Jf81Q4 z?B>!L?`{q`QE`pX?#+P!R0M1z)a{hXMyzxteZr(zoGOxrHC7cwuuHYf02xN==CLlr zW3b6g+7K4_U-dZcgB`|TxQ^C7?!_oVdI@?8zlY*VpTkVZufaa*qQNm&vdKUr`vnkT z88D!jRIa?HcUPP2y!kL<8GqvIsy32YY34Mr;Gto#?hjsE8u#7Xe1dv>>Dl-X6#N&~ z{>IN=6#R#MO#hVsxR2>ip#6iqe>nID_x@1ZAKLo|iGKr*Ui1${{sX+<68wv$Yy`jI z_irMy5HS8_PbP+ci}U}SfWHs%$6feu+XZZ_jQH5^s}82^KSb%fzK&_rqNj_Zc; zX%m(>mz^wLxmLsa3-Ov^-_LxyAPK}lrU)rlB@>pdrQ@1$aWh9<=%ha+RRyX7s0kn?rybL&MO(R`aoxdIr)%VuTjyfbp?&^ESlDAWzOXTwYwXO4Yx ze*!tc*htbzkm=^9U7J04Gh@0x7}aE)E_+{_ZAf``WfsfVEYFNjzCDK<&W!u)cRCy( z5->Sz`nYVSNy6mcu6fdl)1gQN))NEHp>q2D8L|u4Q!$t5Xo%~vHbuW$qh82AwJE+H zoT<#uT-id?Aa{>QYb9Z_MI30fw3vTY{(+DdfH|brYCSW2`Xd*Hi5k!jdsP zD`Qf50RG9mKC?{ATwUn~8zTOJ;Ka!2xrkD$%xUe0(&P9o*B%+RifHflUXWJ3FqC}o zhBZHYgwfnu)U!fM7T@Oi=>hbRy`qSU!G=}Jc)h#Q!aI%xB?D@7a*x^h<3Q%{a>~s? zWjUtGc(?Pe#o0kK5{W|APM+qt#sF0fI#Zt$n@{v4rk{RM`4IFFd((*SMi-8}_*Ugi zp9XauKU-lE=LI684AV5pVufy)!0@qXhse<|w7C9=#Kc)_a@v{#I#M;!L193qyT&R?uQ3kihUz^8t64q=sP+Cq02XK zP4>KZp%1f=5Bu!5Bv~Tgx2mu)mf;%`+VZW6woNKxHTwilDenk~vV#J=jKc%Yj2s~Y zJ-uy2Yj6BWh?t&2vEbM9I6p3cdBaNPZOW^?m&fh|6+`7-WGzI4Y@6a8}C1YHWVBEpl$8tUuSI(Wo>O3*>91si`yw=xiFRvod` zG!M~&vT4r;8%%E;v19?38Qb3d+*iuM$q|a-x~J-GC8zR6Z4QPjd#clAs3ip&k1m*@_lWFCIHHbo@GGWUTHnLhuq!kPX@bbD zD;&uJUTJONn+KDDpzU%ff7vP{ReJus0-8u-T%pC78fV?M1&sO!TZ_a=D^zZ&VUY-i z2gCa=Wp-(U07MOAQHpk8VP*A49Xv;a3odf$iOYAlf@=06v?AzBRYk?d&`@hJ!z~P7 ziJYHfniOs_R!X3mNk1^CNkKnxjtnL@*oHv9%3@X9@xpm~;Rd;fcJC4jI|k~%L2+{S zLdEl~tP5kLwq5F!xzG0=ilyr&!wLc``VKju`zme10CbZw@Nz5zq+^-PgCk7R_0k-{ zI(saG8J>zw`hb$%vFV9H4xu{p)Me#U4E_8dwZF?Ukzwzq? z(9UNVJ4ME2+{*|FR>cSaM*XqO7uy06JtGtU~bUh+#*A4CU&@PM11JxV&%u2U)q zU$P5*@Y;8-id?ep97itm-gDE77Q8okMSPDBtrV2ztW4Pp@Fq}ea^^GF#8qsJo&u{{ z_Ard7<}BE?b5pm>RgNBH83PLarULz@1g6puBEyNWsX?(J&|j0NyR!zwvaDf4rUd!& z3B4&($X2gQH{QiOdGvMIfCfBf~)4dU++xozr`2bBx1S_o;?(789Fit8<@* z2bD|SdZrNIl|y8*j#93%&eEjf0AV4sUr?hffh-Dj=L1nCRA2V`r{2o;CHh)EC$J45 zY-sWG6~)|Y8kA5Y26yVEx&@$&zG~6PHOqMNy4%yue;kKGJC64b7`JmHj2f}CKG&$y z_0^3VX2Xb@;D53~LTTz$=EE+j+-sR7NIx9jSGH>@rR+;bB%W53>C&D6f*PtSRh&Hb zHB$>CW8D(0nE}57&#sCE&~-7Q)(agUs?J{?Dk}ktvQvK{C2VaT1pGixy(oj z4^C{lHDU-7DqCd7uX49AUhRTx^HTN9qwQ*`<}0n%dj zgY~252ljRvA^QREZr=UMeEXa zq3|^}pu$hHyLoB?ZD4~HNImI09=WpDEa!KOd`O{)TU6A}=?jx!WkbZ?(*Z@X7X zwUt!t1Ahb!7f&^QM2?wwC6@~yc+mKS6%DdseA^;+iGo0so z3l%69oWhImmI?(ox((L>f1J`cXsaJ;HYKltbD+NWGJ>XPdIxzMl*>bd!0#za1xna9 z&u4&11|NJ(`9x0kSx=u>UZhDP`1}O?1of`xTGLZGA}Gc8eYaWKptr5uj~aYfQO%Ho zsKs|`o5f#F3Puze`j^>rY0+~ja%Zp_Bf zW~ZW&osWn$mo9FW4)A3;1eM+Dx>5tB3!=hCyB(cZfh=q#ka$wtaQ@dx7=>}T2=~c~ zl>u-Zw?Oc0Q)UANFXNplVsAE3S0aua8vhT1FK7mkCER3yW=3=lAc}cisn-ua56D#T zp>lL@*VY@`;)+Dj!Zn(7o0LX#NW|Cq1@X^CXZzVBvdp8t0F}J}od6MDZBrtyyYNPD zyoYBIiU^mZA9DQD{C0XC41PoV`iu8EMBZ%-?dBA!8L4{_5u!+|ge3rh3QWBi(}qMZ z4Ge^qwy|EIy$gcp1j42%F@Ed3=ndm2U?XCqcRD1T^Rf;r*DaXd(fbN`((UC9gtv1> z4=6~c0BqB0#0VhJ^Kz^WDJY>8Qozq@TnKRfDb?ywsK^rzfNyisA`b^h%X%oOIn-PB zntATp&h5J)d?BbClmQGFsLCQ^sf8mrMm}=%@yGbixzHF5Lc9e{`vm2-uzG8qp4b(P z&HacK7b8V^`jJ4^Ss1$5UB5B3ij@L}O@cF0uEH^?=T?%rha>5Q1>u_B!W($}5W=gg z)^>cJ2%phvVZl)hyaZ8Sk9YT8f`tChcZkO6jbk-T93H|Ckq6OzOL6}fi*>j<3grd- z01-crnO?wlFHQ;?aRr5wm;DD0J`U6>a$HECujU0SOH4b<>@C^xXR{Zv(p<~1x0|$Y zfquncf2(*a@+^dN)Z@A7J?({*$T_xK2#6q3Sb-QX-FSY;H{xDR?gaY5p;}iOo%~kG z3HZQ~dX;{-vqH}51Z?$gq$@a6_kz~e5U^t?de7T2>-v6|347;%P0RA;s0O0_?tlgUHE5a;rO5WKRC#wWO zduxP(hxqjONr5I#Iq-|nriQ(VjmX%dJu*3P%~)uEJA2i70n*umd{h1wk|r2ANw`OZ#bVn zsAO`EDlOg`Dn?*)FA6@NeUt_1%cK|U?>yaU*p%3#LS^G2tXXw~Dc<)81GV<}rCioB zu^YPkxIztf6gg%ioDl80PzG+!t~r&dv184ETfCfZQoU)AqdT9Nr;P9sHqN+Dv^+K( z4;%HZFB|H8Gr+wqip)mal4z5~(Z*8{=WEPIz1}@UCWVokmstj-@0X?nG`K!iShZS; zSFPq30$Jax&Q7+$?mF6St|-0l_o}+GWxN9nl&tzj9IeU*-@602^K)u#skvcCy8W?w ze>aDZ0>%O%8Ic1O(8(f$xRi2TE3JA+#834FiyhXJ9z95cCTums#8yOT)vaV7_H7{+;&>3l&W_2q!=$@vy_RA4g+g``_v><$idGra5^(5N4mO^ z<#qr0-YH<_$~k?ztm8KjP1dV!tlzVyjL)7j7|xI@4L7Afs|>m12LPH|xp7@#Jis#Ul7GXDU7<}0?v zDDO{V(PvwDJ5jG-X2CS!1vd zGD1#>PAWslx@X!SOgVXq@rN{{aolTatxyU*kQUesNw(E+h(&0l<)A(|-A?rbUoJ2# z`pTU`Jrm>uhxk*VcT|h~udjA+RMBlnx+Ot@(GyzuYURQPU<^N6ZReb1{bi7UQ9NdV z>HUHN8&RFGXW8uj_MIC{(-9=a2`DIu^jX6snCxmAPK6EW_kSEQA8CBN&kWwQFAduhfcbS8M`_S&|{ zj*TpPf$lr z!|NvF(-}d-9nn3{Db2X|cOEsb6+hit6I-#J#r>L*fQs%}comFr5+nkw!T!ZFfOkS; z(GnNex43U>ik{%sv*%o?1#jJ-SpX_=X+Y8UYwTc4qACxn=-D*@=YLNU_ zKwBqB2{t*SeFYKX6{_aROJG9aF%MjZRR!Qc3CDgoOgy#@wBN_ikwD+u)elE~iiSYR z1|jI*_0sr-5$_aAz=;wN8QrL0h8#ZE!5e&Q+`lbi*k{CE{1VHsdFwV75{7LlbEJF# z>q{h&LGoMlzO(|LZW@i;%Hx(khjpHaTySe`u##if`Rd2za4Ig#R42R@3r6|vS%|Vo+#5I84}xz z&kn1CpI`v0t#~iL$H0F!#?R-vdq5Ws{Z|VT{c5j*VwobhJi)NXPeZ8Mg<#azki7;8 zeex-O9n*8u63PbFCP%=_HI9vcR=3~`dilMOqBr|Y@vDr4V$v-I($!YJgDOe)gW8;V zBy6o22J|UP9M;EebK#&|Zs^jTG?PI$SL9(!xN8_IOAiy%RY^VYjxs+g2*M|Gc05Xn z>a>IM$?zE>v6!tIN`MAqQIfQw5B5P!5LAh-v z^YYydKkk0F)(|qjuCPhKMx)6#D^tb}^AMb!0^uRCI#gml*0f=G?F8YWtr2L`iIk@B zHj}Fw79fBWX;u{y-r0ssrM_pTdkvldtMS=1;E+XOtB^j`UJb@q6~wY)gt(7&ri>;j zntCD)cz?lv8gX+z*71U`BGUPR`t-D9Kz3IWA^{^QtV`KUv^$TZdT{{HoCZQds0c3o z9_vGWoz!C;OWRkgn?+tgUN8KZV52!-I`Sy?z#Vcsel1b~C?MKEQ4`D;>HWv|P`AQX zscO+4T2c91*hzo^6VA5BYym}R)_}?Nc5!D2^5PmvxKYktM~<#PL>1yuzm%(F#TO#f zervd|YuRI%{QP4j0@s;7NWfu3mr*nD5CYrk&-qUIE%ghvw%W=@P?9`k5qpFSbf2(o#Hqi8-0K7wdor4({U>coo?NI^B5%vNYs z11dSkhe@|w0XZ3xx{{cFkb&+3e58gDf=RJf=i0w0uy>tfF|$$Rj@6}jr10PNcdw+^ zCBq1fM(O*y%C2i|ryP#+8G``CSM|XfXMkvEJ3r#46kzLY1UZwOYxB@=QN#&y98~7G zR=n;82c=Suhj_!Cyvjx%WeY^ruxF3Hkt)8(Yd>&HioOfkMjgv@+IEC2vEdwUP%!y; zT4o%+Yzb#>#P+N|8{5Ow(FoaalYKUG54=uVIf&B$S4xj)II%K9>9vLiCpCFGAHT%1 zs1s{Farzyoqh-d2`Agi2>=Yd|YjSPw3l_ypXdAGJ%RoZL3zci;;w2Meo`b&0ye@*2Ap}jc458SixGna^QyM9-C1DWhzH`CH> zSh!ynt%S43zsjX70jSRI5MzdQ%S|dz$%1HFQ*y+lv$i?<(48g7XGNyLzJF~}d1Ao1 zQj+gt1q^lycTrAahws5>J$Fh@Ya0I)tzU24I4^Z3z4;LVUj3NE-g(;MI(#&9oz>3q z9%~>wEViEs3nSsRD*SM|$i<1%oU-7Mx|8-YmnDk(I8YNbc_%1Q|=)DWwChYcO zsnl{4K@h`6KRJgzqK~F!jHPK**=A51+2J%IEuL`i83$3!HOnR{=O~(O82zjU06LD=zK363=tlh(_?bgpd6K7_=XWTq4xRG>*6q(D6#2ZOAS7+w7;eo_uqdguCz{BD{`@_k+Zp|HgpBEf}*_q=ZlX1h;M0C|Z3N{7LA(bf5&1XY@PFC31PFqad*6Pcbs zWLqr_f>kkiDv@C0C1y*CFJAQ@kbOw2w%DkkP=RWEXJ|oa8Hst{OnN@e`G75`?pXK_ zzWrAR>2K`)<=ejy`Fr&7pYng{+kYthhjjnxcm09p|IFY2B3(9u->3c`&8flFua^lW27cI%~VTrBZYWA?tmX zb{tMRCKqNNRwl~M#%vnMW4}^|BmE@o0OlM?NkN|+9clDs^9W?wv}=i@%idg{N0pb2 zry=kS{zG+w&y=0S%D&XZ@0Yh)>~=4UiNl4h8&ypo4}JQ4n=}WDb-wK{6&$eS^8~OL zChuEf49t}L6v~1kMf+g;^WR#8M`n$OEL6YW8fGgkTlkMDN@fqE?9nlooS`=L7j|21 zZ=S$2e(OF@SEA83&c2>OY~GWPEj+Y!%Cxr=cdL&SIH)i55uqby9?u@oO-LeB-M8!P zB4@21bKQQTBJO0uwxe5QH9*n-5>~bA-F3y6airxs{!}H=^7G{wzQdiE&B8yE)P_>s zH}Qd1KD*AiHI^}Vk!Bah6oM?-`Huc}o;9^~%B{9bjJl`n#o>V08ee(i?0Qw&Decfx zX}!7X{`|co$GA>wlUwuh_j@dYjbmpDLJDvtghFmvrNM+aBT`@|)9p|2zi0Zp-FiQ# zVpc31(MVJ?F@Z9HP5d3%zFZcL*8<=Y(H;(z!WHtm>CRZlkp(O@}*5A;0BtgeV>=(LGrL zZs)UJYr7yHEvl?br5jq8pK}ADDN=?H8Xl+1a9ji=@R)X`koEaoD~yFvPsK%rrVe*v zp+#ht4fi)Jy%j1RZr_U;dRvjQU`lFGP=#-EG$VtSU`tFzPZNHw_ch&~TYt8q{)i!I z3_J%Bd1HS{z<5Is*s40JP)4`H>t2OvKWJRBDz%{Bd0(jukC**D(iw$veHXPck6e|0 z&MVy@WlnlM!n}Ejpf|C$xjLSb5rjE2fR>$4WkCsQ8wK7$X8Vv7HVxve&u57(>{4lvYSS4pJE8-wTo}P7 zCx%>Pl4HGSN11)xAVg8Crf%j^AU-zQh2nShsVoloi;s2lS>z_2CsQG;_D}=fm*d8} zE{NZtUKO=)>x2E_dy!Q$zsR?=@Inc<<6sw$oInDM^Z}1%pG+tZ`XTVb>Ym%Sl5XK*so90;M z&+%$ywjm3}Vq2B6Hq?`OK@+!kEXv+Ha6C;%2YIfD91)!?0KUua!QMF-G7m~vFuM)F zK3vIQ*JO!BuB3L zIeLv4&dG&GsXsxk_uD1ex^g93HZ&WcRdg_5d^WnNvnYX@SKb3*M#oax0VHI-QOifr ztO1uDPLlKyV0Q)t5Coi-#}Z--?t1S7q5H1DBFhne&+F~aw^ZC7N28uQhpbU4Nl!m1 zSloYIPE69?WYmT}5F~$_3l@2*-2j0hVEg9ad%U2qaN!h)e^6i$Bl?*Uu1PG2ZQIxU z`_)L%Zke-4>(uX7!GbmH#(Ayl4Q?XPF!cyZm$7mk&p;ID7wJdCC z#UV_=*Vj@h;#NDmjN_t|V zPzo-O7Li;rtW5VAnA|E0wE2S=1(cxlY2Q?`LD*QKw5v@^^S39H?i3=1^gW%~>W|Gc zo$+h=k!fO4a;320yQGAFy>XhoduSY;n)z%2Bj-dxXPK*Okr!#aD{4e(On1gz`+cDt zCE=T)2|YKvM`1lf8F`9l&}Jpod#f$tLV3ZLtJe=nQPXZthk1gbh8sLsGoHk_-Ja>1btM>drH?s#u#3Dbwp-(HW;pJx zf@36qHVD1w1=vIt;V9-!A+P&Pog3&8pIg@00#_kF2BfeE3m0b^nOOmI`#DCoWz$yT zW7KsdP%PzgNaxNJk(P{U6|o~>BvspSWARjbFs{n2#v{ogB_Dq|*0HA@0*D&>g0 zWAPW^dJq#{&zoc6IE=p9J_Wn$oT?&wFRcDlN9kn?^^-@&b|L?62C4DJZ9~aM#weRf zBv6!Sg-v2wq=@R`LGrUm7;;cNfrdCC5}CVife-(ZjRX~J5W;TRW`T;@l1XPouK74r zD+RAD8Lv$_zZH=#219l2hhvbDe*4u(uQeP>@9A0fwSA!X2wfq3a(!rH-{{piAqtLgN9E zFHlEnBZmSP?y)Li_KkIRtg5V+rb~rQsLeq2P%MG05_LH~W6f^Vq&v;0MP;_8SafIFqY*uBHniWZlO}&fUU|!SvXB zAFf%3xrptI9ULQ{S0L(CfAXm9tLRR1Ifm^YZ3V5DnI6KFyaywYHnJGAIr4^3Je#1A z2BM4m5XrfJxH-$`!->TbNv~I`QD-sQS2$5*vVNDeOxrfRmY|8w67t+>ev%qw^uhjC z2*Y1GAV?0?dvCdV(Z~N*;fMT-uI-CGf<`3l{1RhO0~zerN&t9pOX<3k$U&XDUa{?x z;+XgrghS){sKF^ZhaYy!nWz?-Ieg$e$MT4JGqb6`2o$#<0|i8wc<-<53UV*6hMe(p zH;Ff67w>I{##N=!vY;v@1`Wvq^Ril=fg7%Mt4;a#oT3$y$2&Dscv*+knK)lgp(lF+fe0ZDd_T6fA z5-_5pm{zha%9?Bjaa!`d?&4f=;Pn!dvKN&cL-)6kWgh3(8pqf=-GyA$spH8U3_6U4 z0eqe!2m2iQlXZkSnBA=ANE*Z6_qe%k>`Y#Q`;kdz-fqJS5Id^vmV|jgGYV&%N)+U( z@O!Y@HeZ?ap~?lPlu$Lqu}YPBMBqTcyUU}4DoIxiXjTE;#9*Naz*&_X=+>Qg!gjKx z%8}Y(37jC$M8-wc`V+wmR54XX2qodJhYknsW2kPJ<$@h1rLZpjZG=Z*nQq9~)u>M> zWfp$d8fZ@3=S{`UG~MR_4+B}79>*xtQiO7kp)&5foq+y_+)(lqJoyp_5&(LB<5rOv z@fpm=_0qID6&I6LqPzKP<0&Vg&sg!7G~qR@GWnK@d^`GC~w=Ulcz6c_n+GGEmS zkH1QDa1HZU?RS2BZCdTC{uWU)JY4Pb)#Yb?>?~=&pNiqb0ZeKhf(a~i(^P|pjTIBq zFqA9t8;F5@rIYqA6>N5AG{rQnX4-~BBTHYcC{OY9l~j&=tUuJ~KA&Sgfg5EgTmJ*` z|KmvOe}w%%g8%;+Y5fECf4tcEXD|AX#`RxwsPv+LcBud31A#y3{}1f{&^|N6zsFwx z&oTe|5Pv-C_;35#42(?w1@r4T!}hB~_t{msHo8&E0+;LG_qW2%vD=EMur-o!MS1zr zg!2UbapP;tyCzTJ`2*llYT3gRZa`36kG$U>q7pXAUE}-kx#Pe-4icVWI^V%QF%t0U z$$Y%Uj=-3O(^56py4SIPiT53zZZd^0ITkfcY$UFlm)6l=RV{_c>^q94PAsrpsLx%z zbY{yVRN{_(*@!{yELlIg*QxO;-uHIYb=}irUKqVTp8!{K z+u$pEvyE}C0!vy`&o9H2;mQfY)XfJ$b|VW%qg?}$GzdluyM8F_FkF?meaI$_o@Vj+ z_B|g|Uc~3M)e?zQd>#EU3^+`HR{MEIZqu~_|LCE%DF%iyO_(k=I?%g+ita^qS zC#1s`mL$@C)f0=sb`qA(HUA)Jn69Po*rN+BIFPFiSQ5&prC+#%U8QsSEgopv zF)AwIZq=i=SmE29NgjeN~`YblG<1&ehI6V;|AaTEy4>0SO>j`gH7Ae$8O=3kn zFrE>)qeXB2$`{+F11ZvxNXhYb}F{*RBYR}ZQHhO+qP4&ZC9LBeCqV>{Z)N^-afti?CVWZck1;^(>PusCXe+{V7pat;X3leLSvv_;E6`-++w&yyDw#E%Sj&;+oU zQQy?4CHKqOvP$=4&6);#+vXd7&+9wJhpt6e z%t2NDXb7EXhLnN~1wi;@$}j)03g|a_7eP4i8D@jrb98~mV!((1?58;w2abKvA$K6ke|n=^(3Wf`*OohUqbByuh`#^$}OAjQ25-s^v>FH*J%N2 z|I9a3^&@ZA8+^#n!)5wMWf3b?@ZmE~_qfX=-n-*manX2RpK*VT9h>M-So)9X@oqJK zgiOL7*>!rAFwt3GFR^^Q$vKGRzWF+dCs@P;tApCa2c`Lr-TH^c0@=^&xICi$TgAH- zNdOjJ-V{M<0;o*X(S{&$2w#!9qC`+Kb^i@PpD#$<63S`H)#EcB37prm#3GD+Qc$)$ zQKm#7rhXbOgT_heYV*hD~gdGZp~hmbwzf7`Q`_wVB8(t?CYMgGlgTR_=#J zPARgOKeUW6Q$5XTO+m%_rue~H9uBqsUap}$X@Dhq!CFn>4Wtlkx4!W$^W19-BO#?bYz1Yn&44(jo4HI=;RH$PHLd6=@I!74heY z!=3qErDfDj*>AW{FB*C1EY>BKyjuLlqNvR!0%{-?d7`-J;5#)EJK>@9~aX;@o1q&Mk4)S z>L+7m3>LJEhUPx$Il_vQzB=Xj;QkJ+ZO=?4-A+?Kk5==689rC0K%PXSrm2Nx-F}D8+BUI{;1b>$8}0 zD|Fb!yLGMGNmuJOsBIoxi-_0s8f8wQ{Iycr#q)s3p^W7W7OS2K@MbLjjPmLRqfWZs za5(}@uwJ&cm!A9hlmv-C{HZnA9MUmMJ2kVRU+ncg1(|vq;fl5E5%-ZLH5Q5 z*&q@&F8FyNQn42`Vko3=Y!RWbf>%aS+yQrb$t8$%Ab5v5UFrpe{#th=ifI(miuQhg zA!Y|-&h&Ll^i;np8~upjSxn%=5^9x;wWQC$<}g5K*Lg{h{#*#)0hF%HfzO=lSYXF8KI!V-f?=;QsjjGso-}FMQ_ti^nippS2m7;Rnol=fP=<*Y^ni=lr8!$xnSd1~ z`gTV@d+rt#z5%gp#OLwAO*m#{S&6*1Jyo_SXu!k4VW)h!+u~0LS?eF$0H7LJvcaw* ze#G2h&R@6ni1Uj<@|O5y2iNA<$+^@7MlABno)VP3s^vsG z{2D$5Tu0P6E8v|)_NR)*p{}A6$}$dw(ov1+%|#&i?|7#DedO{%0OBl`)1O2k1~KLd zP1N8a%wRix2nKbYQAPShS%oC9z-ff>W!l_{Wsi~Hwa6q5h%~fzGDzYAsr5lhml8Ru ztw|+*sqO^84?D=~SVKP-Yo$~+ zY`?t%GaR^8Xv(`9<7FgXc5F_!CYNK+VrvFw{Ho5j@MTgR4(7a1_{hJ~OaBq|J)#7M zUsqt!lTye{=Q(`vPa(%CNgz*Dh?&`OMTfpA0FH3L=|tWD7$&J( zeFIJR&bn0x`npvo-IZnh-4S?3^S<>%XJ`8J-Ie126IpBKC+p2Yf}_d8+ScnzyAHK` z0`WcDk%{6Wbk20-VEL5mbmg!DsmrI2u5xMUumbt_FHs+^lu#P3Q=`v(c5bv`|Lu1r zw1*4LRv~8|)=1x-4+t#iRdt4Ph2BP~w4!KCUFzy!RO7D| z_40i`mV1vsp6P)l5c(qf0Jg#9rp(}PX6gi3nd+(y zK(Uv!ii_kwo!4eLkIE@ruzE`jX{F8!IIiDCl6}(`>THK`a5?Qm!I50ktSnI;d-E#F zUcP^!J%Gksm&D>PDtFuHj0EwkjnD=ASN3CS*!ZBU1DL4m9kY_cVa_LQ??fhf#x?bV zXuysvz?eutrIfERHcI(%UioH!q2*iFF-ee2!R5uTAqC}uINoBf8UF&{s0L?$PGyt2 zrGm;+Pmv+#OOPS=Ytk(ONbwK9Lh-vys>44N)|QG(BTG@|(9{^;b&nX*B9=1sK7~wp zrx!r-u2ffT0nJMU0ljB;h&*CB}v9C~!FYPWVxP!J9v!KOQ84y4y9y7e$_|3BQ^`#}7Jh;#Hg%vggaXyf`a5K~_dVb1=sf2kUSQn^R!2Q9*QAjR_r92}J z*L);;LT}r8DtKWX#Y;fO)vkv*LBWHP^{cLp*fY2l3dy%k*s%>b*XaZp>VV>pgtTn5 z)88w*>~Tg9Da`N1UVdI9uandi5Am(hyENl%f+TR#hyrSqQ-d@2&)dw#dj;AUq20O zB|EG1H=5AOD(cNT*J(Y(Hck^)Hz~kwLefCHPNhu!dVZA59= z+2;gw474x!F&ik8rD_jF*=)2fgQw~PXw){n?wijSp z?cG+*4W>If6+gxj5l`L`qVAhP!0m95+LY0EaFwO{M?ZBMrkIms{Xn0t3cPy{oJmQ7 zbf}F^F1WZ7Vp-?8Ga;ZLP7D%LWGi;nF(9R!-fF_7mrMc})FVVtu)z?9 zWEjCNBNBj5zryKCpvMH5*CrO4aItPE??hP8FcvdTUkp5``+OZDclpp9g=72en?2qs zQ(&HjY&p?+qD0cO!Eq$p6@84cCW)_GIAYR^Y*LTAJRo4g8&u3qhN6d3fx>8QNPCht z&rE`T1=isY3pOv>5=F{WC-I$Zj_xls1852C8(#tRMDw`KmsSHPHCXXQ^hZci!&7Uf zU6&w$ey1`@(u!x7GT}$x^Zd91uAfs>i(WH{+LTv>pOOjLReMUe`*FJ0w*|GVOO9!ZcW?)h1Lf zo5?B)$zY(-5l{f!nOh){p?^dvlB_nLYTjVQX#ZVHl?T%xy0*p(=px<1E}}93><-Abb<&(Uq<+A z#@!*aGv*LIPube~YZP?l-b>k=TzeWR?0{)~YyeZCC=~;s&h{!@b6%;6;FMgr(A}aU z9fNN)a7L#hN0-jeliyAIvLmKAKZ7PJzw)fp98AbpuI5QuC;V}zrNA>!x9itrOAJgS z!pgz|eWl$F3bR7>s(;l?B_Z_z*-U{~D`PYVZ0P+bu=9A)b*H$PY{axXI;&YkNHj}4 zOGdx9stFA`iM4SbQvhh_ zpv5SK(P3Vb*mK#H`2&c=19ySG&wLz?N~y%HAGT{5%8$KhEZJheO5!QDHw0tm0i*{@ zkqP4e%mdKSBY%Ls*k)@c*cSE#DL-?bFeo;_FC8+VkAoor>h~c{1PnpB{2qDAqb7x! zW!fgcfHnj+8iY?Qwx{^6AaIc(LQA6NZ27^+kd{ZSOvvzrzNWn*^eaQec)KD!gY8?35kWDD9j2y&R6XHQtA0(qq`@%64VKQ0+Z#QW_ zxD;;2B9iZTmL83;UPE`aB~YEONp6wK(DynLj$u|! zC>h2iDb8{1-enW5rb>d5Ig5_v(yGa4kKN)?DtKp*fK#AOXGm;?dujQFY+-`qOwOHA z8x-RTNrTpv>(^fw>~4>7B1I}^8Fn{vuc;icZo(!fdl`!M54t?gx;!rz>U%$lq&%Fu zf4g*GCPRZppD)s6U070RW!6L{pO7{aj$0ih3>?wXmg1z=&MK;;qNxTR`hexvkyV`A zX+D&xXOdQxr%2eqHbQ^8G~9qU+#{~&^VZftxd5atvqE|gq}5;U`%eWQu3LzJ23cRq zB;dGN4j0mPS1aGS;iryxJq{oBvIbMt9Wv@%AKrSLG!HzYL!gmAoQS226*(^9$k(c1 z2ivPErmRDxj8&41E-um2NyO}{kI&)b(A9Qmk^1V^*v`f1qQxQ=wvI@-(%lPRdR`ud zQyougAOF-w!|A2L-z34uE3EddoCvJlma9Gz6AaYRJ3QtE&nRnhWk?{4dkwKxUFx}6 zK-dUu*5rj9{8;vPK?m)ZLOM$UD)xYESCN>=3En+Oefp}tIr!~%1*7o){0HXyw`k*k z(e3(wNPmBL?JxNI)8q0N@%^(g_HXw4%K^*yFJtU~1N8pOwpK!*`A_ z)V{0LBRJ!eIj0WxHJ5I3LzlT#yLayS>&yOWWn)d3hmo}~NsYp^72b|*7@DP1+e^YG zRk%4*F&pK=eS#^4obl`E3EXYO30FQq4jO(RnU~kP_4jvTG1S-x;-NzDx<#;Tp1yDj z$uPsUhL@x_gzWGZS&W8!+$!~TW7P-ZMF0CvXs-FQYZ?V2#3#0U4wQj&qu)W%=9|6z zrZMIQ3bb$fwWSE~=!I7&4O{HzzCIf|VR^vmT{K>#ay>2U?{_dcyt3Q0KHk${Cy?Ph zl6<3*&G9DbSGr<6%J;a3vrol-4n(LS;;^`%`J;R$reMUSaS}+DCINPP5I@uMnybtt zi{yTMb~E3R`db!F6YfkYk~S6*gZ_;1Vk+!Gyx{{&}MwN ztwV%kg4kcRXaLE4RJ{O(BvV474by1+EKmQ8#D-q01+$RB%10OFpQ*yDlP9X9a>v=FyjfUwrbyWS zV!NQIxN<~^=lzHkQARLR00I~BTA|eH76twBn9>-oB`*%7yA*XE%OoPA`tAv}l!qv6 zcUrh9J}IHqN0GXfNJKC?dS?Ch* z)kX@Z<3%i0_TFlsRR-rC`?#&6!^=|fx+0z$cTzohmNIsM+bqg<+4miWzW2Op9q+l; z=8WZV5(0`M6S`Wk921LSKO({mT4BMCWEu0|ZpcVi+;ib# zNhZ!XS|pZg^kmv4a0rJk&CPu~1eWlD?f34kb_v}~M-M7}^NOvwBdCOFJaK4-dd_jd z`qB!fb6}{sJ2)AL74GrPrV>LZ`hkPZwXX1-#h@maUF~%f{_Qm| zj2x7q8Ot+zT%pxmmYKJ2ZKzL}NsxIRnoVeKZcMm*$PQqCCM*vmDig#ojds^_vEjCiLam+Eo<`sl&2vUiDVgwRXPKP}3nPu#|1(?r+*R(yN^ccu-r%IO4 zMa(yR00r+Kj9yA&naKJe9FMZdsDV+#cacJ<2dMLS`D6^1u>~LU=K&P1ol;Wg zv?Ut?i^DPLq!)|ki+llkI)MvJ9efXhbj($&S~AORomi2Bx6}49hU3PsbsWg01?-mVy+j!V z0)==CR!1Jth&aD?N41^pKqq+!Wx{q#RIa3@o?Ds)&?NmC3)G@trWLc_EqC8pkL(?I z$c}o+N|&t1coRn+rpmy+X9zeatnrKt8nQt~GM0q{f`w;k;V4`{gPEW(Oc?{rm?DQn z0YB!5E<-q$6 z8<0MTJK(trse*v5YNmy`(q@p<0=PH?Y_`?b4Q$>01j6@LaK`I)CBIihH{=^8?<3gWd)*JD zTj*IkdL%tt%tYKa2E!RLMrj4SqSUuN9tv#Cyo(aFO11)`_2*fc_zcqnx zz=uD{;n?)>8D(wy+Sn&co%DWz;-tX{(1x-X4;7)ou#&VHr_FjfbEoB_O|^qTj}mVS zN3H{6s?tDz!IinCU&uUaQ_N@(nqmw#XA`CmTuSPwKo-MT2rNum_&#)>(1E0!hYw^! zr4U-#{4%OTfzL9~rBb6LVO_$9v9LmoE-aPq`Ctdv74saU^2ob99!aa3i z_(feCjZbR`#BkN_jXuf!eZbE9BGr1a3kJ8zO2OM6j^M>Zpn%7fkz`rH)FCWM0O|OZ zdEJ=GmQR`P6ek8k#Rsv!ViE*PSerz-Z41pg8DWe-9UDmD)^xWNRADfh-vj2MLGs!b z2C(+Z=NxP6LnvMql3-|-=WYU2Rtm-ah{ofb*QuPB(hss_=mVyKj*SpM(hzve09fbj z)e-95+*|2$pIdirml~dG<;d2yIc&Xc@#?lG+%tTH{e6`F*W7SPSudbp#E=uOKL@qz z(!#+Vgib~Xv3wADf3^6y))bbsU)}E2LaayG1-|%oVF6OxTh&{-PT*9ulKxa+xU>SU zAenpQLX^oU+7Ie)jVUs8hNu|Cieb{?)%5`achB;_`i)0ZWbSg%_cFa7O@3X;3OP1!+* z_SA!(cWVtxW6!)^hQcRY&PQSWq4loUV0qsG4QMO3#fN{ zv*#al{y$sZ{_I=+X!<`g{ZGE_uPqM~EB^1#f8@~q((!+mIDgsT82(g0{w?1Ba@zeJ zPy0_p8=VLf$Nzm7;Qw6FGynhawz2=aqW_;kwcnlnzk_PC+ePaHDQ>{x)A}a&W#ZOL zq^Q^Cq~PoOYMad@q6r7Ly*oC3@P1&z5)PyXiz*37B&__q7a|82p-gYiBBmVgf~Fb$ zy)T#NXg%KWU)nRzw}?K|x3rskYQPoy^=yuQSLmxMX&Nk29|S;f zceZ)+e#w3WUGnsK(pNm_@Ll~CX-Q}Ad(xZ2c4XbYy>h_ZcYf21 zwm5PA?310AiZ8L)s#%R_m(&!A+qXXHyqRzo z`mj46ORAuwHJ!sR2`o!DjT_RniuI&US8J2PLQ-0hE?}J0NL%Vij z7#Sn}CaWJ}89c`QSDFQvZKRjPlCC_G1HkQs$lfUe=8;sM;w3*kbcClgFaWJm@cDo! zB+*(9#1|5Ko z!fxq&T^SfASa}|Eh-W#fLhjnwf7>)}zR&I5yO_Kx{A#JRsl>wQkL|t9-8lD9hWGLG zZLIxiQ$eMtoY|ZkxP2A*$YUJsBM&&!Emfse0QNpGPI%Cs-K$AA>F_e4 z*uklEK2Q+mWl22$(s*i5N{i{m@y zFnZUXDJ?Egk7o7933!<0S*Y-I3Z6wo7bV)_at1Cpw}Y#V{89FT8Xtc#0bvRrG(`k) zX_Lvf(k^Ux3OF8JQm-6=Sb(-jvQdFN5xa0DJXY#o8O?)TxUid1ks>98(`5sBSL8*C zk;O2DcNCS)-~j;s>9IETWRzEVct4tm&D0Sf+*IYYNLLKw><6TNwXYx8@Ovd#vcu5u zqG==sq=2s)BgD%c%*plk65Iz7!1K?Muej9ORlpw4HDtOqR1=j5`qX6#d$ivX3$hM| zWHl)*fDY9vx;F#Bq&B@c{Z3MWF|oY#w`q2f>y&%8&67oSwRRgb0~iV!8Xcs~ja4o( z;hYimP0RpQaiXo-A-LK!nSj_<%}ocz5x45wz1l=yichie0knSJ>Hq#`x^e)A@mD+` z$NkjW+}h$=PJI+ydbPMvC?1af+Otrus`ZzLs0lfaQBP61Fh8Gv^>T9-P=;YMm_jy6 za#Dfq6SJ|?pm`alv(yX!tWaP3@JRPU9HO#La19FNta8fsgqh_801;Y>!s#Pe#cn30 zC$C%@Lk#pIbQPEV+809ecTK;WWWJmRqo_fz^Rv)KzVN-)Qu7ZiWMD{5a12+0LAW`o zEbw_TKC`7^yI?fQzJl-cc2|YwUG7zCg{yRVGGG3|5IsHmRQACbcwXdTjMew+*Nla0 zjQFUPZTiQ&r}iE-fh*lSN{P)PxU229W3GXk(G zQhj4M`%qj8PyfCCU9H2lTmBIi8MMk7Ena8}i3J#36t{XU9m~Cq$hBI%V(iO9ebOT5 zGecTGqRchx8^IXNrp&dO#$1oPj-IQbWQWk~FCJ=ZJLr)8pP^)T6SfUDtXJ^;R$hjD zwMjFmyVuLFSEWE)rBrnH?b0O2N-=Agu~V*N&up4>)Bp3AHobi`>Qer$w7vG3IRv(- z?QUfR+#{`eG^}>jj`?{aTypXy@rr^-KV^j5oeh%vZEeylx*bjp8(6|wC?W!IhNVDx zt;{ef;4uD|*-f&_WV{BVc`;#s!Fthi(V5yoW^1{aVjgB|SG@f4-3TsX>gpZ?!D0CE zl(kSI5Uq2(N~1^xu~)(S$8QO_AH(V7;l^IX8Z*p~7V&k*JkzJ`+#{U==1o4Ah9+-W ztm6sVCF`1Hwx(+2_e}$^1z9)^hDOcJT3WkK@5f$F$F7?%Ah21mg`hwFenpia46R(f zeb}D)0sQdNaf1cjf0nOxH@KVfo~!JXFs2E>Oa9(OcG$ z1MBKS97DGaI^gRvDstMY&Yrls`AiG$MjMV6ihb$r$#^C?o5Uu@Yow?cqM1{RdoC73 zHuPWXPk><}lvXlR7(pr+_-*Ii*K$h8oG3dfZ=pz0C*{G*un|0{58BPNHu$(o^Dn^0 zCu}4ku{R&T@2+XfTc6c-^ZG@WbXxe=n|mYcWS@o>i8#eS9_?1)S21w04=8EQP+jar zZkdgz8~!fa8on{YGX+TD7{DI$1+=#Hs=F>Xwp$5Icjie^UqNQPc*L)~g{o2#a|$Nw z$ailVXDe-^ci(HoRUn}3=U+%7ZZ)poU{Cj;tU9hNYgy4riJ^0WJro<#p6{a8}TsH(S9T(+El4F7=QAm6EOXtNtO`mZfkP zDXWvp03o~WAHs_Bpr$?8Z=cih7Ebs?ERXWETAxH|CsK9R$svvYyXUrZaXoI2cp}J& z{D{#nXEJ37ubyyQs+`;ir97D*5)*w z?5;`GkjI3;qEAtyXYhfD0 z;V|Ubq)taMq-?Q$xJ-GHB{}9rxXLyY=)NKMTxFw2K`q&n(C96`my0iplg0_uXEh)+ zrNp`TNkm`LHRAB?S+F(Z16h_euZ!k$e~!sbC55Jvwx|mhyx}Mln$JzWU@)HbM#02A z3WmYkA$SE(%RMzO9V3(0L%yks_X7bI&DH^fV+}f!7ZM- z-Rq(;{BjOGv<;CVyO!60S4jBbOgRsK5Uz4=A521IK@Bz2BmOrriv@W_egE<NJr9j1P=zbM`c#5=fBED7T3h^= zaq2Hi++X1I*DmBQhWa}+^!Ebf?>@}G>OTJP)E`d!7g_y|ApPg+<-Y-0|F%8)-}&Ph z>Dm50K(wSG>A3lSLDp{0KsgIR7rzlzD%WL2HF5G~1!X8ZxQ3v)+8zuUQn5ssl(+zG?>S@5STOXg|06dOHs{E)LIG&><6r#Im(^ z2Fyk<>g~Eexs`{i7%i<|?>}0&l-Pv3C)%3M=$=QXFHlv@9o@*`E|&0CzWlwF0;rPj zHtb|jE?Qpdt$H;m(sA{h3(VUM7(e8!Dz(p4j|-Ehpc0tk1dz%*j#_=t5(~{UAfRpg zPiz;)SQE_7a(9N8sSNJxd{EWlXQF*^i;Sqp`x)1}b-uZUCfk7jFiSHE5yvE=wz^{= z4I;41eBAItW(vh8B}ankFAa$cCt3I4Cyt~9o;UfZ>P(KN9A-y6C#()Q;~64O0AXXG z6dNM?HP)675i3PsAkEgeT8+cg^6ad6brB0^39sB4UY4XO1gQ-cM!1*-80JRFcc~W) zr;EU1VDn5N;ek*eh6uy+<5fB%d*PQh@Hf{Kc9n~}U(P~q(w)VdK^W?NW}o8plsW$L ztfQxs21{9v!BFGJ4ysbSLI9B;xL>^fBedbnahn1~<^tJjz11)iOZ-(^Nw_Z7w?eC#efNfQmE(olNr6Z=b*f@KRT$0te(XH}J$Q7Cph9=j{>k zm}Z!TAdYG;M;(cbLCL9vaOhU~i3HsJ9&0Z!oCVw|Nd+LGgBbHbN{IA&y<7w#2yw(I z&+#?mNHLDpbUhE=k{)c2cgZsgH#lmD*u|#0JFXAOGa=KH5RDxa;BKQ|rwX z`Rd?IVzUNyrcyx8W2NZTl+yH9rW^7|@;P#RWpMz)fWl#5IflvkrgLKIbs+HbIc+)O z24G;<1{wWuC;o^C?Y3*l0S#bAQ<``Dytv>^bklc}mo%=RT)I}9q<^2GhS<^!yH43H zmN#NqR}fqdtoNe+dz~@?3^{>h71**b-eBO!ti7&X-mx0s+3#^0JPW}3Ymp0y~{SH!`dCy!3$ z8Frb!hF845XKM6@D;F*2hD*l@0|!Mb!H#wpd60?MU!bHNSiX+{JWw2Ua8Kx5t9@jE z$b6iuz*56uU`;$JjV?C9+!vI?0szX>inNB4LexY7E#G%U>Z4)Q{-#6zV<;qBrh{ez{>$a8EO}AP&sjQM<0yp;pV;pjt3xht?NoHCj^B|VLgC*` zRDZ5hjvcfSX}zy*qJ~y%S#4d(4)cul;pJj*iUOnp7^jO%Y9(zfCSYu#0vmS!Jgkec z?E<&oNwqO1Gs6W5j@)?5CaT^A+&HkCfLw}m6<8Tt11aO;`mzO4;Q)iyXw9sTL`4v! zzWCvDNZcv?`{uNJSSg!KyNhCzOr$|?ZRH*N!d1T3jyqoddEYuBfba$ZxU=nfhrjsN z1^{Z`T=I7dXM?UccFV6x)W);T#tnn(x4;Oe&~^|T5&+VS)HH0CGj9tGBVI-__n4Ca zG)yjsbThIAM?BD;y2O`Mm(`!x>;CbIQqOVsFI~@?D2pzqk&xdG%(56SX-5}yX@b0( zMGRZgj_MK^t?@As zY3qFi^c!3{yL1@do9sk1NjfEH0CbdcRaGRVS`W@logYKx;J4{AfdczW7cmYNV!rF6 zdd}BBP=xKd7tr^q(#pjvo*S5^;eE6)6aeL3Z?2LgFMy9`AyVdgg!LNHz@_`$k*P^i z5fc}leQ^#R(6O&aX46{?;PcnV3~`Guq&@=6KDs}1OLncERNS}!YU1&YAep*(zh_?* z6CIT<%gDV3-qV{!*44e_6G0=cpJ88m@J^^(B@^GRk{~iQu8}ruBq@SCwz|zeNb3ua09MhQR75*U zH(|fL<4TluC*5@ALiTCZ7iiW5?DhKH4N&sSUPxja*k@6V!MrZ?GJV(4lgeDgso?+x zSszRW&^6fiU2gf2imMyhkTkTlX2p+UMP4nS^VcQ0yT`A{?C#K_o!feH9Obwq*U|UE zlh1|_R^t_!*o>Vac3>fV13Nv;R77z7I=Y#nZ22M#Yv2<*rl}Y< z54v?wf^UGg2stm1gfoh_bH6;g!$U*X%_Xe66qj@%5aPA8_QH$tkP%bt!iy6J_X;;` z57xHcT+_asNZ+-xQ4=th3K6qux}_r~s2V#oy62`;MxhAD_gKS8>t3s1q6)uSdYiRU zQO?`6VyfWT`h*~o!}L3jNPY*Qaxf7Y8>g(Sp!8me^6tjn___NU2115pqaxwR@0{z- zIx^4wqr`Nccl6DJxw^wv>R@(_t+(lET6-rure&~1Q*LX8N}*U+C8#u|izm%A@VW=L zQ_vA(!~OFB+A8^s=IQ&I{Bq3#eam-AkBzq9jhEVua~nb~cUg|z^&7k};B3>O1$m)Q zcHq74$;&a3i-zJ94l?6ol9D(64#z1{UKv0dk-`Y+JrAfm=>j5>q)+JPLf`9w9dU!j$(b+a-%4uC#0Y z6f*w7*A;Up=waRo)H1%maWu&zrklcX1o#oEER>T@RFoI!LGh(#9JSDtD=qNlBg>N^ z@|`_krnCiIaj|#g2iKg;4VLjaQyp(+IkT}{dNTIC~zKX6YT5Ge1_>zm#)@(*KTjNs1I}QoL4Xx z*-A$5z`!YQnq*85?hg3DdL1@~P+<~?%NJZp5M02`{mVK#*o-r5F2+i)>uXCYny7^N zfZ|-4K{JiL4gz{>R+@Rs7Wptmtb3me2&o~et}s>lQLq%3R`%`GmhWqHdr+%Q0r^{a zuD;YBbcOlo(^*JoV-WS-)0ywWQXFk6UDpo+*v_9GbV?OjdB_Qr=u5_A#KN?0d~iGv zgrJ%47J9j;9$WibesWGR3CtD)L*`n6BEKHX!p;0mhHiKl(oxV^CHinul$}Zm8{`Mv zWPmK{2!2F7=;CA?1ezv&L@1k8!YJ^@@j|uNVZyWi{BBq{`;$-G>)enH=Bj#`r0DW# zbV03fVCnmF18y|Zj|I#?`-{wnNk>UKs~qOElbVHeTV*JD-B)vRR<=9|#THPZD_b;7QumOgJy0E+y1lPvc9pX=QVnDr1} zG9?&i6Cl595*XvmAKCTs6Y@G<78M7CyvS5IvYk1Fy%pmS+O#Byva=udtjym z&u)@ZRY~RK-*)dUXe!Cx^ky31p-_VdIs%TPLSp!a8xX;!k^s4@;)D#hgSpVRG+qi5 zE0NMB_cy{xRr9bg9zL$B4CYVBe;dgT*)IAnG7p)m5+#$l_#%i{R{S#?q@L9dA2RJ5G}>#TOq0nF z982AoyeTf3i+SQmJ1Mj)C}&_}1_Z$%O2gy-2CJw?*=6HgP@C<8jA zNV^uTec)tMP=niySP|FIM5+b#i;T|X8#SFBpm4IHVj9m-0ug!&`KUP~*jAq@(M#&8 zLEb8$GkC$oE1%e?K8vwZZZRvFLP6})G$XdWYBy7SD;sKpJj4{LiBCv&dW8|^h#!Sf za;XAn9A$FC>ZM#yq(gnKvWVF2A*T}u#G|c_9M;Wc9WEz6y^Pf3@EbHF2q*~!B}#Hg zte5;8#$g|&R<-QsTs#$oeDa}(DTk=m0L{RlFB$@((8*LEnQlRF7oQ%H5gDQ}>IoSz zdWIjZJx3!`!8eJ~RJ>BmiPW*qG%-GVNsn$R4DxFxqW}}&p6AeU5Dpt7#u1$E`+MK$ z$7jXtGO2dJA3*5}!;x)Lk`YICN@ai{SqzX30m;zeHq(6Li+tm?89mwrLC`*KPSwYR zRqwC&<=nX1I<}R5?K%)Ry|;@sFSBW-<^Fm0rugSiz0uc8`Szz(f}t&rFU`>G-83G% zy`1EJ53Y(!h6hd%eh#|0S^n|r?p8$KRowUVwyk%rXwU!|6a29{Gx2{v^K3zP%IaHF zK3tAKE(ATpReIrEPc(D=M)4~m$Gl@tvB^oZZQ-;5CpJOY1*2N(WgGc{0tt8OM@rOV zI1_i|BCsLH6u(}Jdpn?rbx95~5qm&H7r4;S2ELr(J(7+(LcUQ!5$LF;6#)$fk-+Ix zz>?rua-sSS(h-OA&C!xA8v;N9FZjmx4Q*se`!g@NTNEHpevvt-h6(6VzE_Yt?b&;b zD!X^{Ruj`O12x3Vq$Zq^{_st`GSoqK>^@z?9iM2_ejq`MGQecK8EB4s-fweeWoL?? zHTy5FA2ctWS#P3nqDenC86}*q+;E)w+x-RlhXqMoAv+L2C+13fkUAjtKw#{i>h2VS zBnd<37}F#`_SNhv;wB};hpCE7*=bB=3c({p738!&zvLoKsh^Pi6pn%nej%u$t?q7C z_-zZyrHo=r>QMI~_MnJEP|s|;>SD^XLa_hr8QDD)1v0&Il+u!TWF*7?`?2$@#BB;l8B%N&G%H-G{7hd@Gb) zuMITrR4|QNM5Rhjy`YvND^rM=oVC(287h=qvqOfIeRdmgFdZoNzI!kKx%ZB#*JA!W ztv~A*hB-%KAJ^t!6BAWHb~>C@%RTBhAO&Vd7Lm&EWBj@kCeO6Z36pPXAUx!4;yEls z^kXd(#n@ky(=kzC%CzeiCgiBA>lH>-BIDB&EAVAPU1+0BMp|_IO7H%C9%P9_d@U`L zGcL6~3#Oklf2Pr}Lsh&fh}ZLH!SNg3H!LF%%Em33+ZA z-bQfQ0Zz1OQu+wYTODb6as;R9{L%|N$+tRk=x2b{13AE*(dQ#I+|16lx`Z_lxFZ3v z@s+eNRsnBh3$^%`{+G5`jv&~AQ|_X9isPa&yW)5>&dvn8mAk4hW>Z4k4ljz>C%cDL z`zgK+ml6|MjpTR+rLAriND8fJ5iS|ma+hhxgIP6Vf(SsAIiPMx3*T97S!4gQ7T{aATqCgwVajfwqdm&YVvya$!MYiTft`ZS#GoizaO9HaT|u< znd$-3Ppw5-6|xfl0z!khNTWdOiq?Sc7dXMD?33T<0r#0>!!vnvt6RZ+acZieQ(xy( zGLyW~f^jRH%Z}l~=m!akNh_m-A* zOfaB{KcdMj9uzLF=zq}mPGOel-FA1`wr$(CZChQo%`V$Ey3}Rcwr#t*oPP7GqRUyd7k_X2CBqNZHz2ssVFI1HT?N)Gcwu?S2pv$ zBD?LW&z2X=0nt8?+197Mi8vm&J=r?zO4HLrlR&$K&2JuJMRkrfW3s%)Or2rq(urHC zS6Ua(nc!~g)gKzlcrlqzJ9uiQ%DWxiW-3L8W3X!NqbM!q*k3uF^LXOt5i7cycH>Ru zDOYuR-gK#(LfK-&!kBb-M@Jvy`r(`SSW*at7cqKtRtuw)UH~(SJzXUk5WmX2_~@)QFzPGTJK+1?pJ9Q6}VQu8rjpMx;gF zIbbuu%NajbC1iwSC;CTa{J_)KG;3W8|+(wZa!d&EI>2mWVXpLJ% z=LF`Tuz;zeMSGQ5VKbgBtf$G6Sz*mLxl!0yb<#o1mD@MjWc$A9sEh-*IA;YLiws;j zyL7oqpb`**1O^2lcAO;H2RQ$Gzm~j2WuRy?!YHcHVVIfgO^Gofm1KUaCwFe-4Mef; z>vQm{D(JN1?d9cV75;XS^HMEWGXUQ%f!}al=y>#_)`p{iNWKX&F$-c1-a6rV^qNj3 zs{v;oE-VlUqh-hu$GR^NQ=e!g%gr$g$=2;=sjxuf2i3zV^Ye*4_0I?0Lq_}Mh2f80 zSl6`H8a6znK_f9^jI;c`B3J6?z@}gL08Jf00v63W$UnfS0eIYBIgio-#X~8Or#k!- z+gnOyeS7E2at%q;Pb>(-5kGoVW6XjJxS0f*I9H911<*DN6oU7(xQ6?$%%nC!m1WCZ zJ;Q=LtnG;)#b$&>4lIDJ zP1da3+#ttgcE^n}<7V%xB&UFH3!=0AzQ>FLEzj_bh$2XAT+^`eV;^-#l+^paGB?|e zfIQYyX=Mi5z*sCN3U~A4Eg=Y4%UP+_siKn0$jsePjzbzkL}J;(%um@1QDIwS_6R_m zx0IO!E)wj{NOcUPwM~XN3LvHXAcmi=ZeS#K`90sEn@8ezqpW`%fd~VK9bZj!P{*@5 zK;9zOKmp+wxuE^m$II6fs~nnC{_=Ww-_LD3Q}>(A!fza=DlerkqIy?YO&D3 zSDeyZigXualr08J0|5Js!a(QUko=yd|JF8ca5t`67sUO$%O<8Du~9HfxN5Iv(?uWu z9m0&Sqd`fS@NFcPR0$m4fy`C~>u(mhuEN74_wuK~0 zCraLi036%;tk}F}`BLAt_0GxpYY)5W_t;k#nlV}0=JY;9C!Ns^CS>#d7silAXdVuA zdEGB~#+{0Mi%-7C6ga<><;hR1c^{Teeg{C|K!JsPi7)P_P)^71GBH0F*tPPN4@6n) zpAFB>x9j_ay=^>wFW<}AU}6=gk=oxk69wIT+l%y!^~-9&?PA++m6h#;^-RMov$79I zs>Kdy!Ul3oHD4>Nug4vq=c6JTG@2BK^$g5EK-Oey$6c|@?cSy!lbUm4oDU~=e@BdE z9~VJE6y(87j=(a_57GL;WTV?rB41b9wDHYP(%ItPHbrx0LBt`SAK}uHY{+&AP>AYM zQd5AJW85k=z&r5ig3)6b;VA2N*vw+uU|5!tcTkv|DYo$$F^|;O04MAwr38@{aDYn9 z_M9NFM^AiHAwEvp-qHjFTs9i(XkArFQl zpcr5Ti0{!Gy~c!_9}%?B@d!|JP$iEmhe_TKv1?rJWFl6$b_EYYO%k_mWYM6cnOMw2 z&gUVnVX?{fLl}z5&J)ImOltNWJdW48Ynq3edeff|0MdscH**T{Vz0mAc)6{_i)47} z=AMX{?Hse05IxPuo~zQ|zK_lAjSjVUh#lv_Gjg90&dETB^~@%j%!iu{RrE!)1TI!m zR>D(4H?xd|S0X(X40s1r$&^B*Q1~><4xU@ggoVRD0$d-bHpYMDvB`5ZYy&$Z+cN5b z7zj@ri^COt*%_E?A=ZnpAeOxykP@0BVMU6Y0)=Hdd;orag5mfj(!EHe`c)}ieKRhW z^MwO$>R*g2%mn~`!T?JesTQWi_>4#%*-+44b;!$>Tl4W2Py;PH?T*_OJ_NV11Yh0* zNP^YG;cGZ|msd>#G{!G@CnN5-zGt8{qBj(|iOi1F@hRj#F!f6t{~Vz|3hXK!ZvFBO z3e`?+FJ`~#>;|(L(QuhS6j@FG$y5*HyC?A5{p=Ca4$!rRcCDxK1JQ8q;pfA;upw?Yv*qnVl$;yN;3Y zFB~MBhw`#%T64x==vsS+Rg9&@@-3h6K1I=Bd(5|USgzb>LJM%_J9r}6`gw9smzOro zfAN6YPo(wuNTH9`KGWXIkA5;1)%S7Kz0yjrKP;>LI4CXxNjysr?7`QF{`t@efG>hNLqFr)+jNsc|dBgO2Q)DLW`8H{m>iiP| zJ#;d~eDy=M@yFf$s<{$UMJXv_oJ!D?W>R|>Mp5`4lWBGDIt72M<1|jTRRL=Px`EFR zMsd&cKN8CVfs<>E%KXQ*Ait3sp+L6Ca@lG1E^mYeRzy~IY}sT4wo*Cm{%qGNtCA8S zWC4@$+I79`xq1=b>_HUuNzBmv?hOXh7%X?3{@RXl%6avI#c{`nmRF^c3!#s^#UWq+DUtXx7OYc$`SDq^HXA z#21jFGbw)+5N^ih!pmKSjUh)2sz$pV%>6{r$uB-RdSD(IHfq6Nk`F?3{XBSS?==rr zK~98#0eVfg-)@IUJYV86g*f2HWcO1+Ey2;y>B&|wy2rYQ@$jh}dhnvs&6joNqocd_5kKYm6F} zlL(!8mgk8qP(x;>PQ8%w(CFFqAH%a>*Z5YmD}d&dWE66ee}99mJ}TbvY^s5WaXT0O z#e?JaW`$af4ofd1=EVrcoxjqud`aV!L87(PP46~|$F&8NESAP*KNw7sfL@$3u(D@% zZ}_BA!|;JBLCcvB`Ph7n$>DD$hB0%~IKdeAebYVkBqvkB~x8^D!_xA-8(uXLB)x)GE$%xhM*P627ah6mD4s=DwOS$Mk1%!4}z( zQVx_y10-6lY+(FwlY%+nF3j6fNEwX%56g-?HDeupGY3JyW=*x34a_vE5TXr_vD7y! z{b<}CNO`pEb-mD*s4_$sL^AX=2~=6ZwS9BwxqyqSe48ZX)uS5NCh%@xlDA!0f&~j6{NOf(qcN?)>zV z7uTBnK}BqgKkvN}xYnztO+}?KYW!+2OY=a;%omZ)VtPJz9qOt`HJb+!BH0|W(uUe= zu<10wanRC5f=Ikei~urCrSHIys7wtOROL(E-Zt-zTXfuinxKsDAZ1b1-c#0~cowK+ zs-L-(JOmV}eZAV4)d{^r@bh=g5sh#9>f_?MtuGR49JN5#gKvic4WMHRSyp)$5D}k1 zdoM57Bk;zyKR%^72}w|L?WO<%7@=K#kN1m*TJ^yFe##Y0U}EDb$yv6uG<~KzB{hA%uk!r9(yhdE0GDR5|FD+ z!f6^qy!66AXK--w-NaGeQ)mT-3 ziXWOba>Ci~Vs(KN(cIGe;r#o(M$|*TrDmYO*0P&^^{ekzg>0Sg|QR zt*37Rwv>nKs&wdpM2{aVoEwNQi@?mktAEXqB(H$oA0hO3dBcLwuWcO==A%6TLc5>4 z*$2xAE?hs^_$v(4?4>DUWF=VfnF7P%So9s+)8yjxGZhN5Gv5wLiSyS!$ejE|8Lb*pg9(L*jl!e7jlMDTn9DNa2kv zIQ29){jpyQ4|bV(Po^X)j#8Idk^92dddSWsn8CANz;y$sQ0_uAcT9th)H?E=W#yA= z|4ow+G@gj*MgX49;-r`O)tVIp7CZDtG`hPRD;k}}V13}`A`Z?S%?A8*9nuTuLO>M8SCKw$o?lPD~YaH%}7n#a?e&)v;{w=R8$gW%S$zTD6<|wlJ6W= z3Q)Ae(%zwIc8-7i0L{rWL?No-vt^uam=igZF1--aun>?w6>iR{k7O|Y8ouBCM3$>| zeM=qmUBs^W!pS(BeR=hQPr)>B(tWmHx#ZJvo+`c|iU^?Kbe=Xhpacr^0(V|jDY zLrp_Y`o4%{d?@EdNEL(Fc45{tQV2hPrZEf}E>FD#KRZxufmFJ5jlltlSX-4>MKPKs z$dzUkV6R$>#ETR9&0<@7$0;V9h4ew4MMn^i2UlZYT-c9h3f7FkPW53q3?^ zFRwt>*j{zxe$*dzC~X6Zt%_yUU%28nE;Aez{!}Zv2W7v$gDsq;a#OkOmTMi9y(5X^ zy87SHq`eJOaNw0yE=-XkmF=UfC)7R}yLgvZT&^=l1%Y9kt7U|px}0(GL^>#B3wr5W zL8P;J=q)s7$)}aa5EjA2(1yNC?_*0MG#)8^?UjBG+8?AnkWr#Fwbg5w0;5?WZzaO$ z%k&Bn<`K}cniv$)1qk&h_!lTiF9m-?gL2T>W5RPyP&u^lb^AhWV7cw_KPPI@@CLcW zRcul-e!)YqRqY?5{tn~DNTn@B7fEC5WBBxiuKA2d8d-x3 zQKUYSrWHZ0)y0tdZ5(|$wlc%&$d~jRn%Bom*f!vbT}snGDBr(@qy9tr{>8}uXx#iE zhyO#((u@5eg8x#+{{~-rvA=}#-&~!)DEm)}{=A$jLf28#PAJlxX za{iZvHYXG3-=OznE*v z$fCy1&cO7Rl8`DZDi1R;i|;eoWSNcqGL~glRx1}TtsrCT({(3Vb1%^{KPIzAS6!R+ zaMac(eLv?Hw+*GhoS^zbpq%bPZx~1eB!4vitZZMBZ?kr*Y|ZWr;%5+dw|f2@zKs5Q zzv9Z)Q)`jLbeq74pOC#KXZ3EffB3{ay6Kl;lCd=6gc(w-Ic`k%!4EH!DBD4h0jp^K z*>@I5f#_>q3`tT)7L$uUggrN)J8;Qm)_>gZ+Q@nFaZlw<*PLnJle_&k?fT)=u2ap{ z{CQ5uM1b8HVU#~Q7o{zvsqwD5!4pEOS^U0*Qls!aCJ^0i+C|lk#6e#E&6eM7{qd=3 zvtgZ_zCA-4v`}yy1krcl(X~AYmChR~cWHDw z?@Li;8%0c-X#XV4fij41ZnYWIl~Li7;<7o4EhO1WDhie)wzxP;;r-eHGR2aHPgMo6 zu#ZbBbw%oSpm8v$_}e25bn!u}Tx29G1ZouWw|=8GO1rfJh;~`nD;=G#dv$}3r3tuV zV1(j%W)=Y}nHLHfWDiG_o<1{s{1l9gi~aoCfVSRZ@m7h5y!jRiX&n~wy=he4BP3>L z70|{DOD|W7Dc0GsfVKidQdosc-2U|v!^|BLILx7-T=y_P!m)O9DznRL-a{t>@2wwj zyLH&_zZzC>)WV)^>7yJAY(V{HKM7Sl<(xf&1K$IFju@zbfVrDiR6b^|){riN&_gas zlT45B$0-vq;QH!ac;R@g*rduYhYgGucZ<~)r(0tSr=0|oyK8o3zqjV1@Z8%zeuG5j z%y;nfqovFeZOR5zjquKZi7d@r6sPgh!@Uw4pfKo$6Dx^OlsM~97W!;-6AY9p01bwn z3M8jOJPu}V;QN&vO+WRqCVmF3QWpDc1al3pkoa_xCcASsIpV=O0nwfqC~*#Vqm#v& zwJZTrlk{HNvU-G}0H9pPT{qlXBlYVrub9|Fy$_!(uAH-4nR2m;k}+Hw28Ryh39^Nb zZ1+`~OPo`2;s}UQxxZ6Aox;KjkmW#H0;`G%(OL2NQSmvlEx|xnQ_I6l<3 znqbIW)Q?(ZJBtFlua~8r!NWB$QZ#`sG<8^$iQl3eT9YDl2QQhcsd5WJygEVw^QAe& z2gpg59(c?rm=U#q#cC!EWB^f4D#i84nlPA73R(eopJilxg~iDX;dW$zXe%11^C?R` zg@x!RgjziW95<8gS6tAD|6{6U9H(Mltkalr>-Q_}LqR=_S|zW5WhYG2qbHpqe6$K; zz%-nR>zEbWYGas_IdK}=jmCA|_Lz7DH2f{vqlM5J2bzmSxpmAP&R|SEI;m`6b~>G% z)R?q1=`MkAUL;N*KULno*ke;fFs&SSG0DXeK38d={4O+3OT(V{q^n(;LBM2h| z=;4i^^c}nd(5w7e3<_XmOsm;4FMp9LL(G@dGrTFGx}3d zOj+zexD$3g_R$;ToKroxaP}JrBTC&cF|iC;*rA{;qcH3Mjz`9rbTen%q5NpjR7;vl z)qA0^BrJVxn9?xv=7-VK2{9ca>JxH0jN;*g+h27q$>^b`;e&uaOcy)8?H|qbM}2RX zN1vU3S~x_eIQ2d^@a?oqt~t+!1JPd>eE|Gxi(z};R+Ka@IAvTrSAs{^&Mz;`9&?+T zwbT&LPSXwKd@?0ZV*%(mQ{fSz6ZcQy9buKf2Y)J;@MmR9`dI;%lv-wNcTi*hw#cA_ z^bE)sp6biC*xCvn)s1fp2%!+Aqzi_L%@s^4;!~lJ8SsN4v<7H)t8`_ZOvXg zu^JtVXFEv-=)o#3NR&=v0KiQT0|{l}&c26=4VJ{fIb44{VYzH~Qa&{SGzar4rv{@C zQK_}Eis0_ZUc%HF>BF20;zDAzs7~FC-y-f~I=SzvEJ>m==<5Z($b3u9*)7dRSj6ZN z&WP{EI6~JVM^hxo(nLWODuUWw_kS%z=y!RP_6fr#~C{urz zaaIDeB-zbz)mI_}n0>{OlV?fA>7w&JCGw62aXlSIEz8E|=EPaSQn9Z&LWW&WC+&9M zJoR=TeV6|U{_@ev0e;F4lcbw=De|Sx@YPfAe0pIReOTn_ye@(IKr__%V6fJ5lUfFa zmlRYxn4L9DBIz7j=McS=_(J4V-p5GojKfjdn5VtE_6}x?wku8HA}`LP-Io*$=OMug zJOlzdKTa6V%E_ETqphm+$LN_v1`Y3^NdEz+S7FDhi*&X zQ^yLe*YcFF1`m(GE4SzMg}yr=kTA`l@Dmh#H_s*fr{!v!He!H*gCD*={2-5)d@U3+ z?%F0-harL5=L`M$AaLlK)O60Z+Ok`x=2aW+)w*qy@~C5F`0Km+e!}gp z%%)(D`kOF?F+)h2UY8u&D^#V=wb1B?)jXZ+r^h9!4is%|g`93kuqW&rof*AH8qu{aAOP{0~;h2%z+F}e{9^h=Cd6c+#pTIT)=qetD$ZppbBe$3_Mb@K zX-d(~6T_n<2;v!HU0e^NE2{t#Vw3_v$g}ba*tBrk^l=|agqc!XQuwhm>r>) z0~Lg2L#`qo17EG~u_hEaa;bU?Xc)HGR;p`n`; z!z@yHLEoXTK*yMFwJB35 zHBqxb{=3>~);mTKJWdW-n0ZK5kM7t7MHgjNFP&BpT4v)Z)}YEl@)XxnR68r&EWciU z3qTh~aID%pem9Y?3r!Tpkc%*qLZ;(rG_|^OJH|k*LX~@{k!Wc+`s^Y|Da91GsJ8ug zO(1bp9L#(2DiDsb*0KiKF0j5B{A(;r~-mx1vAfM(d3{>wDO%*OgRnwiv+v^!u!>zb~ase`g`5K$r- zgmaXbNt6Tw206uG1}6ts)oh~PPpBw%#QuD~$3wR%k)pDLT(hM;dTP4%iB)+ZEl>pd zvM9oMCz*AHm;Vah&ivg6eR9oz6He7v7EV{aYbrxI%hcA=rlZ*OyM2a)`qL8kr%DZ< z`tW;8<(S#W+hBJdc~CXwZn?9rhfvG8=j2p%;^eJ`#gE>tqaiB5&N&j|G3raMs-%Mm zrJuD*og7wq%=8!R0aJkx+b=gVk-v7ERdvxP^QmgED&vezO>3e{Q`zN^&63heGm3DC zNJz_7_w(11hvPz7NHwjrq2}+TEs8ap6YPY4hvw&+RhfBzn0M(+Bb2hxgpgHfi&lwn zYi(07CN8v4uq>;YqJINL*d_k3_3}%_k5ot_7qMjTjm-}UT$HOgRMGOz)@dP{`!|wX=44|3%2OmTGfNW&NB40ZJte+34$jsx{iRh4=`W zY~TREDc}w}cKDq_AnN1rj1VG}PFaCaG6Qz)>uT*B&V}PuUPkdvjGg8X@X{=}zuvpB zUj(P9kRvUL1o&dtP_jObL<^ZQ$=fK~J~cww79m`X3rpY)&;SlgL{8}EEsiFK_CpG1 zF^rk6U!7*U5r=R0M>Cr}eGm|2-vKj7MtJs59t$ZGxVVgvOL`zA;@tQ?1PF^&mERq* z7oEF7WZ6h8`CJKUiglx6YE?PL4TKbdOKV~#um=h?zBFStx4lA{ z#W)b5l6_Zp0bN)N51+= zSF+=cWW8c$X@V~Hc>MX;lKsjCY(l`Pf}_O4ua*?u}A`UU~zV+CQh0U5|8 z1wI1_AU}WjIiP=FeHdwe7DY+L!6Zro=@gS2%V6dTBA*1rSggr|6NfWA#xRMK94;&mci9dCOAFIID{_`!r)mzL)lQp62V_h!L9Hw60`X%ats@%@tshA7VgN)7 zJii{CUljxKb1;D*WvDSgL|Pbf8q(%Ck4 zZy6+&d(~@KF|khE^!!!j8itnrsLbtx?mxua1%c<_IRkRlbkMb3V*$w~7}j?)Weo&N zo{lusGKDIupIk9pJFP1!#l75gkKYus%b260O&o#pM9cM=3ry{9nDmteS~n-TbPv(i zBCsZ^597WZeUE#o+I643|J1pTCD49rp7TtkS?XKBK+Ow@C{Q6#kmEi)# zswBn11yia~09z53Q_iClKG4Es4n>Hjtv$LIY_a)M7juEO-(*qCPXA!iN4I6NRF_kV z3eaW$Tj3SFAd7U~7|Kqa0#3atYF!`=6fZ}Tf+QO?&t%%_%&w5Te|Eetj1N+g`RR+` zRt<_kBxIO4;WPy*(2ze8l~M3IDzGG6z6T5t@%YW;(XJg=6gYI!O8MfT3fWGiqT6nR z8E`|UD=x+|2|<8lQS1@1uux3oI-4KlrCFkq9B~b{^FFvL$$X*(Xi_2~q$Bg$aTE6N z2i4SG4ecb2K>9M;G+HmBtf6i=1Llkc7k)xd3L-RklD*@mdPI&GCP>{P6soeKl&5Foyfe$24(4)jyB^=3{C3Rtu{PMr z+>5#U0=}t_wcVk9xt`mC)tYRjjiFVycFJU5Fht+*Ro#lFjT_t0DuX9890X;0d1oPT_*6f!M*hh%bpPtqEZ3DrE$4zDs#Zp%_xp4 z;1^HWI1Ie-t%Yhp_K6o$|14o76iz+N1E?0ivOaSue4PJ0GYV;I#5FStYajQRXN&I; z;gkaOsxmFiMl28jqa~l2M19Crvxm3e{Nqwxeig z4{FXo8e7L)upB7_`5l>Q=4g?vLyO>3Z!kBy?nEukS}%)Sr^tJNJXD%uA?mj z!d2|lb)?OfZ^UeU$@>|6KkTHibg-x4e2-6%c&sQgjR#VdhfxUvv%}PNwb0qIS?O;1 zh&)@&I@!G-=phVBmXLJ+ra3Y951d+tg^h7r25K8SbDyi`f;ghn;01^M88Ba@U57C-Nx6FA*k=dIuxbq)^E zRplC}Sv-4t`>=uM#TZT0bkhVA>B1t%sI00gcP@vM+o8iVq4~Xo+)qg1-*-j&u7R4O z5P`u`0NTH2XV2XL>pbycL(F@K?WPYH1%$A4l#<_I9z#QvB26nauHy9f)1Sg?`C0P2 zxh{8q;6tI=tp9^D{acdj|6gVLmm2*;VE&~l|5(xfQ^Wo{t@8gpqr&#L?eqUEqr%L{ z@IQ~v|LO%OvW!4-Gn)62V3ur8KQ(3No)6=IZ;)BfkSZXyGUo2?ItBoNRLG+k-7;Al zJs?T|3kV9j_C5x(f7*|la{LuG#S-Lqzv>9=<`?pHW#;$7@ixyMHC;xaQ?@#+?Vh11 z1*5a=&0iXIBWf0v{&lYG(a+(r?WJ%BT@O~btWk4jPQCDM24bpS@6)xS^K~4y;)-`A~qq3G)Gq-Mf8Fw7JP8achW~t zzQ08dyk*!gety&imNW8p)1xm;_zCq^25$r+jjpSAb=(@CX#!F;ycT8E0y#@H)J5|} zjV-diblDX2rSBslRj}wNLS4T6_uHdyEr5oJV^-?fOp+APnO`$(?44;@_E-`ggCa@+ zp(t(W542?zrP&>`o>B?(YV`OeM}>|BE2sC01fZSne7l~?2)z&Yl+EmZ!ITbM`Zk+q z*Oi+k4ykD8H`=z>d_Tss+Z|domd6);RaxznzAJ!QeE|hWl}CP4NafVj?Jx)yo!l-N zD9SdKjiz^$N;pZ3m<27<5GhO)9dcs((r(mMQ(L$0>UJwhepxa&7Sb~8qD_5#tk~en zSxtJ|JfqyfOLwCOj;*t>gpK!=s?8z_8)Uk-T2_H{;H(M_J0FTqKlfQ=+Fa}?r*eCF zjLjYUsIV1H2zFCpg1Qkx)VP%a=2xr?rY=#jLgg8NC07ce_m%(vU$F}9uqpnu!1n%d zcp`?Oc4qXt2xA3F^J6w{B`dgjK3{eF`8)*}HLi<5X_h{!$eq1`Y5LA_guw&U`uikW z3F6TSfb&oyp9Y1j#Xz2o3`T5v!Ezu4Uj0&}=u4cx!cc=qrx}dDx%Q@O4xLzu(32}J z?fIl|wn&jekwHE^P?c!cNZ);hu<`yb#fHBB_(llHoz<-wRDOcyDy8}_ZvPVqSY;xS z_c5MBLa*EnTDWLIm~r)%#{5yZDkqwWIzEdTNa+aN=eZ1PYdSsfoq6a6bgLrZR4@DQ zy%bk%aX6dX;e#LvZet*s4Nh?cr9QD_F7P?Ah09~c6tRRJS*!p7yx#_x1P4lfbb?nT z#p42yGpd-MGn3bX){3z4gKNtK&Z~ThubesW)D6N22WJJ)f+;36Hapb~HV|>b*A40c zYhNP?I~IHw&@7Lm-nWnD!?Q@p1Pmt1G2t}ytv$E;(okJTk^i1UUIXX-Goz#n$Q^e9 zDxk^*fssoSDqGChH%U=Ls2ff)jPOS@D@GMA`_M>8EVi)~Oh`QQu*9(pz)xWSVJc;J z@DVu14N9rPML=H1RP_dUxqR^%#%dl~1S|7e;zc+nfC#o6i8cScU4n0iQh8@PNrKTK1AN`fRaljj>5WDaAFZVrh8$f!Coz1+M1nq|+4AB`t zz;&ds7zgMt4+^NXh6r7lPND8wol!FGd$QbC35hj~3Eu#~F7>H_mJrO{)NTF7YK+gvtFmqu;yX}W4$=vk?brHa_lMdfFU01@Si0a) zj|L1ZdZn&Q$wtL~jV?sTuL^HHFU|{m*TW`24!e#5nP8Qm-st&H^>R|pwEw-Rm|&Qi1LQ##ylZ%!4ZH(f$5q8 zE|B}C%s+cImR#=0(pxi@36Xv2(qTC51UwM)m9%mF7%A_6N_gZ+e%<-3q8V^AupE|j z_6_+PY!sU|%u(LB)sa9O^jo=jewl}jFS~uvyLW%uSUf%0!5)@kuE8`}ykw0vF z+f1UvbMW%_DvfpNq**>cR^vQh)UB)^Ui{>nThUeBR++SVA+sa~YHs7ang~e`J5&6HG=NUpQL*Uq(PA{+tZ0>+fpxdZAnB_l{OC%2X}E`SekS?MwlJ)lH% zWgtcNg7I_}P%HWn^grrN2MmZz&SYd^HjOl4pltuyoxVFoP&UjDv4i8f(Mh(U_o6{6 zW_+WJ;HpKYd9d>S07?l%hGqCRE+08iZZa1F#Cqs{2kzS$@>#g0zLlEt<8%|0^3c_2 zOlx&VkHVB4qr^<7M+r^w-k1*(>7FjuTS|qVbT{XcTq<>Xbgh)@_A+;#ug%McN^f=h zEfF>>e%w)4crAMsW0B8-*(=;9b4p%E{o8PnP5xjUkb1mf8IuwEcf$aZM9zVn4O;^L zvB<05aLr%MWh8TeB2jAn@=pEokocstjE=c*^$msU9KzdXR!PSX6gA8vfG`#)jAi|b z8dWrqDKV$A+aTvL3(L5oZ6ZMXeP89jI>rrV5iH9%W)zl>f_v<&N%g$4;s@ixfJMb) z(>AktEtnHxd1;xprpv;YOPzf8yDAgaaPW_hRfNE&IzR3kl4vFs?TbTi??Q<9$mMr; zT)%S*m3%iYI4cqw6v)3YEjS}y3pVH&&lTnRP~CfYI7;J;C=5nc1Ew=!&A=$ez&{Kb zB8kCL=9mGI$@RlqWxZ_rjKN6YfGw6Uq)3J<~9lvfeeHQxYg9hjuZk(N21%08|Ya{XGtRsX|)V4 zV++Ha&aWMV@1)?df{7;z-b^EDd5agQ^ATm{zpFw2y)-@?@!%qk8PaQ#2f;~bvRMtJ z=Z+z;yvFl8G!}VEPkAGQONK7Bqc$y>i${Ug z=r?$QA+oe7G(Qf?l zOH1{JT@X0aW%7FA$(PbA*tn-x;$k~CkGb(%nOpmq-DQtYHqY!RL1pS)h_8B>@3M?~ zF)R6+SOl1#e3{hxn)1r$PqpG8U4VC;=v&wB3F<}<0M+L0@LnJuo{O{6#gdEZY(`}b zy;J$LU)jagV{O&fXg623josTTg>+9dW5QkudECuRD~@3=_cu4=Cc#1a(Edj#1ac9| zL^x)Z$AWL;tg<$;UpM{K%(t!IBiPC(M7@@K#nemcW)fECgA1{B5l90l9pASuvwlt< z?eu35x4TZ@L0+0OubdVbYwHqQ`Uo7*6tDGYcI=e{pk;O)+SA5z1}1g~G2FT#fRi72 zEoOIo8v}b)k8dasC!hu~qfDpq)>nCZfAD$U^?rM6{{s4$GX44osQOzb{y(7VAJa?! zIOP8~^3aR@6Epp}s{RK){d0Kf4`<-dz4pKA)_xzvVkY=kwn*t;Q+9d}I>Q)g{@ z1rad-q$aP>k*lUOQ^BX;6Ckxqn@V0J=tx%T=U$})G62It#7R?1 z6?^aO==jJyFY`uc^T>>lg!zq#DE?y4rCGXpaQk&_cK5M(P~&HeT)-qXaBzmDHw8Hw zm8C=Lmy5)fnaDF;dJ(po<;d*Q*``Umt9CG7nQk<1Q@5%+U6!V{?oy|(nz?xqTbXMp z0cCs_<#0M|;xY6dhnYSZ%{X7VJ_p-I(_ERJ-WB#`0OO~AwGq46*zVg55r&SeQ&grd zV@Xzqy9HaZ+E9DB$s4uXcAA%|l5RMI>Gi>ud45X09e$ICiXa$b_h^=pmTjK!wykLe z5Ra+*oJ;z8PE(_e%RExDVnGMfD6GO<17y!p_vb#0?%*k{te?70LD z8nUEh!X)^0RDU^=yq1KxSUb}MIjO*=H?h*(ipefx;hX0M>v`*srA66R%1Uwac1~m@ z&!CjssCK=`iZvj>!7gW6h-A$886k5HXvdfY9>PA(jh93IBKI2YRc~!(0wlVP-k%c< z5AzbqX<%1nITNyE?kwu!knse~Itf`c!@8oHW>L8^ho_?0MV*=p&E=?dGK)#NrHypz zx<3{ze{|mQSMHdHfVAg!OFp2bm$^LoY8)H7CE$H#M&Y7-q#0Gd+w0UaMLi8Y3+b_6JmQZ+@gNzUwioe_~ z&tGCu_JQ7@rg+Xw$%I+yr>C-R)7oCcHlAH*q2Ky#m+sm;SbqHXHExkLcFS*4X{hsx z-^RdyltWaVVrPxgmLIXv6t+lnG6!;>h9kwfj_cV)y1bY@0g17^G_25U&X7ttUQe>k zwAiJ^D{!*RJi>i37PpY?i(gJ#q8+qAIi#ESMJ*A2E2k_#w9s%*GQ@<OrS-$-bc1J>09C*&Z{E6!aR(rD2BU|~ygv{HD_dvf6~x${GE0E#vJ4Vu z;2QV=D?#(VI?kG8N7zwCo*v*O)^%vB3TrQA&f|ka8ZhaInQ=X$vLInnG9Up=8Y&tO)>*Ys`7fuXwyK=9cdOp z^PtIX@(^j}F}XPu7nH@j>5JzfVi=U~SeI!Ggz@Vyb%*?wyZ~TBoWXr*lrKAYKpL%m zI^bQ@OW6wbR-Sy zw1e4{IK;*)zJU^T2H4!5S=|8?ITVxQW6hC_J2Gnui)TiZ>2JvTX1<>}e(#(BY>qAJ zQ!4;;>ba^jQ!d_xU(pPHnOOtNKWE%!fT5m$3If@>2O=EvBOmRRmvB7s)j(qgn_zB@ zI%n1Idz=$o{#JFqNZ!8HvHdtlC!Gr%J~bCZf@d9khZ#~r7nQ2_EE(+LoTVhdZW&=8 z%qSW0P~d9gl;vdQOeVH!G4L`Z!rLW>t(!RHIO78(hJ|4cy00I_Fqik9KH!ZHvC|V2 zk&_4Zthutwvp1uoq(JGZhQMf{sG2L9JY8Q_ej){V@RSv~R#C;1bR$lLwzcbI{|Q(Y z7Lf9lG{pd9O>XTR%4m9)6#XlM>}?%use=~XAKI;ap+LY5TV9HL6&cK42haL-n znx~ZZXh|`c+a~Sz^t`pQh`H?IR_b9m3u#f-_wxZTz*i$n;&CL^bNNtP5<>`FJ$YimX132b! zl8)^ewgwVHhe1A4ny>-qf%WmOv@>oYEzHiP4=F##geJJyrQkzIwtn*#r;hPC4F6bwV?NeOWHP z#y?p%m?W?aEDf+#CnFir5M)TrC&ujpA3OW`_{a zUezOg4r$=bN&0@Nn3n9M>{IH;VjjtM8LP3&8lQMLr;-L0g{~){XnP=uEiH3 zH$h2F&wO7THuCWc>xn#67Wz4$MG}mXv!OrM`OPv2*s6q$7h1T=dK0~aV&m|`>RDr> z^=;etzTAqf)td2%JYkdwJXzO@9Ojs&bvEi_<@^JGN?F z{5R6xIl9sXCly;2SFDO{+qP{x6{C`hZCe%Fwry1SrO)ltRdxDw|GshWf7yHN z%y+Fh*Sp3u^~~Wsc%uwCC~7+pj|uqb$Y6*`SRA_1mfC*#+^P%yl!4_eRxble0*&I% zHazOv%7}2i?rbZ%`WUJ;ngd2GALFY`#jTyaDDC0U8NAj$gJqjSg1FTGCONT8l341O5NUdG;oo>jC08us3E)qdi zME2ktgkq#8Dfg<%g>J6x4;uPYD6SCiCw#lLW>HQ$+jUIyKx+w(lef3CK35jjt4d}t ze`8R&VCiS+ledFnU=76L=`HA?DD7uYCKU3e#~e$ntepk|cK$(L7WXy@`~wd_8pYWr zCbkaBB3D_5DE+EYJxw{VWLf&PeYB{Z7eDu;>RN^bz6&U*3E)0He84H+e(esQ+~Sp? z*K^SbFG%9JKfo`fUcoWD7!JNK~ejEuLI{u0n&^nmS>gTJtuqhYv zqsDX2CYh=*6b(XY9vM(Xn0cIt0TiJWnDs04$1+>&OiI+V0WI>h324SVPkD+k4{n5* zuSeusGjq+tIJCg%L`uxV*QEj=e1{aRGiMwTG_+5jWJ)CZN4zoQuF{uRT-1i$%~TFV zTc4_F9*7OCLn;Kn*GWc1q9X#9#%AW73rvjIUh!@UJ}01T;6?_Dek5Z*K6b-=WR9mlPu=4FRE;r2$Ss1Q*(4rjEJS!ur#IX*S6PA7)q?bVN)Hd>n zTrVM5UI0L5kC~FB8BWJenDH=cF@p4mMhs1`=v;xH1D5i+4&}N|4|$i#@ys4nS9d31 z1jN`pxReeq_kI_+`)gM)uIj`rC>!Yca{G*At9WE#oU{5LvGzg=M z2O-L^2D7(9%$-F;svO{KJ~1ARD(~kg1sM>r32hzA)NSW{6tTqbDqk)cf1>SEdsgUC{tsp6%A@_Je z;~uKcmJ~6V$9->DyKFCxweKU@U5E$S7^nlX)0ged_ml)H6((^7!FMq=>LgLv{i5{x z`3J0IRTjRIJ#-sBwZL$L(s&fAubdV)(~P}ghBdf{eDMb+MaM>ebJ8ApJm-T)7fv?i z5iq@~bsZ)>YEQnq=^vc7NvWrx zO?)}e^8!wB{0`mTeLH&xJ40Q|e|dSowV?dz*Zx2HbN<%D{SReqzvlgZaa?~o!M~KT z{gOlcrAX~(_s#p9kAF1M%R$i!F){sf5aIiuEcpL$RsZ;w`CmVH=STaWVTk{G518dQ zevkj=0W&cCHOHtX9=*(p^p8n}lVF52nS@Q9xD3fGbPJNvRY?YLVP$6~6N%V^Qec-7WQi##3sg!*3~ zR1HepUD6nZs3TY^&?OMsN6PBLGgG~^nJ?t)g1u7gP0`=f8N|?M^;^pCGZQ`vGdN8Bxsi4l+c_eXW?)A;CmZho6d*wJFHtQn<|#`;de$tu;U^+L)h&~ z=zI@H0BWM_`Bh@Gu&so)jds#S5_c~W9Ie+$9}MDAIFY}Tv+TB;H)Iq{@vPOSNqaf0 zCoEHTrGkFC>{K-a7vE}la^h>INE)Hxo`Dx{vhmYi50-UQ_-yZ(Q!o_gw(rb)8qD(K ztSiG2x2Gk|N5%JXK?~{dmafXN1Nd%8_)Ygs;r^-8o!$t36(-`FuEEDg8JaG3PIXId zT5eKmw3jckk^w=BU&yzOz>j@tys zR^%;PF<5PvDoX&Se4>mEmk>1J-gYT@$P8YR`?w#oQwpt@pco_w`nHul&lJ@labg$#h`e70su~Wdv3)QkKh>NBJwt zFX0sMajn=h@4fl_ZS&{>f*6!H8igjxguVyy7K3VuAM(Gtln|qgP`AjqKCLdn9udYn&?aXYnA!aBLri)woij++bWmW)%i*Ua_f?U zW+W5O2CWYT51b%RDYylc(x$%fJ7X~x`Ubz83P|O`ts);CUDd9?fxRQ-4yldV4e53b z-Gi2GZ!E$^*r4C6YipeQRO?1(w|TNZ;I{VErFt8~_(1j zVtAnY_>!ceh2X4U_yqny3nsa>qG!`{W`JD~pRh&5fN{Yjd{fE1K+=PU;seiuNxRNw zg?0ZN9fzWHubxyhvxa3q}`DF#22k0+PqHjyLAg z4IyM>9Ac3cTKXBj|h5zn~so%Sf?Z6%U`j#E{~nUTl$$TDDGviS1(AqkKnPEo>) z923&)^29xC#drHwiX>@1k*RU^)TID8D>fo{glY+q z0+eMnh&0g)-YyjB_1!>wN2363(tQ5hKQyJq$&!c#Zx}=|h>RKja3rSlmYSfu~DHnr;VJQo__qfVRUt}bJqW>9}%X76>;WTkVpMvH0H6GIH)6plT1UdMhQLD zE)+t-Qir@1;jU1g-u7uTq3G(Ym5Z&s`i>Nb9m#Et8{sjWSv-?em^g(p@AxNW$!4u> zvrne-vpY8#K-L4OYw`WVR5oCT=kMVoPv!D{?cd!Z*Av1$<+(FD{*Z7(k&Ep;TzxmZ!~d_g!%n~>jmC~XIwYc`~5RCN$WjwNAD zP;0%>4mjerZjnq^KXcN2s#*(r!u1GTZXz2B^Jj#-%!@++PpdzADKx$Jx_Fg2?^(Jf zXe|Mpwj+q-SiGa{<|^u%NhLA?!>FWZ(uVbJMb3D8;JKCNqx^Rq$nsn9{+~GT|CQhP ziPC<-b9DbqJ-lZjezKYU0_}c+xL>j1-)BJnMU?wK%;V3gY5xa6_Ztn}o$)zQIGeC{wR<>y^=2P&PajRM{ zJKLJ(X;as14^JvN3QRlY?ki)Sy`EBr(oL?&xc6Xo-i>S4r;LZV60rcyyG!;V`GV8Qy=MK$l;$6+#|@C_0$*(pgFhVgRu#^COPZ~DcMj|kBf@Q zPlVLJ6vG%yr`nrhBnk_^4ZoscQUCNI069Pk=@qGTNcU77h1QOojno3qFiH3@TEl&s z`%N~AV9shMfGScR5G}#t#F-zBgvT^b2hp(7c6TSP_ZL2Fp_o}!m8AW$D}*5rj|<&fVAL`F9wiJt+u#j>v=<#Ta3Le(nt%Ft*RCqi}^I zD8kh8F=+Ry+70Ho;l{i z4lEX@!`k@Ukn}L7$xf@xt{qEU`*ZAbQr6Q$(a>-&sa7ev_qd1Zs^)3Q_^8*13baf8 zhLv-)q^H?>v)f1e=VzOirPeY+mYeGF9}gwF;$ylstzkUvi)RcvV#6u^bKpx?6@Yjq zcmrTy6HMKYZ|mxb|{Rzv_-7-rA^(-z4$(uomRtEM#6w*{Bp*omNtpqVqY>H1f4RLSjE3D zJ9Qs}h7Q6;a!_DjB{;!05|&88oM6Mq8;r8!ejxdjAa&*!7gMc87rC;SYtNJ{08lM8 z3TC`x)*z+yQFh_;c4T-|P9s1x=_g+@^VY$LZ!`W7eJR~MMs>It1EDm;M&%oLr?Dpl zBJNAy1{d}HAScTpZF@++-+)4$BID5$u-ao6zf2MwG95k|kOF@R*j@;@CkTw9!?Y3K zXxS{FZ)%|q#X(KDrcq=(gVQL+q;otFn3$#zQ|T`Sg*{3iu{n%L=hr0uav#7JJK2|E zDFtEsgJe+yZ*)(LzTnAgk|HBhUcqVvdQtS0)YjaOkV>1QYro|7$gQg7m6Ne~j3}O| zM^Le?NmI*;MVa2w!dZFvv4Mr9<#g4ot+1LF)u6ca+KL{zodGmuQ(b2YT$(z1mL=XA z8k_Q?&A>Dib}}c4qC97u6`wD#E2`7E<+HQ=CIVO}w~yc$5%dt8s7*ckK=TDR8L4wm zQ>8iJ2RWgF4}|(K9xI%Hx7=935S!98VfPO*f#tjMS2Fx3YDDs^dD)MBj+d=2ZYs?v zS_sg#wz?UiAK(V~x(^8seC2sqgonFBsWNhpRr30=D{k;-$JLH5xASn{F7j}@*$+t3 zXC^N{VvXTDYc zN-9#F>{LjxndvHrfsdKJ)g1SSN+@uXd%Y`QnGOz@lq)yj?(x)XxZbU&O@q_()i4xB`-jFEnQ~TN)({Vx@S+jD!BnD{X{A)=yKl0Cwc{=7?%eK7~Kqc+}_w~GqV%q&jqsrV($M+B++GF+^jPJrFH zQ2y9Op8(hFY`^K~zs!V<4pc3Kufzh!-TL;#u%_+Z64bDu`hNyRAuYBx(z6SMh19(* zxa40X#ysigREZ4vME0TH{Yo}^&sGR0&L0tjjny>)RT&vt#M2g)ZwhWNq}fb-efFTp zyj;eJQ#KCDkTkz^cJI!pj)PN26z&^C0Zb#H&1fVn|wY``SHW3}!$&fho;ll8cEI9tsF`rZKzc_Y zg@VehrH2Z^uX`qBxnsCx=AIIk@%UHX=*Ay6OTJ#S`g-wKH|45R%~Ir%?gt>zCz6=4zlQR)1p{hvoD__*B$tfiy#gj` z-tGJinEI_a{ZBCU3*F<-5|6(PrTqj`zapex2B!T)Q-9z2`3r3NwL;{VB9woH;{Fe4 z>Njei|B9yGM-cp_-_tUByB_g%O?xw%p<3@ddaPa;fM{C2hz!%9p)bJbp8wq35~YPH zk?Fki%k5VJiqNU4L}zpezZPH$Q&#@5W5$~@FYQT1AnyY)`iHbqW?`2{vghTpSErW8 zXZ7~%FuK%oE4+<=^nBVmw!D1G*29@57A3qJWjEpzexob_GBQPa(Kv|`oUOZi(Y)y) z<-t9hJ6^Zy0FOF^O3CFCCKVNe?O*09pJ$*<&9^$aX+Mw>lwAy7i8ORfA}*!m5ccLB zOk_jFb*3Z{1%dc{<{V2j$O-k?;El^UGvS_%M6GGuyRG$+yOq7g>Xx+jDc)x3oGZ5_ zLT2^6ZHXOru`4-OIU=R5H#KY^nWT_nNQ7Mk`dAEk4sTyyhof@!mGwq*=mEt@%6P=M z8LJV#Sx)}WgVeKn4Y^~7%y=xLdHh7vs@BG--sSFFfsZZYp2+*Kg|ci*UA@AEI|9SG zUc$kU4TOEakQwUE%Do*I{HRN6f{*}maS{0>gpsiQviJD}0z8bv-n`1YqFA4L_2p|f z3SE`w5!Kolz;5mr`_}K=o$ml7Z6zU__@wI?obNXw&Autx!jRjKZtTDZ^ z9xnqbrs(ZSO#6X~h**FlnQkHO@stwSMPzV3_fiUCa4*nz8PwCEp|%R+b(Y}waSUVJ z7+O}EpNIs|t7xFlQpMJDI(mBSICEsdGh48WITU5*cNCvwSo*7%RI69uouU~vc&8Qv-ASH9pfv6^^IQZhO6IP=hhkGx)b2d(Z3P1tvV;E#~BLXsP`I2Iwg$;;O0;gFYoJ+Wz~*B&BAWjH))3%>|V@XyM=BucFRtn{`O$rfV+igoC+ZW zC@xA`fH}BLM4yPRi2sU#I`SPz0NbH*=VG&FFo`mCU?6|)1ttu0yt~>&ELqFx78>l3 zYc*EGdRC|PK(&>6rjjbxK)&~ZxkKMC$l(h@O1m1FGEToRwoDw7LVGkvZZwBhD0_SF zl~HPBeA@RYBGS7%uzf;y)Vo#rW6~xZTziQv&B^#TdsfhOt4!>Kj~bkh96vG^7Ejd< z$=@6RbTx#dp5)EL!uuPFIHK3-&r`4TEBE-xuT_)tCcPp7v@Bgc zI6bPb%h7K$S>G0r@w?MKn1bjoFmNS$h0<(&hH~*)vKal7;DWv23g~AuA0_q_Xc@@9 z8c0DU9x{@^`w2}P^KLSGEF}f&IW>n@((I{*sb7j2L984iJ|&dTuP2z#>GvJ+NlNt| z0DQKAnb6Qun%w|&6;Y1YZ(yek&-lEdH#29vS;~x3^JH&VOBVbQtJiNT*{|UuH0(_? z=S<3+B4QH&ENvwY;DQ!DSO(E|=k!i#R+Ak3hO&MTnpO3wC%2SY(zgNdM_2pB6&z<> zny2kaUJGKf#py{Gv4r(|y#}W-dowNb4{=p3q#l7tgzv+&cs8bHlXrlG<#prbECU); ze#l9f)fC_Azk|tqIC85u3)liCDOPTofjckGUXViHk7ibV@bHLan_yTP8($h6Hp-=N zexk8@&)y2ssq)p267h@xeYZH5E*^j-4Sps?U|Q<$|nsQIX_2l9vAUQYER zcNW|5z97MQq-vUlXE`mur_XaNVc)8X-ogXB737SlD7M>L=#(RLndbHAtVRS0CC+es zkMVVsb}S+Do#_Xv$*plrS5Nutw=u0)!JwyVZbed_GBXG@=!=AgBRskxlYV$$HS9l6 zGy|&zUrRMtMBkPd9+5eR(c4(uMyL1@GaN=q5(w;n^3~txpT<3^#VdQ1glXz~>XX7b z6Up|JwZy(1jC}HttSdqJ90EJ2`XSede+!|ten&vN7|HFXZy%vHVY?T*Q>|SFz%P(; zZwQEV7W{llYAoJKUZ7gkF!O!z=`HV;rE@W&b%(gK+K*ko#EC!T?f*E^LLb){wL zDVgwkWpr1OeLobj#@CY%AC9{gRt#|48@qdGn)*Pofz75e(m&OgQ(B;X(sEtvV0@#s zzRSj=r4-btcnKfNAsgdws+_nxav9a$ZC_lZV_Rp{hNdq-WGf4sIQgtaLSfI7cN?-Y z$DU(4-o~Og4UGjM z!m78$k8iO@@#+v*(GG>_n{Q$=bOCqahk4_YXMgSm_4)WCQ#Ud~a)1-;)-Dt;(0wG! z;_bX{d>jIZJP<=1RtI zv$ZkhX4`7e39+U1M6Y4B?q+VJFL2;A%h|SE1U*!i6+9N&-3J~GXtG*LTw;msgqO}{ ze0hGDpce)BfCB+rbyKH^qm+h~_|2IO6u{q@HEk`u(suiKa5%Ldvg}@S?ASHmqL*jS zzo}$Z&ko9$e&@3dKtpD%223H_>w{F@l2fiBT1zpah8erm&z>F0Q!2ZpEkk_zII)tBi zl0i-?<15Flg!s^uDr(~N_VV!!3PK4u`P(Luw!V-AeZ5bdkeS;pp#~(AJ^Gl~IeZr1 zK8R#oJy(&1G{`m4pn{VW|FAsV0=*IK^0g2>*?MX<)qFXYGW*K}Zaw`s|B9*+nIB-b zlWQtGuy6W*!!75{RQ^@42S)Meg6Vt@8Pna;j~|pqJInf z{#D=mKG~KD|DCt+fAXJy0>}S7sAK(&*5to}I!4Cd$4ZT2Eq>XqzvR;HYLG!iCZGYr zPAaJ`Uy!=myH)t1I}blY&nR}NBA-frT;a?D@C5)AcPZtzd2eHuH|Ja^Cr%qVb?1T~ zxp#v_TFKqz5%3i^&iXvA!*)zHoJ zj@4Y6TZ<0E3*KwV*jYxHgML3Y-bo$KMHcs~a}B$7bZ{^2{TpEGQqS;JIt1ha;`tch z12mP$;L85+-Lt`dIZFXNU7q@4Rd6MD29^I9=V^(3+lx2Ir;o&&foV^cAa#W4&ErAj znb6OfXoptrHrDlIEP|WcypRZL|A8(f(Zy>G3O`-W_xR>#JlP-OT}0gL&%8kkFEMkcR08cdkj#@y{l=hRJj~247Iw zHmh@}{9UJp$z3H7N#Z0J_)a^m_4K-1GUELXc_q%SIqp*eXZ%qxZDKwouXOq}Gl~&^ zs(3}575|b{*=@8?-E{(N*y*amgId@f)Fv@8U_f#;Pg50kplSqiAQ{(x@a+o<V&TdNu>~o#nspV)dfZ*&G^JojEQdI(E^$v8N0e7D~bKX>nC?r zoL?VPSu>C+-21Xy&ykWWdAzx3{0t4s1_gtKTg5ZmX6Cm~@cqhSPm`r;Q}TMkzctlzedi`%7a1L|f( zLwf92GT5vq;7gR`kRR^#;gUvc=-zR~w7w@ef4}0W73gH`;y!#%|7j&4Adne^bEe<3 zvu!vVWWPmyxnTBErJ^DDsI_Vw-m%WPfi&l=uWW-~^M_1qU6(N5ZDeTyIv9->IzTys2{}FN~38cV{&Vm3?gz+KqR&FBo`*MWFHnf*?g)>=ipvTAO^reo3WR4 zD^Jcw*r_Xh>h*wS?2*JnQo@clshJ3;)b##wBzH=`zV+@Ar*<=la5Bh-N^yfRA(W}K zPsmvOUSN~i2EL*$#J*xw0)56Y--Shw$Y6b`}Nbr;RSHVZK4kyVW>3*V6#7^vuS_rIoX*4m8|VJ4P?}6tA7I1l#+6Z?g8j za(jAkAcY<%GIU#S^~l^W<^FoguSi=chL>rZ?c`TPJ9 z1g(}ozVDS_Xz#Z6b$Kbc4Gg&lT0Q_$hyc=A)-cOx8i?Xc@|8DHs%7`*f<<}XgLT`? zajZJadhN!`$fMiw`4Vb+xV8ErP`Y5*N`CuL8mw>zNf*y+OQs))$(HqppRuIpZ_o=g zZpr7<33gpVX;RGzhZalva@#+G+}=HuEXSFlTB{}|yk4MheU%v> z`4;FN+T=G|^KdBs5#%6--c<}_0|B%c1n8mBc3k|9ew0;Oi8O=TT2&l)nmAa7V+dM| z-m<<6UBX23G#zK#1fL$n25|Hzo24_J6K*vFY1I4`r*#DJL^crOz1<hH(;}3~d%jbk^NqH1 zB5w>pIkuoRS<g21Pa9(mn%I8)PPKz-Atafsltm!dCa2dKFB zyil2)NHOAtwuI07&WvM=-FscmV%gL(FEtjEoy1j&q7ZA5ug1A zg()9D!*BH)o|_Dp5GQoz9koWQ49iS_l|#D2knbs^*m^d$0!0mAqb7$$KiHeW>A^k3 zp%#Z)1!re|v;en%Ni`T?e6V!# zf=+OXE(@95dhx4n4uuhV#_RZb-h+Y~nDlVI$tH4bayhBR5{UeyHvpT11XB>UBN3Z# zl&FC)bE-N+&LUy#BQ#Ez}Q?j!Kt(z)`@J~SZTQ2oi z#P;C4`cm}W#qpCMS2F--=crBYT`*b%xG)x?O~zPSg>vc$@Xrs z4&yt-;e)xu(`gE5D2XK^bgVx8vp;U_Zvj9^mS;5;MR#w2b-B(G&YUv|A3k<|hViz+ zhj@@I+msF%r+q~()2v7`b@H> zFtw-e3%A4eK}qy^tf{B6up61#8w`E9>-n7_6^l^~3srhx@LGCj`C|OMtwhk6g$h#phI#sq|=Od zPAF)fp{68e$jkfa;!_ZN>HOH#V!VGV3%!Bqnx8bS~5-fuNn zxHE?hsp^d|L;WFD-(-3p>1u}2Fe}uBgF;-v(*BWw**Euo0##%JR5iy1x>!*jW(nNd zkZZpy$~x6a-Y;Wp#0p#RMP*0&?kO9gyqM}oR$u5s8RM}E5!{7{ zZ6&nASijNGV{6IxdFphbTv7vk-7$_G#f?1a4nEnb8sM(*1Co7Kmi^3Jgr9MPupRmp z1~E$|L)4~9n~rUgZl_EduqYek+n^MIgnt4DLXT=`)FDt`pJ~$PpiEf9n`pj8gK5I9 zwjJJvDtPJ>CYAPP5tx$@beajf%PRy*3Bb+XEI$3Htr=gaz{Mz6cEAMNCG;htD+G#U zd^@EO$ZTGEeo-elx-C?IJ=aq4Jv~4)%=r+{U=f9H!!aAcm|I;a!Z1-WV>_Ra&9jw4 zzidWS5LgH;bTjHP@h5kB07Nfde6`3kW`C(p7zFY?I9i?sKS_wYrP!rmIBvt(bxC zYl-OR704K}g+}1lVPpD`GoHkkucmd?%lz?r-wBaWkXdws8i(2qaZlNpbf2*ID|002)8*?y>s63P@3oMh^IVQklX_aFZe?F_@La?rrFD!$ z?^vpBJ1fh?;`_?d=L>6ftfWQ@y`S_MOt4TaLRtkWk)ZrUC=tJ_GsdR;n&QceFup#{ zgc`+{%=oTiI^qHO3EGv*-7~LFUevSrp*LD&_96}&Rrb}S8y$`AnXog+bUd)qRp}fR z7n@QlGlJnL30E8Fm1Lz48&I5QZ#OApT#$xRAPnizSh4v57*U&Z26~Btn}zj3UNL-1 zfxuht<4`hEKjr5<&}QS**Rl8&WSwF@O3T4gzI)A}nFg3kad6v&)hB zwPy~e$a@Yv#-gE3O{3N?1S>01GL|i4XkSAp{l7E%!Bdv|1L8o7&EW9H&xh&78;J|< zUhBfd+hE@k+e|Zh1rs%ZISt|Fj%OR(Ac_ekiIGYvl+3@H_be1C9gC?CmA>Y3Qm57@ z%*t5!<2kvmC*B{q!I5n`J9?9^hN;||%8ZU^em4S~n5koTIl|6jJe}fR&L4L-1vitF zI9+XNJL&0h9JE<97Pqe1$@zGky|SM$`{q76ALCGZE>?0VXjK7WU8*_|-XbT(v6!rF z&7HD8EBqwbErd2|weGO%Ft{+oy~3CkkqGUf!>N>16lZxs70_qnapvaH3i*0YIb`Be zr$_vJfY>1_fVU73NGb1GjFMSO@K`NU%D*CtvbI1WPf{j)zVn^5Q@cfXI8^d`NO2=T z{4|Q^nj(WW8LJ;e0WEo7sb``*P(Uf~b#cw%`=G3hXJK>AF`qi4^&}47)O`;Z1`@GX z^Xtij-S+d3*#Sl4>KZItp8)kj<5TQvlAtg<$g|urjK{yCbJOlf%wB7-k0+}%u9J18 z_{%EhK5T$>C^_kNB;Dq>;-!-+_KU0P@d#%F@N(UGHmw55RYDl9CjBrV<;JFTJyIuq zA&E-$taCoYQurkBeN+0xc)GGNKxy@c-N4sq{v_A*6i)Gc#LBnvl+8U5@TJUX6iyLP zw(JzI)l6TxM=D!?Q8Z7~j{}bqG6%MDifmYqN*Hdn;wyE?x!ng39QGzI1^&AJgW2}c z@OJ7Qo*Mx^IZxm2K(_;oSUAk?=6A#^^P$SU@{)z(W(e$`~=>0_rc;aY;U&5A%niP~eGXn0~SJ6{M*r2}`nX zx93rNsU|ELdL^I|JY6?)tf}j0uX;!FUZuhM7 zk|b$!vwvyBA)m6%of#Pe@4Cvvk8NSd>`6v`lshY#3g{n|_YkA#V zY%;&{m}$AsBR#6S9KEngz(j;f8+y`E(+f%4^OCme)N!18wnNtHeqtqcTF#Mu9rh(U zB^FmcJ^?#wk&tS7DtYHyW>2<e zCS75r$ClUbV*pMJj78}rs3iUe>hGuJP(!25Mb>Arhc2IDT>Ui6GBmQ8*n4{Sy}Fw1 zV+wujUWe{)N6#$PonPncxp9{67a&y?&6ds&%?+fhiN8-3DHwf$DrPc66?U0=`kG!L z>`2ikGU6zxI0aBNAJ2&5bf?af+tZZYjr6)=#eaV0ENme@RSbjM7$W1NsvsDqUKC^I z89gkMa1_`B7jr*Wu?lvX#o5dF@zh#g3^__X=B4P%lIwQiuy0)1E{J5jL_nS&5c46^ zO7?JMz-L7jim$=I?og_fJmXmYY~&3ZCe;+*J2U5%AxPr(wehFX6-+0n0#V5>6;{;h zu!582E)sf(A|A-<6*+u)%6QI_3PE5mntDu*RP-O1L@7*S38P$TByV}A{p65X(z<*w ze6Z`7BbvK#LFeXVptU>NVUkcvA(b0j_;?Xc;sUt9%M75(K$b~^x2ba!0o6XG@KXWb znR1D%Iw-osY0P68kqfGmPWVnhT+zFj4_{ar67BFlRV_=6zMT0q}$#zB0~ zFs-dizt`nOOQjY`m=|!yzwmCaGZ)Op(po zIkeQ!p4>_F?l_^prVh)3aMg#$5esVfP&YRcNDfG%MDn{)1rz3uAjR&n3=ToDj6U_q zYvw90Hq9LPYvIPHqBcLX*p@Vs=u`f~AEEo1Tf+nwN5S77viGBwOp;~`*mtqp_oY-3 z2s$HV-4hEo)i=R=H}GFm7jT)B&Co48%sW)jM~T<=I?9zhN-2*O4`y3XK{<4`akCq5 z4eP0f6pJJuUMe45Z{x;I4Q(x4M8Y?Yych;WJx%X9{c8s{Mx*m(?ohC+_1=+dq7nt> z3$$2AM*M5&#LoCPfQ43|4RNSWP$Aoaw2k*vUnhq1G)jc+KrEUBIFXB|;Xv~lGk1xx zXHMq*t)#t#z3`gumG)SW_wB+eH&cj%q7>?_?f9+d`TXiBF0RL2&MC835Hq!t`nj}Z z$HuB|!>x4d%6Zz^oT1stZIb6y?saCx!UsGW#N9{^c$bbSHc~P9%~CL-^lr8g`eP#O z5726&qI^?_Sb_Kjkj8h7{5oKL&pu6^4gNV_u{BAz}tGWrc@B4>s3d(bVC*WJ-JDxpivS{3^w&7yMDU2+GaIRc7ga5BA0 zO=UGPkeoV~2x%@4BqwQrcK-sHzRqV7in2tSWUd&VL2;B5(PZq+(;wgonP7^D-7rpv z9mpxBjBzrOBXjU3Vi~aG-a(|SV5qw`Ir+TU3~#rW3s%iKNStQTb4mdqogg-ob+-sD zt-=Y5t)$^QUhQl1&~BNqYY(PLC?P8i6eO^2nd4NXIH++Irl!XOhYH)C&cXAwFqlp1 zM71H9l>?u(rF==)*~nD{M7x{3zDEjkvJ|rSr6&YLZ#y+`tUjGDyPbEq;1Obe(iab% z`DSNCjSdb4SK4f$mNKv&?GiKwQ$(?6uKzXjPIH^b`skI9{PIzoY-OR7xO|DJk7Vgx4^v82f)FzSXbwPt@v+Q1MQER0|o%7z86Vn4gE-mK+!N!PQ(JS z=UHdjpyqShh^^S`A-n0EV|?9a)q!S>!NUP(hty^muV0<}P^%~HladnwIDYT}n#Kg5 z_S+Q)luw3g7R@9=x*AWkO6#JC#^cm%Lrd9vRWw~by ze@he3kN!2iO?K(#Ot{F~`jgs@Zg0nVp1Ux=&}_Fh@TnGYjaFA%MH|xj{{9zSH}Vxj zvO2C)mAR8%F?MsIlOSW9h#KO<0Z&Tzs&Ii@4Pv*E;B@5_R z@oTZMfe))OLsi%AC!3A3 z6LVa~jrJn4Cz6t-s}scQ=F4m1Jw6bzoY`a5o*rW4pWe3`rb|>*KbasN9zMid8bg^j zQvlg4B#y32k^>G;LEAZCSeZUaXrG-e+4mtLe);ofN9yZ%@x(44NE#3h`4SZQ5+x-_ zn1Ugag8HQHZLGyI%rAB5MQeV&rbu6n%4+c`hPIsS$c0w#YH6zJhcNuAtNg;+APf6V zJ6Bsu9UQo-AlbmWa%Te^$cHpnO!$^-hx)wbat6`FJiTKgNb4L0G=Z?#fJR*dVGkpR z-CuJ7eE9U5&-wL}hH^{slR5_K@Z)+e=IQw}hSPMU_fxx5?m*$fcYgp2dZ+OU%Gg*3 zF{3C~dDrnWoi2;glBC++hNqik!W}|^AEAqHSy-}sM@ho{B6DBgM^f-?6HyaPT(y!O z?x#rmg&1zg87F>!!413$-edRJnfYWD$7*#MDgmOG*Xwfxe zr47_?2~LEu5pUiI&$0eGgv1I^(4sK8xD8IVlvIec5&~V9^h$xmCb*#cXN@Ht2=kuI zcsWJ881pb6U6AR^y@VDR;5PNN7oVX8<2hvkBd`{}(aUvd*kf$r;qcqx@{i~ajF8AN zzqb9D2aEcMI2-AsAesK+J;YGc$#A=`quP~g-H_Ma)Y_H=spK;4Fq(Dt zA!BJx2oG;HoJ2-6+A=C@0_>cHCnJ?4huWh{#&1g1jy=zTTMWD97<$n&=*`j-MpB(W zJZ;FGi}KTTSabmTNVOKcNtb^+IkE-l?&r;C6z%WlJa2a#i&Dkzf8*W#R(ATQclV2@ z_IGjg-4Po8Cd|A${q6n(4n6Wfcz)1e>#(^`BV!xR(fQ&xkD5U$ zpV{I}T*3PS=!@-YS5`Kfni!)hfzpgD+3i|5gH1v`e6Vv|rNo&9)+^P&gvf1Dbz}4} zrO13SsQw+a{CbM**HgSM8h}tnO=pHEeX(?J&S?MRUg9X1RJ1B$ z`C1ttOiG~kMH7*toVFm<#<5Vwz)iwgrj4nVHf~{JHy8EVny7#LlYr&`k7jBPaw-hBFwVxuq zt7-wT#(hFBzg3CTls6t%FkVo=-i?hsbbGkX{!!Fi(6>XVKQJdmfs^@Lzr)+{oRbvmtBgC)V;KF zOXLdw%RKL(ymo{{%9ZBehRcN%Ah@1ppnx73Lbd`1rt#ekR?X~jX>Xg$mm_$LVSc!O ze}&n8D>C}?75+0)LM!y|Z}9&sK2e(H~kDFs&>Lt2@4D#Uk| zL|r>WD+heGe>6hAb4l>OFYEoYy*m9LU;N69_}(UuC}EGk=lE_UqpNwJQ66?9K6grwsqLXK_=5_x=7s zv4Q{IH}Ds6@Auo^ZTtPM`%g>!t192G+rP^EHMaH3w*Rv#{}AzudET$jzsmf3RWkl( zRsL1xd#mYRWU~F^Cx4p!|F{*?J| zW_ll`{8ObrWxjK~yz2~#_HWktSD8%zZl+(4)4wGA-HHF_p8rR$e|*6IV?n>ElIibN z$@I^E{?`NkvntL5&6(Efs_N=KGpFvU zVg7ej{#TlSXgU9dCi`=fe>c(JHjm#``68VH9@F0~{<+n^llwP||7qkeGmrN&9SV3a zoc(2GQXJoi*yQjFAV)fl`PLT^NZYXEWYUHA6Mmn zRprZT0RKw!_s#P+nlJkKCz|whFXs50E?-{v@>in2+vjgYe`@ScP5ikw|AFWW>%ULX zA8me#|0j+ANt-M$hK9%TVjI8HWB+}^|4!~-tp3HE0e1c(3f{|%DB%5M|99%F&szG$ z?0;1763XEp&554w=Z^5F-M@sm`iov!pJ)0Xi2m!IM^E>%NPn9w*1v6ftpB{}vHrB3 zKQ;5)Wc`ik-<12uz`t1ilg2+x)}L~}*#3)z3V1I({Z;hem(qXq`GVH^7k&O*7JusV z1wQ{5qHO=XH?jTe-b7FLH=-{Ezt8+1ZT=rb|HGtSc={`s|Ge9={p)T=Pxn)R|A_v# z?T+nt>;I2FU#|ZDMW25o`oi#EMSpJde;1wY#enf%c>0Uze;CKV6J-6vCd>)tua96_0&hYy%zuOrg;=7@vfsq}Vp_7@7p|Pb4o)#Gc9UY(-J-rq=Ibf{< zVgNdrSz8I|IT(=%aWK%)Gtx29G1IZru`@AH(=n0K(UFq>77YIPUxnw}C40PI%6M6K zf_e^m@2yRK??Cr!$!jtKt|ysaehi;E|9|^D)A-pFf)4LF_v?5rWdK~hJm;U!ba>2w zUyuLI!2sBPo)0|=zUeW+4F48R)R(_lSO7I_fYh&= zU#*^d0@4uA^}p)a|3e#4`b^^we*ci@dE{q)e?LFB`6a_oJ|Uj-&uLb`@vH9F`4?Z$ z^}ouVNB@=nL%Ki4`}6xn?&sVe9Q|1iDEZ^_-0L5E{@LPJ%b({zDZbFue!la6Hhg-z z-+!zX9rYcaZ@Zr@hh7j6%kjValZus<`LFL5NOyHrQ=FQ-3c+XZF0Mfs2dxGF`or7; z+q`y_Yh@%9BDfEaz&sfQn27HK5fNW9ia~NLoxf{_sQd)S@`y(5(5%M!;?RMm#oU}{ zUD{pq5s%B!!Na$&Pfbf_>+G_z%~z>Y)@8M@QJ<@GUAPtpEYrR;HZ)RABO`dRiR@&9 zE#<52G>i!1AhnlS8JWoMzsI>dRSHdz(Kqr?(GQwhzHG60{3e8#-i-5Zl|I2MCFi=o zAZ{yfY^&bn9&%lLkTgnF8;h)sC{z^O(a^N$z%?3|JKpP^wX{H8*3{Sp)S!N zkT)eC7d7hb^2b+P3cbtO>U$FK`Qc?MVrZ*Q>4XjIxCCl@%%Zdo^B@vA-vs*irn4M5 zoq0J=u@v6SIUP98l0-#|zV&CX@5F+EWM5s!uoJ?`j&C_c`V{O0;eOe^6HKsb8cZPs zpRKiCBM*4ncwTrsE;xSB`Yz$AnAM7Op_r?KOR$3YH_iaEbl;rU1WKp5G86%dVjVG+ z$+=kWr`}lv0vkx^Wq5llh5^xbie$=tgroQ|6r|rr2aWa^(UsePC?YEu{HZv}fqRE? zLka0WvOMW1zVR0#OINb14PCQWJ9JrHz%8w6vLvy?E_Q_kv6@^2F$O)L>qu4cD zJ%{ZHA`09CuPRxn$?)1kNGj{jptxi~X(5Y@Q~D}*Zxn>hKo*2+I+1Z~k&QV*r(9go z)+e)g?h7vFbh|8}2`CAvX0c`=aWYYJ66UZ}X?FPvxe5jQPxTWP6I|vz7aSL$wI4LZ zsB=&hB|m-rls_>y!C=mQ0aNR1SD+$aQp7yLVUAdvVwe3zPP52z!f97~m)rd9hQvXh zlYApNYhU_l)}>s=gpN6GZRTlC6FF{Q(wIEH5>|eplf5lh2pw)-m+KH0_0c?0qj;>i zwKRjYTZirtZ$IwWu&;M2$2nON*G(hBYO*a7m?={!#l4KAQ{1c%^{M2slHnQGzSQk?-q2#` z8tV4B?-UDBy6)Buo$L=NGxnR5Wf-MBeBb|+w37sxPb==37cz!x_|^#iavNNOnME9{ zOhK5uSRVt!q8JkZ0E0;3zT;7wnVN-SSy$XTZYP`Nrf8V`PJ^o3edS*%STPsZYbuwQ zuozcZ-O3Ki?Iz%zlvyPk*l#wSnA*g6klBCZ#^}+5M+yByF7Awn(2bE>6^~;%6C=hJ z1nqwE101Nm=4n6mYwp4BY@6}+wmrx!X6eW9;A3@D{Cez*BV`WP^s5vpOD z-K)<&6jfhF`v>B^jv|rU|Pd3vCn8NF*}?MWAg&1 zLYayzUs>~VdoUEcd0QyttRqeZE_XrK&Ph(TbGayQVbx2nVBpluq*t-dB6!>KNxBII z@w9v2de=sW7C#EYi#TjQjcp_o9H-EjF1>BSiSIn(@6=a~zW}nVAhnZzlE=cqMn;iG zU6@eNoti*UmJRPRHr?yS+I6j6!asBNFeI3D7vK|kS9yoSUO+mrRlCwldg*YJsS??0 zhDLU@kH$U~fyOtEhExgi0Nz407>p2w(+y13ZRcIM(f{BrC@Oz!+u{A49#8M;+Xe|d zo`14)G+pal5?GCcnU}bZj!ZxiS4FarNX%yP`}wrM5hP{(&m`(;@X^AnWxWy=y)smR zaZq>MgE0-=lk+Rtw3)~1Z`{;N`(e*Vh;czgKN1L8ME7s$Ud{WxjpQwFcq*PiyzBBZ zJms2T!f=vAH)QAJL)idC)D?>aA^s4O8m3OnJBe2!`J-K+upJ&$jj*tLvghgBCAdBo zHXJ8HLXujw4HGS~@Z8^QbIKuy7%~spTGV!-AHn&%zY{Xc(>Ipw#D1IWp5uA7xohjK ziVkAto0Hq#j+|;K5jZ{?xarwbUdx`f20OWc>NyygEp(zaxu6?d5zz?gl;zZvit^xq zTjoX4F~^Ivri3pcyadk1+%OFZ>uS1hz~h$mAQax@Zxo#rXR-UJ75jdy17l1-q-b4W zpgpius>fHVyQV2zz>M;|;Bp5J`}$EPd6;UtRXjUFxZm$!)U!O4M z!j|P|u;`z2Z{ZI!vT3LsH7=vDAm4ozsTUg2>>1R3i0v-OMT69^;<`cpdWv#js}()~ zvTFEx%C|%SiR-e@-w3079}|0MY0mB~xs}Tz;)3XFD(c6The)rwA+A{uGn~z`*>6G+ zN6I4i4axAHkwppgdX*8bYbz{7e2Pcj=haAuK~QUEx^yS@9bd1eK-+LOoBiG{X&y13 znvi>_E%4g;!Y|-{qt)R+U;^1niCOc+)xteqqId(_$q(zQ0m|nFO3KUtRp}Jbv{`YD zYS7U$aja*Wzz zFcV2&-MOLXX94t2kif>xN7_unps0N`%0H6kb|q3j+?<_kxIp`Kpm49|zVFz|o+*8L zlJX8ecqAptLV@vUM_tRVtm*4s$B64IN#(uDdc@l-&8ebd@I#xD z8OVWEYR>ei`0kpC#H6XdR(+};@uccwp;^&p*ycFj9PE~y$gg*}5;8)u5o)8_Nc%I% zy`m@)y9pkZNpkiG3@;6Qh}xTOr+H^w4DKj8-`YcWwmI9txGN)&c8GSzIW14cB6u=l z|L7@W9Fbf4PBNQUd+wa$(_!NyZ1)n9%WG)0{g)|*S z9Vp?5dRHf@z4HM?R(^I|IT)o`UItj%PTdz&SG>kqC!*q@-7Z8*<$dN$^o*OOYTU_1H5~-+_VjFrN zZotRf7$7yuehk-tQzc;VUS9!=$d5!-aanOw+vSytul=;lFg52!*eh9I;lX}ccP+Og z${W}ZAjj<^8?q_ap%FAkft-H1l>1fKyO&rncffF&{6}69B)RotkTxV=uEh4}OL9)R z0~sG%q|f>lRf1h|_I2T8q0-_U_Qr!_%_oH8W=}2V63$d{zsXQ!0c$C2g;iCb5Tsi^KCfbOYSwCyK6DUM_y@33 zj%r3lKPC#j-4%xjof1j8JS;q4DuL1OUB14c)eIM4WNtG7jL}i{6wvSLFZn$s6YAcP!|JEsLBgCCS^e%R6HqtA6@${;(u& zo!zEBj4l%~OR?kVssTB#F9(t;=?$@wI;Q-wt+sjJy17Y($T0oeR+MY*Qb!$~4qLQ* zs(h-xG>u#vK4^;|?i_MGdPQ=OziATEH?w;?8yA~viFQXe*!JCwEMsAH!v&fGkz`+A z5PE@J4joKLP_cmsR_vNvWE>&}+}4U!*Xw8~9qVbE#e><&qjggRE+D4n+^>H8k4#!r z%u(ySVXv6Df*UAYTeyX{GEZZ$^yp_r+sk5O???&|zJA)dDe_kNQe6K%Ogv!3`de(oZHJmzBKIY}~OAXqE`1J+&0l0>|>hE++53 zK(g*Ya2UR4gJz{p47%|b?DiIkA$!ubT`w@^+>SGiYkfQ#e=I_^jxKZQ!*vgOP#dU~ z9};h1ehLqjz9FK>nAt3t@d!ekPwJ9iV`qyQgnx%ydn}*I9-_Dkjj?I^V@Sk~CM2xD zALBYiZ)=py`rf~lfT(5?15ax5C}(DzwHHrgcj5%4T1XG*27Y*NBUD4xuC) zm}d&8A$-%J9({38tIdIQDo|iP5a(aLV*D0|;`#vpb*83g;E>?HuIIq;NtU!CUFeX5 zXg$~4rfdy|3v;;5i$QI=VZHP&cyCMeNgx&6nhBE~|MUnJK8l;Reo<|-{#7zwBR*Q_ z5tq|sp%MNv`EtP=##df;4xez5wzjuxS3bB{rC?Swyhyi*KvXWX*Pc({1t#z6Zn36x zY{WGd!eng4F4h#|#iA*oumN$-ZwF3G-CSOoguOMVt##4~jLOoT!=7<4v{7FZhy~ja zkY~5ml&D(Kh5x9pmU%mXYGKE$l^61TTCEW@t_Wzb!S3A_5ZpN@{$(4)E1XSm9keaRqrHtcv zEnU9?YyoRO8W_yCgf6>C zc(4Hmb~oGb74Gj;ptWPRard0!HN&3g&eWV z?y;Cp@+7dLBHtGt7lomY_jP{H7d=Z$Fvsd2V5Ws^_%^*0ph{d7*h79NtFP-OFjKu@4mVX3KFh zuc$po)gEh!1mGY=Cu5`_MQ%l$ z5xW50GMqa}K&xSAk15Qj#)+=>$4d987VoS`g*m+=@58{2RSO_X#Wr(SQ?O&08ht#X z8Qy+eNXeDt+j79j#sshGBJ=aDxzQD`1o4bZ$<#_u*h|(jDkXyXR7TFzKU!O~1F7EG zdr&f`BJt7YZAQC{beR}!5Q6BZFUc}nvD7K%w+^Yy-z@NFITwejbUMmK`nyyiOTTyb zD9i`DYzu9q#O7RuWh!UU^Q4GYAhyo8hvdpZ4jU#Een5aS6Ys@P=+!57;R&5gLMN?L zQVV5c4yzX`?yxk!C6YfAy(c|KxQt(xW};$5OUy&O(kabL+BB71!4ZVONR85`eaioK z>ySZ+inIVgfOB1v*uj(T(|2@rlI1?s;t+|329!eHvHCbR1xB{-y}9_Fvm&7Bsw_Qj z+b>GApX0xF6!|2brAIqn+at_Jfv%&#s-o0=*U!zv;irp0iyBCh=-ktlI7)47UveJC zfps1gMkaQBCsT8Y(~`a)F2ZksYAbh+*ic4=uXY(_QrJ5mu(G^D_CU(O~1zkJ%9srLGeq)y47ZW}nhDWZGFWI`-PQH&Pbv;jBI_vyY># zlop06I0lJ=VzuN$QAK$vd&@=#L<+1+CpOIKrRsY>W+<u|VYRD|O zN@0_Box?mI(r4ef=!P;f zv$kU1T@N*11;OsGby2rNBaMb`%i!FRq*QxM;f78F;n;j4Uls6hHrL!V0@X$-&|+p1 z{u=0ft9ggKB>&AOa z$W59XZ&Zn1r^2!9#IY1IViGIl3#rY z6yd?_ljz{y+h$`Z??}-HytT74<|gk%qsI0O0lg0JGCBz5?ru`FaREXHTe!DX`Qo0o zGh=_ltIa0XOde!=Z?N;ycRbuhVK^tZ3_!PZ%~%2@}x3@m`JS4n8vd(Bh#oGjZE!z4-z< zPBiPU8Re4g#8|w-rEt3puaE@r2P7I%(Imj%FsvbdQ!K@1VLB*k_bWUK5A_mGn-SD+ znpVuhUr|jp7@`60p3M>RMxPw1oXJ}1yXktDzceUIzPZbSZl+F)L>Z}6gcNG7Y@jIZ zsF+(!;@imA3V&eWgjmzEYU&+v`Ppl=MvFB;YYRnom6LZa)nE|tcuHyx2*KJJQ|WN< zWH&nWEE2V8>pO{0p%tSj#0d8xvcc?=B^+TS+D$<^F(F>37@ALSsYv&?-*0eZY@~Hv z>l1Kg57i*=c^Iu#G3^icOn(&Wm{Q-V+b3kt1K+a|Drd6$-e^B=&tS)3$A|?9T`wYL z5E~aEu22gqtQPQCua^K+cp^|EJ2qi+mP;up9S}LmB?$w*EKzH)BcZLt$Izz z<^-ofNs2%~+&XCX7G8d<>C|OYUKMc%w;QOVUNXB4o_mQ)BbdCPYvhq0;%u5YQ^zosseFGZqr3%aJreLPhdCYTsCy;f|*T2 zK4y(@G%`5vOkmME1}`eET@QdW4xjL#3)AG@GZ0wvThWtR8pL#o23CVRHcwJMs8hLb zm`P;E@gJP`uKmcjY=xQ%Y^H3t!_aaBUz{(d3WGc)w4}K94O-FDqmwyx+f? z^B&PGFU2X&=b9#2C|>8t*ifi~IEzWcq0)CTx{PwAq3r8+4U>Um8ShM-A0qy zquH0>5?IJ)BW#T-`%`c_4)I7nJCK#wX4lv}8n+SeL56<7W*E|?99(u-X!V$~ef)5a zGF#1*4|j`xsma|89@keaHHEIAKanl22L~F{Y5T=Mx=MA0kYN4J8AsO)e1XOjbk)ML z$(_h=Iz?a7O5TZ_&Jpodw4|T2`7R8NpF-LBmw6CMt#@)z3mi7Z{2H%>&4>dTEJH@2 zq{?cWs;DPX2p~UzB}74H9iZnXgia3OdF{Xd8|zbAJ5htKvoFhNvw%)v;sx zg^zY%KuTt?PvWg8A)4L!P539S0y>hYtQ!p2ib00yakurVBe73;gymY`df`v>0ZB|C z-v@Sg0e2D@3vWo^Y3U)QJ6+j@%wsIz)fg;-z56gDpm&g4=bvoW4bVR-d^tGmmmNc)53gMx0&9sm&#`Dh%T>TGQIZnaIX! zG&~KZ)D+n0M5Ai2`h_;O@x7!aGY2Y7Tcg@;&Qs%bzUFI>C{B(5e37;V!sV_hh40ge z3#ql-OfB~@Fry+?LqAIqz8|c_;DZj75^T`pp-C7J78a2Vd=n~`q^ZB#V^lgVDd=pH z3MFViqBKw0OTSsLS%B1mnuo*(lsqs=!}NL~hDn>2j(JN4ifkB7ixi5 z5)P`tWTc9)@mZqK$7?4#zs~pOLnJv^qe!EJas?Lb$IuysZ30aU_m%j}OzrZ1n;K@q z3g6U0-;k8dT*7h7g4p*lZlbkqgPj!ZWY3RC%qGcSGSJ8Pp0!b}`h8v(LeDcnXH-~f zl}3=t15WepJQKx~zm26*xCW$% z*bx1CiL~K1aR3924Eij_0&OEG>2Rj7eGkZaLC3s?f|g`cM*}}2XLU;VH$UT$wKJ&2 zE+K8-To!zynJ~OirQqV3sW&S3gy}w+h)Q5#R+?o=VE*C(b$0iT4DM2ERwG?H_>AM) zEVAK+xj%f<1@3`$s7+CG%yaRhcXEk$s)FeY~&I!UE`Ywd42Hm@e zT1vZ@6f=mK`%h3AsF;)Rq0o_c`3j)dFgs-&=tqA(^>+SX(A#|CY3sWZ!0WPecZV6u z>%#35zWcNQbO?R6tgZuor+T7uzM?+MGt_lhjW3%f*HCPDSpSsDQGZk4t(XdV7ACz} zq==ggApr?dAR}1M_=w5w@f7fPQ2O6sB_aR>I0Wrqyww1(nzgc(nSr&T5dfL-6B4Cr zX6RrFfRw)=9ssx&5i>h`2SHOkJ3M*_S}DC>X;uKvLqN~o=$S07sDPN1ybz^~nWes? zy@Iu+j5WIywStj}BcMB=UdYJaz|PFZ!5Tn=?hlX@00IA}H~n{9%?tkGuYCaU4m}$& zBQq0I2LO4(7oiIC48>^Blma6#821?pw$Z$S_=B_O6x(wRp!8Sma~jYS;+dD1UO(%eIr$9;@*h|R{WA~0kV$_r^#2K# z!9ou(XTUW6e3_`rY`Tl9mZIw7RfO1~e7wr4Wwv>&25PB_rG-VUm17ZQXyd1SqUcxP zL_om)MElE8+@<{Bv9J0_f`M~T_9o>yX=*i08l(@+cz5@hcx25k+7XU37%Y^7dRea9Jmr10KUh2sa6PhE?i(NENLO5w6DWP( zZM-K6%%oZ^3^#DuA=BCHlEsovj6U*WerRad=5S?iJvPAN4A7hJlFAyECmsfqU8_Ft zZIZ%`(>>Oo7o{iY(pI8qAa*0daC1DoXZ3Kln&Y;(+-EPTvF+thHjL+g+|3aVTi5G7 zT~b*uL3UHl6XEgm5>x6hUDHR#XxF-N3J|agR_IA6Mho!xf%5d>B5kVAbINLwT(@L| z%psfJ?#aIrO}Wk^jzTMYl+w62K_i{Zcs-0ut0Y7YT}dOttNb3jnM5c z_g*f6auW`>JLEMuenL%v-|ZoH7GSoMz`Y@ zYm9Qnz?kM5(3jFZV4`EBV}e3wO$V8hFhF6w za=^*>ZFSsC=f3eJ9ngS|F>bXI-WFLw^S)(-1}PpsA+x>((4E^6Gpo}?xi zr!vx?_Jlbzmaz3bKqua1VC|HSK3)WMmfQ zy1rtddJ4qL{y;Vq6yp4A96qZZHN}C(!n>grR zZq8;$4$>v0v}PYYa_s#3Q7i~wPtybfn=mEVE(u4Aj+5zGHNH@`X7jBh0^H@VRjep$ z=nQN|yQ2<79E!!?VexyDrXr`XefqZ_H?ImLJ@tfJBhADr$9yt7t?o-;X!l#kdnK=l zd!z0>-mhIVTUS5!_XwR{-nwdTUc)(S@fB3X2Dxx#I3YKN5W|X3+Y8}$L3m82L-gHa zX9f@xcn#prA5%Rd1!;D0tF6i$hU$`dyT&^bG_nqESsc_`R^nK~!YtA-^Jytxk48^U z@4E2CoHTsWPRjY#6?UAAdmP5#^7%xOz+7Ib3yGEjeu9a08%H-;9Z9y(^XTWPp~ZoiUOiRwmMZ z3ezcis#i^NUnd19mU3)QVRno+FvuqVTwgt;tfrt25PYP4YL%RT$LpBd%G8G~d3#=a zwZUTO_UwaAUGhFI$L6CL)u$;Awv%90MjTlYy+{mvLY`^A+g)vss5xV%p+&=6m21yf__AMr8=f2Iu=9xGT2aD=3#B z89|Vro~ElFAQ}K@o4vs>&-O z@gGoc@|PONoAhq5pge}3Y+oHk|}8dWTy zq6;7ws?js(MGg8<=nL{q4XHZ@4+pmC&RbMWifs5|%ktZ+gYITq-#Sk-WdN!(hn<^( z7r@WhX$;JgLC|Ss!X3=kqnOIspH(yja3Tgs{CV^8sYUs+2as%tl z$^7p)OooPfQN5oT5XC1rJd*NJBEE$!7>$^4!T&&TR5H>v5RF9(pLLgMCEebtN9~;( z8(imcR-%%B@^B(WzpztlU0sg%Yi9WN?wsEJ!nTNLQ^lf(k|DWxGS=i2j(Nt#%|-fxfZa~d z{v#W8pE^VfJy8g2a>Rj{gQ#4(G&l@7(UVN7$Y8bkx_)u?% z1_f#DH?6KyutnKm+$nk$eh&1lJO0XH%K$GbJO~0LxVogSeUfnwq$Oh(!ckfhUNYnV zQGd9N!(cAUIqef-McZqpeo%W`R#BY2jw}0pmFbXz&+bg%dwFSiH8Kl`9{49b%eG*Y zrf)je@(WGH+>yCML4Q2qjL~6?p&MeT^m&0&+3D;FsD1x_&{y2Zf-%LB%6D|NhLW^x z%~U#bEzSB3=_!VgoN8ZMT$5bwW~8&6LbfcBF}UzcrsKpS89&XbT=!z1ZJxj@f)ygn zAlQm|1eI^2Ra4clDchmTCCwyfsZbOfn5d0oi3)=G%Sf{=9<9t|P9c??!X1ZE>|kOt znlZvx5BvH_NoW@D-l17$eY=!_Pq?X$Y))6S&ao{-Hg}qP7cHse503(V`>j=XdD$uA zq5RcjSmXoMaEu5xn?vLUfn7C+ z;Z_*rH|es+lCt%zJ#|f9*-*il=ikLYij?Z4A|WDU7tCigL5&#usCqy_I$IRCP!weG z?o4CW2YDIf=Yd=%mr*iCcj$I68F71SbL;QYlHM2tpe8o-Ppnp-;sXxM67~FA9I7NK z$0%0_JFE+AtLAu7_Q~|j;)3z-ZqS?+iV?j(YFnW66dLJ;&3p#@sW8(?L%}@RhTT!3 zuElU(=8kBTz%Ua-+v>`_v!Qw+5zZFCkSw&@0mEj>(F_f3rZ#OXp-Jvf)Z0lzDO-*h zZBiM_<8?Ozer22?lZskW!dsdpA+$HmsqPq3i4h~Y&xF(SNBQ{bV8>^s6_RAN3JmVE-KP567FjX)05 zz6U<^x@46f+|!Y?HZBVM?(#?3!y0bhqN0@HoA()$5*)~4w`6CZEfn;iF>+we7)cL? zhy2bxO60z_*i}hVF!Ze$5Y4m~Mp&__{kRm?q)Y$&E>0NUdW5v7TBTi#9aG$%3d#`k z#ICow?Hy_o)aKZ^IYMw_6YW%eahkShs(E8Jtls1m#mqI*gN#fBxC(S`g_Nu=McwI~ zHwgTZnZ7OCO*1D9vg9R{<$B9jR?W1Il7@!7<|^=c7NcP?6iX^W4&s`kl6pU^oJeMF zq-S>L_VI3h_)x*?R?ViEDLXcn#KF+v0jX?POKLz|q~7L-+R=Q7)Y-Tt4Us0p>!F3Zxlof9BxGE9VQu|Mcrw@ z=F)BMDY$%?6{am`UY1oB?)>>WW!|UNuj4f~{MH)ZRrXP*E78b9@HO5g8e2dnwMhFu z)<+4<3l*Puiu7v$L>)y)&^&{f*k7z?Yq6%p%V@v947d@NX_~STLNcqNRfn(sx;BzK zO*vy{)~7!R$DK8#D&{HfOac(ZE+vW%n)AB0OoxW+wYxrfif^Hq)oImK-T8S_Q`2kq z<+wy;9m;m*{mjHn!i)~jn+#+S!qwFCZl|6Te6;(>t69HQc>;CLCuunaPIMEq|E;I9lSuvigFa$f zgOSb7davwWKx;wm>G)E&MS9MhL%c??NyCa*+qt&eNm2MI6qu->Z1FU&4jZx))dkh{ zyUZZj?Ka_teR|utgV#o(48WF{o|WD5lCTk~8j~?wAxuu~T_bgg<4o3okQrw@)C8zr zqY*HR1TyFtnJA#9ZIKnn>zSGrFg@mN8S3WLy{|ru_%;VYrGJoN;fT^zcfNIGaNP_u z#E9`)3(HJc@PnjII)o~5$Ite`b@!o=^4yU`P865A_DSJXKA@;qaO&J#Xaz+{DOn*} zwT?68cIPhS3UhM$90SdctcfWW!fqb(Q7TD%wr3r1FA|gC_ht66n(XK`%;#}Ms!bxn z9A=;qnuWIx$s4IOy0NwVVc$f2KrF1*sMB5e!-6w?NNrZ!4PpiHfSH02IAb*#=j^Nr zv)^(Dds zX1{aybc})9uj92;2n)fUTH%haan=tD1ph!t7L58qE#oAeoe#kybbYJZ3|UF)zUWoA zCTEl=3{mf@KC^>fphcONn=In#UfBP`b>^uuqZAV;`8vKSvS>y=Hpdf*!zo&rJ|iN=+&=reW_6_xQB@s z*xPSa%^KT9?ZS2}-m?L1WzE?s&4njIAFLALYA#tz$-g}ezVhU*%vJ@xFiIGN7Gp@e zNgZCk-9xh9!XUgllH|EOZfqFxn(6TjnsW51VHG{(oVW4ko5cn;>t`q;5j3LmH#P<_ zlKX1Jscsa~36l=SsYXUq@`;Rhe!0~A)r2jbRb%*iWfoImamHdeQp!O*cio5Pmc4s| z9U3{3gGGs;CzQ~e;xn3ztqY(G(JfhY?$^S{+3i`)0tNo~W5WV!D#lp}5`7Mz<%tt9 zwsU&F20n43A|NAUOcWd*SX%EL$UFM?m{yA0Kt6rdi%HIAD1_-RMKJ{3={(v{Q8$$s zx2o$ml*1e}LRKInr=TqR^ohFMAHsoY2)%4#hv0!Wz>}sKd@D6|c%pW;VVhpTTUQQ5x8Fuc>~QgrPT2hOLHAz1q*t7`=deuQPHW0k}7K6BtI*4 zkaHk6_Kt^J716!;(6SAG@4>|JzC^!bd)ef&)U8wEyEVpzM{Zh`Tj1nB&x~W1fLU!JfwAR<{o%OED5vbHB%XFh> zG{EK7Zp!P9D9!tlv7i;d`e6^Or6*%?$@DOv+u^)W)-)l$%tffbmRATv{|iBH-giEj zzCMeRV(cKyVwl$$Hdfh=cj{$NEGZaF&;>M1rNN3v-@}%+3ctG5D!y6DE1&nrZ65H^ zHSPk1jQu#O7Ze9gRah;>x{8}Toj-SV-Z2640oK)OQHjG|`o@q2rS~>F_fm+pfsRAF zC|4Tdrqe^LnZD>^^2cGpwx>WGnoOxw&=e}t3dtmxvDJ?-_s^7rHFr>ol%DEXd&9ZN(ijO4^wIJ~mC3I)a>agz7S2@r+iDxUg}fPNK~&bG zyyRR)A+LZKcuWJ+g6tD2@eauHy~f<`Twj;@7H$=CuQWbuc~j@|l+YA*iMsdCLi}(@E2~eo z8sC}e`nbAZa53#{TKZKnoOHQ_H>TteTAwQ_Q)kYsnmO@0eBPBh2NWY+%UoQ=R)zSa zQ{)J@N>$r0_j7(nw|L_A%<1bduZ2f!S`(p3=m0kkxz*LuB8vJ>>Q-htw&%UqI1pOO zinEt#8xi&S?2&3*F(57$@wU6+H3vsT`DAD0nn@5}_sxvny>(yfEmsT>Hv01Ulw*)z z+f2l-;X4>gWu8$t7-x0BoC1PdOv@464}DnH#bfUPJYGV9Jk>a#mdAg%Hhq0SPR%oE9&=Qi*IFBlxmQ`+hJ->E96X?15j-=Y(*T5?acKZDrfIm z@FLI(PZ<|5gVb2Uq#Ui08gZB>^>2XmaZWELPY@;9H&bH^rssHd_{qAgg@zp5&{v7j5$=_K0PoKXy+gJe( zvtQ1(=k$M^ZFB&i+CMtm=$Qb1w}11tF#@9D{NZh5q5G@1?ZtKT>}>qyZToj2fAhAz z#IpJ&%zyjbEhGJ3U+$+J(`MyI2Nih4B^;Sv5aO>eD-KrlhJxO5ucihT4q+TW0xsaZ zbqQp6#4NXtGMJKNZWhI(>WS^}R&-6e-UxO}t2RnL+g97$+D ztR7G2E28oxbDi{zdPEKIl54J}7Of%CMEEz_bQvbEiR!zhJGXkmCq&fmE6`^Y;(of;)q9SC zQ^J(nM&KZ>P;qPWo{}OlXc>*+_pWp{L0$Kiit{ss3>xcOzAi#4OE5P&m*Si1Y zm|h}4F*DFZFuj;6zybLZir`lZW!j~vgzuNrE`M0OJ|E0xmRR32k zep38{=l@lY|7nDOyPR8ZsRG6n}hYV}hg)cm&5_S*vY&z8(I^-_>E*wMr~IzbxWv zYVI{~?|aQ^J32OAvhGx7E`(Tqz1w;`W4Q5La$mYy^zc3tBOvm}6F<$qR$UuUEF6$t zQznV%D-iEzC3!QX3RVrS2SYvpP3XUkhtHuF3`=~}<}$0# zC|M^jkf&5+9Jw{YGWmTR!C?0knfFJJNy+sq+HMIt%Snk0jOtk{!@O%sPWUf);8+`f?kRO$roY5zVT;=?2mbx-+?EX-x8IU9C1(r=SI=7T)Ji4rQO!pl+`8 z2d|nQ`-e}l3`V-{Id-4cknaiD0JxgOnbuKp5dOs$tym$9s=yIA4Thk~==ycIlL(M~ zJjz~*6v10AAk4YAc_4~d*(8hb(Y&G`)YW6Nctk!FyXNKM()(C2YZrFv{kK@&u@ z!LJ^$%JK$muBGw^~bCfk9tQiQ~Z5iNTT_-=?u4BDU4N z=fJs?>o+ewh>Ti#?QFSZ72cG@<8!n;xhmU9Cwocbd2pM$d$xE9$=pK-qiKX%(ww+^ zJz(x>!>IF+N_g@8hTGo&uz7FoVyhlQiym zKSS7({xwuQ5?H(1j16)H?1ZOtCU3|^E!fzEq>FMxx1-_?sz2uyqA1U8m}2S~(CFqV zB+Z!nYsJ^e4e;Td{m3rn{Znip$7>&O!y1YEFh{l+w##feW*O3BV9L8d&1?8b0+BmI zk%A@Qa=&>X$WjV38dYY`Y8l}yV5o2S&F<>0Cm5}$L!2$nZ&F*{o;3B_ys_CH2?(n- z&C;?R*S)Qxd3aO z;Sk(|y9Rf6cL{F6-Ccr9a0_n1-66PJ@Ze5xcXyX>lfLOrpUye=p7;5F6eYW=_Nrp9 zx#k>m%&|@jo3dagHpMoE^`ryxze{}I0Q%Y{=zRB@%1wft_ql&Ar$O$OtVSonZC#V_ zNQVc8Hc+1NE0U&RjT6G#+_Ekq;Y-gMU^s`R+4&D^UGK zyWh#5=(?+~a!yw|!Hhx}qF8bcb~{efb?VSif^af4TH^G>+0-54nVm2#nbx)8$3Bi8eu!YH{myP4K^R{2KEZgvTVrOSzNY4Y&yewE#qP1LNm{J3 zp61C{BCy#mX4Zm+2_*-_Pj(^Vez{w-g~;lZR>_1Hmtbvm?4A>^^r-_qjs$HW+%-ZgJcgd);G%?9pK`lJ{okRnJEM)XPn@PSwRh-c z%8seKmT%}BMb4cgasijc5pC{DIM1U}8t@JCjVWEvrl!(`4{yU&T6{6{N1Q&IY(fgv z8k92>+o;Wpu5C_>hF@XQuxwi39Ch50U0>nZh{{zlwq`}<%~yXU3W6t;yPaKkibbN^ z+voTmN0-D1v@>k%R3YC;rZBzadTZ$cT}7EIk|bYfat}snHR34j+&d6He_ww5nG1pT z^gCt0S?!eKtGSFZLt*dQDIR6NjbipMGZ5@wnfC7;N@{c@`M*dT$^@{kCcEbmEOI0Zhe06^Bu*0>UY>~{~O)Rrxb6jr( zHu=#~CrRuFAh$;_z7hH4kEH|4Eq$h#{`xkyCTk=5hq+(+;rLW~)SBi??pZ}l`RbUL z$_ull2G6Y}YM_+HYoPfcW8*@T6LwWQDY zC@~H7o0c=KlndB2O!n9s`Z83gJX~ z4p*tPbRVvoisdwI>I)e2J;C`>FA`76(DK*bv?@TY(6=6te055yh$H-e7}CXf&Gx}bYoha3xXBO)a>8?J+=|CqzOhw~bgT3k< zqewKwCw3H0qsYT37+q<&HEiUU(*pb5?OChVGG;s?vur}<4V#EW8;0M(PIA#aYM_0# z2&{|rtLSu1TU$rp3E>^^*4xpST=I1C#5T+KL{!=)j~O zQGWHu<}c7b5)b#B0AS%;`e5{f`)p#YQJr4z_aMoL;-KuF_A4`C ztE*#RuyOtY_QM(UnB&#uB@@%DVCSbuqZ@+G8^QS9KomHL}xQhTR_$S zZiGy3)Mi?duDY5@#b!{7y8oT@pu&k1RiD_96cv!29kS1P45NZ1#U(PfJz$5ABLu}q zK2#yJUtR$}++lcxnv7bUTK;56Mx44Ic&^)^+XT8gA>BKH|CIq{jNOu1>+`3qUc<&V z2A+rh2kwoJJ0WY`E-u}GB{Wo}-Msh+fRXBL5$BQPZ)1GbVZ!JoZx$_^T=WCs28bma7x>jpU>k=iubLKkJbRTh)K#y z#A!Jv*q-f10_~|<`^Igy+LUp|lT=z?yZb|;Tb~dvE<5cx`yE$`opO(kPATo{SLgC+ zN5A=r{MJ1DC!mV{hYaE`M(igo`cI&W`Bx*x0^o@M2~tkURv4(lP(5C41>QzXDW$f4E<4*bm|IADGA=1nU1^Z~?%V11Qjcqkz9q zqW>U)|Lz<9pjH3%$qQ}!$MTC3AYlJb0{F}Me`w>q(5_#o*e}%X7pnEkRX^81so6jG zUz8hPu$Y%?{^z@XAQ->Uvwu*vU+(;3kA5EiX`g-`f4Se!&wj3d(7plGZ@{@fv;tqw zeQDFn`egxp{+DI@fe8IX0{<(^#=_3b`ZrW0)!9i={rmWF6yzG4t#}C;Pop?dZo_xB zZsH;CqxyAJEZ?sTuR#PLP$uui1pEmj`9ALI0QZ0*T_YyU*otG%i(93nEf6gyoTW6u z&o&>oQoA2Z9l0Kt)xF;@@f}X#W^7Bm9U5Gfh3De4Wy4;b%O$t|qQ+~R%jA|XUqQm^ zW_VPx8S`C?Ax;uX-q1D} zR0|xv8Aj4IItvlk(@!I?OQfglgswqeCMNV`TTXH9O^6_|-RqS76zxDRI*zN|>2t)Sk>WPxBRl{D%;^3Q}?lu<#@ zj^bSy@`*xRUP@%<$ci`7;jwxGFN9Bj1L|-wd4F_nlju`C-SU6qCv3Y)Wo|>SfWpv}fJ3pdLt22kk3~ z_37JMfknL=ky7YsxxKFPQ8Wz~(7-3B2-=?|N642%u~RKd+94M0JJ0ncAwwBY8RV^& zLEM&PP&l73MC@K^uvL6Ik$E63Q`odibUj&I;4k#rPe3Ijs{BOm)wS|WOL1K#_HLYv zS@a!)c(Vq!46&+ND_ffMc=faT$1FC%K-qP+n1I2&EjZ059jKZ_2^3jH7Uo#jNKEOl z3=#PV1sR1A*%A2>IsJl)Nj5VsX7401sk}T{g+kLwhdmcFu*=t%gqMhy3;>xv!J+Ie z1?U3*NkTLFOOhHtH3{nMcm>LWxJe3%L^Y|>%xU@kg3C!Tv$t^qmV}sfvQ=xr?0zxd zR0nNs8`+O-cyP|T-gtD}_^klL^Om#Pimag=p;}qW3yjC-(C!*EI_>NW9&?+x?<59J zb|MB^qF*hZV04y+z30xd-+1Z-gPnbZpslMHw_gR$Z=jy!_2bwjV4HAx&%2ftkxoyKE@E=Oa4j^V?a%YaYTmSRm9vqjrNoZ{SEztPJi^I@mV~U%Gdo9wQj5rp%hMv zeH;m+&s;!#WyIAhthYP5LO5P^XtqgZiW)x2Hq&QTr!GTEn%nAlXtRkeRmDb~@4s@9 zdz!|u8Jjxp^&4J5@NS(SU*WI=8}Fn&)Go41#A!ezeXI~sP&%ml2)O}z7S^F87levjun-z{Bzkmaj9G2JCqXiJpT(9s1!llYZ21Fywee8!K zSEcTrMy#>;kSn94Yt8etqLxuXueKGCEoj?@c(*YvLvM{y_OntbE;}9KY%R;0Qs%K{ z^KW5a&S*RNMF;KpCdzT9Cq5@NfkcQYDKkT6X009GMRc}!-<{YdIjssJZ-VbpyuSB- zs+Z(Y0Wn9OcOuIvqMqL6i`YpoIx_Uy+tA>LC%On#g=~Yi6sOuyt0qZ?qS84*y<4V` zfi{S8k6pWT#v1O8LGUMMQoW#bcfZ+pOOi0U`!qFM6~xz3sUAf8`eJn6SiO03@ z7RnvE_j`hF2w6XRm!BY=Ze6w?$i@5Tw-2E#Ynds|1?5}Mvx3x6M46c<*R}J;p3SzX zus}i+CL~)+ouPj9VWIKFNC`zg+%~A;yYncbjLGqxlphNfAHJ@2_Z1r%^8#PgW}S&3 z_&t6YJ9pqB#5q`m3&(;)x)Z(N?Zzuda6dL@opYR>@||Ngr<$&JtR>ndbQQ;%YowyJ z4wQ(@RJCvg-l++x5P_58$-h9?6z?{x ztm~V?3+@>=Rof$=b1E9Gd_TE43Pqr;lyO8TPpA2X!wKggFr#Tw&Jc2sA5<-&og{QF zQC+O;s*QPZx2LQgr0XMJ34_fmkexW`M<|4uuSe5OmMe}}YsweK1x+(gEh$JQ5PO2m zkdNe#NH>j$VFLR7z}}EBJcc$32BIdU!44!^fpvNf5U6!j2lIAZo4~hdC&bO#_V=T5 z)gi$t!HOC*nQ!Ywk`-6snj|thG3dQ9V{0`wH8$PzyLDtKhy&`ri9fioj+sO=zKtMU z5_NLBr(x0b9%n4O;JAd*H z%*kFRGfb%$%X~Nig0NmLnF)O{q=^?fj%LwBTB;^71>ipE#(WMM&(cN&l#Ap$?k#s#5 zdN`)<02Nx|Af9BWAUoqZ0X~iHE>R5T`r2C`R&95}YCbU6^tzf`KlYOVZXf*gM$Q(I zW3~+;91DxL=`?-!>G`!EEK#apsFJtl`KIc8oR4NwYAxDFPi|hJJ<^@!^)if$eV*E! zNb9BRwr8*2k<`v^ZP?G#6?sC(X>h3UOqz*8snZXQcbmp#;U_`Y04t{Wg1RsQ%Qd*-FdY@7J!yB3U30hR@G$x{ z^b-iL89mJOLN`m@%IlyY+XoM4t&;`pX?OTg=E5>IiH|Mw-z5F!b{Vr z2p_6ZB2+nC7AYym(Oy5E)j|g$wl9Zgo^H3Xo%i`4!GCOBPHt=(T~dbIe_{p-BOr2_ zRx=IYLaY;bRKIEWR(aL|Rv|KVDO?11%j{5Bo_0YjHO90E`vQET;!NvWaQI$jz|=YL zX*De729n^)X3S^mfzML7Jh5E3j$C=6fMz71w7gnp{)#J+WU^Be;7ZhqayH%~bFr ztSAx*9E;q{dlZ?B1(Sd4UI=$obgXr%Ry+>Wx@&6aJ=KQ5Ry*QPUe+{%odpJ?^J)K5 z-hZ4R%s>v!==~i-Tn(f0E)%%leRbT!IMT1dLiFwFp%7DeDCLYbWYVe*=V&@^TbrrCHf1+WnDEA!X6MA*#P8OiW6695K=1Rt7$33hiLrBOaTdIkW-G3rWB)&f8Vi~!` z7#qEWbfpw~BuqFxoU+xroYv-8p3uNFcCWed>i!yiJE08e4)~dB(9t-txI^9u8r2uK z+GWJDy^P}mE)1X|t(cG(n^*Rp_U$E|{m}e(;qp3ISTA_f7Jlo|^|BV+!e-1I@ZAS) zb(dyR%oMdiBVesw1AU1$nDL$9Wg3BOKNBW**LAw26Y@Qy#xZ^3r_i`lKiS?pJVKZX ze5-E~)OFvrEPV*cDCR2MV3&ebjUb!)rNmHPzn)Q7btM1NpC`qkf5~Bf`ZgU_C=ru} zGq!syPfWN))P}cnZSwlv!&e9D>w?k_i5qEaMr89-duOg+}w%Y#jzUN7CQTDg89MaVqM zC!U+M6EE7qIh8X5{f4~a^Cd~DKpFCFWqcvZIH9*RLWokP6?OOP-5>vcdJscr}kfiQ);<1-;$= z!bPChgDd3D7@nTG*TYW2-&bXO6Lxf`ilw>9Otd7V{WB9wL}8g(+cI5rxxiaSmiLPk zzS20mAbHx1Y4~dt^#Qr6@DCs$r0hLij&`TndmM5PJ9A^~&jv==z2B+=VaoAhdd5-t z3MoOy3Cof@uvgi5NJHtHj&4KD5e;Q!oK7G%EOI_}v7a2#LaqUUSq_V@=;oyhRiU< ze${U4FqwX3Ss5E2no)@pw!A9!Sj+-KSWZrR#EFct`aK*d`B=aDG$DGJLA{~&*I`D z2nJKGU5tkw#lkGpwl_T70Xvl6lhqr|k~DoGE-E9Y?dMwggjEnnkAphX)2Sv9>!%GI z(g-0BN}+046X;9?4z24}?C*3O*GV3z(!z~bA**CcTi!MU)xkHPR`WrNxb(+>3h#nRcg!}fk_R_S*mq(QBYug*c3@U~=l}Unn zwz#} z?f&i3b2)<}mlyGONXIf_{IVrYlHge0y9WKB4!<9zBmMDPu3>b_iSy& zA{9y?O)&GJIsK^&xyUBLl?})9Re0JYl;sl(fk!yo8NhhAM?~d_OtEdA73~GYogp=` zI_jtm$lPOR9z#+yg4f@Y$NeRB+oQ>E*qJ_Q_Rc&OU+zvTDSLmR?*rZ#QNWnV_SPe- z-A=Y&urjWY3dX}DGvwL0${=5D;YO2oceq^R$tdmsYk|O)ZV_yP%cs8^QpP~vX)dS@ zhN-wu8umhnXsw9Y>>a&B-`)v?B*U}44WTOTHkdSV@P#peL;#~WR{}Nvx()3rSk2nE z{)p(Ya}iE1&pwg*+Hzd{HG--Sm2|084JfTab+ILb>=*`uQt=6dLrq$XBwD5Q`DT&N zK}k|ae9zt8R=kf$g9+W`-mErQ&3a%N2|jDnr{fErvPFZa2GF@YqDmTPJ(e~>*|n3z zb`X-Lg?fFSBjT2uKA%HVJ}e93u4crDx-L8jm&Z4Ri5TQ$qXj5U9B1JWZ6D9;Tt{K< ztauX&RQjJ3xXH_ru&-R?RT{Z!26ZOAGu}XPj(e2{en?GvG@-&=MBP7+im!Z!C2m$w zjVYWlSMAd8qnF*DLmxR~@wP&ITC$|iz){+DUP1p7xq(T!!818~#?(Po!wBpgOfeYG zZdt?{*CN8gT0=FJ+(cVTbMiI!=**~_6WuF%>5)SaML&_VA(1mlfhD z3gtDpetyHP#T3xY}s6EAeu^thXCNU(PQ*?_l->EcnlwN^!l!b^npp*jv9XiiYPph3O zUp!r)mpffYab!4sR&od5goGry>f~hey-e@<2epHlQ!LRkT+W5p4lad#=%jYO znk|^-==K5G5bqoub8F>hzymp@moC5)z2e5nCeJhPk(P`P;MU}HwWI^o)L~vne$$Zhx@BOB84<;eJROV7QQoeq3 zseuo(b?OHkCY%9mPvYr{X0)M?5>vw7W9ixn$BLmRUmRU)CSfj48M+j_Xfdk7x!32w z04Bv>mVx0^drkd@+Mimr*tqVY>qY`-0k=+N<&5ae$aUeBz>;MGmW&)p7DUCQQVe*p zuJ~{$r*aO7b(AFthl-MtXkM>0Q{$%5#FV{g1S}lvd-<>>u0FW3btd;#yjjGV-cz;K zfMg(lLtFv;G(;K5q`oDCE!z+3HKK}9slLF2q0a1S)jH4W2|}zZV&7GQuDN(Rb|$Lh zb5B(VYMGsuL!7y#1=m~p z4p`yWPYji~iky0mNu}|iiSIBC@5A>wuG;gxO`37gw zhG!6&y>smd$I;)~p5AHsG=+3*h08y>TLo=t>sg+YUosPGI9&JM(%{t2cVIoo+HQN@ zC}H-{AqjNLVt}T6v|nu;J)BSUJoos5-{{<~lw~R1A`@y%XX4Z&n8*02$F2I*KmupR;tHm)ep(8IEaiLyOp`5nGpElB(H>LuG3l zNwqdM);iTiM7tpJ)v?lN-q!U;4eek?jg^Ui?wk&XHI6+cjWL)A|x z+=iT)ZH0HB%|`gZpXS#T=f5Ws)wWwV&|l>`TUPS64(*3Tc6_qsUIA{)pH(-4lAxGY zl12rXLF!Hh(&sX`PPI&NO`o?YT^O&Ebm=!LO>S5ZJ4*Mthn~Iyz7{ zO6Htkr8I3w2}V6}PmQ1{ghm%d?HK65jT@#tEO3pkW!ErZj5OE2Td97+;T~_R#k$0( zmG3g~2~Cp#IMO-h$l8GnyXg>)t^wwHyWf5%nGxF&2E&EgsA>JDHPqw&_>dBe} zPG1iPo@bpwir|)yxZceH`K1_ML79)DgvdlH)zl;f2~^_{C5CqOOuRc)(tjtd3|#1v z+rOhD;joySyCnaHiSMgMLlJ0%fzfJakwx4b#A~e2?s*@1OfFPE(v0say3kt|7r;_T zL};3rm05B)e?fuQ?;zK;HmCcy?9~!ez$C^HhWJ3lCB$s7H4IRfY zw=lO6H1QQHK=Gq7^jt9aWF#uOs`V7puI4KS898Ww5v~$TaIjgl0%!YrFkEd(H@oO+ zY>O@4elXYinK{6dhZjndZK&xHvhiCPH!96x=s6XdHfDz8P?XIK9%wu6&gk_fcFf@v zE3n6bjj@cStx{&t_hO1^Bu9EA#ZNp~vp1>LvnCTz=k0IiJZ$b~vrhKtIQ%>f`fXLB zVMvL?WxHoU>8q)GP=;x|jxKluU`xGDh6S04bAcF=MFU_3TScGYlgzNA|CwO^mA~ewICKEIGZeyWZE(zXAl5JExXy_k&BzZ62esE)lPfB%_p2ILrDQntT`DVbJmoKcDf69;j zoGJUyf{6e8u)jXk3kCmYD)c{cXcz%3d%%T%ie70((OY-Wz43Q?hKf*BLYen|C67!F znPHSsiYYr~)!r~F7N*axyR!V-h(A(BZYb9{58P7Q0vcPS3ZBNNlJFWwRE^`x-zEv~t;`xS| z*zdZ2U+APp)<4_gy5Du_I;ikS?mvOZIA0%`*_5)M&(hQG<~6^+2gmsw1szX>Oq!qM zpxvoM3Hyb?Sf}C*WQ0?bpLZeNlDnn>JM&$g9hLI9WSmB^UpK*AEJQF$B_idV$z^SZlXA1X@UC^rUZ(^{@yOUi_@cKEJu<-?s5Z zW$xvBe@^}P^V*mFpWA<|f06>|!(_2;;l3Tr`sgPElJNt|lTGb|%KH5GX69+1VL!xU<8MvQq`q z`r)#%&#De?{$3{4aqi#|*hdEy3?y`dFol8rz7#cZc7u&ur;ju~2ck5$DXqNNHPBSE`7D1z`6)r=xcgO@VaB?L>Ms?vOZMC%rJC$=H z-*+#hH0Li$Ww^#Nml^rYFB7R;flEn7qfx*f>CLsz-7h4=U9AG>BXk;7GvOpWUW>SjwQ%J$pYZIb}KJJJleykVib# zf8!?nAPaeJU+@6$F5S{}|Bm#AogPQx)Fp^m|8!Ty%k%ua?!50kvb+Wb8^&q`?Ze6C z(!4xL%E@cAlRzPy8?Uk3ZL1?IWqKZ{&dw^jQiat7TC`1X_Ua%_D(L~Z4`!GQZ?@x0 z&Xrr?yBMRB7usB9k)k?~=-OSpP{q#a#rP_}7Pb~8d2YtFBJ!xP?@ZIG-deiWb+~*^ z#sW&Px&#m5vg%6a?F{?6%F^BPYF9Rr<%~`)inNcWIc{nph*WJ8E>FL7IXl z?V6~>O_RMzL)TKKlOzgxw<^R=xw7iV^UhAXwY9$ESQ_-iWZ!d8txFVnZF8cS?l}F} z%Dk?%RKu7%TnEeVtQmGY<|%o8bqYI2cC`M(@;kG(o~2UkaK_{gwO`kfC{y=L$;Q8t zQJ)b}Gf2GcHtp{{V)t|}b!!eV2QA6zJBotmoB7))IW(D6mQUq*Oq%KgctTK>W!j|KVBy_WyE}0sO#UJY_b3-}xsKQ&>eoP3(n< zsi68hCMLrlB+p-+$lp5h|HdiLnrTYPs6iDNtUnIpF z%)rtqlNx(5m@uYjGDz?zPjNo(gE#lHE}m!h%1%=GIe`ay%*SJ$WO3y?7kca+9|25q zS^$&$nnD=BB(J=SNu*_YYk;?Xwe8?iYvsW1(V#j1fCCbawb_X2r&rdLr=8l{ppYF< zN%U&gN!DTMiwzqj_lm+nYAGM(6iA@@V!m`6`gtfL1$?ZcQuIJwYCY->%(_WpQeR^T4N1y^_JHLPaJn0#JQpMF-SpMX8{^Fbgbe#Y4)Yx9wvOndV0sq0j;*bB% z6Jr8!bAJs;xE0K8kd%<6O-$o!l`V!M39F-kT%@Dqs5a??rb6%mGNH)1)TT+*Qb<+e zFj zag@Se{`ume(=Jh@QS)sXef<9BPLj}50M{-{oWvcID5>x!2fKDX;c+6mH(jA@xny}n zezjsGsk2lhmnc5+AcCH_sXdy(;Kr2bj2GcSSWx+Kaa*gD9^MiP>s`egzs$uEhl^^_ zrtC+}cj`=&aOr{xi9!f<5Q-wImJM>*6O-tQJ(&4$k&AOWzP8vn3Q&CQ6nzbq|wU_4Ap&ili;W~ie$o#kulY#?Kovw;tNpAGJby72jKY}@PwW;F=w|*=*U5L=uem1>3YcMw+ejR^ zliCG*TROCS!syu~V8Rvto@iFQ%AdXF2TTBZ1bVW!S z&`Wwpnl7FPF(-J&@(L*EZ8tEk&q+qVnSTjtUt`v|N}?=ZWryP+-Y_UHMuuQ!;Zn@o z{G+P1P>U^Y<-xql0b)p2W8i$Q*e?F{U=AUcI)C*;8y1d~;e#Pz^$^ z^ld1Pt;C9QrX9JucBT`x2ctW(B!<6a3MYU@M__T)1|Qo3RvNaq=dQ;{>htACF|qW+ zH_|I?MY7}@MFAql3cdpe)jFa#&)XoR{^BD`kEARH|K8oG%?1Q4IBd;Q>st*ntuKx{o0kT)*vft+-Pu}X|u3^Gkt$2JUE_T zx2b74N2vaMxRsw1{_=^)ZZeAhy`&SlBn+|amBYA3P@9FKJy3uS6<7Z!`cB`$QM3eU z5Af|EA!^n`uu#c00vpfqHwh5^tk%kSET;Q4n7&JX9Pex(96oW1R7>c5VrO=B+&jDQ z-(Rl_f1GncvFcEor$-^3E4SLsOEC60(Wy_S?aF(j$FUjID?J0T#GJ+%Er*s!9vGW~ zbBkj>v3)zC(05TSW=2H4h9l_}-g3U?#S3-t?l+^#%aHLCn)(xO`%mR34F6MZ@~7AH zvkc=;cn~0B|CiUp#_)^NBPJuF!Y@l{XK!TxJEw>7r7?el1AiR(NArH~^sv56H}HRO zdH@aj0|$JOaQPh$2&g(?1PJW|prRKYeE_2I>m&p}#?oK?oxeZRFa8eWOBu$`w*O~; z2T-H)>maKMsHg7)RL<>FUVWAg!RyWh(iO9Su@XaC+W@vOJ%ln7|8~{xrOhn>$8F-| zSk2k=PI1zZx*KL}ifnoXrX_M=B?qTC5U&#Du}L=?ny9hkXWFI!mlmaDY&<_X>SpcF%9uk)@md;V z&l>>rP+K~CKSrQ>#p2EjnV{Ybo~o``+PS5LSY=mjZNjL3s$g|{ZpJ#YAviUxP@a>z zy#^0DbiVk_FBMP?^vC;D|5=CfEA;f2>+{d8zW}O#eg-)5Z$Ys?&VGT#=w86FzZ@z+ zEzV#6+W*R-V)>Vtt6ve7z&%&r#HHP~o>Ux)1(RUgbF_1&K^MzETq-x$TzXfe{U(%}R z!#ap{ZEk-zPF;KJp($@ON{+3-m+;ytH~ev(>nW|(I|KPm@&k^1M#7sS z%Dmj1cn#9S#7%ah1oU9O;TUM4GJ;r>poHdJqd5^@hv{a~-qwM4S`u}{yUXy{Ru%M= z-{{z@zd@Csz-fU|fjhMEv8t7?>~g*HvG^R^C#Q?7k)ZZ|j5!ZO7h6&A5Sy_@zwv|7 z?KB;9z%IEHW4G=f^;6mHDAeK}&!dLEyS9+oVgEpAevRYJD~ zVO)H*uF+lLrR{*H_RmiBGo<)G$Gks`8o>PhwEjOj<%>D|)B3-tP5qf2Vh6;be}=pg z{IZfVl7Ns`{E>MeQM=eSg@07C?3PZ*;L3nCX9(9n!Jm zv$Ftd+I}4Xe)Roc2Y|ml*00U~iGQoV)YARa@&Lqtei0F3{58D)uS^OvAaMV6^dKHy zlvJ=q2R~W1PBu1foQB4cU`tEIuT+t0l5K({RfYggEmd=_x|kGUG*sWSZEa)PIHj7O zmB?e19EDz2G;z>HqiiG-fPDTac92z!59QhG>0{}5>b`Q@aqbh<=SSC5dnXw_=h{nd zoZYGF$dbV3fV(UF9u1~(u>g+&@&WXtX2}-id|Y$x&GBwCq2K7GkTWw(;MdjoR8G<<;^)Id8L|gch>hEYo|#_da6oF{_htlKp%&enzAOauEa~1 zY-%Bc!Yqe8$*B^8ro2Dy^h@~(B_K!p;K&a=lbRoc=HLs=tO!WWW^dadW57bZ1+HBw zuEpte-6SzFkb8T~^dNel83lHjU_?}95a!lSFRaqFXJ-09Yxd! zG-ar#`Bd|5IjKlFb$+BQYOO(HOR~tmQx;)#icbji1Y1F$tkL3~>y~HT-85Rg z&9^S|U`n_1rctAjP5WYNhKY*bz88WKO~;#J1lf5ZoPp#za~NoZ?&qjvPLZHgIE?@MRr-cBmL zOHiXGvOmEKojMl!r?L1^SNhYT`LjR%!&m&%H2g${{xl6QzTjV`0kHF@X^<5a5SA67 zlu{6o`mJsF!{_|9bNvb?{n?g(XBz+**Z=Am{%IEeja(ixGd?vFAQ#TS$ixUp4*yFr z@{jKOt5x{>6aCuqUv2JxbPE}oS^n0sHKXUveEHr49D9VcSdbGp;%4Fd1VW7GQ8Q<@ zFzd%FqFohnd#hg|Q=jynT2LSBYT~&DA<+*G>fW z5cVTIX^&U%;S?TcF>i&6*ILO_SIa~Tr$^J4_=9@d?OB3)5B*BV!j-T_Y!Y~3okSUg zbXA;EM^;B_aH~g$+;{{k!GG^8dW{ zmr>w<@j8E=2|!(cmDc;Cu={VRYXC%t|FZmVe(cXX{uk^2&_*U^HvAt8K;nYwhs?!4 z@B3H9J2N{g{>#G3$N~je0D6Id%JY}d>gQ_)gj)ZP9yJ349oyf!$p7F4#T{GFCWFkgr>i}1))3hgzSUlUphwQOI3BGR9xWj zEp4pdoBp6-bnq#nv|ici`{J&0Db6$2Q-K?eEZ+i2Ow4`yGw1SiYoN{25;j2>FNNOW z)`#S!;P=mC@sXh8(thYY!N&-;{t5N+B+}Q)ki}#;8ty3M9TDO_Balw1GWfkN+%5`g zO(c^0q}Jte(0T(ofeQ7iTG*@Z4X>Vn+T=f7HRudzcX49IPP?eR`vT8Z3G2Sz zH5RpCi0|BO$0?Y-TH`eHj#vMUTt^);4u99W~ z?s`51Jj8uDRYw!5+9p6z^Qvc1SQ-B zQu^2g5P0JCu&;|Z)@OPrdi@90%kc^6`#9<|6R}QfNr;#n3b%ZLsbDJ_L55sY4bx9Q z4tIdW7%AvkG>_?}=HGrb7i6&rK6ct@W!@hKp)HdKr&GS-YfiFqGMl?Rb6`~>=8 ziFBTw+dM#7mGt{zXOy12fJK)ynQf%}8j;}!1UV^6PPAf$Q6WK1PI%2bU{fNgoJ4m4 zwV=@IXqIv5@M!%FHdetsaat?Z{T9#Zt*UQkS#L2me7+l$m1>n%7FH6@Y92!zgB_nQ z!Ml^(Qe6}#3~bnMVr`J08HW&cx81&98ur>c_9U-gwu3wiqy~}peMcf~P+3`%GF>dW zh}DK*-3hO!EQ~^(o9q68U`W!fpIE8O#x+}9=D&4kSnCCwA{7Z!fUDa)-zQJXbooOzk|inc0V#0SOMO?{yc0ytwC0 zD98=zt4TcZ`;lj#7o&32C}k?=W2O#XbvLluzC92HT_)q*v#BmLty+{jV5$*LSv;lf z47*6aP=9)+lRCGMAMYkd_s3hqnsssHtT{sseEeL*4@a_M{Z(X(kv4#`XAWx(K`1Kj z*m1M-3B+u_%m&-;# zQen(h#n8@RE?nWX>Sl6toRZsL?ei%p5XXsxaMV#W5T89<^#-)%@@Bw0(;q0E52#i? z46osqXM8k8uZO)vCOxxwMhP8{9YkmJv3Zm<#H7x;(qNI81m?5Jc)L?(0(kd==zCZt zhJgbXxsHJ?QD#4{GT94+)+F3Mu<`a5z{S#XlR}Wv zXM7rWtBRz8iM@d4v967Temp9>Hw13devl7V{?s1#xucc7915;zK?dc+1-vWHlyPBN zC{#&+&^w>yDr-U_{+fR3@V(iU=5-AcEj#W8A-GT#gVEJtMLklQFXH}=pJ7C8?JSEU zp84{e7eSF|qSm}$qoy`V@7k__$C2v+6?6$GD%IZKv=Ol;EE>D)AZ)Z95=2hF^{sA4 zkU8e3o(Hys&l~9Ntfik}X~)SGI)oET&_dtkZl$-&-7Nwam(UD-B&Gy9N8GRJCzPc zMR8k0bL!n~rG)axsgd1m@_N>`Ov%1+k}j!qAc{+kxz&4euliBtjJ)n#VnbqM7Hv&W zD6|^tf+XSXv5be=K5HyFB$Qf1g(q24XbKBaMcC@=k(x`Hug4T7Sc2xx9CnKf=J zrmWtYiwrZ}M8rZ)`X^r%AdY%WZrNnnfFDI(LoTJF<3P95rs>&~bS$5zN;ZFOPJL{E z$zq5Nn~aN>n1CT3Ns5_)dP17dhV^mK^EKk}b!H^rq=jlb-6CXwei8EyEah!UO4R$IJ@PB+03Y-o8dN#6aa%d{cTmvo+_ z_Z_?3(BsFwhGDzUDqFRt%GuqnY{<>OSXnm_7Vf9Xzf-?V(EnZBH??T{!vRs;v*N73 zTrrPI{=Y>T9I@(1USQ}yko#{*3w=jL3m?BFE!fcrP+$}gY3YxsB_^vOrvjib;+lUG zwSaiwSQz|I3Xa(KcTo!vqW%|x7J%3P4S#{51K6Pr4q$K~$t@CsiNE~3DPl-k7y~*Y zX~F&ljQ`)E>#zb20Ra53&~*R+pO<(4hP*>jnD%+q%-qXSjP0Kr7v5LK57SMaH15Jry!e98W2IE_ zCjy^+bsm&!hDPA;FkNec>70Z|PoW zeD;fTHNpf7L2p_DpD@Id@e8^IdT7*b<^ZoF4B|@r{Pm{~YUfO(5 zBsy030bg`PmY6%MteqBL>@|~bV~o6N;F&mMsI1(~!RK3EPMc2(oMu^5r<10qce^&n zsUjaupz13Zg7x(eew7UZhCjCYTcKY+sM^3W3NnU;tmYTdXpVd)n3(cNnY4vXY^pddtZ*cLzC{;JOd z-JAr$dHT~2--HL+(p@o9at~fm@tf!SmPVF&qFQ})bcmJ3hnuc&WOivToiFF!Y36f? z9kpXwKqRd&SVy!x4M{Ew$@%0V=89s!whP^-cKyJ{44{oXTiH=HCBoQfjlBG(TPdML z(TrbnPnpy3I-87HP#V$?H2&Cp_Doc^=!`QAnm$p}Yq@mVu!%ck&Puz8n)o2dR#;q| zKZIe2apVJpfhy)PS!6=r>j9(vlaALFiTXF*v`_l_tL=wu(C*V)R(28V58a<#yg3_q zw~ybvrmb!2hu)rz5qo)Nec6lWHQS!w!n-ppQyt!!lm#zxY$l(;m*VezUTvSzHbejk zb0&*=%N9Jl`eAZ@zhzSsmJz{C+$LuH7Gjy|t5x+aiCBS~Q=@E*HY9aK;Z1ziY^Gp! zwWG;76QbM8f|9X2E6HOwd!Z+o=YA}JitFg~QryGl;}_yAQs*@tC5%p~Kj)00(09&i zu=y%u{koj*DzSZpk>^f}zgBs`?SM#ek7B0uc%lIM5CpN(niF*2iPQ7b2fEyqV6TzM z93pa-9fmF5&xvmyRHx}v`CoUs@loIH2f5U^&!W#ndi5}?67l1L69ofdfg3#rdl76W z1>anQ+wNCdHwsbq83bhGoCPF5Ro{!TR8d zL@SkQRq_dy6MfhBBY54Q!$MzD7^vbk3c^YUDnwgcJ=3HOr)4io_`c|0kUII9mYJ48 zIp2INqoH!8oO^8*aXgxlbHobz;8dAmHW!axE9FCwALHn!N)axL^nr_tyfH$eSJl}W z)rhnM(t^L*u1M{#NlKzB93-n>CNZG__ubDam%ACVPfbk5H*t!kA&%W$H46XQ$R z7E2cfoghD6dGD8y4B?)gKg|Sj_~(D|_n(XlU~&KQ_n(I^27iYGK^=c1sbDaGZ~o@* z>Z0OuQp%j-Y7&2iQenSP*`sXoUp)ne66o*z9l*VQb9f-j!;uh=5HJKY#N%%~6`iK! zZ)_d`uzA2_5)1;6RU{0I#pQo#gZ`KmVh-!*{MV9!}C=TxWlgitdPZDvc1)r7!KeZu)no*iUDovoh#uhQ$A7e~9 zV(Nl7TkZt}^L+H~kQH)uPF>#hs2|%DVg+*Bg|XiGsH$ILqhq81UQ=~#Qtnpi{6g`v zB>vtjl8DE>oCr=Wzmh;zO4?IRx0Ies%b1pY`P|Bp-}_WOuaaTwl4_ux2nTCB#$n_q*l2ZmCq1JXNJ*F%YSzkd;fjZq|huj*2W+rvec2gg^1v* zgRG&ezCJ_F>HFSPMWK{w!GzZ=X)krz)diSl=_*Nl5OMhM>J&B2^H0hpx5ez4T6ws5 zi2Px)#E277F8NgEMB?uhN||30pm>jg&I;d8zD=*>L&rJe17|Ke7XEBeiT}p#BCPO& z>@h`R2KJy~1`)C<0$R>qQbv2cl6%eH-Yu3NDuhPkU9+QE?xm8?^Sf}lmq$b&KjC&; z&H7pQs8NLUCPkXW@$OtTK2)tn>I@m%M@CNkM;o#=iWDStO4HOjB0u^wU5<5^k5e#x zb6cn9V9Li9R8S4 zJ3@r)UB>h}o}m1@1A`RCR`P`V1hOYH6+7D8Zm|^mv$Is3A9>{JrhbM%Y?OI_I`-kG zhw+YCnfB_^!txAndnSD@MXt#2)#W+}&XzOHdoDks=A0LPH^OtsWWaD>zO(RkoPbZ( zv(Ejwrsqu^&b~T|Qt?ghvGn+}g@-b^{0+#*MjdMfvVk-UXWR;M3SM_n+xY;;1{%p#}2UaH=$3{;1_*BZpf*Il;0cYist!`IedeK}*x_2SMO zA zwVwW}QLoj-1+BUdb-6}rDq8si?b8P-l+%*(uVr#*w(0J!e0nL`Dm_uw7wpnCwBNJT zy83nnFWt>8QBPK5VB#IaUOlOmC?q?)471^@SvyCAg*9 z9QCe$NIf`b&l(6Mma_+PzrFs}{rI_4QIhBKxzB%hS`N2-67b}q*%qQyqf7D8vx?0% zx_NPMAN`^=FC{}rYv7K}Mx^a?bD1jL4PHSCsi#I3j^^flkjE0b`X9%IuL_ z-GkEm!#St=s29xzlt1m$;IsQ|ENqJRiO+6fPN_^bbocY*&wDsk$`=A6rbmezgQ5l{MHdQys$jMOD^oQ&!^;B1GnWo;Eee zxvZ(CmX9bzVl-wOnc*nUj?2w3^wj?&X%*X_6ox*qF}NAvZ;8Rqj@rq~swv%2m&EcY zMW@#KyGJPyC>UFOJ*sc}{lNb>_6C>){3F03c!BTeVkS0@0H^w!M=4<3@XL|_3<0>^ zUrosXJ2Gx4z~y*(5r8QHz;lk862N|`HUBWV{~qiSrUwK?{#P6W147bYe*R&8z<Lgt%m4Op^zT1CpFT?ad#&H?{9(#~6~_OkNC$<%FzxBeHC*jf zBon+FH&pIYuLPfmFfAWbi8PK3JBA;RF9%{xVlqS^#>3+6cnyn=$quYKYL&2F+A-Ft z^!Qq4Wp$fvbmFAOnMS(i*B6oq9l%D2qBi3S)3!`;xVKeD*vBsQMFSljZl_%BPs^Sy z%e$TpF`&7*kQ>a@wH~Xq#Ip?>jXJ^Kzh}#*^1;hvB0Ykn6{uo7__()k@Ch3+ym|+d zkvR}ykZX-|_hy{B^U$cCDmG#2wsNVZl|_okGqA6gT*8frZpHYW_Z@|cTpzQzIHMFj z?#|ALZihZ{oqQo$UKjXc?};~+gip3{U1Mj2l_8?IY3@6$+|LLS5AM`7rHgE`>%7oe z822oWu=87|s3}=#oK_>3NetK)!WkDW$5R^Q8r*jKdwhSVcJ_T&H!2pRhv1KLWOqfs z=Ve+BmA=`?mX|HfR+P2vY3=@MXb@#8TbNE~OkHoYwMf=LYwtAOd~-@dErbD4Blsgj zt`0JxWM-e8YFFN=WX(;)a{hQW`xE{lJKt-pA{kjX4S>A5UmTtrI%&Q-fpE{FH{r8; zn4Hr2x*R2@uFJhdz&k0I)f=(7*~~XQqM9r&5UWDczhNN~&#Ag8W+Ck`ux|n>9?q_q zXN!z5Ywb3OJfE-djDY(+oGM|P525|d21w3M8gN#e^ftpKYVYxUF$4Oo;r?+;KZ!mo z^LIbsB1E3v+uO!>+czRTUB&>t+KcK`9+pUw{I*09i8nH1?E`h)O)rUs0xaL%eX+Z@ zdy)3VYrM6DYpw3*oXe&oDN?(Sz11u9;c%y5{EpgI9$@$9uU(xQb9DPwSFSID%82AL zV1IRfD#H5k`PJcKC$Y;V#TU}ZdkVKgBp7ez)TF-XZlv%W719ldwK8zUF{{PNr(ZD) zJ>|mPv1s9Q#r?w5iojC&@eThFq05KL@7sJjCXOL3z({i!Le&^8r^x|&9b|m;fHIqv zq}qEv`Jz1Pu*gq34QxY{iZ8je205h_=4E9S_^z=aHk5m!RW5exf1R5P5M~mH0i~Xw z$r|HIu4Boxe&jC-W}uPRU%6gotyl&g?whwF>}w@eB{^U)Z7gKFrkSL}Ja)Y$LT##x zGMI2pitL5O%&H!OJa742P1Z!aQf^NEXp>pO`K>M9q~x$9>bJf1FoE-9F}+(`7B3$= z7fu>!il%zxC||qZWa@i5Gtm6@YPMZRxp?i}wz5aYH1P@y-&kE;PMIEf5S0pZ?S(Ub zemish!L1*r(@ZSJHgn@f^1tR&Hg2!YQmP~lWXFY$-Rl`o1d=vO1??bS<9LvXS!2WJQ00{dA@BX~uC5xkD-3t`FZHY&1SqCi zny^+5%;XS^ocp@E!!$nSY5vD41>gyl4E(rTd z!$J1!QKIw62p+uHzCoC|PkOQI#1qo62(@lCM7gQ!l46V_ zGEDjoEOM@Y&tYl|V4Tjk759bGS#CFlS!yQMn!JoVyB&C@R{H%4>%ncQx0`f#iSVzR zOOO@Fw#42SyM4ZC(t3v*L?7d+zE1dEChhRut7!9g)DC`(CyEm^*E7!P$&ODvdhQu( z?|I1?|1eJAGD~Tezut)NH}gQ~-M}c&1tMua37=R&{YvELPx6m~lqo0IOpd99943*# zU0H7WN|Jw8csOM4-w>7BVNp(5-fbIr(wKhxEH!Fzef&mh^6rP&x=8uHq|N{}C7WwR z7lxU?C~)Z@ZH0u15T8r*rK$bd*2mc{oEJDz7&CEifY7FvNJ-#a;J!6nfkiR0liH7o zD|{bD_~abVD>iFAL7voFGJH5whR$(*yr?VITGHY5=Vlt~f+>*U8Im*9RgQB{-jOEH zJT6#)a&Q>Ik`zl%I1Hru> zo4PU5kd~i>w+yzx1EyD?E$?<+Vec%eSUL*LYl zf}2*5AFnIr<)rJedu~CAil&>ylC0ajC>Y!aB|-0CW}Z0d*Qen z{<#D)=ZruN+q4H_s7XGmJ$45R?|rT5@X4FTRvwgx__b<-pP5iuq>A+PwM~K)?s%VS zyuO6ueagP4C)rA|Caw}P_dFNQ%lV1YAo`M$tQdP;B}kK%ywNRL`BC7P2jZrRY6|r8 zi`M*Y21dI}A5FWMRXR;Xc?2$$>fY$fnu=>>r&PSew_Q9%PB%K7?b|Squf8^PEp?@bDz`(%ePHH-YZJTP+TcxzyJES zdEWIcI@)zYAEU@Z)h&|xH}?Y9wNvB_%TMnrs1>D)uiPJ;II$*J(Hg~9ofF8eGu3Mz z{7Uah{%wbpTG>*w!Ut*D#%Y8~67HfO!)A>`RBejb)w%}4?%Nj2m#3(Xkes9WV%)zh{b&7VD?@z&yB%YZktX!%Dor}CZdD%RFoV10 z2hl9cQ}=lGO7CdVMl-7q*B_>54?X*YVD@Nf#;><~JFY@p_ElweMPN>AIF+<-#(MVA zbs48%-xn5Zrsa9B&r>XwgdhGm=36%C$eB2H<{QQEtu8O|6~Uns{Ej9jUyV2hSPzJ4 z2Uj|$QCg*CO$*niW{cA6MdhQ_Z;bCKgdO0=@UI>E#F5K;#)q-;Obva3=>lFwEE$h& z&z+K!U|sBZ3~ zJK>o`yeCLW@i`RU%YWJEDY@@1M;X@4K||iKvOIF(Y)!5=^6=te(9n{#d-SDVbD4&n zQyC51&2QSwC+ID_dhhvJwkgLudA%0M>!*C_K2?WD5{mcE=$V1z++_UcL^iYf=ChBK zN5oRzIv><<70-AK5V_2i2z3X`t_a5OOG(r*GtNq%Xo?UQF9WX}a5r;B>N@iH6T=CMqRqze3cJd};Pj$$l8{8w zcb7uVt9ZQ}{3|szNr{6h3KjglDWV0bx0*(OXdOTG;+Sx?#yyu=uPJ*GXILj?u7IG>_+oZ@`?r-wA(YX^3rXDo6;eJKr{qvOrK-!1giArv@52Ks=|3b>_V9Io<>w^LHFaLREDE*;IBUaI*KFXG!@f~z0D4^j z5|aVT(E^B5hnNRvUuBi3n0Zjc z5FaU)o#uJg-kX8XsjWL+ITE2>sgsJYg z;B04lLanX$RGZ1pa1HY^rN+(Mp~BC2TdFhke+bbXbAC!Jtai!q1XCcL)naot$%C%? zf~l7}37k4<#7ShcOU<;8k+il|8&$RQwK)ee;pY}hI39$Uc65HxE+`b>NHQ4=`<$oJ zuD>77W?j%MK}i0fye~V4J(s;WN;OEmSfaD#T1cYu_eq@BO&s6pYjm>HYyp_ zAE`u0bH|pg*G@F9D#@}l+@W1wLkS)eVMw4+oIeE{Su2@3lRy*IcjDWdJl9YPC(7vT z*L0K#L)DR`-ks)#EF|@Is*;2s?{dw`J)*8ryaNgPZl@;YV*ZjiEHNvn81|I-YNLsf zf90s<$vCAe!Xv5sBS3833<;FPfxyuM_-_bYPEuCz&ZVo#LozZ zqg9v~j%Gh8I3WF>Iv7c~!GFB#5#XbFjvzqX8jL(gzd>;LZ-4-eh69iDE5i{4P^NN2 z(YkJQB5o7}%h%wi42&N2zs~j8BRc{K{DfKl9l?Lw6=R9VddmN5yFKL2QW&<%ib@gq zyiGeBeWSe}EE}X6V$#awJ*Jm9^X|BdK<7f_)0__NP3T#n#T=SA*THWCjj+!J_+I`x zg<7mGBl)h?)s-}vM%P!bbk)+`Ct|Cjn8GKoE@xM4JWJOGQd$qsXobJQu);h&vOn7vsI~vPC z)VZ%@JdejbG;02k*G~0yV+?84qV*zqCx$YMOh)YH67;Q)6;Y-p2i>L90hNK`RN)c} z0u3y6n{iuJ4pe7jUdRTl8qRgki5Fk5d*YeoV>b!D$X>!6r>g zLjW}i5HXW@h(FU3_Z0vGS+f7&8UMLH5ME4&4!v-BTR%p??t3qYcZq?fLHm<@$fMo_ zm#>oZOJ|j+3Z%t-+*Zb%@oEDY3>h9y(7UV#)ja=F<+GV<_IdpDKD&Rj$!D14S39c9 z#G>a|44yYo9+|;3X%UI;RTdBw7*HXii=&5C&XCf?? z0Kr=ho{mvl27=g(PJEmeDie{{wyU}LxC@r3ER0IieQl;?`UT&a$s#z|f_Gk>v{iYm zhp`|pB#r!V>bhYYlqu2v4j9osRVVM_sk&S_2QlY!9W$3^z*;YG}WyALQU~|mP z$*JAG=bcyiy^fu(3_FfH<1P*+rU0A;2BO4)et#Gda5xmsXv+ADhD3k?VD9IC8EyX1 z(D}{LpFcDRk{7@cF=!|l0t~3mFlfAB1R5YcN&}LYfzd__m^35^4TECP080cUfT$g% zfq3CybdL6;G$5}d6m67_K?4IB*07%$D1h^PAi#S8t1bv|aYX@G+tKzw091+2m3fo~ zXc?h^%{K-O1cCq)h)sj@q7`vR>jHi7BCzKQgn)ps<^TlbtVDa1Vb+EI41IBw2IN(Q z;>;C@_h-Piqvb$AO|-ob1`P=W*~9Jw4D^BhEI>Fw5CG6(*TvZ{V8HPhd;WlP9cQkP zP&oQL$7m0Lm2t)kfuhiE&lu$Zn|WZ@V$gskM+aoVpn(9FWgzt@77c+yd$6KEfA%vJ ziL-7HB+w*QIVcE%GtWpU3WYU)fEpBnv%XLe9F4|f^a~W@#To|)3FSq{Gr=l{HUPt- z!BI%;a!42meKWwU3%r&%G!)<^hgA*T<%E5rc37duloJ6pn1%^W4>=!r~ zg~aXy2}9w`6&!-QUjSu0Ze2JCXK%payg2g$M*(qvu*QLejFm(It~LyIV2o76tQU#5L!!vSq^vyarPAgD1u!M3WH;x2S_Lg zmw!N^=)gmmeZU~-+{&0VpcoDf23&lx%fWbY&Ql}|j(eU0wt(1cgoFbO1iL-ph{bt6 zI2^YRU;|>!J#el8ObWX_#9#I)u^(z*1tb2QUik_Y$~lfU$W6a1R3(1bZBS$u{~{gE3*6$c`US4GM|pswgV7x;6Nl4i$U)_fo5@c>;F_|nts^5a^JoJE kX&X~pMxd2nNWfi3BL~NyG6N9!1qMQ#zI<6+QR4Lf0S`Pn4gdfE From d83b5b20cd6ea2fa64cc905841ceb658622ccf05 Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Thu, 16 May 2013 15:24:38 +0000 Subject: [PATCH 008/256] Removed 'using namespace std' from the inline header file --- gtsam/linear/GaussianBayesTree-inl.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/gtsam/linear/GaussianBayesTree-inl.h b/gtsam/linear/GaussianBayesTree-inl.h index 4d659019d..1f6c8e9f5 100644 --- a/gtsam/linear/GaussianBayesTree-inl.h +++ b/gtsam/linear/GaussianBayesTree-inl.h @@ -25,8 +25,6 @@ #include -using namespace std; - namespace gtsam { /* ************************************************************************* */ @@ -47,7 +45,7 @@ double logDeterminant(const typename BAYESTREE::sharedClique& clique) { double result = 0.0; // this clique - result += clique->conditional()->get_R().diagonal().unaryExpr(ptr_fun(log)).sum(); + result += clique->conditional()->get_R().diagonal().unaryExpr(std::ptr_fun(log)).sum(); // sum of children BOOST_FOREACH(const typename BAYESTREE::sharedClique& child, clique->children_) From 1c5061cf3cf4064ed429479452b0458e13f3c8fc Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Fri, 17 May 2013 08:06:06 +0000 Subject: [PATCH 009/256] Added optional flag to ConcurrentBatchFilter to control relinearization during syncs. --- gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp | 2 +- gtsam_unstable/nonlinear/ConcurrentBatchFilter.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp index c0dab4d83..1e1e39e10 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp @@ -126,7 +126,7 @@ void ConcurrentBatchFilter::synchronize(const NonlinearFactorGraph& summarizedFa if(factors_.size() > 0) { // Perform an optional optimization on the to-be-sent-to-the-smoother factors - if(true) { + if(relin_) { // Create ordering and delta Ordering ordering = *graph.orderingCOLAMD(values); VectorValues delta = values.zeroVectors(ordering); diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h index df05bdc51..9a7690786 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h @@ -54,7 +54,7 @@ public: }; /** Default constructor */ - ConcurrentBatchFilter(const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams()) : parameters_(parameters) {}; + ConcurrentBatchFilter(const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams(), bool relin = true) : parameters_(parameters), relin_(relin) {}; /** Default destructor */ virtual ~ConcurrentBatchFilter() {}; @@ -122,6 +122,7 @@ public: protected: LevenbergMarquardtParams parameters_; ///< LM parameters + bool relin_; NonlinearFactorGraph factors_; ///< The set of all factors currently in the filter Values theta_; ///< Current linearization point of all variables in the filter Ordering ordering_; ///< The current ordering used to calculate the linear deltas From 54b094facb9e04b2fef0dd81bed18bae8146f43c Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Sun, 19 May 2013 20:25:40 +0000 Subject: [PATCH 010/256] Updated ImuBias to better conform with GTSAM standards --- gtsam/navigation/ImuBias.h | 228 +++++++++++++++++++++---------------- 1 file changed, 133 insertions(+), 95 deletions(-) diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index b9cfebf46..3a2010c3b 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -26,7 +26,7 @@ /* * NOTES: * - Earth-rate correction: - * + Currently the user should supply R_ECEF_to_G, which is the rotation from ECEF to Local-Level system (NED or ENU as defened by the user). + * + Currently the user should supply R_ECEF_to_G, which is the rotation from ECEF to Local-Level system (NED or ENU as defined by the user). * + R_ECEF_to_G can be calculated by approximated values of latitude and longitude of the system. * + A relatively small distance is traveled w.r.t. to initial pose is assumed, since R_ECEF_to_G is constant. * Otherwise, R_ECEF_to_G should be updated each time using the current lat-lon. @@ -41,136 +41,174 @@ namespace imuBias { class ConstantBias : public DerivedValue { private: - Vector bias_acc_; - Vector bias_gyro_; + Vector3 biasAcc_; + Vector3 biasGyro_; public: + /// dimension of the variable - used to autodetect sizes + static const size_t dimension = 6; ConstantBias(): - bias_acc_(Vector_(3, 0.0, 0.0, 0.0)), bias_gyro_(Vector_(3, 0.0, 0.0, 0.0)) { + biasAcc_(0.0, 0.0, 0.0), biasGyro_(0.0, 0.0, 0.0) { } - ConstantBias(const Vector& bias_acc, const Vector& bias_gyro): - bias_acc_(bias_acc), bias_gyro_(bias_gyro) { + ConstantBias(const Vector3& biasAcc, const Vector3& biasGyro): + biasAcc_(biasAcc), biasGyro_(biasGyro) { } - Vector CorrectAcc(Vector measurment, boost::optional H=boost::none) const { - if (H){ - Matrix zeros3_3(zeros(3,3)); - Matrix m_eye3(-eye(3)); + /** return the accelerometer and gyro biases in a single vector */ + Vector vector() const { + Vector v(6); + v << biasAcc_, biasGyro_; + return v; + } - *H = collect(2, &m_eye3, &zeros3_3); - } + /** get accelerometer bias */ + const Vector3& accelerometer() const { return biasAcc_; } - return measurment - bias_acc_; - } + /** get gyroscope bias */ + const Vector3& gyroscope() const { return biasGyro_; } + /** Correct an accelerometer measurement using this bias model, and optionally compute Jacobians */ + Vector correctAccelerometer(const Vector3& measurment, boost::optional H=boost::none) const { + if (H){ + H->resize(6,3); + (*H) << -Matrix3::Identity(), Matrix3::Zero(); + } + return measurment - biasAcc_; + } - Vector CorrectGyro(Vector measurment, boost::optional H=boost::none) const { - if (H){ - Matrix zeros3_3(zeros(3,3)); - Matrix m_eye3(-eye(3)); + /** Correct a gyroscope measurement using this bias model, and optionally compute Jacobians */ + Vector correctGyroscope(const Vector3& measurment, boost::optional H=boost::none) const { + if (H){ + H->resize(6,3); + (*H) << Matrix3::Zero(), -Matrix3::Identity(); + } + return measurment - biasGyro_; + } - *H = collect(2, &zeros3_3, &m_eye3); - } +// // H1: Jacobian w.r.t. IMUBias +// // H2: Jacobian w.r.t. pose +// Vector CorrectGyroWithEarthRotRate(Vector measurement, const Pose3& pose, const Vector& w_earth_rate_G, +// boost::optional H1=boost::none, boost::optional H2=boost::none) const { +// +// Matrix R_G_to_I( pose.rotation().matrix().transpose() ); +// Vector w_earth_rate_I = R_G_to_I * w_earth_rate_G; +// +// if (H1){ +// Matrix zeros3_3(zeros(3,3)); +// Matrix m_eye3(-eye(3)); +// +// *H1 = collect(2, &zeros3_3, &m_eye3); +// } +// +// if (H2){ +// Matrix zeros3_3(zeros(3,3)); +// Matrix H = -skewSymmetric(w_earth_rate_I); +// +// *H2 = collect(2, &H, &zeros3_3); +// } +// +// //TODO: Make sure H2 is correct. +// +// return measurement - biasGyro_ - w_earth_rate_I; +// +//// Vector bias_gyro_temp(Vector_(3, -bias_gyro_(0), bias_gyro_(1), bias_gyro_(2))); +//// return measurement - bias_gyro_temp - R_G_to_I * w_earth_rate_G; +// } - return measurment - bias_gyro_; - } + /// @} + /// @name Testable + /// @{ - // H1: Jacobian w.r.t. IMUBias - // H2: Jacobian w.r.t. pose - Vector CorrectGyroWithEarthRotRate(Vector measurement, const Pose3& pose, const Vector& w_earth_rate_G, - boost::optional H1=boost::none, boost::optional H2=boost::none) const { + /// print with optional string + void print(const std::string& s = "") const { + // explicit printing for now. + std::cout << s + ".biasAcc [" << biasAcc_.transpose() << "]" << std::endl; + std::cout << s + ".biasGyro [" << biasGyro_.transpose() << "]" << std::endl; + } - Matrix R_G_to_I( pose.rotation().matrix().transpose() ); - Vector w_earth_rate_I = R_G_to_I * w_earth_rate_G; + /** equality up to tolerance */ + inline bool equals(const ConstantBias& expected, double tol=1e-5) const { + return equal_with_abs_tol(biasAcc_, expected.biasAcc_, tol) + && equal_with_abs_tol(biasGyro_, expected.biasGyro_, tol); + } - if (H1){ - Matrix zeros3_3(zeros(3,3)); - Matrix m_eye3(-eye(3)); + /// @} + /// @name Manifold + /// @{ - *H1 = collect(2, &zeros3_3, &m_eye3); - } + /// dimension of the variable - used to autodetect sizes + inline static size_t Dim() { return dimension; } - if (H2){ - Matrix zeros3_3(zeros(3,3)); - Matrix H = -skewSymmetric(w_earth_rate_I); - - *H2 = collect(2, &H, &zeros3_3); - } - - //TODO: Make sure H2 is correct. - - return measurement - bias_gyro_ - w_earth_rate_I; - -// Vector bias_gyro_temp(Vector_(3, -bias_gyro_(0), bias_gyro_(1), bias_gyro_(2))); -// return measurement - bias_gyro_temp - R_G_to_I * w_earth_rate_G; - } - - /** Expmap around identity */ - static inline ConstantBias Expmap(const Vector& v) { return ConstantBias(v.head(3), v.tail(3)); } - - /** Logmap around identity - just returns with default cast back */ - static inline Vector Logmap(const ConstantBias& p) { return concatVectors(2, &p.bias_acc_, &p.bias_gyro_); } + /// return dimensionality of tangent space + inline size_t dim() const { return dimension; } /** Update the LieVector with a tangent space update */ - inline ConstantBias retract(const Vector& v) const { return ConstantBias(bias_acc_ + v.head(3), bias_gyro_ + v.tail(3)); } + inline ConstantBias retract(const Vector& v) const { return ConstantBias(biasAcc_ + v.head(3), biasGyro_ + v.tail(3)); } /** @return the local coordinates of another object */ - inline Vector localCoordinates(const ConstantBias& t2) const { - Vector delta_acc(t2.bias_acc_ - bias_acc_); - Vector delta_gyro(t2.bias_gyro_ - bias_gyro_); - return concatVectors(2, &delta_acc, &delta_gyro); - } + inline Vector localCoordinates(const ConstantBias& t2) const { return t2.vector() - vector(); } - /** Returns dimensionality of the tangent space */ - inline size_t dim() const { return this->bias_acc_.size() + this->bias_gyro_.size(); } + /// @} + /// @name Group + /// @{ - /// print with optional string - void print(const std::string& s = "") const { - // explicit printing for now. - std::cout << s + ".bias_acc [" << bias_acc_.transpose() << "]" << std::endl; - std::cout << s + ".bias_gyro [" << bias_gyro_.transpose() << "]" << std::endl; - } + ConstantBias compose(const ConstantBias& b2, + boost::optional H1=boost::none, + boost::optional H2=boost::none) const { + if(H1) *H1 = gtsam::Matrix::Identity(6,6); + if(H2) *H2 = gtsam::Matrix::Identity(6,6); - /** equality up to tolerance */ - inline bool equals(const ConstantBias& expected, double tol=1e-5) const { - return equal(bias_acc_, expected.bias_acc_, tol) && equal(bias_gyro_, expected.bias_gyro_, tol); - } + return ConstantBias(biasAcc_ + b2.biasAcc_, biasGyro_ + b2.biasGyro_); + } - /** get bias_acc */ - const Vector& bias_acc() const { return bias_acc_; } + /** between operation */ + ConstantBias between(const ConstantBias& b2, + boost::optional H1=boost::none, + boost::optional H2=boost::none) const { + if(H1) *H1 = -gtsam::Matrix::Identity(6,6); + if(H2) *H2 = gtsam::Matrix::Identity(6,6); - /** get bias_gyro */ - const Vector& bias_gyro() const { return bias_gyro_; } + return ConstantBias(b2.biasAcc_ - biasAcc_, b2.biasGyro_ - biasGyro_); + } + /** invert the object and yield a new one */ + inline ConstantBias inverse(boost::optional H=boost::none) const { + if(H) *H = -gtsam::Matrix::Identity(6,6); - ConstantBias compose(const ConstantBias& b2, - boost::optional H1=boost::none, - boost::optional H2=boost::none) const { - if(H1) *H1 = eye(dim()); - if(H2) *H2 = eye(b2.dim()); + return ConstantBias(-biasAcc_, -biasGyro_); + } - return ConstantBias(bias_acc_ + b2.bias_acc_, bias_gyro_ + b2.bias_gyro_); - } + /// @} + /// @name Lie Group + /// @{ - /** between operation */ - ConstantBias between(const ConstantBias& b2, - boost::optional H1=boost::none, - boost::optional H2=boost::none) const { - if(H1) *H1 = -eye(dim()); - if(H2) *H2 = eye(b2.dim()); - return ConstantBias(b2.bias_acc_ - bias_acc_, b2.bias_gyro_ - bias_gyro_); - } + /** Expmap around identity */ + static inline ConstantBias Expmap(const Vector& v) { return ConstantBias(v.head(3), v.tail(3)); } - /** invert the object and yield a new one */ - inline ConstantBias inverse(boost::optional H=boost::none) const { - if(H) *H = -eye(dim()); + /** Logmap around identity - just returns with default cast back */ + static inline Vector Logmap(const ConstantBias& p) { return p.vector(); } - return ConstantBias(-1.0 * bias_acc_, -1.0 * bias_gyro_); - } + /// @} + private: + /// @name Advanced Interface + /// @{ + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) + { + ar & boost::serialization::make_nvp("imuBias::ConstantBias", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(biasAcc_); + ar & BOOST_SERIALIZATION_NVP(biasGyro_); + } + + /// @} }; // ConstantBias class From dbc05045cda3f1f76abb757682e9f21d77cf923b Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Sun, 19 May 2013 20:25:49 +0000 Subject: [PATCH 011/256] Updated Imu Factors for changes in the ImuBias class --- .../EquivInertialNavFactor_GlobalVel.h | 38 +++++++++---------- .../InertialNavFactor_GlobalVelocity.h | 6 +-- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/gtsam/navigation/EquivInertialNavFactor_GlobalVel.h b/gtsam/navigation/EquivInertialNavFactor_GlobalVel.h index 5d221246b..564f5a2c8 100644 --- a/gtsam/navigation/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam/navigation/EquivInertialNavFactor_GlobalVel.h @@ -171,11 +171,11 @@ public: POSE predictPose(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1) const { // Correct delta_pos_in_t0_ using (Bias1 - Bias_t0) - Vector delta_BiasAcc = Bias1.bias_acc(); - Vector delta_BiasGyro = Bias1.bias_gyro(); + Vector delta_BiasAcc = Bias1.accelerometer(); + Vector delta_BiasGyro = Bias1.gyroscope(); if (Bias_initial_){ - delta_BiasAcc -= Bias_initial_->bias_acc(); - delta_BiasGyro -= Bias_initial_->bias_gyro(); + delta_BiasAcc -= Bias_initial_->accelerometer(); + delta_BiasGyro -= Bias_initial_->gyroscope(); } Matrix J_Pos_wrt_BiasAcc = Jacobian_wrt_t0_Overall_.block(4,9,3,3); @@ -236,11 +236,11 @@ public: VELOCITY predictVelocity(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1) const { // Correct delta_vel_in_t0_ using (Bias1 - Bias_t0) - Vector delta_BiasAcc = Bias1.bias_acc(); - Vector delta_BiasGyro = Bias1.bias_gyro(); + Vector delta_BiasAcc = Bias1.accelerometer(); + Vector delta_BiasGyro = Bias1.gyroscope(); if (Bias_initial_){ - delta_BiasAcc -= Bias_initial_->bias_acc(); - delta_BiasGyro -= Bias_initial_->bias_gyro(); + delta_BiasAcc -= Bias_initial_->accelerometer(); + delta_BiasGyro -= Bias_initial_->gyroscope(); } Matrix J_Vel_wrt_BiasAcc = Jacobian_wrt_t0_Overall_.block(6,9,3,3); @@ -353,11 +353,11 @@ public: // Correct delta_pos_in_t0_ using (Bias1 - Bias_t0) - Vector delta_BiasAcc = Bias1.bias_acc(); - Vector delta_BiasGyro = Bias1.bias_gyro(); + Vector delta_BiasAcc = Bias1.accelerometer(); + Vector delta_BiasGyro = Bias1.gyroscope(); if (Bias_initial){ - delta_BiasAcc -= Bias_initial->bias_acc(); - delta_BiasGyro -= Bias_initial->bias_gyro(); + delta_BiasAcc -= Bias_initial->accelerometer(); + delta_BiasGyro -= Bias_initial->gyroscope(); } Matrix J_Pos_wrt_BiasAcc = Jacobian_wrt_t0_Overall.block(4,9,3,3); @@ -381,11 +381,11 @@ public: const boost::optional& Bias_initial = boost::none) { // Correct delta_vel_in_t0_ using (Bias1 - Bias_t0) - Vector delta_BiasAcc = Bias1.bias_acc(); - Vector delta_BiasGyro = Bias1.bias_gyro(); + Vector delta_BiasAcc = Bias1.accelerometer(); + Vector delta_BiasGyro = Bias1.gyroscope(); if (Bias_initial){ - delta_BiasAcc -= Bias_initial->bias_acc(); - delta_BiasGyro -= Bias_initial->bias_gyro(); + delta_BiasAcc -= Bias_initial->accelerometer(); + delta_BiasGyro -= Bias_initial->gyroscope(); } Matrix J_Vel_wrt_BiasAcc = Jacobian_wrt_t0_Overall.block(6,9,3,3); @@ -481,12 +481,12 @@ public: // Note: all delta terms refer to an IMU\sensor system at t0 // Calculate the corrected measurements using the Bias object - Vector AccCorrected = Bias_t0.CorrectAcc(msr_acc_t); + Vector AccCorrected = Bias_t0.correctAccelerometer(msr_acc_t); Vector body_t_a_body; if (flag_use_body_P_sensor){ Matrix body_R_sensor = body_P_sensor.rotation().matrix(); - Vector GyroCorrected(Bias_t0.CorrectGyro(msr_gyro_t)); + Vector GyroCorrected(Bias_t0.correctGyroscope(msr_gyro_t)); Vector body_omega_body = body_R_sensor * GyroCorrected; Matrix body_omega_body__cross = skewSymmetric(body_omega_body); @@ -509,7 +509,7 @@ public: // Note: all delta terms refer to an IMU\sensor system at t0 // Calculate the corrected measurements using the Bias object - Vector GyroCorrected = Bias_t0.CorrectGyro(msr_gyro_t); + Vector GyroCorrected = Bias_t0.correctGyroscope(msr_gyro_t); Vector body_t_omega_body; if (flag_use_body_P_sensor){ diff --git a/gtsam/navigation/InertialNavFactor_GlobalVelocity.h b/gtsam/navigation/InertialNavFactor_GlobalVelocity.h index 8f7f14d7e..33eb8777d 100644 --- a/gtsam/navigation/InertialNavFactor_GlobalVelocity.h +++ b/gtsam/navigation/InertialNavFactor_GlobalVelocity.h @@ -148,7 +148,7 @@ public: POSE predictPose(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1) const { // Calculate the corrected measurements using the Bias object - Vector GyroCorrected(Bias1.CorrectGyro(measurement_gyro_)); + Vector GyroCorrected(Bias1.correctGyroscope(measurement_gyro_)); const POSE& world_P1_body = Pose1; const VELOCITY& world_V1_body = Vel1; @@ -175,7 +175,7 @@ public: VELOCITY predictVelocity(const POSE& Pose1, const VELOCITY& Vel1, const IMUBIAS& Bias1) const { // Calculate the corrected measurements using the Bias object - Vector AccCorrected(Bias1.CorrectAcc(measurement_acc_)); + Vector AccCorrected(Bias1.correctAccelerometer(measurement_acc_)); const POSE& world_P1_body = Pose1; const VELOCITY& world_V1_body = Vel1; @@ -185,7 +185,7 @@ public: if(body_P_sensor_) { Matrix body_R_sensor = body_P_sensor_->rotation().matrix(); - Vector GyroCorrected(Bias1.CorrectGyro(measurement_gyro_)); + Vector GyroCorrected(Bias1.correctGyroscope(measurement_gyro_)); body_omega_body = body_R_sensor * GyroCorrected; Matrix body_omega_body__cross = skewSymmetric(body_omega_body); body_a_body = body_R_sensor * AccCorrected - body_omega_body__cross * body_omega_body__cross * body_P_sensor_->translation().vector(); From cff6d814ebfdc683e8b9c76f443b05e8addec0b9 Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Sun, 19 May 2013 20:25:57 +0000 Subject: [PATCH 012/256] Fixed bug in Imu Bias Jacobian sizes --- gtsam/navigation/ImuBias.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 3a2010c3b..352bb1918 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -72,7 +72,7 @@ namespace imuBias { /** Correct an accelerometer measurement using this bias model, and optionally compute Jacobians */ Vector correctAccelerometer(const Vector3& measurment, boost::optional H=boost::none) const { if (H){ - H->resize(6,3); + H->resize(3,6); (*H) << -Matrix3::Identity(), Matrix3::Zero(); } return measurment - biasAcc_; @@ -81,7 +81,7 @@ namespace imuBias { /** Correct a gyroscope measurement using this bias model, and optionally compute Jacobians */ Vector correctGyroscope(const Vector3& measurment, boost::optional H=boost::none) const { if (H){ - H->resize(6,3); + H->resize(3,6); (*H) << Matrix3::Zero(), -Matrix3::Identity(); } return measurment - biasGyro_; From 4d71fa10af4af1cedaa8c60c00797b6dcd737f0e Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Mon, 20 May 2013 17:26:49 +0000 Subject: [PATCH 013/256] Added missing GTSAM_EXPORT tag --- gtsam/base/LieVector.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 3bb0ffd39..c978500dd 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -53,7 +53,7 @@ struct LieVector : public Vector, public DerivedValue { } /** print @param name optional string naming the object */ - void print(const std::string& name="") const; + GTSAM_EXPORT void print(const std::string& name="") const; /** equality up to tolerance */ bool equals(const LieVector& expected, double tol=1e-5) const { From e6993668efb26a9a6c2d60859f9bcd3728e9fabe Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Mon, 20 May 2013 17:26:53 +0000 Subject: [PATCH 014/256] Disabled extra debug-mode consistency checks that may affect runtime complexity, these are now only enabled when GTSAM_EXTRA_CONSISTENCY_CHECKS is defined --- gtsam/inference/BayesNet-inl.h | 2 +- gtsam/inference/BayesNet.h | 6 +++--- gtsam/inference/BayesTree-inl.h | 14 +------------- gtsam/inference/BayesTreeCliqueBase-inl.h | 10 +--------- gtsam/inference/Factor-inl.h | 2 +- gtsam/inference/IndexConditional.cpp | 2 +- gtsam/inference/JunctionTree-inl.h | 2 ++ gtsam/inference/VariableIndex.cpp | 2 +- gtsam/linear/GaussianFactorGraph.cpp | 4 ++-- gtsam/nonlinear/ISAM2-impl.cpp | 20 +++----------------- gtsam/nonlinear/ISAM2-inl.h | 4 ++-- gtsam/nonlinear/ISAM2.cpp | 13 +++++-------- 12 files changed, 23 insertions(+), 58 deletions(-) diff --git a/gtsam/inference/BayesNet-inl.h b/gtsam/inference/BayesNet-inl.h index 903826e3a..f0e26c98b 100644 --- a/gtsam/inference/BayesNet-inl.h +++ b/gtsam/inference/BayesNet-inl.h @@ -134,7 +134,7 @@ namespace gtsam { /* ************************************************************************* */ template void BayesNet::popLeaf(iterator conditional) { -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS BOOST_FOREACH(typename CONDITIONAL::shared_ptr checkConditional, conditionals_) { BOOST_FOREACH(Index key, (*conditional)->frontals()) { if(std::find(checkConditional->beginParents(), checkConditional->endParents(), key) != checkConditional->endParents()) diff --git a/gtsam/inference/BayesNet.h b/gtsam/inference/BayesNet.h index 7aa54b216..ad39da301 100644 --- a/gtsam/inference/BayesNet.h +++ b/gtsam/inference/BayesNet.h @@ -153,9 +153,9 @@ public: * particular key, use find(), which has \f$ O(n) \f$ complexity. The * popLeaf function by itself has \f$ O(1) \f$ complexity. * - * If gtsam is compiled without NDEBUG defined, this function will check that - * the node is indeed a leaf, but otherwise will not check, because the check - * has \f$ O(n^2) \f$ complexity. + * If gtsam is compiled with GTSAM_EXTRA_CONSISTENCY_CHECKS defined, this + * function will check that the node is indeed a leaf, but otherwise will + * not check, because the check has \f$ O(n^2) \f$ complexity. * * Example 1: \code diff --git a/gtsam/inference/BayesTree-inl.h b/gtsam/inference/BayesTree-inl.h index 3ebb502f2..9f672e56f 100644 --- a/gtsam/inference/BayesTree-inl.h +++ b/gtsam/inference/BayesTree-inl.h @@ -224,7 +224,7 @@ namespace gtsam { template inline void BayesTree::addToCliqueFront(BayesTree& bayesTree, const sharedConditional& conditional, const sharedClique& clique) { static const bool debug = false; -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS // Debug check to make sure the conditional variable is ordered lower than // its parents and that all of its parents are present either in this // clique or its separator. @@ -431,18 +431,6 @@ namespace gtsam { // if the parents and parent clique have the same size, add to parent clique if ((*parent_clique)->size() == size_t(parents.size())) { if(debug) std::cout << "Adding to parent clique" << std::endl; -#ifndef NDEBUG - // Debug check that the parent indices of the new conditional match the indices - // currently in the clique. -// list::const_iterator parent = parents.begin(); -// typename Clique::const_iterator cond = parent_clique->begin(); -// while(parent != parents.end()) { -// assert(cond != parent_clique->end()); -// assert(*parent == (*cond)->key()); -// ++ parent; -// ++ cond; -// } -#endif addToCliqueFront(bayesTree, conditional, parent_clique); } else { if(debug) std::cout << "Starting new clique" << std::endl; diff --git a/gtsam/inference/BayesTreeCliqueBase-inl.h b/gtsam/inference/BayesTreeCliqueBase-inl.h index 5f01aa395..e2ac492b7 100644 --- a/gtsam/inference/BayesTreeCliqueBase-inl.h +++ b/gtsam/inference/BayesTreeCliqueBase-inl.h @@ -24,14 +24,6 @@ namespace gtsam { /* ************************************************************************* */ template void BayesTreeCliqueBase::assertInvariants() const { -#ifndef NDEBUG - // We rely on the keys being sorted -// FastVector sortedUniqueKeys(conditional_->begin(), conditional_->end()); -// std::sort(sortedUniqueKeys.begin(), sortedUniqueKeys.end()); -// std::unique(sortedUniqueKeys.begin(), sortedUniqueKeys.end()); -// assert(sortedUniqueKeys.size() == conditional_->size() && -// std::equal(sortedUniqueKeys.begin(), sortedUniqueKeys.end(), conditional_->begin())); -#endif } /* ************************************************************************* */ @@ -138,7 +130,7 @@ namespace gtsam { const internal::Reduction& inverseReduction) { bool changed = conditional_->reduceSeparatorWithInverse(inverseReduction); -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS if(!changed) { BOOST_FOREACH(const derived_ptr& child, children_) { assert(child->reduceSeparatorWithInverse(inverseReduction) == false); } diff --git a/gtsam/inference/Factor-inl.h b/gtsam/inference/Factor-inl.h index 1283f44c6..7b22e083e 100644 --- a/gtsam/inference/Factor-inl.h +++ b/gtsam/inference/Factor-inl.h @@ -43,7 +43,7 @@ namespace gtsam { /* ************************************************************************* */ template void Factor::assertInvariants() const { -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS // Check that keys are all unique std::multiset nonunique(keys_.begin(), keys_.end()); std::set unique(keys_.begin(), keys_.end()); diff --git a/gtsam/inference/IndexConditional.cpp b/gtsam/inference/IndexConditional.cpp index f2ff4c645..20e978afe 100644 --- a/gtsam/inference/IndexConditional.cpp +++ b/gtsam/inference/IndexConditional.cpp @@ -39,7 +39,7 @@ namespace gtsam { /* ************************************************************************* */ bool IndexConditional::reduceSeparatorWithInverse(const internal::Reduction& inverseReduction) { -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS BOOST_FOREACH(KeyType key, frontals()) { assert(inverseReduction.find(key) == inverseReduction.end()); } #endif bool parentChanged = false; diff --git a/gtsam/inference/JunctionTree-inl.h b/gtsam/inference/JunctionTree-inl.h index 1fc58cbb6..1978bde38 100644 --- a/gtsam/inference/JunctionTree-inl.h +++ b/gtsam/inference/JunctionTree-inl.h @@ -169,7 +169,9 @@ namespace gtsam { current->frontal.size())); gttoc(CombineAndEliminate); +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS assert(std::equal(eliminated.second->begin(), eliminated.second->end(), current->separator.begin())); +#endif gttic(Update_tree); // create a new clique corresponding the combined factors diff --git a/gtsam/inference/VariableIndex.cpp b/gtsam/inference/VariableIndex.cpp index 11ce68ec6..91036e82a 100644 --- a/gtsam/inference/VariableIndex.cpp +++ b/gtsam/inference/VariableIndex.cpp @@ -92,7 +92,7 @@ void VariableIndex::permuteInPlace(const Permutation& selector, const Permutatio /* ************************************************************************* */ void VariableIndex::removeUnusedAtEnd(size_t nToRemove) { -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS for(size_t i = this->size() - nToRemove; i < this->size(); ++i) if(!(*this)[i].empty()) throw std::invalid_argument("Attempting to remove non-empty variables with VariableIndex::removeUnusedAtEnd()"); diff --git a/gtsam/linear/GaussianFactorGraph.cpp b/gtsam/linear/GaussianFactorGraph.cpp index d9212703b..b04287288 100644 --- a/gtsam/linear/GaussianFactorGraph.cpp +++ b/gtsam/linear/GaussianFactorGraph.cpp @@ -195,7 +195,7 @@ namespace gtsam { /* ************************************************************************* */ // Helper functions for Combine static boost::tuple, size_t, size_t> countDims(const FactorGraph& factors, const VariableSlots& variableSlots) { -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS vector varDims(variableSlots.size(), numeric_limits::max()); #else vector varDims(variableSlots.size()); @@ -213,7 +213,7 @@ namespace gtsam { if(sourceVarpos < numeric_limits::max()) { const JacobianFactor& sourceFactor = *factors[sourceFactorI]; size_t vardim = sourceFactor.getDim(sourceFactor.begin() + sourceVarpos); -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS if(varDims[jointVarpos] == numeric_limits::max()) { varDims[jointVarpos] = vardim; n += vardim; diff --git a/gtsam/nonlinear/ISAM2-impl.cpp b/gtsam/nonlinear/ISAM2-impl.cpp index b1034a594..9abd62016 100644 --- a/gtsam/nonlinear/ISAM2-impl.cpp +++ b/gtsam/nonlinear/ISAM2-impl.cpp @@ -303,7 +303,7 @@ ISAM2::Impl::PartialSolve(GaussianFactorGraph& factors, PartialSolveResult result; gttic(select_affected_variables); -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS // Debug check that all variables involved in the factors to be re-eliminated // are in affectedKeys, since we will use it to select a subset of variables. BOOST_FOREACH(const GaussianFactor::shared_ptr& factor, factors) { @@ -368,7 +368,7 @@ ISAM2::Impl::PartialSolve(GaussianFactorGraph& factors, if(debug) factors.print("Colamd-ordered affected factors: "); -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS VariableIndex fromScratchIndex(factors); assert(assert_equal(fromScratchIndex, affectedFactorsIndex)); #endif @@ -422,7 +422,7 @@ size_t ISAM2::Impl::UpdateDelta(const boost::shared_ptr& root, std: // Optimize with wildfire lastBacksubVariableCount = optimizeWildfireNonRecursive(root, wildfireThreshold, replacedKeys, delta); // modifies delta_ -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS for(size_t j=0; j)).all()); #endif @@ -487,20 +487,6 @@ size_t ISAM2::Impl::UpdateDoglegDeltas(const ISAM2& isam, double wildfireThresho internal::updateDoglegDeltas(isam.root(), replacedKeys, grad, deltaNewton, RgProd, varsUpdated); optimizeWildfireNonRecursive(isam.root(), wildfireThreshold, replacedKeys, deltaNewton); -#if 0 - VectorValues expected = *allocateVectorValues(isam); - internal::optimizeInPlace(isam.root(), expected); - for(size_t j = 0; j Rd_jfg(isam); - Errors Rg = Rd_jfg * grad; - double RgMagExpected = dot(Rg, Rg); - double RgMagActual = RgProd.container().vector().squaredNorm(); - cout << fabs(RgMagExpected - RgMagActual) << endl; - assert(fabs(RgMagExpected - RgMagActual) < (1e-8 * RgMagActual + 1e-4)); -#endif - replacedKeys.assign(replacedKeys.size(), false); return varsUpdated; diff --git a/gtsam/nonlinear/ISAM2-inl.h b/gtsam/nonlinear/ISAM2-inl.h index 87975f59b..4a9cf105a 100644 --- a/gtsam/nonlinear/ISAM2-inl.h +++ b/gtsam/nonlinear/ISAM2-inl.h @@ -44,7 +44,7 @@ void optimizeWildfire(const boost::shared_ptr& clique, double threshold, // Are any clique variables part of the tree that has been redone? bool cliqueReplaced = replaced[(*clique)->frontals().front()]; -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS BOOST_FOREACH(Index frontal, (*clique)->frontals()) { assert(cliqueReplaced == replaced[frontal]); } @@ -120,7 +120,7 @@ bool optimizeWildfireNode(const boost::shared_ptr& clique, double thresh // Are any clique variables part of the tree that has been redone? bool cliqueReplaced = replaced[(*clique)->frontals().front()]; -#ifndef NDEBUG +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS BOOST_FOREACH(Index frontal, (*clique)->frontals()) { assert(cliqueReplaced == replaced[frontal]); } diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index 3dc0b430d..9b063f0ce 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -201,14 +201,18 @@ ISAM2::relinearizeAffectedFactors(const FastList& affectedKeys, const Fas } if(inside) { if(useCachedLinear) { +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS assert(linearFactors_[idx]); - linearized->push_back(linearFactors_[idx]); assert(linearFactors_[idx]->keys() == nonlinearFactors_[idx]->symbolic(ordering_)->keys()); +#endif + linearized->push_back(linearFactors_[idx]); } else { GaussianFactor::shared_ptr linearFactor = nonlinearFactors_[idx]->linearize(theta_, ordering_); linearized->push_back(linearFactor); if(params_.cacheLinearizedFactors) { +#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS assert(linearFactors_[idx]->keys() == linearFactor->keys()); +#endif linearFactors_[idx] = linearFactor; } } @@ -230,13 +234,6 @@ GaussianFactorGraph ISAM2::getCachedBoundaryFactors(Cliques& orphans) { BOOST_FOREACH(sharedClique orphan, orphans) { // find the last variable that was eliminated Index key = (*orphan)->frontals().back(); -#ifndef NDEBUG -// typename BayesNet::const_iterator it = orphan->end(); -// const CONDITIONAL& lastCONDITIONAL = **(--it); -// typename CONDITIONAL::const_iterator keyit = lastCONDITIONAL.endParents(); -// const Index lastKey = *(--keyit); -// assert(key == lastKey); -#endif // retrieve the cached factor and add to boundary cachedBoundary.push_back(orphan->cachedFactor()); if(debug) { cout << "Cached factor for variable " << key; orphan->cachedFactor()->print(""); } From 3a13d6b2ad8ed0b8db258a42610e7c11dbe12cc6 Mon Sep 17 00:00:00 2001 From: Vadim Indelman Date: Mon, 20 May 2013 21:46:30 +0000 Subject: [PATCH 015/256] Added load2D_robust function to allow robust noise models when loading datasets. --- gtsam.h | 3 +- gtsam/slam/dataset.cpp | 97 ++++++++++++++++++++++++++++++++++++++++++ gtsam/slam/dataset.h | 4 ++ 3 files changed, 103 insertions(+), 1 deletion(-) diff --git a/gtsam.h b/gtsam.h index 04d02872e..0c393a433 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2089,7 +2089,8 @@ pair load2D(string filename, gtsam::noiseModel::Diagonal* model, int maxID); pair load2D(string filename, gtsam::noiseModel::Diagonal* model); - +pair load2D_robust(string filename, + gtsam::noiseModel::Base* model); //************************************************************************* // Utilities diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 6b5aeabd9..05bb6521b 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -256,6 +256,103 @@ bool load3D(const string& filename) { } return true; } + /* ************************************************************************* */ +pair load2D_robust( + const string& filename, noiseModel::Base::shared_ptr& model, int maxID) { + cout << "Will try to read " << filename << endl; + ifstream is(filename.c_str()); + if (!is) + throw std::invalid_argument("load2D: can not find the file!"); + + Values::shared_ptr initial(new Values); + NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph); + + string tag; + + // load the poses + while (is) { + is >> tag; + + if ((tag == "VERTEX2") || (tag == "VERTEX")) { + int id; + double x, y, yaw; + is >> id >> x >> y >> yaw; + // optional filter + if (maxID && id >= maxID) + continue; + initial->insert(id, Pose2(x, y, yaw)); + } + is.ignore(LINESIZE, '\n'); + } + is.clear(); /* clears the end-of-file and error flags */ + is.seekg(0, ios::beg); + + // Create a sampler with random number generator + Sampler sampler(42u); + + // load the factors + while (is) { + is >> tag; + + if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "ODOMETRY")) { + int id1, id2; + double x, y, yaw; + + is >> id1 >> id2 >> x >> y >> yaw; + Matrix m = eye(3); + is >> m(0, 0) >> m(0, 1) >> m(1, 1) >> m(2, 2) >> m(0, 2) >> m(1, 2); + m(2, 0) = m(0, 2); + m(2, 1) = m(1, 2); + m(1, 0) = m(0, 1); + + // optional filter + if (maxID && (id1 >= maxID || id2 >= maxID)) + continue; + + Pose2 l1Xl2(x, y, yaw); + + // Insert vertices if pure odometry file + if (!initial->exists(id1)) + initial->insert(id1, Pose2()); + if (!initial->exists(id2)) + initial->insert(id2, initial->at(id1) * l1Xl2); + + NonlinearFactor::shared_ptr factor( + new BetweenFactor(id1, id2, l1Xl2, model)); + graph->push_back(factor); + } + if (tag == "BR") { + int id1, id2; + double bearing, range, bearing_std, range_std; + + is >> id1 >> id2 >> bearing >> range >> bearing_std >> range_std; + + // optional filter + if (maxID && (id1 >= maxID || id2 >= maxID)) + continue; + + noiseModel::Diagonal::shared_ptr measurementNoise = + noiseModel::Diagonal::Sigmas(Vector_(2, bearing_std, range_std)); + graph->add(BearingRangeFactor(id1, id2, bearing, range, measurementNoise)); + + // Insert poses or points if they do not exist yet + if (!initial->exists(id1)) + initial->insert(id1, Pose2()); + if (!initial->exists(id2)) { + Pose2 pose = initial->at(id1); + Point2 local(cos(bearing)*range,sin(bearing)*range); + Point2 global = pose.transform_from(local); + initial->insert(id2, global); + } + } + is.ignore(LINESIZE, '\n'); + } + + cout << "load2D read a graph file with " << initial->size() + << " vertices and " << graph->nrFactors() << " factors" << endl; + + return make_pair(graph, initial); +} } // \namespace gtsam diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 9c70c2bea..053da842a 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -65,6 +65,10 @@ namespace gtsam { noiseModel::Diagonal::shared_ptr>(), int maxID = 0, bool addNoise = false, bool smart = true); + GTSAM_EXPORT std::pair load2D_robust( + const std::string& filename, + gtsam::noiseModel::Base::shared_ptr& model, int maxID = 0); + /** save 2d graph */ GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph, const Values& config, const noiseModel::Diagonal::shared_ptr model, const std::string& filename); From d05560687bf80c91dc728ec3275d37463a9be29b Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 20 May 2013 22:23:04 +0000 Subject: [PATCH 016/256] Avoid segfault on linking --- tests/CMakeLists.txt | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 59e801bda..0ebada21e 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -26,6 +26,11 @@ set (tests_exclude #"${CMAKE_CURRENT_SOURCE_DIR}/testOccupancyGrid.cpp" ) +if ("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") # might not be best test - Richard & Jason & Frank + # clang linker segfaults on large testSerializationSLAM + list (APPEND tests_exclude "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationSLAM.cpp") +endif() + if(MSVC) add_definitions("/bigobj") # testSerializationSLAM needs this endif() From 314b854ecb4934dbd5b00b2955a38612f85cec4f Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 20 May 2013 22:23:50 +0000 Subject: [PATCH 017/256] Use rr instead of r for squared radius in undistort --- gtsam/geometry/Cal3DS2.cpp | 50 +++++++++++++++++++------------------- gtsam/geometry/Cal3DS2.h | 6 ++--- 2 files changed, 28 insertions(+), 28 deletions(-) diff --git a/gtsam/geometry/Cal3DS2.cpp b/gtsam/geometry/Cal3DS2.cpp index 35e56a188..6816346e8 100644 --- a/gtsam/geometry/Cal3DS2.cpp +++ b/gtsam/geometry/Cal3DS2.cpp @@ -49,15 +49,15 @@ bool Cal3DS2::equals(const Cal3DS2& K, double tol) const { Point2 Cal3DS2::uncalibrate(const Point2& p, boost::optional H1, boost::optional H2) const { -// r = x^2 + y^2 ; -// g = (1 + k(1)*r + k(2)*r^2) ; -// dp = [2*k(3)*x*y + k(4)*(r + 2*x^2) ; 2*k(4)*x*y + k(3)*(r + 2*y^2)] ; +// rr = x^2 + y^2 ; +// g = (1 + k(1)*rr + k(2)*rr^2) ; +// dp = [2*k(3)*x*y + k(4)*(rr + 2*x^2) ; 2*k(4)*x*y + k(3)*(rr + 2*y^2)] ; // pi(:,i) = g * pn(:,i) + dp ; const double x = p.x(), y = p.y(), xy = x*y, xx = x*x, yy = y*y ; - const double r = xx + yy ; - const double g = (1+k1_*r+k2_*r*r) ; - const double dx = 2*k3_*xy + k4_*(r+2*xx) ; - const double dy = 2*k4_*xy + k3_*(r+2*yy) ; + const double rr = xx + yy ; + const double g = (1+k1_*rr+k2_*rr*rr) ; + const double dx = 2*k3_*xy + k4_*(rr+2*xx) ; + const double dy = 2*k4_*xy + k3_*(rr+2*yy) ; const double x2 = g*x + dx ; const double y2 = g*y + dy ; @@ -85,10 +85,10 @@ Point2 Cal3DS2::calibrate(const Point2& pi, const double tol) const { for ( iteration = 0 ; iteration < maxIterations ; ++iteration ) { if ( uncalibrate(pn).dist(pi) <= tol ) break; const double x = pn.x(), y = pn.y(), xy = x*y, xx = x*x, yy = y*y ; - const double r = xx + yy ; - const double g = (1+k1_*r+k2_*r*r) ; - const double dx = 2*k3_*xy + k4_*(r+2*xx) ; - const double dy = 2*k4_*xy + k3_*(r+2*yy) ; + const double rr = xx + yy ; + const double g = (1+k1_*rr+k2_*rr*rr) ; + const double dx = 2*k3_*xy + k4_*(rr+2*xx) ; + const double dy = 2*k4_*xy + k3_*(rr+2*yy) ; pn = (invKPi - Point2(dx,dy))/g ; } @@ -104,16 +104,16 @@ Matrix Cal3DS2::D2d_intrinsic(const Point2& p) const { const double k1 = k1_, k2 = k2_, k3 = k3_, k4 = k4_; //const double x = p.x(), y = p.y(), xx = x*x, yy = y*y, xy = x*y ; const double x = p.x(), y = p.y(), xx = x*x, yy = y*y ; - const double r = xx + yy ; + const double rr = xx + yy ; const double dr_dx = 2*x ; const double dr_dy = 2*y ; - const double r2 = r*r ; - const double g = 1 + k1*r + k2*r2 ; - const double dg_dx = k1*dr_dx + k2*2*r*dr_dx ; - const double dg_dy = k1*dr_dy + k2*2*r*dr_dy ; + const double r4 = rr*rr ; + const double g = 1 + k1*rr + k2*r4 ; + const double dg_dx = k1*dr_dx + k2*2*rr*dr_dx ; + const double dg_dy = k1*dr_dy + k2*2*rr*dr_dy ; - // Dx = 2*k3*xy + k4*(r+2*xx) ; - // Dy = 2*k4*xy + k3*(r+2*yy) ; + // Dx = 2*k3*xy + k4*(rr+2*xx) ; + // Dy = 2*k4*xy + k3*(rr+2*yy) ; const double dDx_dx = 2*k3*y + k4*(dr_dx + 4*x) ; const double dDx_dy = 2*k3*x + k4*dr_dy ; const double dDy_dx = 2*k4*y + k3*dr_dx ; @@ -129,18 +129,18 @@ Matrix Cal3DS2::D2d_intrinsic(const Point2& p) const { /* ************************************************************************* */ Matrix Cal3DS2::D2d_calibration(const Point2& p) const { const double x = p.x(), y = p.y(), xx = x*x, yy = y*y, xy = x*y ; - const double r = xx + yy ; - const double r2 = r*r ; + const double rr = xx + yy ; + const double r4 = rr*rr ; const double fx = fx_, fy = fy_, s = s_ ; - const double g = (1+k1_*r+k2_*r2) ; - const double dx = 2*k3_*xy + k4_*(r+2*xx) ; - const double dy = 2*k4_*xy + k3_*(r+2*yy) ; + const double g = (1+k1_*rr+k2_*r4) ; + const double dx = 2*k3_*xy + k4_*(rr+2*xx) ; + const double dy = 2*k4_*xy + k3_*(rr+2*yy) ; const double pnx = g*x + dx; const double pny = g*y + dy; return Matrix_(2, 9, - pnx, 0.0, pny, 1.0, 0.0, fx*x*r + s*y*r, fx*x*r2 + s*y*r2, fx*2*xy + s*(r+2*yy), fx*(r+2*xx) + s*(2*xy), - 0.0, pny, 0.0, 0.0, 1.0, fy*y*r , fy*y*r2 , fy*(r+2*yy) , fy*(2*xy) ); + pnx, 0.0, pny, 1.0, 0.0, fx*x*rr + s*y*rr, fx*x*r4 + s*y*r4, fx*2*xy + s*(rr+2*yy), fx*(rr+2*xx) + s*(2*xy), + 0.0, pny, 0.0, 0.0, 1.0, fy*y*rr , fy*y*r4 , fy*(rr+2*yy) , fy*(2*xy) ); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 6bf52d7e4..32a4654cb 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -37,9 +37,9 @@ private: double k3_, k4_ ; // tangential distortion // K = [ fx s u0 ; 0 fy v0 ; 0 0 1 ] - // r = Pn.x^2 + Pn.y^2 - // \hat{pn} = (1 + k1*r + k2*r^2 ) pn + [ 2*k3 pn.x pn.y + k4 (r + 2 Pn.x^2) ; - // k3 (r + 2 Pn.y^2) + 2*k4 pn.x pn.y ] + // rr = Pn.x^2 + Pn.y^2 + // \hat{pn} = (1 + k1*rr + k2*rr^2 ) pn + [ 2*k3 pn.x pn.y + k4 (rr + 2 Pn.x^2) ; + // k3 (rr + 2 Pn.y^2) + 2*k4 pn.x pn.y ] // pi = K*pn public: From 1d9000724d307f216f93535fa818970b0ef24923 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 20 May 2013 23:16:44 +0000 Subject: [PATCH 018/256] Moved AHRS to gtsam_unstable --- .cproject | 362 +++++++++++---------- gtsam_unstable/slam/AHRS.cpp | 244 ++++++++++++++ gtsam_unstable/slam/AHRS.h | 68 ++++ gtsam_unstable/slam/Mechanization_bRn2.cpp | 101 ++++++ gtsam_unstable/slam/Mechanization_bRn2.h | 81 +++++ gtsam_unstable/slam/doc/ypr.nb | 147 +++++++++ gtsam_unstable/slam/tests/testAHRS.cpp | 83 +++++ 7 files changed, 915 insertions(+), 171 deletions(-) create mode 100644 gtsam_unstable/slam/AHRS.cpp create mode 100644 gtsam_unstable/slam/AHRS.h create mode 100644 gtsam_unstable/slam/Mechanization_bRn2.cpp create mode 100644 gtsam_unstable/slam/Mechanization_bRn2.h create mode 100644 gtsam_unstable/slam/doc/ypr.nb create mode 100644 gtsam_unstable/slam/tests/testAHRS.cpp diff --git a/.cproject b/.cproject index 42416eeb8..e5b4e113a 100644 --- a/.cproject +++ b/.cproject @@ -1,5 +1,7 @@ - + + + @@ -307,14 +309,6 @@ true true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j2 @@ -341,6 +335,7 @@ make + tests/testBayesTree.run true false @@ -348,6 +343,7 @@ make + testBinaryBayesNet.run true false @@ -395,6 +391,7 @@ make + testSymbolicBayesNet.run true false @@ -402,6 +399,7 @@ make + tests/testSymbolicFactor.run true false @@ -409,6 +407,7 @@ make + testSymbolicFactorGraph.run true false @@ -424,11 +423,20 @@ make + tests/testBayesTree true false true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j5 @@ -517,22 +525,6 @@ false true - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - make -j2 @@ -549,6 +541,22 @@ true true + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + make -j2 @@ -573,34 +581,26 @@ true true - + make - -j5 - testValues.run + -j2 + all true true true - + make - -j5 - testOrdering.run + -j2 + check true true true - + make - -j5 - testKey.run - true - true - true - - - make - -j5 - testLinearContainerFactor.run + -j2 + clean true true true @@ -685,26 +685,34 @@ true true - + make - -j2 - all + -j5 + testValues.run true true true - + make - -j2 - check + -j5 + testOrdering.run true true true - + make - -j2 - clean + -j5 + testKey.run + true + true + true + + + make + -j5 + testLinearContainerFactor.run true true true @@ -821,6 +829,14 @@ true true + + make + -j5 + testAHRS.run + true + true + true + make -j5 @@ -1055,6 +1071,7 @@ make + testGraph.run true false @@ -1062,6 +1079,7 @@ make + testJunctionTree.run true false @@ -1069,6 +1087,7 @@ make + testSymbolicBayesNetB.run true false @@ -1236,6 +1255,7 @@ make + testErrors.run true false @@ -1281,14 +1301,6 @@ true true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j2 @@ -1369,6 +1381,14 @@ true true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j2 @@ -1675,7 +1695,6 @@ make - testSimulated2DOriented.run true false @@ -1715,7 +1734,6 @@ make - testSimulated2D.run true false @@ -1723,7 +1741,6 @@ make - testSimulated3D.run true false @@ -1923,7 +1940,6 @@ make - tests/testGaussianISAM2 true false @@ -1945,102 +1961,6 @@ true true - - make - -j2 - testRot3.run - true - true - true - - - make - -j2 - testRot2.run - true - true - true - - - make - -j2 - testPose3.run - true - true - true - - - make - -j2 - timeRot3.run - true - true - true - - - make - -j2 - testPose2.run - true - true - true - - - make - -j2 - testCal3_S2.run - true - true - true - - - make - -j2 - testSimpleCamera.run - true - true - true - - - make - -j2 - testHomography2.run - true - true - true - - - make - -j2 - testCalibratedCamera.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testPoint2.run - true - true - true - make -j3 @@ -2242,6 +2162,7 @@ cpack + -G DEB true false @@ -2249,6 +2170,7 @@ cpack + -G RPM true false @@ -2256,6 +2178,7 @@ cpack + -G TGZ true false @@ -2263,6 +2186,7 @@ cpack + --config CPackSourceConfig.cmake true false @@ -2404,34 +2328,98 @@ true true - + make - -j5 - testSpirit.run + -j2 + testRot3.run true true true - + make - -j5 - testWrap.run + -j2 + testRot2.run true true true - + make - -j5 - check.wrap + -j2 + testPose3.run true true true - + make - -j5 - wrap + -j2 + timeRot3.run + true + true + true + + + make + -j2 + testPose2.run + true + true + true + + + make + -j2 + testCal3_S2.run + true + true + true + + + make + -j2 + testSimpleCamera.run + true + true + true + + + make + -j2 + testHomography2.run + true + true + true + + + make + -j2 + testCalibratedCamera.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPoint2.run true true true @@ -2475,6 +2463,38 @@ false true + + make + -j5 + testSpirit.run + true + true + true + + + make + -j5 + testWrap.run + true + true + true + + + make + -j5 + check.wrap + true + true + true + + + make + -j5 + wrap + true + true + true + diff --git a/gtsam_unstable/slam/AHRS.cpp b/gtsam_unstable/slam/AHRS.cpp new file mode 100644 index 000000000..bee6bcef6 --- /dev/null +++ b/gtsam_unstable/slam/AHRS.cpp @@ -0,0 +1,244 @@ +/* + * @file AHRS.cpp + * @brief Attitude and Heading Reference System implementation + * Created on: Jan 26, 2012 + * Author: cbeall3 + */ + +#include "AHRS.h" +#include + +using namespace std; + +namespace gtsam { + +Matrix cov(const Matrix& m) { + const double num_observations = m.cols(); + const Vector mean = m.rowwise().sum() / num_observations; + Matrix D = m.colwise() - mean; + Matrix DDt = D * trans(D); + return DDt / (num_observations - 1); +} + +Matrix I3 = eye(3); +Matrix Z3 = zeros(3, 3); + +/* ************************************************************************* */ +AHRS::AHRS(const Matrix& stationaryU, const Matrix& stationaryF, double g_e) : + KF_(9) { + + // Initial state + mech0_ = Mechanization_bRn2::initialize(stationaryU, stationaryF, g_e); + + size_t T = stationaryU.cols(); + + // estimate standard deviation on gyroscope readings + Pg_ = cov(stationaryU); + Vector sigmas_v_g = esqrt(Pg_.diagonal() * T); + + // estimate standard deviation on accelerometer readings + Pa_ = cov(stationaryF); + + // Quantities needed for integration + + // dynamics, Chris' email September 23, 2011 3:38:05 PM EDT + double tau_g = 730; // correlation time for gyroscope + double tau_a = 730; // correlation time for accelerometer + + F_g_ = -I3 / tau_g; + F_a_ = -I3 / tau_a; + Vector var_omega_w = 0 * ones(3); // TODO + Vector var_omega_g = (0.0034 * 0.0034) * ones(3); + Vector var_omega_a = (0.034 * 0.034) * ones(3); + Vector sigmas_v_g_sq = emul(sigmas_v_g, sigmas_v_g); + Vector vars = concatVectors(4, &var_omega_w, &var_omega_g, &sigmas_v_g_sq, + &var_omega_a); + var_w_ = diag(vars); + + // Quantities needed for aiding + sigmas_v_a_ = esqrt(T * Pa_.diagonal()); + + // gravity in nav frame + n_g_ = Vector_(3, 0.0, 0.0, g_e); + n_g_cross_ = skewSymmetric(n_g_); // nav frame has Z down !!! +} + +/* ************************************************************************* */ +std::pair AHRS::initialize(double g_e) { + + // Calculate Omega_T, formula 2.80 in Farrell08book + double cp = cos(mech0_.bRn().inverse().pitch()); + double sp = sin(mech0_.bRn().inverse().pitch()); + double cy = cos(0); + double sy = sin(0); + Matrix Omega_T = Matrix_(3, 3, cy * cp, -sy, 0.0, sy * cp, cy, 0.0, -sp, 0.0, 1.0); + + // Calculate Jacobian of roll/pitch/yaw wrpt (g1,g2,g3), see doc/ypr.nb + Vector b_g = mech0_.b_g(g_e); + double g1 = b_g(0); + double g2 = b_g(1); + double g3 = b_g(2); + double g23 = g2 * g2 + g3 * g3; + double g123 = g1 * g1 + g23; + double f = 1 / (sqrt(g23) * g123); + Matrix H_g = Matrix_(3, 3, + 0.0, g3 / g23, -(g2 / g23), // roll + sqrt(g23) / g123, -f * (g1 * g2), -f * (g1 * g3), // pitch + 0.0, 0.0, 0.0); // we don't know anything on yaw + + // Calculate the initial covariance matrix for the error state dx, Farrell08book eq. 10.66 + Matrix Pa = 0.025 * 0.025 * eye(3); + Matrix P11 = Omega_T * (H_g * (Pa + Pa_) * trans(H_g)) * trans(Omega_T); + P11(2, 2) = 0.0001; + Matrix P12 = -Omega_T * H_g * Pa; + + Matrix P_plus_k2 = Matrix(9, 9); + P_plus_k2.block(0, 0, 3, 3) = P11; + P_plus_k2.block(0, 3, 3, 3) = Z3; + P_plus_k2.block(0, 6, 3, 3) = P12; + + P_plus_k2.block(3, 0, 3, 3) = Z3; + P_plus_k2.block(3, 3, 3, 3) = Pg_; + P_plus_k2.block(3, 6, 3, 3) = Z3; + + P_plus_k2.block(6, 0, 3, 3) = trans(P12); + P_plus_k2.block(6, 3, 3, 3) = Z3; + P_plus_k2.block(6, 6, 3, 3) = Pa; + + Vector dx = zero(9); + KalmanFilter::State state = KF_.init(dx, P_plus_k2); + return std::make_pair(mech0_, state); +} + +/* ************************************************************************* */ +std::pair AHRS::integrate( + const Mechanization_bRn2& mech, KalmanFilter::State state, + const Vector& u, double dt) { + + // Integrate full state + Mechanization_bRn2 newMech = mech.integrate(u, dt); + + // Integrate error state Kalman filter + // FIXME: + //if nargout>1 + Matrix bRn = mech.bRn().matrix(); + Matrix I3 = eye(3); + Matrix Z3 = zeros(3, 3); + + Matrix F_k = zeros(9, 9); + F_k.block(0, 3, 3, 3) = -bRn; + F_k.block(3, 3, 3, 3) = F_g_; + F_k.block(6, 6, 3, 3) = F_a_; + + Matrix G_k = zeros(9, 12); + G_k.block(0, 0, 3, 3) = -bRn; + G_k.block(0, 6, 3, 3) = -bRn; + G_k.block(3, 3, 3, 3) = I3; + G_k.block(6, 9, 3, 3) = I3; + + Matrix Q_k = G_k * var_w_ * trans(G_k); + Matrix Psi_k = eye(9) + dt * F_k; // +dt*dt*F_k*F_k/2; // transition matrix + + Matrix B = zeros(9, 9); + Vector u2 = zero(9); + KalmanFilter::State newState = KF_.predictQ(state, Psi_k,B,u2,dt*Q_k); + return make_pair(newMech, newState); +} + + +/* ************************************************************************* */ +std::pair AHRS::aid( + const Mechanization_bRn2& mech, KalmanFilter::State state, + const Vector& f, bool Farrell) { + + Matrix bRn = mech.bRn().matrix(); + + // get gravity in body from accelerometer + Vector measured_b_g = mech.x_a() - f; + + Matrix R, H; + Vector z; + if (Farrell) { + // calculate residual gravity measurement + z = n_g_ - trans(bRn) * measured_b_g; + H = collect(3, &n_g_cross_, &Z3, &bRn); + R = trans(bRn) * diag(emul(sigmas_v_a_, sigmas_v_a_)) * bRn; + } else { + // my measurement prediction (in body frame): + // F(:,k) = bias - b_g + // F(:,k) = mech.x_a + dx_a - bRn*n_g; + // F(:,k) = mech.x_a + dx_a - bRn*(I+P)*n_g; + // F(:,k) = mech.x_a + dx_a - b_g - bRn*(rho x n_g); // P = [rho]_x + // b_g - (mech.x_a - F(:,k)) = dx_a + bRn*(n_g x rho); + z = bRn * n_g_ - measured_b_g; + Matrix b_g = bRn * n_g_cross_; + H = collect(3, &b_g, &Z3, &I3); + R = diag(emul(sigmas_v_a_, sigmas_v_a_)); + } + +// update the Kalman filter + KalmanFilter::State updatedState = KF_.updateQ(state, H, z, R); + +// update full state (rotation and accelerometer bias) + Mechanization_bRn2 newMech = mech.correct(updatedState->mean()); + +// reset KF state + Vector dx = zeros(9, 1); + updatedState = KF_.init(dx, updatedState->covariance()); + + return make_pair(newMech, updatedState); +} + +/* ************************************************************************* */ +std::pair AHRS::aidGeneral( + const Mechanization_bRn2& mech, KalmanFilter::State state, + const Vector& f, const Vector& f_previous, + const Rot3& R_previous) { + + Matrix increment = R_previous.between(mech.bRn()).matrix(); + + // expected - measured + Vector z = f - increment * f_previous; + //Vector z = increment * f_previous - f; + Matrix b_g = skewSymmetric(increment* f_previous); + Matrix H = collect(3, &b_g, &I3, &Z3); +// Matrix R = diag(emul(sigmas_v_a_, sigmas_v_a_)); +// Matrix R = diag(Vector_(3, 1.0, 0.2, 1.0)); // good for L_twice + Matrix R = diag(Vector_(3, 0.01, 0.0001, 0.01)); + +// update the Kalman filter + KalmanFilter::State updatedState = KF_.updateQ(state, H, z, R); + +// update full state (rotation and gyro bias) + Mechanization_bRn2 newMech = mech.correct(updatedState->mean()); + +// reset KF state + Vector dx = zeros(9, 1); + updatedState = KF_.init(dx, updatedState->covariance()); + + return make_pair(newMech, updatedState); +} + +/* ************************************************************************* */ +void AHRS::print(const std::string& s) const { + mech0_.print(s + ".mech0_"); + gtsam::print(F_g_, s + ".F_g"); + gtsam::print(F_a_, s + ".F_a"); + gtsam::print(var_w_, s + ".var_w"); + + gtsam::print(sigmas_v_a_, s + ".sigmas_v_a"); + gtsam::print(n_g_, s + ".n_g"); + gtsam::print(n_g_cross_, s + ".n_g_cross"); + + gtsam::print(Pg_, s + ".P_g"); + gtsam::print(Pa_, s + ".P_a"); + +} + +/* ************************************************************************* */ +AHRS::~AHRS() { +} + +/* ************************************************************************* */ + +} /* namespace gtsam */ diff --git a/gtsam_unstable/slam/AHRS.h b/gtsam_unstable/slam/AHRS.h new file mode 100644 index 000000000..89f8b2b5e --- /dev/null +++ b/gtsam_unstable/slam/AHRS.h @@ -0,0 +1,68 @@ +/* + * AHRS.h + * + * Created on: Jan 26, 2012 + * Author: cbeall3 + */ + +#ifndef AHRS_H_ +#define AHRS_H_ + +#include "Mechanization_bRn2.h" +#include + +namespace gtsam { + +Matrix cov(const Matrix& m); + +class AHRS { + +private: + + // Initial state + Mechanization_bRn2 mech0_; ///< Initial mechanization state + KalmanFilter KF_; ///< initial Kalman filter + + // Quantities needed for integration + Matrix F_g_; ///< gyro bias dynamics + Matrix F_a_; ///< acc bias dynamics + Matrix var_w_; ///< dynamic noise variances + + // Quantities needed for aiding + Vector sigmas_v_a_; ///< measurement sigma + Vector n_g_; ///< gravity in nav frame + Matrix n_g_cross_; ///< and its skew-symmetric matrix + + Matrix Pg_, Pa_; + +public: + /** + * AHRS constructor + * @param stationaryU initial interval of gyro measurements, 3xn matrix + * @param stationaryF initial interval of accelerator measurements, 3xn matrix + * @param g_e if given, initializes gravity with correct value g_e + */ + AHRS(const Matrix& stationaryU, const Matrix& stationaryF, double g_e); + + std::pair initialize(double g_e); + + std::pair integrate( + const Mechanization_bRn2& mech, KalmanFilter::State state, + const Vector& u, double dt); + + std::pair aid( + const Mechanization_bRn2& mech, KalmanFilter::State state, + const Vector& f, bool Farrell=0); + + std::pair aidGeneral( + const Mechanization_bRn2& mech, KalmanFilter::State state, + const Vector& f, const Vector& f_expected, const Rot3& R_previous); + + /// print + void print(const std::string& s = "") const; + + virtual ~AHRS(); +}; + +} /* namespace gtsam */ +#endif /* AHRS_H_ */ diff --git a/gtsam_unstable/slam/Mechanization_bRn2.cpp b/gtsam_unstable/slam/Mechanization_bRn2.cpp new file mode 100644 index 000000000..ca95843af --- /dev/null +++ b/gtsam_unstable/slam/Mechanization_bRn2.cpp @@ -0,0 +1,101 @@ +/** + * @file Mechanization_bRn.cpp + * @date Jan 25, 2012 + * @author Chris Beall + * @author Frank Dellaert + */ + +#include "Mechanization_bRn2.h" +#include + +namespace gtsam { + +/* ************************************************************************* */ +Mechanization_bRn2 Mechanization_bRn2::initializeVector(const std::list& U, + const std::list& F, const double g_e) { + Matrix Umat = Matrix_(3,U.size(), concatVectors(U)); + Matrix Fmat = Matrix_(3,F.size(), concatVectors(F)); + + return initialize(Umat, Fmat, g_e); +} + + +/* ************************************************************************* */ +Mechanization_bRn2 Mechanization_bRn2::initialize(const Matrix& U, + const Matrix& F, const double g_e) { + + // estimate gyro bias by averaging gyroscope readings (10.62) + Vector x_g = U.rowwise().mean(); + Vector meanF = -F.rowwise().mean(); + + Vector b_g, x_a; + if(g_e == 0) { + // estimate gravity in body frame from accelerometer (10.13) + b_g = meanF; + // estimate accelerometer bias as zero (10.65) + x_a = zero(3); + + } else { + // normalize b_g and attribute remainder to biases + b_g = g_e * meanF/meanF.norm(); + x_a = -(meanF - b_g); + } + + // initialize roll, pitch (eqns. 10.14, 10.15) + double g1=b_g(0); + double g2=b_g(1); + double g3=b_g(2); + + // Farrell08book eqn. 10.14 + double roll = atan2(g2, g3); + // Farrell08book eqn. 10.15 + double pitch = atan2(-g1, sqrt(g2 * g2 + g3 * g3)); + double yaw = 0; + // This returns body-to-nav nRb + Rot3 bRn = Rot3::ypr(yaw, pitch, roll).inverse(); + + return Mechanization_bRn2(bRn, x_g, x_a); +} + +/* ************************************************************************* */ +Mechanization_bRn2 Mechanization_bRn2::correct(const Vector& dx) const { + Vector rho = sub(dx, 0, 3); + + Rot3 delta_nRn = Rot3::rodriguez(rho); + Rot3 bRn = bRn_ * delta_nRn; + + Vector x_g = x_g_ + sub(dx, 3, 6); + Vector x_a = x_a_ + sub(dx, 6, 9); + + return Mechanization_bRn2(bRn, x_g, x_a); +} + +/* ************************************************************************* */ +Mechanization_bRn2 Mechanization_bRn2::integrate(const Vector& u, + const double dt) const { + // integrate rotation nRb based on gyro measurement u and bias x_g + + // get body to inertial (measured in b) from gyro, subtract bias + Vector b_omega_ib = u - x_g_; + + // assume nav to inertial through movement is unknown + Vector b_omega_in = zero(3); + + // get angular velocity on bRn measured in body frame + Vector b_omega_bn = b_omega_in - b_omega_ib; + + // convert to navigation frame + Rot3 nRb = bRn_.inverse(); + Vector n_omega_bn = (nRb*b_omega_bn).vector(); + + // integrate bRn using exponential map, assuming constant over dt + Rot3 delta_nRn = Rot3::rodriguez(n_omega_bn*dt); + Rot3 bRn = bRn_.compose(delta_nRn); + + // implicit updating of biases (variables just do not change) + // x_g = x_g; + // x_a = x_a; + return Mechanization_bRn2(bRn, x_g_, x_a_); +} + +} /* namespace gtsam */ diff --git a/gtsam_unstable/slam/Mechanization_bRn2.h b/gtsam_unstable/slam/Mechanization_bRn2.h new file mode 100644 index 000000000..0a71da06d --- /dev/null +++ b/gtsam_unstable/slam/Mechanization_bRn2.h @@ -0,0 +1,81 @@ +/** + * @file Mechanization_bRn.h + * @date Jan 25, 2012 + * @author Chris Beall + * @author Frank Dellaert + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +class Mechanization_bRn2 { + +private: + Rot3 bRn_; ///< rotation from nav to body + Vector x_g_; ///< gyroscope bias + Vector x_a_; ///< accelerometer bias + +public: + + /** + * Constructor + * @param initial_bRn initial rotation from nav to body frame + * @param initial_x_g initial gyro bias + * @param r3 Z-axis of rotated frame + */ + Mechanization_bRn2(const Rot3& initial_bRn = Rot3(), + const Vector& initial_x_g = zero(3), const Vector& initial_x_a = zero(3)) : + bRn_(initial_bRn), x_g_(initial_x_g), x_a_(initial_x_a) { + } + + Vector b_g(double g_e) { + Vector n_g = Vector_(3, 0.0, 0.0, g_e); + return (bRn_ * n_g).vector(); + } + + Rot3 bRn() const {return bRn_; } + Vector x_g() const { return x_g_; } + Vector x_a() const { return x_a_; } + + /** + * Initialize the first Mechanization state + * @param U a list of gyro measurement vectors + * @param F a list of accelerometer measurement vectors + */ + static Mechanization_bRn2 initializeVector(const std::list& U, + const std::list& F, const double g_e = 0); + + static Mechanization_bRn2 initialize(const Matrix& U, + const Matrix& F, const double g_e = 0); + + /** + * Correct AHRS full state given error state dx + * @param obj The current state + * @param dx The error used to correct and return a new state + */ + Mechanization_bRn2 correct(const Vector& dx) const; + + /** + * Integrate to get new state + * @param obj The current state + * @param u gyro measurement to integrate + * @param dt time elapsed since previous state in seconds + */ + Mechanization_bRn2 integrate(const Vector& u, const double dt) const; + + /// print + void print(const std::string& s = "") const { + bRn_.print(s + ".R"); + + gtsam::print(x_g_, s + ".x_g"); + gtsam::print(x_a_, s + ".x_a"); + } + +}; + +} // namespace gtsam diff --git a/gtsam_unstable/slam/doc/ypr.nb b/gtsam_unstable/slam/doc/ypr.nb new file mode 100644 index 000000000..e21cc18f1 --- /dev/null +++ b/gtsam_unstable/slam/doc/ypr.nb @@ -0,0 +1,147 @@ +(* Content-type: application/vnd.wolfram.mathematica *) + +(*** Wolfram Notebook File ***) +(* http://www.wolfram.com/nb *) + +(* CreatedBy='Mathematica 8.0' *) + +(*CacheID: 234*) +(* Internal cache information: +NotebookFileLineBreakTest +NotebookFileLineBreakTest +NotebookDataPosition[ 157, 7] +NotebookDataLength[ 3876, 137] +NotebookOptionsPosition[ 3514, 119] +NotebookOutlinePosition[ 3867, 135] +CellTagsIndexPosition[ 3824, 132] +WindowFrame->Normal*) + +(* Beginning of Notebook Content *) +Notebook[{ +Cell[BoxData[{ + RowBox[{ + RowBox[{"roll", "=", + RowBox[{"ArcTan", "[", + RowBox[{"g3", ",", "g2"}], "]"}]}], ";"}], "\n", + RowBox[{ + RowBox[{"pitch", "=", + RowBox[{"ArcTan", "[", + RowBox[{ + RowBox[{"-", "g1"}], ",", + SqrtBox[ + RowBox[{ + SuperscriptBox["g2", "2"], "+", + SuperscriptBox["g3", "2"]}]]}], "]"}]}], ";"}], "\n"}], "Input", + CellChangeTimes->{{3.535838264320565*^9, 3.535838380686434*^9}, { + 3.53583852660116*^9, 3.5358385374458313`*^9}, {3.5358391717151127`*^9, + 3.535839173489215*^9}}], + +Cell[CellGroupData[{ + +Cell[BoxData[ + RowBox[{ + RowBox[{"(", "\[NoBreak]", GridBox[{ + { + RowBox[{"D", "[", + RowBox[{"roll", ",", "g1"}], "]"}], + RowBox[{"D", "[", + RowBox[{"roll", ",", "g2"}], "]"}], + RowBox[{"D", "[", + RowBox[{"roll", ",", "g3"}], "]"}]}, + { + RowBox[{"D", "[", + RowBox[{"pitch", ",", "g1"}], "]"}], + RowBox[{"D", "[", + RowBox[{"pitch", ",", "g2"}], "]"}], + RowBox[{"D", "[", + RowBox[{"pitch", ",", "g3"}], "]"}]}, + {"0", "0", "0"} + }], "\[NoBreak]", ")"}], "//", "FullSimplify"}]], "Input", + CellChangeTimes->{{3.535838384786139*^9, 3.535838492987266*^9}, { + 3.535838580947555*^9, 3.535838595178028*^9}}], + +Cell[BoxData[ + RowBox[{"{", + RowBox[{ + RowBox[{"{", + RowBox[{"0", ",", + FractionBox["g3", + RowBox[{ + SuperscriptBox["g2", "2"], "+", + SuperscriptBox["g3", "2"]}]], ",", + RowBox[{"-", + FractionBox["g2", + RowBox[{ + SuperscriptBox["g2", "2"], "+", + SuperscriptBox["g3", "2"]}]]}]}], "}"}], ",", + RowBox[{"{", + RowBox[{ + FractionBox[ + SqrtBox[ + RowBox[{ + SuperscriptBox["g2", "2"], "+", + SuperscriptBox["g3", "2"]}]], + RowBox[{ + SuperscriptBox["g1", "2"], "+", + SuperscriptBox["g2", "2"], "+", + SuperscriptBox["g3", "2"]}]], ",", + RowBox[{"-", + FractionBox[ + RowBox[{"g1", " ", "g2"}], + RowBox[{ + SqrtBox[ + RowBox[{ + SuperscriptBox["g2", "2"], "+", + SuperscriptBox["g3", "2"]}]], " ", + RowBox[{"(", + RowBox[{ + SuperscriptBox["g1", "2"], "+", + SuperscriptBox["g2", "2"], "+", + SuperscriptBox["g3", "2"]}], ")"}]}]]}], ",", + RowBox[{"-", + FractionBox[ + RowBox[{"g1", " ", "g3"}], + RowBox[{ + SqrtBox[ + RowBox[{ + SuperscriptBox["g2", "2"], "+", + SuperscriptBox["g3", "2"]}]], " ", + RowBox[{"(", + RowBox[{ + SuperscriptBox["g1", "2"], "+", + SuperscriptBox["g2", "2"], "+", + SuperscriptBox["g3", "2"]}], ")"}]}]]}]}], "}"}], ",", + RowBox[{"{", + RowBox[{"0", ",", "0", ",", "0"}], "}"}]}], "}"}]], "Output", + CellChangeTimes->{{3.5358383879873047`*^9, 3.535838493685678*^9}, + 3.53583853974876*^9, {3.535838581771779*^9, 3.535838595765464*^9}}] +}, Open ]] +}, +WindowSize->{740, 752}, +WindowMargins->{{4, Automatic}, {Automatic, 4}}, +FrontEndVersion->"8.0 for Mac OS X x86 (32-bit, 64-bit Kernel) (October 5, \ +2011)", +StyleDefinitions->"Default.nb" +] +(* End of Notebook Content *) + +(* Internal cache information *) +(*CellTagsOutline +CellTagsIndex->{} +*) +(*CellTagsIndex +CellTagsIndex->{} +*) +(*NotebookFileOutline +Notebook[{ +Cell[557, 20, 544, 16, 75, "Input"], +Cell[CellGroupData[{ +Cell[1126, 40, 692, 20, 61, "Input"], +Cell[1821, 62, 1677, 54, 109, "Output"] +}, Open ]] +} +] +*) + +(* End of internal cache information *) + diff --git a/gtsam_unstable/slam/tests/testAHRS.cpp b/gtsam_unstable/slam/tests/testAHRS.cpp new file mode 100644 index 000000000..f9731113b --- /dev/null +++ b/gtsam_unstable/slam/tests/testAHRS.cpp @@ -0,0 +1,83 @@ +/* + * @file testAHRS.cpp + * @brief Test AHRS + * @author Frank Dellaert + * @author Chris Beall + */ + +#include +#include +#include +#include "../AHRS.h" +#include + +using namespace std; +using namespace gtsam; + +// stationary interval of gyro U and acc F +Matrix stationaryU = trans(Matrix_(3,3,-0.0004,-0.0002,-0.0014,0.0006,-0.0003,0.0007,0.0006,-0.0002,-0.0003)); +Matrix stationaryF = trans(Matrix_(3,3,0.1152,-0.0188,9.7419,-0.0163,0.0146,9.7753,-0.0283,-0.0428,9.9021)); +double g_e = 9.7963; // Atlanta + +/* ************************************************************************* */ +TEST (AHRS, cov) { + + // samples stored by row + Matrix A = Matrix_(4, 3, + 1.0, 2.0, 3.0, + 5.0, 7.0, 0.0, + 9.0, 4.0, 7.0, + 6.0, 3.0, 2.0); + + Matrix actual = cov(trans(A)); + Matrix expected = Matrix_(3, 3, + 10.9167, 2.3333, 5.0000, + 2.3333, 4.6667, -2.6667, + 5.0000, -2.6667, 8.6667); + + EXPECT(assert_equal(expected, actual, 1e-4)); +} + +/* ************************************************************************* */ +TEST (AHRS, covU) { + + Matrix actual = cov(10000*stationaryU); + Matrix expected = Matrix_(3, 3, + 33.3333333, -1.66666667, 53.3333333, + -1.66666667, 0.333333333, -5.16666667, + 53.3333333, -5.16666667, 110.333333); + + EXPECT(assert_equal(expected, actual, 1e-4)); +} + +/* ************************************************************************* */ +TEST (AHRS, covF) { + + Matrix actual = cov(100*stationaryF); + Matrix expected = Matrix_(3, 3, + 63.3808333, -0.432166667, -48.1706667, + -0.432166667, 8.31053333, -16.6792667, + -48.1706667, -16.6792667, 71.4297333); + + EXPECT(assert_equal(expected, actual, 1e-4)); +} + +/* ************************************************************************* */ +TEST (AHRS, constructor) { + AHRS ahrs = AHRS(stationaryU,stationaryF,g_e); +} + +/* ************************************************************************* */ +/* TODO: currently fails because of problem with ill-conditioned system +TEST (AHRS, init) { + AHRS ahrs = AHRS(stationaryU,stationaryF,g_e); + std::pair result = ahrs.initialize(g_e); +} +*/ +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + From 03977ba628ae7bd264c66fbb64c08402514a5b2a Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 20 May 2013 23:28:38 +0000 Subject: [PATCH 019/256] Added wrapping of AHRS --- gtsam_unstable/gtsam_unstable.h | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index fc2fc1fff..27dd8ba1c 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -28,6 +28,7 @@ class gtsam::KeySet; class gtsam::KeyVector; class gtsam::LevenbergMarquardtParams; class gtsam::ISAM2Params; +class gtsam::GaussianDensity; namespace gtsam { @@ -599,4 +600,29 @@ virtual class InvDepthFactorVariant3b : gtsam::NonlinearFactor { InvDepthFactorVariant3b(size_t poseKey1, size_t poseKey2, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model); }; +#include +class Mechanization_bRn2 { + Mechanization_bRn2(); + Mechanization_bRn2(gtsam::Rot3& initial_bRn, Vector initial_x_g, + Vector initial_x_a); + Vector b_g(double g_e); + gtsam::Rot3 bRn(); + Vector x_g(); + Vector x_a(); + static gtsam::Mechanization_bRn2 initialize(Matrix U, Matrix F, double g_e); + gtsam::Mechanization_bRn2 correct(Vector dx) const; + gtsam::Mechanization_bRn2 integrate(Vector u, double dt) const; + void print(string s) const; +}; + +#include +class AHRS { + AHRS(Matrix U, Matrix F, double g_e); + pair initialize(double g_e); + pair integrate(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector u, double dt); + pair aid(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, bool Farrel); + pair aidGeneral(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, Vector f_expected, const gtsam::Rot3& increment); + void print(string s) const; +}; + } //\namespace gtsam From 77c2e37a4da4f0388bce61d1b494aa5670bac28c Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Tue, 21 May 2013 00:03:05 +0000 Subject: [PATCH 020/256] remove unused debug variables --- gtsam_unstable/dynamics/SimpleHelicopter.h | 4 ---- 1 file changed, 4 deletions(-) diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index eadcb8739..94bbc6092 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -46,8 +46,6 @@ public: boost::optional H2 = boost::none, boost::optional H3 = boost::none) const { - static const bool debug = false; - Matrix D_gkxi_gk, D_gkxi_exphxi; Pose3 gkxi = gk.compose(Pose3::Expmap(h_*xik), D_gkxi_gk, D_gkxi_exphxi); @@ -115,8 +113,6 @@ public: boost::optional H2 = boost::none, boost::optional H3 = boost::none) const { - static const bool debug = false; - Vector muk = Inertia_*xik; Vector muk_1 = Inertia_*xik_1; From 6b47aaeba387a028c76d5f1f65bca321a8161c17 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 21 May 2013 14:18:01 +0000 Subject: [PATCH 021/256] Added cmake option for extra consistency checks and added functionality to Pose3 expmap flag --- CMakeLists.txt | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 159975c77..e4b6efb0e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -58,6 +58,7 @@ if(NOT MSVC) option(GTSAM_BUILD_CONVENIENCE_LIBRARIES "Enable/Disable use of convenience libraries for faster development rebuilds, but slower install" OFF) endif() option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." OFF) +option(GTSAM_ENABLE_CONSISTENCY_CHECKS "Enable/Disable expensive consistency checks" OFF) # Options relating to MATLAB wrapper # TODO: Check for matlab mex binary before handling building of binaries @@ -172,6 +173,13 @@ if(MSVC) add_definitions(/wd4251 /wd4275 /wd4251) # Disable non-DLL-exported base class warnings endif() +if(GTSAM_ENABLE_CONSISTENCY_CHECKS) + add_definitions(-DGTSAM_EXTRA_CONSISTENCY_CHECKS) +endif() + +if(GTSAM_POSE3_EXPMAP) + add_definitions(-DGTSAM_POSE3_EXPMAP) +endif() ############################################################################### # Add components @@ -287,7 +295,9 @@ message(STATUS " CPack Source Generator message(STATUS " CPack Generator : ${CPACK_GENERATOR}") message(STATUS "GTSAM flags ") -print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default Rot3") +print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default Rot3 ") +print_config_flag(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ") +print_config_flag(${GTSAM_POSE3_EXPMAP} "Using full expmap as defaul retract for Pose3 ") message(STATUS "MATLAB toolbox flags ") print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox ") From 13d3f1cb6e4da5fee68f8a8d54d8dd7bef349902 Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Tue, 21 May 2013 14:57:40 +0000 Subject: [PATCH 022/256] Updated Fixed-Lag smoother example --- gtsam_unstable/examples/FixedLagSmootherExample.cpp | 8 +++++++- gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp | 13 +++++-------- 2 files changed, 12 insertions(+), 9 deletions(-) diff --git a/gtsam_unstable/examples/FixedLagSmootherExample.cpp b/gtsam_unstable/examples/FixedLagSmootherExample.cpp index 4c2b9ba89..69712540c 100644 --- a/gtsam_unstable/examples/FixedLagSmootherExample.cpp +++ b/gtsam_unstable/examples/FixedLagSmootherExample.cpp @@ -65,7 +65,10 @@ int main(int argc, char** argv) { // The Batch version uses Levenberg-Marquardt to perform the nonlinear optimization BatchFixedLagSmoother smootherBatch(lag); // The Incremental version uses iSAM2 to perform the nonlinear optimization - IncrementalFixedLagSmoother smootherISAM2(lag); + ISAM2Params parameters; + parameters.relinearizeThreshold = 0.0; // Set the relin threshold to zero such that the batch estimate is recovered + parameters.relinearizeSkip = 1; // Relinearize every time + IncrementalFixedLagSmoother smootherISAM2(lag, parameters); // Create containers to store the factors and linearization points that // will be sent to the smoothers @@ -111,6 +114,9 @@ int main(int argc, char** argv) { // Update the smoothers with the new factors smootherBatch.update(newFactors, newValues, newTimestamps); smootherISAM2.update(newFactors, newValues, newTimestamps); + for(size_t i = 1; i < 2; ++i) { // Optionally perform multiple iSAM2 iterations + smootherISAM2.update(); + } // Print the optimized current pose cout << setprecision(5) << "Timestamp = " << time << endl; diff --git a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp index 7e8c4cddf..0a84d307a 100644 --- a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp +++ b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp @@ -233,7 +233,7 @@ FixedLagSmoother::Result BatchFixedLagSmoother::optimize() { // Create a Values that holds the current evaluation point Values evalpoint = theta_.retract(delta_, ordering_); result.error = factors_.error(evalpoint); -std::cout << "Initial Error = " << result.error << std::endl; + // Use a custom optimization loop so the linearization points can be controlled double previousError; VectorValues newDelta; @@ -266,22 +266,20 @@ std::cout << "Initial Error = " << result.error << std::endl; } gttoc(damp); result.intermediateSteps++; -std::cout << "Trying Lambda = " << lambda << std::endl; + gttic(solve); // Solve Damped Gaussian Factor Graph newDelta = GaussianJunctionTree(dampedFactorGraph).optimize(parameters_.getEliminationFunction()); // update the evalpoint with the new delta evalpoint = theta_.retract(newDelta, ordering_); gttoc(solve); -std::cout << " Max Delta = " << newDelta.asVector().maxCoeff() << std::endl; + // Evaluate the new error gttic(compute_error); double error = factors_.error(evalpoint); gttoc(compute_error); -std::cout << " New Error = " << error << std::endl; -std::cout << " Change = " << result.error - error << std::endl; + if(error < result.error) { -std::cout << " Keeping Change" << std::endl; // Keep this change // Update the error value result.error = error; @@ -305,7 +303,6 @@ std::cout << " Keeping Change" << std::endl; // End this lambda search iteration break; } else { -std::cout << " Rejecting Change" << std::endl; // Reject this change // Increase lambda and continue searching lambda *= lambdaFactor; @@ -322,7 +319,7 @@ std::cout << " Rejecting Change" << std::endl; result.iterations++; } while(result.iterations < maxIterations && !checkConvergence(relativeErrorTol, absoluteErrorTol, errorTol, previousError, result.error, NonlinearOptimizerParams::SILENT)); -std::cout << "Final Error = " << result.error << std::endl; + return result; } From cd470df6721f546ff8ad5346b024fa9c615f569b Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Tue, 21 May 2013 15:23:42 +0000 Subject: [PATCH 023/256] Added GTSAM_EXPORT tags --- gtsam/nonlinear/Key.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/nonlinear/Key.h b/gtsam/nonlinear/Key.h index d7e7ed224..bcc08d9cd 100644 --- a/gtsam/nonlinear/Key.h +++ b/gtsam/nonlinear/Key.h @@ -58,16 +58,16 @@ namespace gtsam { typedef FastSet KeySet; /// Utility function to print sets of keys with optional prefix - void printKeySet(const KeySet& keys, const std::string& s = "", + GTSAM_EXPORT void printKeySet(const KeySet& keys, const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter); /// Computes the intersection between two sets - gtsam::KeySet keyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); + GTSAM_EXPORT gtsam::KeySet keyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); /// Checks if an intersection exists - faster checking size of above - bool hasKeyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); + GTSAM_EXPORT bool hasKeyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); /// Computes a difference between sets, so result is those that are in A, but not B - gtsam::KeySet keyDifference(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); + GTSAM_EXPORT gtsam::KeySet keyDifference(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); } From 16c11c70fb573f44558205e1551f4ad5541ddda0 Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Tue, 21 May 2013 17:24:49 +0000 Subject: [PATCH 024/256] Fixes to compile on Windows --- gtsam_unstable/slam/AHRS.cpp | 4 ++-- gtsam_unstable/slam/AHRS.h | 3 ++- gtsam_unstable/slam/Mechanization_bRn2.h | 3 ++- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/gtsam_unstable/slam/AHRS.cpp b/gtsam_unstable/slam/AHRS.cpp index bee6bcef6..cbd1096a9 100644 --- a/gtsam_unstable/slam/AHRS.cpp +++ b/gtsam_unstable/slam/AHRS.cpp @@ -80,10 +80,10 @@ std::pair AHRS::initialize(double g_e) double g3 = b_g(2); double g23 = g2 * g2 + g3 * g3; double g123 = g1 * g1 + g23; - double f = 1 / (sqrt(g23) * g123); + double f = 1 / (std::sqrt(g23) * g123); Matrix H_g = Matrix_(3, 3, 0.0, g3 / g23, -(g2 / g23), // roll - sqrt(g23) / g123, -f * (g1 * g2), -f * (g1 * g3), // pitch + std::sqrt(g23) / g123, -f * (g1 * g2), -f * (g1 * g3), // pitch 0.0, 0.0, 0.0); // we don't know anything on yaw // Calculate the initial covariance matrix for the error state dx, Farrell08book eq. 10.66 diff --git a/gtsam_unstable/slam/AHRS.h b/gtsam_unstable/slam/AHRS.h index 89f8b2b5e..284fe2fc6 100644 --- a/gtsam_unstable/slam/AHRS.h +++ b/gtsam_unstable/slam/AHRS.h @@ -9,13 +9,14 @@ #define AHRS_H_ #include "Mechanization_bRn2.h" +#include #include namespace gtsam { Matrix cov(const Matrix& m); -class AHRS { +class GTSAM_UNSTABLE_EXPORT AHRS { private: diff --git a/gtsam_unstable/slam/Mechanization_bRn2.h b/gtsam_unstable/slam/Mechanization_bRn2.h index 0a71da06d..b81e685d4 100644 --- a/gtsam_unstable/slam/Mechanization_bRn2.h +++ b/gtsam_unstable/slam/Mechanization_bRn2.h @@ -9,11 +9,12 @@ #include #include +#include #include namespace gtsam { -class Mechanization_bRn2 { +class GTSAM_UNSTABLE_EXPORT Mechanization_bRn2 { private: Rot3 bRn_; ///< rotation from nav to body From 48fc15552afe256b01c9842056678e831c2b792a Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 21 May 2013 17:50:04 +0000 Subject: [PATCH 025/256] Moved key utilty functions back to MastSLAM --- gtsam.h | 5 ----- gtsam/nonlinear/Key.cpp | 33 --------------------------------- gtsam/nonlinear/Key.h | 9 --------- 3 files changed, 47 deletions(-) diff --git a/gtsam.h b/gtsam.h index 0c393a433..dbd3d9fad 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1450,11 +1450,6 @@ size_t symbol(char chr, size_t index); char symbolChr(size_t key); size_t symbolIndex(size_t key); -// Key utilities -gtsam::KeySet keyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); -gtsam::KeySet keyDifference(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); -bool hasKeyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); - // Default keyformatter void printKeySet(const gtsam::KeySet& keys); void printKeySet(const gtsam::KeySet& keys, string s); diff --git a/gtsam/nonlinear/Key.cpp b/gtsam/nonlinear/Key.cpp index fe9f8c480..c4b21e681 100644 --- a/gtsam/nonlinear/Key.cpp +++ b/gtsam/nonlinear/Key.cpp @@ -60,39 +60,6 @@ void printKeySet(const gtsam::KeySet& keys, const std::string& s, const KeyForma std::cout << std::endl; } } - -/* ************************************************************************* */ -gtsam::KeySet keyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB) { - gtsam::KeySet intersection; - if (keysA.empty() || keysB.empty()) - return intersection; - BOOST_FOREACH(const gtsam::Key& key, keysA) - if (keysB.count(key)) - intersection.insert(key); - return intersection; -} - -/* ************************************************************************* */ -bool hasKeyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB) { - if (keysA.empty() || keysB.empty()) - return false; - BOOST_FOREACH(const gtsam::Key& key, keysA) - if (keysB.count(key)) - return true; - return false; -} - -/* ************************************************************************* */ -gtsam::KeySet keyDifference(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB) { - if (keysA.empty() || keysB.empty()) - return keysA; - - gtsam::KeySet difference; - BOOST_FOREACH(const gtsam::Key& key, keysA) - if (!keysB.count(key)) - difference.insert(key); - return difference; -} /* ************************************************************************* */ } // \namespace gtsam diff --git a/gtsam/nonlinear/Key.h b/gtsam/nonlinear/Key.h index bcc08d9cd..edeea396f 100644 --- a/gtsam/nonlinear/Key.h +++ b/gtsam/nonlinear/Key.h @@ -60,14 +60,5 @@ namespace gtsam { /// Utility function to print sets of keys with optional prefix GTSAM_EXPORT void printKeySet(const KeySet& keys, const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter); - - /// Computes the intersection between two sets - GTSAM_EXPORT gtsam::KeySet keyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); - - /// Checks if an intersection exists - faster checking size of above - GTSAM_EXPORT bool hasKeyIntersection(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); - - /// Computes a difference between sets, so result is those that are in A, but not B - GTSAM_EXPORT gtsam::KeySet keyDifference(const gtsam::KeySet& keysA, const gtsam::KeySet& keysB); } From 5f371a4e55072ff73910467558b6cfe9be910482 Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Tue, 21 May 2013 21:07:43 +0000 Subject: [PATCH 026/256] Modified Concurrent Filter to calculate marginals using a "shortcut" that allows constant-time updates during synchronization. Still need to test implementation. --- .../nonlinear/ConcurrentBatchFilter.cpp | 621 ++++++++++++------ .../nonlinear/ConcurrentBatchFilter.h | 20 +- 2 files changed, 450 insertions(+), 191 deletions(-) diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp index 1e1e39e10..d8dcd6c14 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp @@ -85,11 +85,11 @@ ConcurrentBatchFilter::Result ConcurrentBatchFilter::update(const NonlinearFacto } gttoc(optimize); - gttic(marginalize); + gttic(move_separator); if(keysToMove && keysToMove->size() > 0){ - marginalize(*keysToMove); + moveSeparator(*keysToMove); } - gttoc(marginalize); + gttoc(move_separator); gttoc(update); @@ -109,100 +109,169 @@ void ConcurrentBatchFilter::synchronize(const NonlinearFactorGraph& summarizedFa gttic(synchronize); - // Remove the previous smoother summarization - removeFactors(smootherSummarizationSlots_); + // Update the smoother summarization on the old separator + previousSmootherSummarization_ = summarizedFactors; - // Create a factor graph containing the new smoother summarization, the factors to be sent to the smoother, - // and all of the filter factors. This is the set of factors on the filter side since the smoother started - // its previous update cycle. - NonlinearFactorGraph graph; - graph.push_back(factors_); - graph.push_back(smootherFactors_); - graph.push_back(summarizedFactors); - Values values; - values.insert(theta_); - values.insert(smootherValues_); - values.update(separatorValues); // ensure the smoother summarized factors are linearized around the values in the smoother + // Use the shortcut to calculate an updated marginal on the current separator + { + // Combine the new smoother summarization and the existing shortcut + NonlinearFactorGraph graph; + graph.push_back(previousSmootherSummarization_); + graph.push_back(smootherShortcut_); - if(factors_.size() > 0) { - // Perform an optional optimization on the to-be-sent-to-the-smoother factors - if(relin_) { - // Create ordering and delta - Ordering ordering = *graph.orderingCOLAMD(values); - VectorValues delta = values.zeroVectors(ordering); - // Optimize this graph using a modified version of L-M - optimize(graph, values, ordering, delta, separatorValues, parameters_); - // Update filter theta and delta - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { - theta_.update(key_value.key, values.at(key_value.key)); - delta_.at(ordering_.at(key_value.key)) = delta.at(ordering.at(key_value.key)); + // Extract the values needed for just this graph + Values values; + BOOST_FOREACH(Key key, graph.keys()) { + values.insert(key, theta_.at(key)); + } + + // Calculate the ordering: [OldSeparator NewSeparator] + // And determine the set of variables to be marginalized out + std::map constraints; + std::set marginalizeKeys; + int group = 0; + if(values.size() > 0) { + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, values) { + constraints[key_value.key] = group; + marginalizeKeys.insert(key_value.key); } - // Update the fixed linearization points (since they just changed) + ++group; + } + if(separatorValues_.size() > 0) { BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { - separatorValues_.update(key_value.key, values.at(key_value.key)); + constraints[key_value.key] = group; + marginalizeKeys.erase(key_value.key); } } + Ordering ordering = *graph.orderingCOLAMDConstrained(values, constraints); - // Create separate ordering constraints that force either the filter keys or the smoother keys to the front - typedef std::map OrderingConstraints; - OrderingConstraints filterConstraints; - OrderingConstraints smootherConstraints; - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { /// the filter keys - filterConstraints[key_value.key] = 0; - smootherConstraints[key_value.key] = 1; - } - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, smootherValues_) { /// the smoother keys - filterConstraints[key_value.key] = 1; - smootherConstraints[key_value.key] = 0; - } - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { /// the *new* separator keys - filterConstraints[key_value.key] = 2; - smootherConstraints[key_value.key] = 2; - } + // Calculate the marginal on the new separator (from the smoother side) + NonlinearFactorGraph marginals = marginalize(graph, values, ordering, marginalizeKeys, parameters_.getEliminationFunction()); - // Generate separate orderings that place the filter keys or the smoother keys first - // TODO: This is convenient, but it recalculates the variable index each time - Ordering filterOrdering = *graph.orderingCOLAMDConstrained(values, filterConstraints); - Ordering smootherOrdering = *graph.orderingCOLAMDConstrained(values, smootherConstraints); - - // Extract the set of filter keys and smoother keys - std::set filterKeys; - std::set separatorKeys; - std::set smootherKeys; - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { - filterKeys.insert(key_value.key); - } - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { - separatorKeys.insert(key_value.key); - filterKeys.erase(key_value.key); - } - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, smootherValues_) { - smootherKeys.insert(key_value.key); - } - - // Calculate the marginal on the new separator from the filter factors. This is performed by marginalizing out - // all of the filter variables that are not part of the new separator. This filter summarization will then be - // sent to the smoother. - filterSummarization_ = marginalize(graph, values, filterOrdering, filterKeys, parameters_.getEliminationFunction()); - // The filter summarization should also include any nonlinear factors that involve only the separator variables. - // Otherwise the smoother will be missing this information - BOOST_FOREACH(const NonlinearFactor::shared_ptr& factor, factors_) { - if(factor) { - NonlinearFactor::const_iterator key = factor->begin(); - while((key != factor->end()) && (std::binary_search(separatorKeys.begin(), separatorKeys.end(), *key))) { - ++key; - } - if(key == factor->end()) { - filterSummarization_.push_back(factor); - } - } - } - - // Calculate the marginal on the new separator from the smoother factors. This is performed by marginalizing out - // all of the smoother variables that are not part of the new separator. This smoother summarization will be - // stored locally for use in the filter - smootherSummarizationSlots_ = insertFactors( marginalize(graph, values, smootherOrdering, smootherKeys, parameters_.getEliminationFunction()) ); + // Remove old summarization and insert new + removeFactors(currentSmootherSummarizationSlots_); + currentSmootherSummarizationSlots_ = insertFactors(marginals); } + + // Calculate the marginal on the new separator from the filter factors + // Note: This could also be done during each filter update so it would simply be available + { + // Calculate an ordering that places the new separator at the root + // And determine the set of variables to be marginalized out + std::map constraints; + std::set marginalizeKeys; + int group = 0; + if(theta_.size() > 0) { + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { + constraints[key_value.key] = group; + marginalizeKeys.insert(key_value.key); + } + ++group; + } + if(separatorValues_.size() > 0) { + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { + constraints[key_value.key] = group; + marginalizeKeys.erase(key_value.key); + } + } + Ordering ordering = *factors_.orderingCOLAMDConstrained(theta_, constraints); + + // Calculate the marginal on the new separator (from the filter side) + filterSummarization_ = marginalize(factors_, theta_, ordering, marginalizeKeys, parameters_.getEliminationFunction()); + } + +// // Create a factor graph containing the new smoother summarization, the factors to be sent to the smoother, +// // and all of the filter factors. This is the set of factors on the filter side since the smoother started +// // its previous update cycle. +// NonlinearFactorGraph graph; +// graph.push_back(factors_); +// graph.push_back(smootherFactors_); +// graph.push_back(summarizedFactors); +// Values values; +// values.insert(theta_); +// values.insert(smootherValues_); +// values.update(separatorValues); // ensure the smoother summarized factors are linearized around the values in the smoother +// +// if(factors_.size() > 0) { +// // Perform an optional optimization on the to-be-sent-to-the-smoother factors +// if(true) { +// // Create ordering and delta +// Ordering ordering = *graph.orderingCOLAMD(values); +// VectorValues delta = values.zeroVectors(ordering); +// // Optimize this graph using a modified version of L-M +// optimize(graph, values, ordering, delta, separatorValues, parameters_); +// // Update filter theta and delta +// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { +// theta_.update(key_value.key, values.at(key_value.key)); +// delta_.at(ordering_.at(key_value.key)) = delta.at(ordering.at(key_value.key)); +// } +// // Update the fixed linearization points (since they just changed) +// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { +// separatorValues_.update(key_value.key, values.at(key_value.key)); +// } +// } +// +// // Create separate ordering constraints that force either the filter keys or the smoother keys to the front +// typedef std::map OrderingConstraints; +// OrderingConstraints filterConstraints; +// OrderingConstraints smootherConstraints; +// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { /// the filter keys +// filterConstraints[key_value.key] = 0; +// smootherConstraints[key_value.key] = 1; +// } +// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, smootherValues_) { /// the smoother keys +// filterConstraints[key_value.key] = 1; +// smootherConstraints[key_value.key] = 0; +// } +// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { /// the *new* separator keys +// filterConstraints[key_value.key] = 2; +// smootherConstraints[key_value.key] = 2; +// } +// +// // Generate separate orderings that place the filter keys or the smoother keys first +// // TODO: This is convenient, but it recalculates the variable index each time +// Ordering filterOrdering = *graph.orderingCOLAMDConstrained(values, filterConstraints); +// Ordering smootherOrdering = *graph.orderingCOLAMDConstrained(values, smootherConstraints); +// +// // Extract the set of filter keys and smoother keys +// std::set filterKeys; +// std::set separatorKeys; +// std::set smootherKeys; +// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { +// filterKeys.insert(key_value.key); +// } +// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { +// separatorKeys.insert(key_value.key); +// filterKeys.erase(key_value.key); +// } +// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, smootherValues_) { +// smootherKeys.insert(key_value.key); +// } +// +// // Calculate the marginal on the new separator from the filter factors. This is performed by marginalizing out +// // all of the filter variables that are not part of the new separator. This filter summarization will then be +// // sent to the smoother. +// filterSummarization_ = marginalize(graph, values, filterOrdering, filterKeys, parameters_.getEliminationFunction()); +// // The filter summarization should also include any nonlinear factors that involve only the separator variables. +// // Otherwise the smoother will be missing this information +// BOOST_FOREACH(const NonlinearFactor::shared_ptr& factor, factors_) { +// if(factor) { +// NonlinearFactor::const_iterator key = factor->begin(); +// while((key != factor->end()) && (std::binary_search(separatorKeys.begin(), separatorKeys.end(), *key))) { +// ++key; +// } +// if(key == factor->end()) { +// filterSummarization_.push_back(factor); +// } +// } +// } +// +// // Calculate the marginal on the new separator from the smoother factors. This is performed by marginalizing out +// // all of the smoother variables that are not part of the new separator. This smoother summarization will be +// // stored locally for use in the filter +// smootherSummarizationSlots_ = insertFactors( marginalize(graph, values, smootherOrdering, smootherKeys, parameters_.getEliminationFunction()) ); +// } + gttoc(synchronize); } @@ -430,117 +499,301 @@ ConcurrentBatchFilter::Result ConcurrentBatchFilter::optimize(const NonlinearFac } /* ************************************************************************* */ -void ConcurrentBatchFilter::marginalize(const FastList& keysToMove) { - // In order to marginalize out the selected variables, the factors involved in those variables - // must be identified and removed. Also, the effect of those removed factors on the - // remaining variables needs to be accounted for. This will be done with linear container factors - // from the result of a partial elimination. This function removes the marginalized factors and - // adds the linearized factors back in. +void ConcurrentBatchFilter::moveSeparator(const FastList& keysToMove) { + // In order to move the separator, we need to calculate the marginal information on the new + // separator from all of the factors on the smoother side (both the factors actually in the + // smoother and the ones to be transitioned to the smoother but stored in the filter). + // This is exactly the same operation that is performed by a fixed-lag smoother, calculating + // a marginal factor from the variables outside the smoother window. + // + // However, for the concurrent system, we would like to calculate this marginal in a particular + // way, such that an intermediate term is produced that provides a "shortcut" between the old + // separator (as defined in the smoother) and the new separator. This will allow us to quickly + // update the new separator with changes at the old separator (from the smoother) + + // TODO: This is currently not very efficient: multiple calls to graph.keys(), etc. - // Calculate marginal factors on the remaining variables (after marginalizing 'keyToMove') - // Note: It is assumed the ordering already has these keys first - - // Create the linear factor graph - GaussianFactorGraph linearFactorGraph = *factors_.linearize(theta_, ordering_); - - // Calculate the variable index - VariableIndex variableIndex(linearFactorGraph, ordering_.size()); - - // Use the variable Index to mark the factors that will be marginalized - std::set removedFactorSlots; + // Identify all of the new factors to be sent to the smoother (any factor involving keysToMove) + std::vector removedFactorSlots; + VariableIndex variableIndex(*factors_.symbolic(ordering_), theta_.size()); BOOST_FOREACH(Key key, keysToMove) { const FastList& slots = variableIndex[ordering_.at(key)]; - removedFactorSlots.insert(slots.begin(), slots.end()); + removedFactorSlots.insert(removedFactorSlots.end(), slots.begin(), slots.end()); + } + // Sort and remove duplicates + std::sort(removedFactorSlots.begin(), removedFactorSlots.end()); + removedFactorSlots.erase(std::unique(removedFactorSlots.begin(), removedFactorSlots.end()), removedFactorSlots.end()); + // Remove any linear,marginal factor that made it into the set + BOOST_FOREACH(size_t index, currentSmootherSummarizationSlots_) { + removedFactorSlots.erase(std::remove(removedFactorSlots.begin(), removedFactorSlots.end(), index), removedFactorSlots.end()); } - // Construct an elimination tree to perform sparse elimination - std::vector forest( EliminationForest::Create(linearFactorGraph, variableIndex) ); + // Add these factors to a factor graph + NonlinearFactorGraph removedFactors; + BOOST_FOREACH(size_t slot, removedFactorSlots) { + if(factors_.at(slot)) { + removedFactors.push_back(factors_.at(slot)); + } + } - // This is a tree. Only the top-most nodes/indices need to be eliminated; all of the children will be eliminated automatically - // Find the subset of nodes/keys that must be eliminated - std::set indicesToEliminate; + // Combine the previous shortcut factor with all of the new factors being sent to the smoother + NonlinearFactorGraph graph; + graph.push_back(removedFactors); + graph.push_back(smootherShortcut_); + + // Extract just the values needed for the current marginalization + // and the set all keys + Values values; + BOOST_FOREACH(Key key, graph.keys()) { + values.insert(key, theta_.at(key)); + } + + // Calculate the set of new separator keys (AllAffectedKeys - KeysToMove) + FastSet newSeparatorKeys = removedFactors.keys(); BOOST_FOREACH(Key key, keysToMove) { - indicesToEliminate.insert(ordering_.at(key)); + newSeparatorKeys.erase(key); } + + // Calculate the set of old set of separator keys from the previous summarization factors + FastSet oldSeparatorKeys = previousSmootherSummarization_.keys(); + BOOST_FOREACH(Key key, newSeparatorKeys) { + oldSeparatorKeys.erase(key); + } + + // Calculate the set of OtherKeys = AllKeys - OldSeparator - NewSeparator + FastSet otherKeys(graph.keys()); + BOOST_FOREACH(Key key, oldSeparatorKeys) { + otherKeys.erase(key); + } + BOOST_FOREACH(Key key, newSeparatorKeys) { + otherKeys.erase(key); + } + + // Calculate the ordering: [Others OldSeparator NewSeparator] + typedef std::map OrderingConstraints; + OrderingConstraints constraints; + int group = 0; + if(otherKeys.size() > 0) { + BOOST_FOREACH(Key key, otherKeys) { + constraints[key] = group; + } + ++group; + } + if(oldSeparatorKeys.size() > 0) { + BOOST_FOREACH(Key key, oldSeparatorKeys) { + constraints[key] = group; + } + ++group; + } + if(newSeparatorKeys.size() > 0) { + BOOST_FOREACH(Key key, newSeparatorKeys) { + constraints[key] = group; + } + } + Ordering ordering = *graph.orderingCOLAMDConstrained(values, constraints); + + // Calculate the new shortcut marginal on the OldSeparator + NewSeparator + smootherShortcut_ = marginalize(graph, values, ordering, otherKeys, parameters_.getEliminationFunction()); + + // Combine the old smoother summarization and the new shortcut + graph = NonlinearFactorGraph(); + graph.push_back(previousSmootherSummarization_); + graph.push_back(smootherShortcut_); + + // Extract the values needed for just this graph + values = Values(); + BOOST_FOREACH(Key key, graph.keys()) { + values.insert(key, theta_.at(key)); + } + + // Calculate the ordering: [OldSeparator NewSeparator] + constraints = OrderingConstraints(); + group = 0; + if(oldSeparatorKeys.size() > 0) { + BOOST_FOREACH(Key key, oldSeparatorKeys) { + constraints[key] = group; + } + ++group; + } + if(newSeparatorKeys.size() > 0) { + BOOST_FOREACH(Key key, newSeparatorKeys) { + constraints[key] = group; + } + } + ordering = *graph.orderingCOLAMDConstrained(values, constraints); + + // Calculate the marginal on the new separator + NonlinearFactorGraph marginals = marginalize(graph, values, ordering, oldSeparatorKeys, parameters_.getEliminationFunction()); + + // Remove the previous marginal factors and insert the new marginal factors + removeFactors(currentSmootherSummarizationSlots_); + currentSmootherSummarizationSlots_ = insertFactors(marginals); + + // Update the separatorValues object (should only contain the new separator keys) + separatorValues_.clear(); + BOOST_FOREACH(Key key, marginals.keys()) { + separatorValues_.insert(key, theta_.at(key)); + } + + // Remove the marginalized factors and add them to the smoother cache + smootherFactors_.push_back(removedFactors); + removeFactors(removedFactorSlots); + + // Add the linearization point of the moved variables to the smoother cache BOOST_FOREACH(Key key, keysToMove) { - EliminationForest::removeChildrenIndices(indicesToEliminate, forest.at(ordering_.at(key))); + smootherValues_.insert(key, theta_.at(key)); } - // Eliminate each top-most key, returning a Gaussian Factor on some of the remaining variables - // Convert the marginal factors into Linear Container Factors - // Add the marginal factor variables to the separator - NonlinearFactorGraph marginalFactors; - BOOST_FOREACH(Index index, indicesToEliminate) { - GaussianFactor::shared_ptr gaussianFactor = forest.at(index)->eliminateRecursive(parameters_.getEliminationFunction()); - if(gaussianFactor->size() > 0) { - LinearContainerFactor::shared_ptr marginalFactor(new LinearContainerFactor(gaussianFactor, ordering_, theta_)); - marginalFactors.push_back(marginalFactor); - // Add the keys associated with the marginal factor to the separator values - BOOST_FOREACH(Key key, *marginalFactor) { - if(!separatorValues_.exists(key)) { - separatorValues_.insert(key, theta_.at(key)); - } - } - } - } - std::vector marginalSlots = insertFactors(marginalFactors); - - - // Cache marginalized variables and factors for later transmission to the smoother - { - // Add the new marginal factors to the list of smootherSeparatorFactors. In essence, we have just moved the separator - smootherSummarizationSlots_.insert(smootherSummarizationSlots_.end(), marginalSlots.begin(), marginalSlots.end()); - - // Move the marginalized factors from the filter to the smoother (holding area) - // Note: Be careful to only move nonlinear factors and not any marginals that may also need to be removed - BOOST_FOREACH(size_t slot, removedFactorSlots) { - std::vector::iterator iter = std::find(smootherSummarizationSlots_.begin(), smootherSummarizationSlots_.end(), slot); - if(iter == smootherSummarizationSlots_.end()) { - // This is a real nonlinear factor. Add it to the smoother factor cache. - smootherFactors_.push_back(factors_.at(slot)); - } else { - // This is a marginal factor that was removed and replaced by a new marginal factor. Remove this slot from the separator factor list. - smootherSummarizationSlots_.erase(iter); - } - } - - // Add the linearization point of the moved variables to the smoother cache - BOOST_FOREACH(Key key, keysToMove) { - smootherValues_.insert(key, theta_.at(key)); - } + // Remove marginalized keys from values (and separator) + BOOST_FOREACH(Key key, keysToMove) { + theta_.erase(key); } - // Remove the marginalized variables and factors from the filter - { - // Remove marginalized factors from the factor graph - std::vector slots(removedFactorSlots.begin(), removedFactorSlots.end()); - removeFactors(slots); - - // Remove marginalized keys from values (and separator) - BOOST_FOREACH(Key key, keysToMove) { - theta_.erase(key); - if(separatorValues_.exists(key)) { - separatorValues_.erase(key); - } - } - - // Permute the ordering such that the removed keys are at the end. - // This is a prerequisite for removing them from several structures - std::vector toBack; - BOOST_FOREACH(Key key, keysToMove) { - toBack.push_back(ordering_.at(key)); - } - Permutation forwardPermutation = Permutation::PushToBack(toBack, ordering_.size()); - ordering_.permuteInPlace(forwardPermutation); - delta_.permuteInPlace(forwardPermutation); - - // Remove marginalized keys from the ordering and delta - for(size_t i = 0; i < keysToMove.size(); ++i) { - ordering_.pop_back(); - delta_.pop_back(); - } + // Permute the ordering such that the removed keys are at the end. + // This is a prerequisite for removing them from several structures + std::vector toBack; + BOOST_FOREACH(Key key, keysToMove) { + toBack.push_back(ordering_.at(key)); } + Permutation forwardPermutation = Permutation::PushToBack(toBack, ordering_.size()); + ordering_.permuteInPlace(forwardPermutation); + delta_.permuteInPlace(forwardPermutation); + + // Remove marginalized keys from the ordering and delta + for(size_t i = 0; i < keysToMove.size(); ++i) { + ordering_.pop_back(); + delta_.pop_back(); + } + + +// // Calculate marginal factors on the remaining variables (after marginalizing 'keyToMove') +// // Note: It is assumed the ordering already has these keys first +// +// // text +// NonlinearFactorGraph marginalFactors = marginalize(factors_, theta_, ordering_, keysToMove, parameters_.getEliminationFunction()); +// +// // text +// BOOST_FOREACH(const NonlinearFactor::shared_ptr& marginalFactor, marginalFactors) { +// BOOST_FOREACH(Key key, *marginalFactor) { +// if(!separatorValues_.exists(key)) { +// separatorValues_.insert(key, theta_.at(key)); +// } +// } +// } +// std::vector marginalSlots = insertFactors(marginalFactors); +// +// // text +// // Use the variable Index to mark the factors that will be marginalized +// std::set removedFactorSlots; +// BOOST_FOREACH(Key key, keysToMove) { +// const FastList& slots = variableIndex[ordering_.at(key)]; +// removedFactorSlots.insert(slots.begin(), slots.end()); +// } +// +// +// +// +// // Create the linear factor graph +// GaussianFactorGraph linearFactorGraph = *factors_.linearize(theta_, ordering_); +// +// // Calculate the variable index +// VariableIndex variableIndex(linearFactorGraph, ordering_.size()); +// +// // Use the variable Index to mark the factors that will be marginalized +// std::set removedFactorSlots; +// BOOST_FOREACH(Key key, keysToMove) { +// const FastList& slots = variableIndex[ordering_.at(key)]; +// removedFactorSlots.insert(slots.begin(), slots.end()); +// } +// +// // Construct an elimination tree to perform sparse elimination +// std::vector forest( EliminationForest::Create(linearFactorGraph, variableIndex) ); +// +// // This is a tree. Only the top-most nodes/indices need to be eliminated; all of the children will be eliminated automatically +// // Find the subset of nodes/keys that must be eliminated +// std::set indicesToEliminate; +// BOOST_FOREACH(Key key, keysToMove) { +// indicesToEliminate.insert(ordering_.at(key)); +// } +// BOOST_FOREACH(Key key, keysToMove) { +// EliminationForest::removeChildrenIndices(indicesToEliminate, forest.at(ordering_.at(key))); +// } +// +// // Eliminate each top-most key, returning a Gaussian Factor on some of the remaining variables +// // Convert the marginal factors into Linear Container Factors +// // Add the marginal factor variables to the separator +// NonlinearFactorGraph marginalFactors; +// BOOST_FOREACH(Index index, indicesToEliminate) { +// GaussianFactor::shared_ptr gaussianFactor = forest.at(index)->eliminateRecursive(parameters_.getEliminationFunction()); +// if(gaussianFactor->size() > 0) { +// LinearContainerFactor::shared_ptr marginalFactor(new LinearContainerFactor(gaussianFactor, ordering_, theta_)); +// marginalFactors.push_back(marginalFactor); +// // Add the keys associated with the marginal factor to the separator values +// BOOST_FOREACH(Key key, *marginalFactor) { +// if(!separatorValues_.exists(key)) { +// separatorValues_.insert(key, theta_.at(key)); +// } +// } +// } +// } +// std::vector marginalSlots = insertFactors(marginalFactors); +// +// +// // Cache marginalized variables and factors for later transmission to the smoother +// { +// // Add the new marginal factors to the list of smootherSeparatorFactors. In essence, we have just moved the separator +// smootherSummarizationSlots_.insert(smootherSummarizationSlots_.end(), marginalSlots.begin(), marginalSlots.end()); +// +// // Move the marginalized factors from the filter to the smoother (holding area) +// // Note: Be careful to only move nonlinear factors and not any marginals that may also need to be removed +// BOOST_FOREACH(size_t slot, removedFactorSlots) { +// std::vector::iterator iter = std::find(smootherSummarizationSlots_.begin(), smootherSummarizationSlots_.end(), slot); +// if(iter == smootherSummarizationSlots_.end()) { +// // This is a real nonlinear factor. Add it to the smoother factor cache. +// smootherFactors_.push_back(factors_.at(slot)); +// } else { +// // This is a marginal factor that was removed and replaced by a new marginal factor. Remove this slot from the smoother summarization list. +// smootherSummarizationSlots_.erase(iter); +// } +// } +// +// // Add the linearization point of the moved variables to the smoother cache +// BOOST_FOREACH(Key key, keysToMove) { +// smootherValues_.insert(key, theta_.at(key)); +// } +// } +// +// // Remove the marginalized variables and factors from the filter +// { +// // Remove marginalized factors from the factor graph +// std::vector slots(removedFactorSlots.begin(), removedFactorSlots.end()); +// removeFactors(slots); +// +// // Remove marginalized keys from values (and separator) +// BOOST_FOREACH(Key key, keysToMove) { +// theta_.erase(key); +// if(separatorValues_.exists(key)) { +// separatorValues_.erase(key); +// } +// } +// +// // Permute the ordering such that the removed keys are at the end. +// // This is a prerequisite for removing them from several structures +// std::vector toBack; +// BOOST_FOREACH(Key key, keysToMove) { +// toBack.push_back(ordering_.at(key)); +// } +// Permutation forwardPermutation = Permutation::PushToBack(toBack, ordering_.size()); +// ordering_.permuteInPlace(forwardPermutation); +// delta_.permuteInPlace(forwardPermutation); +// +// // Remove marginalized keys from the ordering and delta +// for(size_t i = 0; i < keysToMove.size(); ++i) { +// ordering_.pop_back(); +// delta_.pop_back(); +// } +// } } /* ************************************************************************* */ diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h index 9a7690786..7feee4d82 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h @@ -114,7 +114,7 @@ public: * @param newTheta Initialization points for new variables to be added to the filter * You must include here all new variables occurring in newFactors that were not already * in the filter. - * @param keysToMove An optional set of keys to remove from the filter and + * @param keysToMove An optional set of keys to move from the filter to the smoother */ Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), const Values& newTheta = Values(), const boost::optional >& keysToMove = boost::none); @@ -129,7 +129,11 @@ protected: VectorValues delta_; ///< The current set of linear deltas from the linearization point std::queue availableSlots_; ///< The set of available factor graph slots caused by deleting factors Values separatorValues_; ///< The linearization points of the separator variables. These should not be updated during optimization. - std::vector smootherSummarizationSlots_; ///< The slots in factor graph that correspond to the current smoother summarization factors + std::vector currentSmootherSummarizationSlots_; ///< The slots in factor graph that correspond to the current smoother summarization on the current separator + + // Storage for information from the Smoother + NonlinearFactorGraph previousSmootherSummarization_; ///< The smoother summarization on the old separator sent by the smoother during the last synchronization + NonlinearFactorGraph smootherShortcut_; ///< A set of conditional factors from the old separator to the current separator (recursively calculated during each filter update) // Storage for information to be sent to the smoother NonlinearFactorGraph filterSummarization_; ///< A temporary holding place for calculated filter summarization factors to be sent to the smoother @@ -193,15 +197,17 @@ private: /** Use colamd to update into an efficient ordering */ void reorder(const boost::optional >& keysToMove = boost::none); + /** Marginalize out the set of requested variables from the filter, caching them for the smoother + * This effectively moves the separator. + * + * @param keysToMove The set of keys to move from the filter to the smoother + */ + void moveSeparator(const FastList& keysToMove); + /** Use a modified version of L-M to update the linearization point and delta */ static Result optimize(const NonlinearFactorGraph& factors, Values& theta, const Ordering& ordering, VectorValues& delta, const Values& linearValues, const LevenbergMarquardtParams& parameters); - /** Marginalize out the set of requested variables from the filter, caching them for the smoother - * This effectively moves the separator. - */ - void marginalize(const FastList& keysToMove); - /** Marginalize out the set of requested variables from the filter, caching them for the smoother * This effectively moves the separator. */ From 8e26da7396bb5286e77037181327dfe409049848 Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Tue, 21 May 2013 21:07:45 +0000 Subject: [PATCH 027/256] Added matlab version of the Concurrent Filtering and Smoothing example --- ...ConcurrentFilteringAndSmoothingExample.cpp | 2 +- .../ConcurrentFilteringAndSmoothingExample.m | 131 ++++++++++++++++++ 2 files changed, 132 insertions(+), 1 deletion(-) create mode 100644 matlab/unstable_examples/ConcurrentFilteringAndSmoothingExample.m diff --git a/gtsam_unstable/examples/ConcurrentFilteringAndSmoothingExample.cpp b/gtsam_unstable/examples/ConcurrentFilteringAndSmoothingExample.cpp index 002d24ad4..65fc681c4 100644 --- a/gtsam_unstable/examples/ConcurrentFilteringAndSmoothingExample.cpp +++ b/gtsam_unstable/examples/ConcurrentFilteringAndSmoothingExample.cpp @@ -118,7 +118,7 @@ int main(int argc, char** argv) { newFactors.add(BetweenFactor(previousKey, currentKey, odometryMeasurement2, odometryNoise2)); // Unlike the fixed-lag versions, the concurrent filter implementation - // requires the user to supply the specify which keys to marginalize + // requires the user to supply the specify which keys to move to the smoother FastList oldKeys; if(time >= lag+deltaT) { oldKeys.push_back(1000 * (time-lag-deltaT)); diff --git a/matlab/unstable_examples/ConcurrentFilteringAndSmoothingExample.m b/matlab/unstable_examples/ConcurrentFilteringAndSmoothingExample.m new file mode 100644 index 000000000..bb6e63dc6 --- /dev/null +++ b/matlab/unstable_examples/ConcurrentFilteringAndSmoothingExample.m @@ -0,0 +1,131 @@ +% ---------------------------------------------------------------------------- +% +% GTSAM Copyright 2010, Georgia Tech Research Corporation, +% Atlanta, Georgia 30332-0415 +% All Rights Reserved +% Authors: Frank Dellaert, et al. (see THANKS for the full author list) +% +% See LICENSE for the license information +% +% -------------------------------------------------------------------------- + +% @file ConcurrentFilteringAndSmoothingExample.m +% @brief Demonstration of the concurrent filtering and smoothing architecture using +% a planar robot example and multiple odometry-like sensors +% @author Stephen Williams + +% A simple 2D pose slam example with multiple odometry-like measurements +% - The robot initially faces along the X axis (horizontal, to the right in 2D) +% - The robot moves forward at 2m/s +% - We have measurements between each pose from multiple odometry sensors + +clear all; +import gtsam.*; + +% Define the smoother lag (in seconds) +lag = 2.0; + +% Create a Concurrent Filter and Smoother +concurrentFilter = ConcurrentBatchFilter; +concurrentSmoother = ConcurrentBatchSmoother; + +%% Create containers to store the factors and linearization points that +% will be sent to the smoothers +newFactors = NonlinearFactorGraph; +newValues = Values; + +%% Create a prior on the first pose, placing it at the origin +priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin +priorNoise = noiseModel.Diagonal.Sigmas([0.3 ; 0.3 ; 0.1]); +priorKey = uint64(0); +newFactors.add(PriorFactorPose2(priorKey, priorMean, priorNoise)); +newValues.insert(priorKey, priorMean); % Initialize the first pose at the mean of the prior + +%% Insert the prior factor into the filter +concurrentFilter.update(newFactors, newValues); + +%% Now, loop through several time steps, creating factors from different "sensors" +% and adding them to the fixed-lag smoothers +deltaT = 0.25; +for time = deltaT : deltaT : 10.0 + + %% Initialize factor and values for this loop iteration + newFactors = NonlinearFactorGraph; + newValues = Values; + + %% Define the keys related to this timestamp + previousKey = uint64(1000 * (time-deltaT)); + currentKey = uint64(1000 * (time)); + + %% Add a guess for this pose to the new values + % Since the robot moves forward at 2 m/s, then the position is simply: time[s]*2.0[m/s] + % {This is not a particularly good way to guess, but this is just an example} + currentPose = Pose2(time * 2.0, 0.0, 0.0); + newValues.insert(currentKey, currentPose); + + %% Add odometry factors from two different sources with different error stats + odometryMeasurement1 = Pose2(0.61, -0.08, 0.02); + odometryNoise1 = noiseModel.Diagonal.Sigmas([0.1; 0.1; 0.05]); + newFactors.add(BetweenFactorPose2(previousKey, currentKey, odometryMeasurement1, odometryNoise1)); + + odometryMeasurement2 = Pose2(0.47, 0.03, 0.01); + odometryNoise2 = noiseModel.Isotropic.Sigma(3, 0.05); + newFactors.add(BetweenFactorPose2(previousKey, currentKey, odometryMeasurement2, odometryNoise2)); + + %% Unlike the fixed-lag versions, the concurrent filter implementation + % requires the user to supply the specify which keys to move to the smoother + oldKeys = KeyList; + if time >= lag+deltaT + oldKeys.push_back(uint64(1000 * (time-lag-deltaT))); + end + + %% Update the various inference engines + concurrentFilter.update(newFactors, newValues, oldKeys); + + %% Add a loop closure to the smoother at a particular time + if time == 8.0 + % Now lets create a "loop closure" factor between some poses + loopKey1 = uint64(1000 * (0.0)); + loopKey2 = uint64(1000 * (5.0)); + loopMeasurement = Pose2(9.5, 1.00, 0.00); + loopNoise = noiseModel.Diagonal.Sigmas([0.5; 0.5; 0.25]); + loopFactor = BetweenFactorPose2(loopKey1, loopKey2, loopMeasurement, loopNoise); + % The state at 5.0s should have been transferred to the concurrent smoother at this point. Add the loop closure. + smootherFactors = NonlinearFactorGraph; + smootherFactors.push_back(loopFactor); + concurrentSmoother.update(smootherFactors, Values()); + end + + %% Manually synchronize the Concurrent Filter and Smoother every 1.0 s + if mod(time, 1.0) < 0.01 + % Synchronize the Filter and Smoother + concurrentSmoother.update(); + synchronize(concurrentFilter, concurrentSmoother); + end + + %% Print the filter optimized poses + fprintf(1, 'Timestamp = %5.3f\n', time); + filterResult = concurrentFilter.calculateEstimate; + filterResult.at(currentKey).print('Concurrent Estimate: '); + + %% Plot Covariance Ellipses + cla; + hold on + filterMarginals = Marginals(concurrentFilter.getFactors, filterResult); + plot2DTrajectory(filterResult, 'k*-', filterMarginals); + + smootherGraph = concurrentSmoother.getFactors; + if smootherGraph.size > 0 + smootherResult = concurrentSmoother.calculateEstimate; + smootherMarginals = Marginals(smootherGraph, smootherResult); + plot2DTrajectory(smootherResult, 'r*-', smootherMarginals); + end + + axis equal + axis tight + view(2) +pause +end + + + From 75803f02294e2136e8af2f2a7f11455e022731fb Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 21 May 2013 21:22:55 +0000 Subject: [PATCH 028/256] smart indent, and change push_back to add --- .../ConcurrentFilteringAndSmoothingExample.m | 169 +++++++++--------- 1 file changed, 85 insertions(+), 84 deletions(-) diff --git a/matlab/unstable_examples/ConcurrentFilteringAndSmoothingExample.m b/matlab/unstable_examples/ConcurrentFilteringAndSmoothingExample.m index bb6e63dc6..d1d225545 100644 --- a/matlab/unstable_examples/ConcurrentFilteringAndSmoothingExample.m +++ b/matlab/unstable_examples/ConcurrentFilteringAndSmoothingExample.m @@ -1,14 +1,14 @@ % ---------------------------------------------------------------------------- -% -% GTSAM Copyright 2010, Georgia Tech Research Corporation, +% +% GTSAM Copyright 2010, Georgia Tech Research Corporation, % Atlanta, Georgia 30332-0415 % All Rights Reserved % Authors: Frank Dellaert, et al. (see THANKS for the full author list) -% +% % See LICENSE for the license information -% +% % -------------------------------------------------------------------------- - + % @file ConcurrentFilteringAndSmoothingExample.m % @brief Demonstration of the concurrent filtering and smoothing architecture using % a planar robot example and multiple odometry-like sensors @@ -19,6 +19,7 @@ % - The robot moves forward at 2m/s % - We have measurements between each pose from multiple odometry sensors +clear all; clear all; import gtsam.*; @@ -33,7 +34,7 @@ concurrentSmoother = ConcurrentBatchSmoother; % will be sent to the smoothers newFactors = NonlinearFactorGraph; newValues = Values; - + %% Create a prior on the first pose, placing it at the origin priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin priorNoise = noiseModel.Diagonal.Sigmas([0.3 ; 0.3 ; 0.1]); @@ -48,84 +49,84 @@ concurrentFilter.update(newFactors, newValues); % and adding them to the fixed-lag smoothers deltaT = 0.25; for time = deltaT : deltaT : 10.0 - - %% Initialize factor and values for this loop iteration - newFactors = NonlinearFactorGraph; - newValues = Values; - - %% Define the keys related to this timestamp - previousKey = uint64(1000 * (time-deltaT)); - currentKey = uint64(1000 * (time)); - - %% Add a guess for this pose to the new values - % Since the robot moves forward at 2 m/s, then the position is simply: time[s]*2.0[m/s] - % {This is not a particularly good way to guess, but this is just an example} - currentPose = Pose2(time * 2.0, 0.0, 0.0); - newValues.insert(currentKey, currentPose); - - %% Add odometry factors from two different sources with different error stats - odometryMeasurement1 = Pose2(0.61, -0.08, 0.02); - odometryNoise1 = noiseModel.Diagonal.Sigmas([0.1; 0.1; 0.05]); - newFactors.add(BetweenFactorPose2(previousKey, currentKey, odometryMeasurement1, odometryNoise1)); - - odometryMeasurement2 = Pose2(0.47, 0.03, 0.01); - odometryNoise2 = noiseModel.Isotropic.Sigma(3, 0.05); - newFactors.add(BetweenFactorPose2(previousKey, currentKey, odometryMeasurement2, odometryNoise2)); - - %% Unlike the fixed-lag versions, the concurrent filter implementation - % requires the user to supply the specify which keys to move to the smoother - oldKeys = KeyList; - if time >= lag+deltaT - oldKeys.push_back(uint64(1000 * (time-lag-deltaT))); - end - - %% Update the various inference engines - concurrentFilter.update(newFactors, newValues, oldKeys); - - %% Add a loop closure to the smoother at a particular time - if time == 8.0 - % Now lets create a "loop closure" factor between some poses - loopKey1 = uint64(1000 * (0.0)); - loopKey2 = uint64(1000 * (5.0)); - loopMeasurement = Pose2(9.5, 1.00, 0.00); - loopNoise = noiseModel.Diagonal.Sigmas([0.5; 0.5; 0.25]); - loopFactor = BetweenFactorPose2(loopKey1, loopKey2, loopMeasurement, loopNoise); - % The state at 5.0s should have been transferred to the concurrent smoother at this point. Add the loop closure. - smootherFactors = NonlinearFactorGraph; - smootherFactors.push_back(loopFactor); - concurrentSmoother.update(smootherFactors, Values()); - end - - %% Manually synchronize the Concurrent Filter and Smoother every 1.0 s - if mod(time, 1.0) < 0.01 - % Synchronize the Filter and Smoother - concurrentSmoother.update(); - synchronize(concurrentFilter, concurrentSmoother); - end - - %% Print the filter optimized poses - fprintf(1, 'Timestamp = %5.3f\n', time); - filterResult = concurrentFilter.calculateEstimate; - filterResult.at(currentKey).print('Concurrent Estimate: '); - - %% Plot Covariance Ellipses - cla; - hold on - filterMarginals = Marginals(concurrentFilter.getFactors, filterResult); - plot2DTrajectory(filterResult, 'k*-', filterMarginals); - - smootherGraph = concurrentSmoother.getFactors; - if smootherGraph.size > 0 - smootherResult = concurrentSmoother.calculateEstimate; - smootherMarginals = Marginals(smootherGraph, smootherResult); - plot2DTrajectory(smootherResult, 'r*-', smootherMarginals); - end - - axis equal - axis tight - view(2) -pause -end + %% Initialize factor and values for this loop iteration + newFactors = NonlinearFactorGraph; + newValues = Values; + + %% Define the keys related to this timestamp + previousKey = uint64(1000 * (time-deltaT)); + currentKey = uint64(1000 * (time)); + + %% Add a guess for this pose to the new values + % Since the robot moves forward at 2 m/s, then the position is simply: time[s]*2.0[m/s] + % {This is not a particularly good way to guess, but this is just an example} + currentPose = Pose2(time * 2.0, 0.0, 0.0); + newValues.insert(currentKey, currentPose); + + %% Add odometry factors from two different sources with different error stats + odometryMeasurement1 = Pose2(0.61, -0.08, 0.02); + odometryNoise1 = noiseModel.Diagonal.Sigmas([0.1; 0.1; 0.05]); + newFactors.add(BetweenFactorPose2(previousKey, currentKey, odometryMeasurement1, odometryNoise1)); + + odometryMeasurement2 = Pose2(0.47, 0.03, 0.01); + odometryNoise2 = noiseModel.Isotropic.Sigma(3, 0.05); + newFactors.add(BetweenFactorPose2(previousKey, currentKey, odometryMeasurement2, odometryNoise2)); + + %% Unlike the fixed-lag versions, the concurrent filter implementation + % requires the user to supply the specify which keys to move to the smoother + oldKeys = KeyList; + if time >= lag+deltaT + oldKeys.push_back(uint64(1000 * (time-lag-deltaT))); + end + + %% Update the various inference engines + concurrentFilter.update(newFactors, newValues, oldKeys); + + %% Add a loop closure to the smoother at a particular time + if time == 8.0 + % Now lets create a "loop closure" factor between some poses + loopKey1 = uint64(1000 * (0.0)); + loopKey2 = uint64(1000 * (5.0)); + loopMeasurement = Pose2(9.5, 1.00, 0.00); + loopNoise = noiseModel.Diagonal.Sigmas([0.5; 0.5; 0.25]); + loopFactor = BetweenFactorPose2(loopKey1, loopKey2, loopMeasurement, loopNoise); + % The state at 5.0s should have been transferred to the concurrent smoother at this point. Add the loop closure. + smootherFactors = NonlinearFactorGraph; + smootherFactors.add(loopFactor); + concurrentSmoother.update(smootherFactors, Values()); + end + + %% Manually synchronize the Concurrent Filter and Smoother every 1.0 s + if mod(time, 1.0) < 0.01 + % Synchronize the Filter and Smoother + concurrentSmoother.update(); + synchronize(concurrentFilter, concurrentSmoother); + end + + %% Print the filter optimized poses + fprintf(1, 'Timestamp = %5.3f\n', time); + filterResult = concurrentFilter.calculateEstimate; + filterResult.at(currentKey).print('Concurrent Estimate: '); + + %% Plot Covariance Ellipses + cla; + hold on + filterMarginals = Marginals(concurrentFilter.getFactors, filterResult); + plot2DTrajectory(filterResult, 'k*-', filterMarginals); + + smootherGraph = concurrentSmoother.getFactors; + if smootherGraph.size > 0 + smootherResult = concurrentSmoother.calculateEstimate; + smootherMarginals = Marginals(smootherGraph, smootherResult); + plot2DTrajectory(smootherResult, 'r*-', smootherMarginals); + end + + axis equal + axis tight + view(2) + pause(0.01) +end + From 1e5f9c742d49d99c23fa5b582e3c02754b19758a Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Wed, 22 May 2013 00:05:03 +0000 Subject: [PATCH 029/256] Revert "Modified Concurrent Filter to calculate marginals using a "shortcut" that allows constant-time updates during synchronization. Still need to test implementation." This reverts commit f24a4f4668006cfe9a3eeb1658b7df03c74490d5. --- .../nonlinear/ConcurrentBatchFilter.cpp | 621 ++++++------------ .../nonlinear/ConcurrentBatchFilter.h | 20 +- 2 files changed, 191 insertions(+), 450 deletions(-) diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp index d8dcd6c14..1e1e39e10 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp @@ -85,11 +85,11 @@ ConcurrentBatchFilter::Result ConcurrentBatchFilter::update(const NonlinearFacto } gttoc(optimize); - gttic(move_separator); + gttic(marginalize); if(keysToMove && keysToMove->size() > 0){ - moveSeparator(*keysToMove); + marginalize(*keysToMove); } - gttoc(move_separator); + gttoc(marginalize); gttoc(update); @@ -109,169 +109,100 @@ void ConcurrentBatchFilter::synchronize(const NonlinearFactorGraph& summarizedFa gttic(synchronize); - // Update the smoother summarization on the old separator - previousSmootherSummarization_ = summarizedFactors; + // Remove the previous smoother summarization + removeFactors(smootherSummarizationSlots_); - // Use the shortcut to calculate an updated marginal on the current separator - { - // Combine the new smoother summarization and the existing shortcut - NonlinearFactorGraph graph; - graph.push_back(previousSmootherSummarization_); - graph.push_back(smootherShortcut_); + // Create a factor graph containing the new smoother summarization, the factors to be sent to the smoother, + // and all of the filter factors. This is the set of factors on the filter side since the smoother started + // its previous update cycle. + NonlinearFactorGraph graph; + graph.push_back(factors_); + graph.push_back(smootherFactors_); + graph.push_back(summarizedFactors); + Values values; + values.insert(theta_); + values.insert(smootherValues_); + values.update(separatorValues); // ensure the smoother summarized factors are linearized around the values in the smoother - // Extract the values needed for just this graph - Values values; - BOOST_FOREACH(Key key, graph.keys()) { - values.insert(key, theta_.at(key)); - } - - // Calculate the ordering: [OldSeparator NewSeparator] - // And determine the set of variables to be marginalized out - std::map constraints; - std::set marginalizeKeys; - int group = 0; - if(values.size() > 0) { - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, values) { - constraints[key_value.key] = group; - marginalizeKeys.insert(key_value.key); - } - ++group; - } - if(separatorValues_.size() > 0) { - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { - constraints[key_value.key] = group; - marginalizeKeys.erase(key_value.key); - } - } - Ordering ordering = *graph.orderingCOLAMDConstrained(values, constraints); - - // Calculate the marginal on the new separator (from the smoother side) - NonlinearFactorGraph marginals = marginalize(graph, values, ordering, marginalizeKeys, parameters_.getEliminationFunction()); - - // Remove old summarization and insert new - removeFactors(currentSmootherSummarizationSlots_); - currentSmootherSummarizationSlots_ = insertFactors(marginals); - } - - // Calculate the marginal on the new separator from the filter factors - // Note: This could also be done during each filter update so it would simply be available - { - // Calculate an ordering that places the new separator at the root - // And determine the set of variables to be marginalized out - std::map constraints; - std::set marginalizeKeys; - int group = 0; - if(theta_.size() > 0) { + if(factors_.size() > 0) { + // Perform an optional optimization on the to-be-sent-to-the-smoother factors + if(relin_) { + // Create ordering and delta + Ordering ordering = *graph.orderingCOLAMD(values); + VectorValues delta = values.zeroVectors(ordering); + // Optimize this graph using a modified version of L-M + optimize(graph, values, ordering, delta, separatorValues, parameters_); + // Update filter theta and delta BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { - constraints[key_value.key] = group; - marginalizeKeys.insert(key_value.key); + theta_.update(key_value.key, values.at(key_value.key)); + delta_.at(ordering_.at(key_value.key)) = delta.at(ordering.at(key_value.key)); } - ++group; - } - if(separatorValues_.size() > 0) { + // Update the fixed linearization points (since they just changed) BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { - constraints[key_value.key] = group; - marginalizeKeys.erase(key_value.key); + separatorValues_.update(key_value.key, values.at(key_value.key)); } } - Ordering ordering = *factors_.orderingCOLAMDConstrained(theta_, constraints); - // Calculate the marginal on the new separator (from the filter side) - filterSummarization_ = marginalize(factors_, theta_, ordering, marginalizeKeys, parameters_.getEliminationFunction()); + // Create separate ordering constraints that force either the filter keys or the smoother keys to the front + typedef std::map OrderingConstraints; + OrderingConstraints filterConstraints; + OrderingConstraints smootherConstraints; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { /// the filter keys + filterConstraints[key_value.key] = 0; + smootherConstraints[key_value.key] = 1; + } + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, smootherValues_) { /// the smoother keys + filterConstraints[key_value.key] = 1; + smootherConstraints[key_value.key] = 0; + } + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { /// the *new* separator keys + filterConstraints[key_value.key] = 2; + smootherConstraints[key_value.key] = 2; + } + + // Generate separate orderings that place the filter keys or the smoother keys first + // TODO: This is convenient, but it recalculates the variable index each time + Ordering filterOrdering = *graph.orderingCOLAMDConstrained(values, filterConstraints); + Ordering smootherOrdering = *graph.orderingCOLAMDConstrained(values, smootherConstraints); + + // Extract the set of filter keys and smoother keys + std::set filterKeys; + std::set separatorKeys; + std::set smootherKeys; + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { + filterKeys.insert(key_value.key); + } + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { + separatorKeys.insert(key_value.key); + filterKeys.erase(key_value.key); + } + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, smootherValues_) { + smootherKeys.insert(key_value.key); + } + + // Calculate the marginal on the new separator from the filter factors. This is performed by marginalizing out + // all of the filter variables that are not part of the new separator. This filter summarization will then be + // sent to the smoother. + filterSummarization_ = marginalize(graph, values, filterOrdering, filterKeys, parameters_.getEliminationFunction()); + // The filter summarization should also include any nonlinear factors that involve only the separator variables. + // Otherwise the smoother will be missing this information + BOOST_FOREACH(const NonlinearFactor::shared_ptr& factor, factors_) { + if(factor) { + NonlinearFactor::const_iterator key = factor->begin(); + while((key != factor->end()) && (std::binary_search(separatorKeys.begin(), separatorKeys.end(), *key))) { + ++key; + } + if(key == factor->end()) { + filterSummarization_.push_back(factor); + } + } + } + + // Calculate the marginal on the new separator from the smoother factors. This is performed by marginalizing out + // all of the smoother variables that are not part of the new separator. This smoother summarization will be + // stored locally for use in the filter + smootherSummarizationSlots_ = insertFactors( marginalize(graph, values, smootherOrdering, smootherKeys, parameters_.getEliminationFunction()) ); } - -// // Create a factor graph containing the new smoother summarization, the factors to be sent to the smoother, -// // and all of the filter factors. This is the set of factors on the filter side since the smoother started -// // its previous update cycle. -// NonlinearFactorGraph graph; -// graph.push_back(factors_); -// graph.push_back(smootherFactors_); -// graph.push_back(summarizedFactors); -// Values values; -// values.insert(theta_); -// values.insert(smootherValues_); -// values.update(separatorValues); // ensure the smoother summarized factors are linearized around the values in the smoother -// -// if(factors_.size() > 0) { -// // Perform an optional optimization on the to-be-sent-to-the-smoother factors -// if(true) { -// // Create ordering and delta -// Ordering ordering = *graph.orderingCOLAMD(values); -// VectorValues delta = values.zeroVectors(ordering); -// // Optimize this graph using a modified version of L-M -// optimize(graph, values, ordering, delta, separatorValues, parameters_); -// // Update filter theta and delta -// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { -// theta_.update(key_value.key, values.at(key_value.key)); -// delta_.at(ordering_.at(key_value.key)) = delta.at(ordering.at(key_value.key)); -// } -// // Update the fixed linearization points (since they just changed) -// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { -// separatorValues_.update(key_value.key, values.at(key_value.key)); -// } -// } -// -// // Create separate ordering constraints that force either the filter keys or the smoother keys to the front -// typedef std::map OrderingConstraints; -// OrderingConstraints filterConstraints; -// OrderingConstraints smootherConstraints; -// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { /// the filter keys -// filterConstraints[key_value.key] = 0; -// smootherConstraints[key_value.key] = 1; -// } -// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, smootherValues_) { /// the smoother keys -// filterConstraints[key_value.key] = 1; -// smootherConstraints[key_value.key] = 0; -// } -// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { /// the *new* separator keys -// filterConstraints[key_value.key] = 2; -// smootherConstraints[key_value.key] = 2; -// } -// -// // Generate separate orderings that place the filter keys or the smoother keys first -// // TODO: This is convenient, but it recalculates the variable index each time -// Ordering filterOrdering = *graph.orderingCOLAMDConstrained(values, filterConstraints); -// Ordering smootherOrdering = *graph.orderingCOLAMDConstrained(values, smootherConstraints); -// -// // Extract the set of filter keys and smoother keys -// std::set filterKeys; -// std::set separatorKeys; -// std::set smootherKeys; -// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, theta_) { -// filterKeys.insert(key_value.key); -// } -// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { -// separatorKeys.insert(key_value.key); -// filterKeys.erase(key_value.key); -// } -// BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, smootherValues_) { -// smootherKeys.insert(key_value.key); -// } -// -// // Calculate the marginal on the new separator from the filter factors. This is performed by marginalizing out -// // all of the filter variables that are not part of the new separator. This filter summarization will then be -// // sent to the smoother. -// filterSummarization_ = marginalize(graph, values, filterOrdering, filterKeys, parameters_.getEliminationFunction()); -// // The filter summarization should also include any nonlinear factors that involve only the separator variables. -// // Otherwise the smoother will be missing this information -// BOOST_FOREACH(const NonlinearFactor::shared_ptr& factor, factors_) { -// if(factor) { -// NonlinearFactor::const_iterator key = factor->begin(); -// while((key != factor->end()) && (std::binary_search(separatorKeys.begin(), separatorKeys.end(), *key))) { -// ++key; -// } -// if(key == factor->end()) { -// filterSummarization_.push_back(factor); -// } -// } -// } -// -// // Calculate the marginal on the new separator from the smoother factors. This is performed by marginalizing out -// // all of the smoother variables that are not part of the new separator. This smoother summarization will be -// // stored locally for use in the filter -// smootherSummarizationSlots_ = insertFactors( marginalize(graph, values, smootherOrdering, smootherKeys, parameters_.getEliminationFunction()) ); -// } - gttoc(synchronize); } @@ -499,301 +430,117 @@ ConcurrentBatchFilter::Result ConcurrentBatchFilter::optimize(const NonlinearFac } /* ************************************************************************* */ -void ConcurrentBatchFilter::moveSeparator(const FastList& keysToMove) { - // In order to move the separator, we need to calculate the marginal information on the new - // separator from all of the factors on the smoother side (both the factors actually in the - // smoother and the ones to be transitioned to the smoother but stored in the filter). - // This is exactly the same operation that is performed by a fixed-lag smoother, calculating - // a marginal factor from the variables outside the smoother window. - // - // However, for the concurrent system, we would like to calculate this marginal in a particular - // way, such that an intermediate term is produced that provides a "shortcut" between the old - // separator (as defined in the smoother) and the new separator. This will allow us to quickly - // update the new separator with changes at the old separator (from the smoother) - - // TODO: This is currently not very efficient: multiple calls to graph.keys(), etc. +void ConcurrentBatchFilter::marginalize(const FastList& keysToMove) { + // In order to marginalize out the selected variables, the factors involved in those variables + // must be identified and removed. Also, the effect of those removed factors on the + // remaining variables needs to be accounted for. This will be done with linear container factors + // from the result of a partial elimination. This function removes the marginalized factors and + // adds the linearized factors back in. - // Identify all of the new factors to be sent to the smoother (any factor involving keysToMove) - std::vector removedFactorSlots; - VariableIndex variableIndex(*factors_.symbolic(ordering_), theta_.size()); + // Calculate marginal factors on the remaining variables (after marginalizing 'keyToMove') + // Note: It is assumed the ordering already has these keys first + + // Create the linear factor graph + GaussianFactorGraph linearFactorGraph = *factors_.linearize(theta_, ordering_); + + // Calculate the variable index + VariableIndex variableIndex(linearFactorGraph, ordering_.size()); + + // Use the variable Index to mark the factors that will be marginalized + std::set removedFactorSlots; BOOST_FOREACH(Key key, keysToMove) { const FastList& slots = variableIndex[ordering_.at(key)]; - removedFactorSlots.insert(removedFactorSlots.end(), slots.begin(), slots.end()); - } - // Sort and remove duplicates - std::sort(removedFactorSlots.begin(), removedFactorSlots.end()); - removedFactorSlots.erase(std::unique(removedFactorSlots.begin(), removedFactorSlots.end()), removedFactorSlots.end()); - // Remove any linear,marginal factor that made it into the set - BOOST_FOREACH(size_t index, currentSmootherSummarizationSlots_) { - removedFactorSlots.erase(std::remove(removedFactorSlots.begin(), removedFactorSlots.end(), index), removedFactorSlots.end()); + removedFactorSlots.insert(slots.begin(), slots.end()); } - // Add these factors to a factor graph - NonlinearFactorGraph removedFactors; - BOOST_FOREACH(size_t slot, removedFactorSlots) { - if(factors_.at(slot)) { - removedFactors.push_back(factors_.at(slot)); - } - } + // Construct an elimination tree to perform sparse elimination + std::vector forest( EliminationForest::Create(linearFactorGraph, variableIndex) ); - // Combine the previous shortcut factor with all of the new factors being sent to the smoother - NonlinearFactorGraph graph; - graph.push_back(removedFactors); - graph.push_back(smootherShortcut_); - - // Extract just the values needed for the current marginalization - // and the set all keys - Values values; - BOOST_FOREACH(Key key, graph.keys()) { - values.insert(key, theta_.at(key)); - } - - // Calculate the set of new separator keys (AllAffectedKeys - KeysToMove) - FastSet newSeparatorKeys = removedFactors.keys(); + // This is a tree. Only the top-most nodes/indices need to be eliminated; all of the children will be eliminated automatically + // Find the subset of nodes/keys that must be eliminated + std::set indicesToEliminate; BOOST_FOREACH(Key key, keysToMove) { - newSeparatorKeys.erase(key); + indicesToEliminate.insert(ordering_.at(key)); } - - // Calculate the set of old set of separator keys from the previous summarization factors - FastSet oldSeparatorKeys = previousSmootherSummarization_.keys(); - BOOST_FOREACH(Key key, newSeparatorKeys) { - oldSeparatorKeys.erase(key); - } - - // Calculate the set of OtherKeys = AllKeys - OldSeparator - NewSeparator - FastSet otherKeys(graph.keys()); - BOOST_FOREACH(Key key, oldSeparatorKeys) { - otherKeys.erase(key); - } - BOOST_FOREACH(Key key, newSeparatorKeys) { - otherKeys.erase(key); - } - - // Calculate the ordering: [Others OldSeparator NewSeparator] - typedef std::map OrderingConstraints; - OrderingConstraints constraints; - int group = 0; - if(otherKeys.size() > 0) { - BOOST_FOREACH(Key key, otherKeys) { - constraints[key] = group; - } - ++group; - } - if(oldSeparatorKeys.size() > 0) { - BOOST_FOREACH(Key key, oldSeparatorKeys) { - constraints[key] = group; - } - ++group; - } - if(newSeparatorKeys.size() > 0) { - BOOST_FOREACH(Key key, newSeparatorKeys) { - constraints[key] = group; - } - } - Ordering ordering = *graph.orderingCOLAMDConstrained(values, constraints); - - // Calculate the new shortcut marginal on the OldSeparator + NewSeparator - smootherShortcut_ = marginalize(graph, values, ordering, otherKeys, parameters_.getEliminationFunction()); - - // Combine the old smoother summarization and the new shortcut - graph = NonlinearFactorGraph(); - graph.push_back(previousSmootherSummarization_); - graph.push_back(smootherShortcut_); - - // Extract the values needed for just this graph - values = Values(); - BOOST_FOREACH(Key key, graph.keys()) { - values.insert(key, theta_.at(key)); - } - - // Calculate the ordering: [OldSeparator NewSeparator] - constraints = OrderingConstraints(); - group = 0; - if(oldSeparatorKeys.size() > 0) { - BOOST_FOREACH(Key key, oldSeparatorKeys) { - constraints[key] = group; - } - ++group; - } - if(newSeparatorKeys.size() > 0) { - BOOST_FOREACH(Key key, newSeparatorKeys) { - constraints[key] = group; - } - } - ordering = *graph.orderingCOLAMDConstrained(values, constraints); - - // Calculate the marginal on the new separator - NonlinearFactorGraph marginals = marginalize(graph, values, ordering, oldSeparatorKeys, parameters_.getEliminationFunction()); - - // Remove the previous marginal factors and insert the new marginal factors - removeFactors(currentSmootherSummarizationSlots_); - currentSmootherSummarizationSlots_ = insertFactors(marginals); - - // Update the separatorValues object (should only contain the new separator keys) - separatorValues_.clear(); - BOOST_FOREACH(Key key, marginals.keys()) { - separatorValues_.insert(key, theta_.at(key)); - } - - // Remove the marginalized factors and add them to the smoother cache - smootherFactors_.push_back(removedFactors); - removeFactors(removedFactorSlots); - - // Add the linearization point of the moved variables to the smoother cache BOOST_FOREACH(Key key, keysToMove) { - smootherValues_.insert(key, theta_.at(key)); + EliminationForest::removeChildrenIndices(indicesToEliminate, forest.at(ordering_.at(key))); } - // Remove marginalized keys from values (and separator) - BOOST_FOREACH(Key key, keysToMove) { - theta_.erase(key); + // Eliminate each top-most key, returning a Gaussian Factor on some of the remaining variables + // Convert the marginal factors into Linear Container Factors + // Add the marginal factor variables to the separator + NonlinearFactorGraph marginalFactors; + BOOST_FOREACH(Index index, indicesToEliminate) { + GaussianFactor::shared_ptr gaussianFactor = forest.at(index)->eliminateRecursive(parameters_.getEliminationFunction()); + if(gaussianFactor->size() > 0) { + LinearContainerFactor::shared_ptr marginalFactor(new LinearContainerFactor(gaussianFactor, ordering_, theta_)); + marginalFactors.push_back(marginalFactor); + // Add the keys associated with the marginal factor to the separator values + BOOST_FOREACH(Key key, *marginalFactor) { + if(!separatorValues_.exists(key)) { + separatorValues_.insert(key, theta_.at(key)); + } + } + } + } + std::vector marginalSlots = insertFactors(marginalFactors); + + + // Cache marginalized variables and factors for later transmission to the smoother + { + // Add the new marginal factors to the list of smootherSeparatorFactors. In essence, we have just moved the separator + smootherSummarizationSlots_.insert(smootherSummarizationSlots_.end(), marginalSlots.begin(), marginalSlots.end()); + + // Move the marginalized factors from the filter to the smoother (holding area) + // Note: Be careful to only move nonlinear factors and not any marginals that may also need to be removed + BOOST_FOREACH(size_t slot, removedFactorSlots) { + std::vector::iterator iter = std::find(smootherSummarizationSlots_.begin(), smootherSummarizationSlots_.end(), slot); + if(iter == smootherSummarizationSlots_.end()) { + // This is a real nonlinear factor. Add it to the smoother factor cache. + smootherFactors_.push_back(factors_.at(slot)); + } else { + // This is a marginal factor that was removed and replaced by a new marginal factor. Remove this slot from the separator factor list. + smootherSummarizationSlots_.erase(iter); + } + } + + // Add the linearization point of the moved variables to the smoother cache + BOOST_FOREACH(Key key, keysToMove) { + smootherValues_.insert(key, theta_.at(key)); + } } - // Permute the ordering such that the removed keys are at the end. - // This is a prerequisite for removing them from several structures - std::vector toBack; - BOOST_FOREACH(Key key, keysToMove) { - toBack.push_back(ordering_.at(key)); + // Remove the marginalized variables and factors from the filter + { + // Remove marginalized factors from the factor graph + std::vector slots(removedFactorSlots.begin(), removedFactorSlots.end()); + removeFactors(slots); + + // Remove marginalized keys from values (and separator) + BOOST_FOREACH(Key key, keysToMove) { + theta_.erase(key); + if(separatorValues_.exists(key)) { + separatorValues_.erase(key); + } + } + + // Permute the ordering such that the removed keys are at the end. + // This is a prerequisite for removing them from several structures + std::vector toBack; + BOOST_FOREACH(Key key, keysToMove) { + toBack.push_back(ordering_.at(key)); + } + Permutation forwardPermutation = Permutation::PushToBack(toBack, ordering_.size()); + ordering_.permuteInPlace(forwardPermutation); + delta_.permuteInPlace(forwardPermutation); + + // Remove marginalized keys from the ordering and delta + for(size_t i = 0; i < keysToMove.size(); ++i) { + ordering_.pop_back(); + delta_.pop_back(); + } } - Permutation forwardPermutation = Permutation::PushToBack(toBack, ordering_.size()); - ordering_.permuteInPlace(forwardPermutation); - delta_.permuteInPlace(forwardPermutation); - - // Remove marginalized keys from the ordering and delta - for(size_t i = 0; i < keysToMove.size(); ++i) { - ordering_.pop_back(); - delta_.pop_back(); - } - - -// // Calculate marginal factors on the remaining variables (after marginalizing 'keyToMove') -// // Note: It is assumed the ordering already has these keys first -// -// // text -// NonlinearFactorGraph marginalFactors = marginalize(factors_, theta_, ordering_, keysToMove, parameters_.getEliminationFunction()); -// -// // text -// BOOST_FOREACH(const NonlinearFactor::shared_ptr& marginalFactor, marginalFactors) { -// BOOST_FOREACH(Key key, *marginalFactor) { -// if(!separatorValues_.exists(key)) { -// separatorValues_.insert(key, theta_.at(key)); -// } -// } -// } -// std::vector marginalSlots = insertFactors(marginalFactors); -// -// // text -// // Use the variable Index to mark the factors that will be marginalized -// std::set removedFactorSlots; -// BOOST_FOREACH(Key key, keysToMove) { -// const FastList& slots = variableIndex[ordering_.at(key)]; -// removedFactorSlots.insert(slots.begin(), slots.end()); -// } -// -// -// -// -// // Create the linear factor graph -// GaussianFactorGraph linearFactorGraph = *factors_.linearize(theta_, ordering_); -// -// // Calculate the variable index -// VariableIndex variableIndex(linearFactorGraph, ordering_.size()); -// -// // Use the variable Index to mark the factors that will be marginalized -// std::set removedFactorSlots; -// BOOST_FOREACH(Key key, keysToMove) { -// const FastList& slots = variableIndex[ordering_.at(key)]; -// removedFactorSlots.insert(slots.begin(), slots.end()); -// } -// -// // Construct an elimination tree to perform sparse elimination -// std::vector forest( EliminationForest::Create(linearFactorGraph, variableIndex) ); -// -// // This is a tree. Only the top-most nodes/indices need to be eliminated; all of the children will be eliminated automatically -// // Find the subset of nodes/keys that must be eliminated -// std::set indicesToEliminate; -// BOOST_FOREACH(Key key, keysToMove) { -// indicesToEliminate.insert(ordering_.at(key)); -// } -// BOOST_FOREACH(Key key, keysToMove) { -// EliminationForest::removeChildrenIndices(indicesToEliminate, forest.at(ordering_.at(key))); -// } -// -// // Eliminate each top-most key, returning a Gaussian Factor on some of the remaining variables -// // Convert the marginal factors into Linear Container Factors -// // Add the marginal factor variables to the separator -// NonlinearFactorGraph marginalFactors; -// BOOST_FOREACH(Index index, indicesToEliminate) { -// GaussianFactor::shared_ptr gaussianFactor = forest.at(index)->eliminateRecursive(parameters_.getEliminationFunction()); -// if(gaussianFactor->size() > 0) { -// LinearContainerFactor::shared_ptr marginalFactor(new LinearContainerFactor(gaussianFactor, ordering_, theta_)); -// marginalFactors.push_back(marginalFactor); -// // Add the keys associated with the marginal factor to the separator values -// BOOST_FOREACH(Key key, *marginalFactor) { -// if(!separatorValues_.exists(key)) { -// separatorValues_.insert(key, theta_.at(key)); -// } -// } -// } -// } -// std::vector marginalSlots = insertFactors(marginalFactors); -// -// -// // Cache marginalized variables and factors for later transmission to the smoother -// { -// // Add the new marginal factors to the list of smootherSeparatorFactors. In essence, we have just moved the separator -// smootherSummarizationSlots_.insert(smootherSummarizationSlots_.end(), marginalSlots.begin(), marginalSlots.end()); -// -// // Move the marginalized factors from the filter to the smoother (holding area) -// // Note: Be careful to only move nonlinear factors and not any marginals that may also need to be removed -// BOOST_FOREACH(size_t slot, removedFactorSlots) { -// std::vector::iterator iter = std::find(smootherSummarizationSlots_.begin(), smootherSummarizationSlots_.end(), slot); -// if(iter == smootherSummarizationSlots_.end()) { -// // This is a real nonlinear factor. Add it to the smoother factor cache. -// smootherFactors_.push_back(factors_.at(slot)); -// } else { -// // This is a marginal factor that was removed and replaced by a new marginal factor. Remove this slot from the smoother summarization list. -// smootherSummarizationSlots_.erase(iter); -// } -// } -// -// // Add the linearization point of the moved variables to the smoother cache -// BOOST_FOREACH(Key key, keysToMove) { -// smootherValues_.insert(key, theta_.at(key)); -// } -// } -// -// // Remove the marginalized variables and factors from the filter -// { -// // Remove marginalized factors from the factor graph -// std::vector slots(removedFactorSlots.begin(), removedFactorSlots.end()); -// removeFactors(slots); -// -// // Remove marginalized keys from values (and separator) -// BOOST_FOREACH(Key key, keysToMove) { -// theta_.erase(key); -// if(separatorValues_.exists(key)) { -// separatorValues_.erase(key); -// } -// } -// -// // Permute the ordering such that the removed keys are at the end. -// // This is a prerequisite for removing them from several structures -// std::vector toBack; -// BOOST_FOREACH(Key key, keysToMove) { -// toBack.push_back(ordering_.at(key)); -// } -// Permutation forwardPermutation = Permutation::PushToBack(toBack, ordering_.size()); -// ordering_.permuteInPlace(forwardPermutation); -// delta_.permuteInPlace(forwardPermutation); -// -// // Remove marginalized keys from the ordering and delta -// for(size_t i = 0; i < keysToMove.size(); ++i) { -// ordering_.pop_back(); -// delta_.pop_back(); -// } -// } } /* ************************************************************************* */ diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h index 7feee4d82..9a7690786 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h @@ -114,7 +114,7 @@ public: * @param newTheta Initialization points for new variables to be added to the filter * You must include here all new variables occurring in newFactors that were not already * in the filter. - * @param keysToMove An optional set of keys to move from the filter to the smoother + * @param keysToMove An optional set of keys to remove from the filter and */ Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), const Values& newTheta = Values(), const boost::optional >& keysToMove = boost::none); @@ -129,11 +129,7 @@ protected: VectorValues delta_; ///< The current set of linear deltas from the linearization point std::queue availableSlots_; ///< The set of available factor graph slots caused by deleting factors Values separatorValues_; ///< The linearization points of the separator variables. These should not be updated during optimization. - std::vector currentSmootherSummarizationSlots_; ///< The slots in factor graph that correspond to the current smoother summarization on the current separator - - // Storage for information from the Smoother - NonlinearFactorGraph previousSmootherSummarization_; ///< The smoother summarization on the old separator sent by the smoother during the last synchronization - NonlinearFactorGraph smootherShortcut_; ///< A set of conditional factors from the old separator to the current separator (recursively calculated during each filter update) + std::vector smootherSummarizationSlots_; ///< The slots in factor graph that correspond to the current smoother summarization factors // Storage for information to be sent to the smoother NonlinearFactorGraph filterSummarization_; ///< A temporary holding place for calculated filter summarization factors to be sent to the smoother @@ -197,17 +193,15 @@ private: /** Use colamd to update into an efficient ordering */ void reorder(const boost::optional >& keysToMove = boost::none); - /** Marginalize out the set of requested variables from the filter, caching them for the smoother - * This effectively moves the separator. - * - * @param keysToMove The set of keys to move from the filter to the smoother - */ - void moveSeparator(const FastList& keysToMove); - /** Use a modified version of L-M to update the linearization point and delta */ static Result optimize(const NonlinearFactorGraph& factors, Values& theta, const Ordering& ordering, VectorValues& delta, const Values& linearValues, const LevenbergMarquardtParams& parameters); + /** Marginalize out the set of requested variables from the filter, caching them for the smoother + * This effectively moves the separator. + */ + void marginalize(const FastList& keysToMove); + /** Marginalize out the set of requested variables from the filter, caching them for the smoother * This effectively moves the separator. */ From 41b0b903768931a63f704be4d8e204e454090544 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 22 May 2013 17:27:42 +0000 Subject: [PATCH 030/256] Added nrNodes() and checkConsistency() to BayesTree --- gtsam.h | 2 ++ gtsam/inference/BayesTree-inl.h | 23 +++++++++++++++++++++-- gtsam/inference/BayesTree.h | 10 ++++++++++ 3 files changed, 33 insertions(+), 2 deletions(-) diff --git a/gtsam.h b/gtsam.h index dbd3d9fad..841c4b01c 100644 --- a/gtsam.h +++ b/gtsam.h @@ -811,6 +811,7 @@ virtual class BayesTree { //Standard Interface //size_t findParentClique(const gtsam::IndexVector& parents) const; size_t size(); + size_t nrNodes() const; void saveGraph(string s) const; CLIQUE* root() const; void clear(); @@ -818,6 +819,7 @@ virtual class BayesTree { void insert(const CLIQUE* subtree); size_t numCachedSeparatorMarginals() const; CLIQUE* clique(size_t j) const; + bool checkConsistency() const; }; template diff --git a/gtsam/inference/BayesTree-inl.h b/gtsam/inference/BayesTree-inl.h index 9f672e56f..f3aeacb36 100644 --- a/gtsam/inference/BayesTree-inl.h +++ b/gtsam/inference/BayesTree-inl.h @@ -799,5 +799,24 @@ namespace gtsam { } } -} -/// namespace gtsam + /* ************************************************************************* */ + template + bool BayesTree::checkConsistency() const { + // Verify all nodes are mapped to initialized cliques + bool result = true; + for (gtsam::Index idx=0; idx Date: Wed, 22 May 2013 17:27:43 +0000 Subject: [PATCH 031/256] Added check to prevent trying to add disconnected factors in iSAM1 --- gtsam/inference/ISAM-inl.h | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/gtsam/inference/ISAM-inl.h b/gtsam/inference/ISAM-inl.h index 45031191b..4b5333f33 100644 --- a/gtsam/inference/ISAM-inl.h +++ b/gtsam/inference/ISAM-inl.h @@ -36,8 +36,14 @@ namespace gtsam { const FG& newFactors, Cliques& orphans, typename FG::Eliminate function) { // Remove the contaminated part of the Bayes tree + // Throw exception if disconnected BayesNet bn; - this->removeTop(newFactors.keys(), bn, orphans); + if (!this->empty()) { + this->removeTop(newFactors.keys(), bn, orphans); + if (bn.empty()) + throw std::runtime_error( + "ISAM::update_internal(): no variables in common between existing Bayes tree and incoming factors!"); + } FG factors(bn); // add the factors themselves From 228a26947f180108b355c1a5274b46e473b00183 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 22 May 2013 17:27:44 +0000 Subject: [PATCH 032/256] Removed checkConsistency() from BayesTree --- gtsam.h | 1 - gtsam/inference/BayesTree-inl.h | 18 ------------------ gtsam/inference/BayesTree.h | 7 ------- 3 files changed, 26 deletions(-) diff --git a/gtsam.h b/gtsam.h index 841c4b01c..429cbc7d3 100644 --- a/gtsam.h +++ b/gtsam.h @@ -819,7 +819,6 @@ virtual class BayesTree { void insert(const CLIQUE* subtree); size_t numCachedSeparatorMarginals() const; CLIQUE* clique(size_t j) const; - bool checkConsistency() const; }; template diff --git a/gtsam/inference/BayesTree-inl.h b/gtsam/inference/BayesTree-inl.h index f3aeacb36..d5592ed2a 100644 --- a/gtsam/inference/BayesTree-inl.h +++ b/gtsam/inference/BayesTree-inl.h @@ -800,23 +800,5 @@ namespace gtsam { } /* ************************************************************************* */ - template - bool BayesTree::checkConsistency() const { - // Verify all nodes are mapped to initialized cliques - bool result = true; - for (gtsam::Index idx=0; idx Date: Thu, 23 May 2013 18:12:00 +0000 Subject: [PATCH 033/256] Caught corner case in summarization causing ccolamd to segfault --- gtsam/nonlinear/summarization.cpp | 19 +++++++------------ gtsam/nonlinear/summarization.h | 3 +++ tests/testSummarization.cpp | 27 +++++++++++++++++++++++---- 3 files changed, 33 insertions(+), 16 deletions(-) diff --git a/gtsam/nonlinear/summarization.cpp b/gtsam/nonlinear/summarization.cpp index 5722f9c2c..acd222d43 100644 --- a/gtsam/nonlinear/summarization.cpp +++ b/gtsam/nonlinear/summarization.cpp @@ -18,18 +18,13 @@ std::pair summarize(const NonlinearFactorGraph& graph, const Values& values, const KeySet& saved_keys, SummarizationMode mode) { const size_t nrEliminatedKeys = values.size() - saved_keys.size(); - // // compute a new ordering with non-saved keys first - // Ordering ordering; - // KeySet eliminatedKeys; - // BOOST_FOREACH(const Key& key, values.keys()) { - // if (!saved_keys.count(key)) { - // eliminatedKeys.insert(key); - // ordering += key; - // } - // } - // - // BOOST_FOREACH(const Key& key, saved_keys) - // ordering += key; + + // If we aren't eliminating anything, linearize and return + if (!nrEliminatedKeys || saved_keys.empty()) { + Ordering ordering = *values.orderingArbitrary(); + GaussianFactorGraph linear_graph = *graph.linearize(values, ordering); + return make_pair(linear_graph, ordering); + } // Compute a constrained ordering with variables grouped to end std::map ordering_constraints; diff --git a/gtsam/nonlinear/summarization.h b/gtsam/nonlinear/summarization.h index faa2003ef..c25d5d934 100644 --- a/gtsam/nonlinear/summarization.h +++ b/gtsam/nonlinear/summarization.h @@ -29,6 +29,9 @@ typedef enum { * Summarization function to remove a subset of variables from a system with the * sequential solver. This does not require that the system be fully constrained. * + * Requirement: set of keys in the graph should match the set of keys in the + * values structure. + * * @param graph A full nonlinear graph * @param values The chosen linearization point * @param saved_keys is the set of keys for variables that should remain diff --git a/tests/testSummarization.cpp b/tests/testSummarization.cpp index 2f3cfdf03..bf7342202 100644 --- a/tests/testSummarization.cpp +++ b/tests/testSummarization.cpp @@ -34,17 +34,16 @@ typedef gtsam::PriorFactor PosePrior; typedef gtsam::BetweenFactor PoseBetween; typedef gtsam::BearingRangeFactor PosePointBearingRange; +gtsam::noiseModel::Base::shared_ptr model2 = noiseModel::Unit::Create(2); +gtsam::noiseModel::Base::shared_ptr model3 = noiseModel::Unit::Create(3); + /* ************************************************************************* */ TEST( testSummarization, example_from_ddf1 ) { - Key xA0 = LabeledSymbol('x', 'A', 0), xA1 = LabeledSymbol('x', 'A', 1), xA2 = LabeledSymbol('x', 'A', 2); Key lA3 = LabeledSymbol('l', 'A', 3), lA5 = LabeledSymbol('l', 'A', 5); - gtsam::noiseModel::Base::shared_ptr model2 = noiseModel::Unit::Create(2); - gtsam::noiseModel::Base::shared_ptr model3 = noiseModel::Unit::Create(3); - SharedDiagonal diagmodel2 = noiseModel::Unit::Create(2); SharedDiagonal diagmodel4 = noiseModel::Unit::Create(4); @@ -218,6 +217,26 @@ TEST( testSummarization, example_from_ddf1 ) { } } +/* ************************************************************************* */ +TEST( testSummarization, no_summarize_case ) { + // Checks a corner case in which no variables are being eliminated + gtsam::Key key = 7; + gtsam::KeySet saved_keys; saved_keys.insert(key); + NonlinearFactorGraph graph; + graph.add(PosePrior(key, Pose2(1.0, 2.0, 0.3), model3)); + graph.add(PosePrior(key, Pose2(2.0, 3.0, 0.4), model3)); + Values values; + values.insert(key, Pose2(0.0, 0.0, 0.1)); + + SummarizationMode mode = SEQUENTIAL_CHOLESKY; + GaussianFactorGraph actLinGraph; Ordering actOrdering; + boost::tie(actLinGraph, actOrdering) = summarize(graph, values, saved_keys, mode); + Ordering expOrdering; expOrdering += key; + GaussianFactorGraph expLinGraph = *graph.linearize(values, expOrdering); + EXPECT(assert_equal(expOrdering, actOrdering)); + EXPECT(assert_equal(expLinGraph, actLinGraph)); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ From 045a3d281f3c704f003cc3034d40ed353dbbe22f Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Tue, 4 Jun 2013 13:37:12 +0000 Subject: [PATCH 034/256] Only use Boost dynamic auto-linking flag on Windows --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e4b6efb0e..bdbd25abf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -100,7 +100,7 @@ endif() # Find boost # If using Boost shared libs, set up auto linking for shared libs -if(NOT Boost_USE_STATIC_LIBS) +if(MSVC AND NOT Boost_USE_STATIC_LIBS) add_definitions(-DBOOST_ALL_DYN_LINK) endif() From ac50d39a97c58348ef51ffe182816ec28e3b3fec Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Tue, 4 Jun 2013 13:37:13 +0000 Subject: [PATCH 035/256] Swapped group name and test name in CppUnitLite to match the convention we use in unit tests --- CppUnitLite/Test.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/CppUnitLite/Test.h b/CppUnitLite/Test.h index 52b79f65c..9f97757b6 100644 --- a/CppUnitLite/Test.h +++ b/CppUnitLite/Test.h @@ -60,7 +60,7 @@ protected: /** * Normal test will wrap execution in a try/catch block to catch exceptions more effectively */ -#define TEST(testName, testGroup)\ +#define TEST(testGroup, testName)\ class testGroup##testName##Test : public Test \ { public: testGroup##testName##Test () : Test (#testName "Test", __FILE__, __LINE__, true) {} \ virtual ~testGroup##testName##Test () {};\ @@ -72,7 +72,7 @@ protected: * For debugging only: use TEST_UNSAFE to allow debuggers to have access to exceptions, as this * will not wrap execution with a try/catch block */ -#define TEST_UNSAFE(testName, testGroup)\ +#define TEST_UNSAFE(testGroup, testName)\ class testGroup##testName##Test : public Test \ { public: testGroup##testName##Test () : Test (#testName "Test", __FILE__, __LINE__, false) {} \ virtual ~testGroup##testName##Test () {};\ From b3282577fbb1aa14637ecb36974af812a0c52830 Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Tue, 4 Jun 2013 14:07:44 +0000 Subject: [PATCH 037/256] Revert "Swapped group name and test name in CppUnitLite to match the convention we use in unit tests" This reverts commit c186908e755d034cc821376fd78c7118c9ccf48a. --- CppUnitLite/Test.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/CppUnitLite/Test.h b/CppUnitLite/Test.h index 9f97757b6..52b79f65c 100644 --- a/CppUnitLite/Test.h +++ b/CppUnitLite/Test.h @@ -60,7 +60,7 @@ protected: /** * Normal test will wrap execution in a try/catch block to catch exceptions more effectively */ -#define TEST(testGroup, testName)\ +#define TEST(testName, testGroup)\ class testGroup##testName##Test : public Test \ { public: testGroup##testName##Test () : Test (#testName "Test", __FILE__, __LINE__, true) {} \ virtual ~testGroup##testName##Test () {};\ @@ -72,7 +72,7 @@ protected: * For debugging only: use TEST_UNSAFE to allow debuggers to have access to exceptions, as this * will not wrap execution with a try/catch block */ -#define TEST_UNSAFE(testGroup, testName)\ +#define TEST_UNSAFE(testName, testGroup)\ class testGroup##testName##Test : public Test \ { public: testGroup##testName##Test () : Test (#testName "Test", __FILE__, __LINE__, false) {} \ virtual ~testGroup##testName##Test () {};\ From b2d4469cb3ae993bad52f83d7f5f533110d032d2 Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Tue, 4 Jun 2013 17:34:02 +0000 Subject: [PATCH 038/256] Added missing export tag --- gtsam_unstable/slam/AHRS.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/slam/AHRS.h b/gtsam_unstable/slam/AHRS.h index 284fe2fc6..01c61704b 100644 --- a/gtsam_unstable/slam/AHRS.h +++ b/gtsam_unstable/slam/AHRS.h @@ -14,7 +14,7 @@ namespace gtsam { -Matrix cov(const Matrix& m); +GTSAM_UNSTABLE_EXPORT Matrix cov(const Matrix& m); class GTSAM_UNSTABLE_EXPORT AHRS { From 84903d05c2846014fda650921e5f948ea60774cb Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Tue, 4 Jun 2013 17:34:03 +0000 Subject: [PATCH 039/256] Fixed iSAM2 bug where assignment operator and copy constructor may cause null pointer exception when trying to clone cached linear factors, which become null by calling marginalizeLeaves with linear factor caching enabled. --- gtsam/nonlinear/ISAM2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index 9b063f0ce..a209c3d44 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -125,7 +125,7 @@ ISAM2& ISAM2::operator=(const ISAM2& rhs) { linearFactors_ = GaussianFactorGraph(); linearFactors_.reserve(rhs.linearFactors_.size()); BOOST_FOREACH(const GaussianFactor::shared_ptr& linearFactor, rhs.linearFactors_) { - linearFactors_.push_back(linearFactor->clone()); } + linearFactors_.push_back(linearFactor ? linearFactor->clone() : GaussianFactor::shared_ptr()); } ordering_ = rhs.ordering_; params_ = rhs.params_; From 7fcdc467c17b081498ffc778890becd651eca6a3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 5 Jun 2013 16:10:16 +0000 Subject: [PATCH 040/256] Added stream operator << and renamed dist to distance --- gtsam/geometry/Point2.cpp | 6 ++++++ gtsam/geometry/Point2.h | 8 ++++++++ 2 files changed, 14 insertions(+) diff --git a/gtsam/geometry/Point2.cpp b/gtsam/geometry/Point2.cpp index 444f5d759..e188b2930 100644 --- a/gtsam/geometry/Point2.cpp +++ b/gtsam/geometry/Point2.cpp @@ -40,4 +40,10 @@ double Point2::norm() const { return sqrt(x_*x_ + y_*y_); } +/* ************************************************************************* */ +ostream &operator<<(ostream &os, const Point2& p) { + os << '(' << p.x() << ", " << p.y() << ')'; + return os; +} + } // namespace gtsam diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 850f84b01..74ea16638 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -151,6 +151,11 @@ public: Point2 unit() const { return *this/norm(); } /** distance between two points */ + inline double distance(const Point2& p2) const { + return (p2 - *this).norm(); + } + + /** @deprecated The following function has been deprecated, use distance above */ inline double dist(const Point2& p2) const { return (p2 - *this).norm(); } @@ -184,6 +189,9 @@ public: inline void operator *= (double s) {x_*=s;y_*=s;} /// @} + /// Streaming + friend std::ostream &operator<<(std::ostream &os, const Point2& p); + private: /// @name Advanced Interface From ebcc638ef5e07d9630c6b5112c6de6e27212c985 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 5 Jun 2013 16:11:36 +0000 Subject: [PATCH 041/256] renamed dist to distance (dist still works but now deprecated) --- gtsam/geometry/Cal3DS2.cpp | 2 +- gtsam/geometry/Point3.h | 9 +++++++-- gtsam/geometry/tests/testPoint2.cpp | 17 +++++++++++++---- gtsam_unstable/dynamics/PoseRTV.cpp | 2 +- gtsam_unstable/geometry/SimPolygon2D.cpp | 6 +++--- gtsam_unstable/geometry/SimWall2D.cpp | 4 ++-- gtsam_unstable/geometry/SimWall2D.h | 2 +- 7 files changed, 28 insertions(+), 14 deletions(-) diff --git a/gtsam/geometry/Cal3DS2.cpp b/gtsam/geometry/Cal3DS2.cpp index 6816346e8..1d5ad695a 100644 --- a/gtsam/geometry/Cal3DS2.cpp +++ b/gtsam/geometry/Cal3DS2.cpp @@ -83,7 +83,7 @@ Point2 Cal3DS2::calibrate(const Point2& pi, const double tol) const { const int maxIterations = 10; int iteration; for ( iteration = 0 ; iteration < maxIterations ; ++iteration ) { - if ( uncalibrate(pn).dist(pi) <= tol ) break; + if ( uncalibrate(pn).distance(pi) <= tol ) break; const double x = pn.x(), y = pn.y(), xy = x*y, xx = x*x, yy = y*y ; const double rr = xx + yy ; const double g = (1+k1_*rr+k2_*rr*rr) ; diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 7e0c59ba9..4713dacab 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -153,8 +153,13 @@ namespace gtsam { Point3 operator / (double s) const; /** distance between two points */ - double dist(const Point3& p2) const { - return std::sqrt(pow(x()-p2.x(),2.0) + pow(y()-p2.y(),2.0) + pow(z()-p2.z(),2.0)); + inline double distance(const Point3& p2) const { + return (p2 - *this).norm(); + } + + /** @deprecated The following function has been deprecated, use distance above */ + inline double dist(const Point3& p2) const { + return (p2 - *this).norm(); } /** Distance of the point from the origin */ diff --git a/gtsam/geometry/tests/testPoint2.cpp b/gtsam/geometry/tests/testPoint2.cpp index 446255803..7c73b28a2 100644 --- a/gtsam/geometry/tests/testPoint2.cpp +++ b/gtsam/geometry/tests/testPoint2.cpp @@ -75,19 +75,28 @@ TEST( Point2, norm) Point2 p0(cos(5.0), sin(5.0)); DOUBLES_EQUAL(1,p0.norm(),1e-6); Point2 p1(4, 5), p2(1, 1); - DOUBLES_EQUAL( 5,p1.dist(p2),1e-6); + DOUBLES_EQUAL( 5,p1.distance(p2),1e-6); DOUBLES_EQUAL( 5,(p2-p1).norm(),1e-6); } /* ************************************************************************* */ TEST( Point2, unit) { - Point2 p0(10.0, 0.0), p1(0.0,-10.0), p2(10.0, 10.0); - EXPECT(assert_equal(Point2(1.0, 0.0), p0.unit(), 1e-6)); - EXPECT(assert_equal(Point2(0.0,-1.0), p1.unit(), 1e-6)); + Point2 p0(10, 0), p1(0,-10), p2(10, 10); + EXPECT(assert_equal(Point2(1, 0), p0.unit(), 1e-6)); + EXPECT(assert_equal(Point2(0,-1), p1.unit(), 1e-6)); EXPECT(assert_equal(Point2(sqrt(2.0)/2.0, sqrt(2.0)/2.0), p2.unit(), 1e-6)); } +/* ************************************************************************* */ +TEST( Point2, stream) +{ + Point2 p(1,2); + std::ostringstream os; + os << p; + EXPECT(os.str() == "(1, 2)"); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ diff --git a/gtsam_unstable/dynamics/PoseRTV.cpp b/gtsam_unstable/dynamics/PoseRTV.cpp index 5a442560e..dd2671530 100644 --- a/gtsam_unstable/dynamics/PoseRTV.cpp +++ b/gtsam_unstable/dynamics/PoseRTV.cpp @@ -232,7 +232,7 @@ double PoseRTV::range(const PoseRTV& other, boost::optional H1, boost::optional H2) const { if (H1) *H1 = numericalDerivative21(range_, *this, other, 1e-5); if (H2) *H2 = numericalDerivative22(range_, *this, other, 1e-5); - return t().dist(other.t()); + return t().distance(other.t()); } /* ************************************************************************* */ diff --git a/gtsam_unstable/geometry/SimPolygon2D.cpp b/gtsam_unstable/geometry/SimPolygon2D.cpp index bc22cb024..85b592b98 100644 --- a/gtsam_unstable/geometry/SimPolygon2D.cpp +++ b/gtsam_unstable/geometry/SimPolygon2D.cpp @@ -152,7 +152,7 @@ SimPolygon2D SimPolygon2D::randomTriangle( Pose2 xC = xB.retract(delta(3, 0, dBC)); // use triangle equality to verify non-degenerate triangle - double dAC = xA.t().dist(xC.t()); + double dAC = xA.t().distance(xC.t()); // form a triangle and test if it meets requirements SimPolygon2D test_tri = SimPolygon2D::createTriangle(xA.t(), xB.t(), xC.t()); @@ -165,7 +165,7 @@ SimPolygon2D SimPolygon2D::randomTriangle( insideBox(side_len, test_tri.landmark(0)) && insideBox(side_len, test_tri.landmark(1)) && insideBox(side_len, test_tri.landmark(2)) && - test_tri.landmark(1).dist(test_tri.landmark(2)) > min_side_len && + test_tri.landmark(1).distance(test_tri.landmark(2)) > min_side_len && !nearExisting(lms, test_tri.landmark(0), min_vertex_dist) && !nearExisting(lms, test_tri.landmark(1), min_vertex_dist) && !nearExisting(lms, test_tri.landmark(2), min_vertex_dist) && @@ -321,7 +321,7 @@ bool SimPolygon2D::insideBox(double s, const Point2& p) { bool SimPolygon2D::nearExisting(const std::vector& S, const Point2& p, double threshold) { BOOST_FOREACH(const Point2& Sp, S) - if (Sp.dist(p) < threshold) + if (Sp.distance(p) < threshold) return true; return false; } diff --git a/gtsam_unstable/geometry/SimWall2D.cpp b/gtsam_unstable/geometry/SimWall2D.cpp index b03f52890..78347a077 100644 --- a/gtsam_unstable/geometry/SimWall2D.cpp +++ b/gtsam_unstable/geometry/SimWall2D.cpp @@ -139,7 +139,7 @@ std::pair moveWithBounce(const Pose2& cur_pose, double step_size, Point2 cur_intersection; if (wall.intersects(traj,cur_intersection)) { collision = true; - if (cur_pose.t().dist(cur_intersection) < cur_pose.t().dist(intersection)) { + if (cur_pose.t().distance(cur_intersection) < cur_pose.t().distance(intersection)) { intersection = cur_intersection; closest_wall = wall; } @@ -155,7 +155,7 @@ std::pair moveWithBounce(const Pose2& cur_pose, double step_size, norm = norm / norm.norm(); // Simple check to make sure norm is on side closest robot - if (cur_pose.t().dist(intersection + norm) > cur_pose.t().dist(intersection - norm)) + if (cur_pose.t().distance(intersection + norm) > cur_pose.t().distance(intersection - norm)) norm = norm.inverse(); // using the reflection diff --git a/gtsam_unstable/geometry/SimWall2D.h b/gtsam_unstable/geometry/SimWall2D.h index d3e86296a..cf2142af8 100644 --- a/gtsam_unstable/geometry/SimWall2D.h +++ b/gtsam_unstable/geometry/SimWall2D.h @@ -43,7 +43,7 @@ namespace gtsam { SimWall2D scale(double s) const { return SimWall2D(s*a_, s*b_); } /** geometry */ - double length() const { return a_.dist(b_); } + double length() const { return a_.distance(b_); } Point2 midpoint() const; /** From 0789954ec5e410efa0a3f097b584d4ca823aafad Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 5 Jun 2013 18:43:54 +0000 Subject: [PATCH 042/256] Added stream operator << --- gtsam/geometry/Point3.cpp | 21 ++++++++++++++++++--- gtsam/geometry/Point3.h | 10 +++++++--- gtsam/geometry/tests/testPoint3.cpp | 9 +++++++++ 3 files changed, 34 insertions(+), 6 deletions(-) diff --git a/gtsam/geometry/Point3.cpp b/gtsam/geometry/Point3.cpp index 95c7582c6..c8ee78565 100644 --- a/gtsam/geometry/Point3.cpp +++ b/gtsam/geometry/Point3.cpp @@ -14,10 +14,11 @@ * @brief 3D Point */ -#include #include #include +using namespace std; + namespace gtsam { /** Explicit instantiation of base class to export members */ @@ -30,8 +31,8 @@ bool Point3::equals(const Point3 & q, double tol) const { /* ************************************************************************* */ -void Point3::print(const std::string& s) const { - std::cout << s << "(" << x_ << ", " << y_ << ", " << z_ << ")" << std::endl; +void Point3::print(const string& s) const { + cout << s << "(" << x_ << ", " << y_ << ", " << z_ << ")" << endl; } /* ************************************************************************* */ @@ -49,14 +50,17 @@ Point3 Point3::operator+(const Point3& q) const { Point3 Point3::operator- (const Point3& q) const { return Point3( x_ - q.x_, y_ - q.y_, z_ - q.z_ ); } + /* ************************************************************************* */ Point3 Point3::operator*(double s) const { return Point3(x_ * s, y_ * s, z_ * s); } + /* ************************************************************************* */ Point3 Point3::operator/(double s) const { return Point3(x_ / s, y_ / s, z_ / s); } + /* ************************************************************************* */ Point3 Point3::add(const Point3 &q, boost::optional H1, boost::optional H2) const { @@ -64,6 +68,7 @@ Point3 Point3::add(const Point3 &q, if (H2) *H2 = eye(3,3); return *this + q; } + /* ************************************************************************* */ Point3 Point3::sub(const Point3 &q, boost::optional H1, boost::optional H2) const { @@ -71,20 +76,30 @@ Point3 Point3::sub(const Point3 &q, if (H2) *H2 = -eye(3,3); return *this - q; } + /* ************************************************************************* */ Point3 Point3::cross(const Point3 &q) const { return Point3( y_*q.z_ - z_*q.y_, z_*q.x_ - x_*q.z_, x_*q.y_ - y_*q.x_ ); } + /* ************************************************************************* */ double Point3::dot(const Point3 &q) const { return ( x_*q.x_ + y_*q.y_ + z_*q.z_ ); } + /* ************************************************************************* */ double Point3::norm() const { return sqrt( x_*x_ + y_*y_ + z_*z_ ); } + +/* ************************************************************************* */ +ostream &operator<<(ostream &os, const Point3& p) { + os << '(' << p.x() << ", " << p.y() << ", " << p.z() << ')'; + return os; +} + /* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 4713dacab..cf30bd1ff 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -21,13 +21,14 @@ #pragma once -#include -#include - #include #include #include +#include + +#include + namespace gtsam { /** @@ -202,6 +203,9 @@ namespace gtsam { /// @} + /// Output stream operator + friend std::ostream &operator<<(std::ostream &os, const Point3& p); + private: /// @name Advanced Interface diff --git a/gtsam/geometry/tests/testPoint3.cpp b/gtsam/geometry/tests/testPoint3.cpp index 07152df36..b50e1b9d9 100644 --- a/gtsam/geometry/tests/testPoint3.cpp +++ b/gtsam/geometry/tests/testPoint3.cpp @@ -71,6 +71,15 @@ TEST( Point3, dot) CHECK(ones.dot(Point3(1,1,0)) == 2); } +/* ************************************************************************* */ +TEST( Point3, stream) +{ + Point3 p(1,2, -3); + std::ostringstream os; + os << p; + EXPECT(os.str() == "(1, 2, -3)"); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ From f4ad135040248a432bffc3431eb4e75c3f03fd5e Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 5 Jun 2013 23:39:42 +0000 Subject: [PATCH 043/256] testVelocityConstraint3.run target --- .cproject | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/.cproject b/.cproject index e5b4e113a..ff425c83f 100644 --- a/.cproject +++ b/.cproject @@ -453,6 +453,14 @@ true true + + make + -j5 + testVelocityConstraint3.run + true + true + true + make -j5 From 64334e25842ca47dcda2372da2201f8a1df24496 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 5 Jun 2013 23:40:05 +0000 Subject: [PATCH 044/256] smarter compose --- gtsam/geometry/Rot2.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 591e5c8a0..45012770f 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -116,11 +116,11 @@ namespace gtsam { } /** Compose - make a new rotation by adding angles */ - inline Rot2 compose(const Rot2& R1, boost::optional H1 = + inline Rot2 compose(const Rot2& R, boost::optional H1 = boost::none, boost::optional H2 = boost::none) const { if (H1) *H1 = eye(1); if (H2) *H2 = eye(1); - return *this * R1; + return fromCosSin(c_ * R.c_ - s_ * R.s_, s_ * R.c_ + c_ * R.s_); } /** Compose - make a new rotation by adding angles */ @@ -129,11 +129,11 @@ namespace gtsam { } /** Between using the default implementation */ - inline Rot2 between(const Rot2& p2, boost::optional H1 = + inline Rot2 between(const Rot2& R, boost::optional H1 = boost::none, boost::optional H2 = boost::none) const { if (H1) *H1 = -eye(1); if (H2) *H2 = eye(1); - return between_default(*this, p2); + return fromCosSin(c_ * R.c_ + s_ * R.s_, -s_ * R.c_ + c_ * R.s_); } /// @} From 640fcd94b11bc836fac15e54d7a80f1e39fd7530 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 5 Jun 2013 23:41:46 +0000 Subject: [PATCH 045/256] Added stream operator << --- .cproject | 358 ++++++++++++++--------------- gtsam/geometry/Rot3.h | 3 + gtsam/geometry/Rot3M.cpp | 9 + gtsam/geometry/Rot3Q.cpp | 9 + gtsam/geometry/tests/testRot3M.cpp | 9 + gtsam/geometry/tests/testRot3Q.cpp | 9 + 6 files changed, 217 insertions(+), 180 deletions(-) diff --git a/.cproject b/.cproject index ff425c83f..872909c06 100644 --- a/.cproject +++ b/.cproject @@ -309,6 +309,14 @@ true true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j2 @@ -335,7 +343,6 @@ make - tests/testBayesTree.run true false @@ -343,7 +350,6 @@ make - testBinaryBayesNet.run true false @@ -391,7 +397,6 @@ make - testSymbolicBayesNet.run true false @@ -399,7 +404,6 @@ make - tests/testSymbolicFactor.run true false @@ -407,7 +411,6 @@ make - testSymbolicFactorGraph.run true false @@ -423,20 +426,11 @@ make - tests/testBayesTree true false true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j5 @@ -533,22 +527,6 @@ false true - - make - -j2 - tests/testPose2.run - true - true - true - - - make - -j2 - tests/testPose3.run - true - true - true - make -j2 @@ -565,6 +543,22 @@ true true + + make + -j2 + tests/testPose2.run + true + true + true + + + make + -j2 + tests/testPose3.run + true + true + true + make -j2 @@ -589,26 +583,34 @@ true true - + make - -j2 - all + -j5 + testValues.run true true true - + make - -j2 - check + -j5 + testOrdering.run true true true - + make - -j2 - clean + -j5 + testKey.run + true + true + true + + + make + -j5 + testLinearContainerFactor.run true true true @@ -693,34 +695,26 @@ true true - + make - -j5 - testValues.run + -j2 + all true true true - + make - -j5 - testOrdering.run + -j2 + check true true true - + make - -j5 - testKey.run - true - true - true - - - make - -j5 - testLinearContainerFactor.run + -j2 + clean true true true @@ -1079,7 +1073,6 @@ make - testGraph.run true false @@ -1087,7 +1080,6 @@ make - testJunctionTree.run true false @@ -1095,7 +1087,6 @@ make - testSymbolicBayesNetB.run true false @@ -1263,7 +1254,6 @@ make - testErrors.run true false @@ -1309,6 +1299,14 @@ true true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j2 @@ -1389,14 +1387,6 @@ true true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j2 @@ -1621,6 +1611,14 @@ true true + + make + -j5 + testRot3Q.run + true + true + true + make -j2 @@ -1703,6 +1701,7 @@ make + testSimulated2DOriented.run true false @@ -1742,6 +1741,7 @@ make + testSimulated2D.run true false @@ -1749,6 +1749,7 @@ make + testSimulated3D.run true false @@ -1948,6 +1949,7 @@ make + tests/testGaussianISAM2 true false @@ -1969,6 +1971,102 @@ true true + + make + -j2 + testRot3.run + true + true + true + + + make + -j2 + testRot2.run + true + true + true + + + make + -j2 + testPose3.run + true + true + true + + + make + -j2 + timeRot3.run + true + true + true + + + make + -j2 + testPose2.run + true + true + true + + + make + -j2 + testCal3_S2.run + true + true + true + + + make + -j2 + testSimpleCamera.run + true + true + true + + + make + -j2 + testHomography2.run + true + true + true + + + make + -j2 + testCalibratedCamera.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPoint2.run + true + true + true + make -j3 @@ -2170,7 +2268,6 @@ cpack - -G DEB true false @@ -2178,7 +2275,6 @@ cpack - -G RPM true false @@ -2186,7 +2282,6 @@ cpack - -G TGZ true false @@ -2194,7 +2289,6 @@ cpack - --config CPackSourceConfig.cmake true false @@ -2336,98 +2430,34 @@ true true - + make - -j2 - testRot3.run + -j5 + testSpirit.run true true true - + make - -j2 - testRot2.run + -j5 + testWrap.run true true true - + make - -j2 - testPose3.run + -j5 + check.wrap true true true - + make - -j2 - timeRot3.run - true - true - true - - - make - -j2 - testPose2.run - true - true - true - - - make - -j2 - testCal3_S2.run - true - true - true - - - make - -j2 - testSimpleCamera.run - true - true - true - - - make - -j2 - testHomography2.run - true - true - true - - - make - -j2 - testCalibratedCamera.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testPoint2.run + -j5 + wrap true true true @@ -2471,38 +2501,6 @@ false true - - make - -j5 - testSpirit.run - true - true - true - - - make - -j5 - testWrap.run - true - true - true - - - make - -j5 - check.wrap - true - true - true - - - make - -j5 - wrap - true - true - true - diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index e9c7c6b64..6adcd8a1b 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -355,6 +355,9 @@ namespace gtsam { */ Vector quaternion() const; + /// Output stream operator + friend std::ostream &operator<<(std::ostream &os, const Rot3& p); + private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/geometry/Rot3M.cpp b/gtsam/geometry/Rot3M.cpp index b63499d6d..cb6660dae 100644 --- a/gtsam/geometry/Rot3M.cpp +++ b/gtsam/geometry/Rot3M.cpp @@ -380,6 +380,15 @@ pair RQ(const Matrix3& A) { return make_pair(R, xyz); } +/* ************************************************************************* */ +ostream &operator<<(ostream &os, const Rot3& R) { + os << "\n"; + os << '|' << R.r1().x() << ", " << R.r2().x() << ", " << R.r3().x() << "|\n"; + os << '|' << R.r1().y() << ", " << R.r2().y() << ", " << R.r3().y() << "|\n"; + os << '|' << R.r1().z() << ", " << R.r2().z() << ", " << R.r3().z() << "|\n"; + return os; +} + /* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/geometry/Rot3Q.cpp b/gtsam/geometry/Rot3Q.cpp index afab3900c..72d50484b 100644 --- a/gtsam/geometry/Rot3Q.cpp +++ b/gtsam/geometry/Rot3Q.cpp @@ -237,6 +237,15 @@ namespace gtsam { return make_pair(R, xyz); } + /* ************************************************************************* */ + ostream &operator<<(ostream &os, const Rot3& R) { + os << "\n"; + os << '|' << R.r1().x() << ", " << R.r2().x() << ", " << R.r3().x() << "|\n"; + os << '|' << R.r1().y() << ", " << R.r2().y() << ", " << R.r3().y() << "|\n"; + os << '|' << R.r1().z() << ", " << R.r2().z() << ", " << R.r3().z() << "|\n"; + return os; + } + } // namespace gtsam #endif diff --git a/gtsam/geometry/tests/testRot3M.cpp b/gtsam/geometry/tests/testRot3M.cpp index f59455e2f..b50ad1253 100644 --- a/gtsam/geometry/tests/testRot3M.cpp +++ b/gtsam/geometry/tests/testRot3M.cpp @@ -562,6 +562,15 @@ TEST( Rot3, Cayley ) { EXPECT(assert_equal(A, Cayley(Q))); } +/* ************************************************************************* */ +TEST( Rot3, stream) +{ + Rot3 R; + std::ostringstream os; + os << R; + EXPECT(os.str() == "\n|1, 0, 0|\n|0, 1, 0|\n|0, 0, 1|\n"); +} + #endif /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot3Q.cpp b/gtsam/geometry/tests/testRot3Q.cpp index e8733c24d..d44b8f34c 100644 --- a/gtsam/geometry/tests/testRot3Q.cpp +++ b/gtsam/geometry/tests/testRot3Q.cpp @@ -475,6 +475,15 @@ TEST(Rot3, quaternion) { EXPECT(assert_equal(expected2, actual2)); } +/* ************************************************************************* */ +TEST( Rot3, stream) +{ + Rot3 R; + std::ostringstream os; + os << R; + EXPECT(os.str() == "\n|1, 0, 0|\n|0, 1, 0|\n|0, 0, 1|\n"); +} + #endif /* ************************************************************************* */ From 1251ba9abb7e27ea49e8ba56d3a410eb16c07507 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 6 Jun 2013 01:21:34 +0000 Subject: [PATCH 046/256] ostream << operator --- gtsam/geometry/Pose3.cpp | 7 +++++++ gtsam/geometry/Pose3.h | 3 +++ gtsam/geometry/tests/testPose3.cpp | 9 +++++++++ 3 files changed, 19 insertions(+) diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index adaa2ce69..faec92a6b 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -348,4 +348,11 @@ namespace gtsam { Point3 t = Point3(cq) - R * Point3(cp); return Pose3(R, t); } + + /* ************************************************************************* */ + std::ostream &operator<<(std::ostream &os, const Pose3& pose) { + os << pose.rotation() << "\n" << pose.translation() << endl; + return os; + } + } // namespace gtsam diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 9d7444233..234e2cad6 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -290,6 +290,9 @@ namespace gtsam { */ static std::pair rotationInterval() { return std::make_pair(0, 2); } + /// Output stream operator + friend std::ostream &operator<<(std::ostream &os, const Pose3& p); + private: /** Serialization function */ friend class boost::serialization::access; diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index ed8f850d2..5f4a68d3b 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -741,6 +741,15 @@ TEST( Pose3, adjointTranspose) { EXPECT(assert_equal(numericalH,actualH,1e-5)); } +/* ************************************************************************* */ +TEST( Pose3, stream) +{ + Pose3 T; + std::ostringstream os; + os << T; + EXPECT(os.str() == "\n|1, 0, 0|\n|0, 1, 0|\n|0, 0, 1|\n\n(0, 0, 0)\n"); +} + /* ************************************************************************* */ int main(){ TestResult tr; return TestRegistry::runAllTests(tr);} /* ************************************************************************* */ From 709d18a83dc4e1dbe1f11de54a737e9cf5cd494f Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 6 Jun 2013 02:09:52 +0000 Subject: [PATCH 047/256] A more modern (and presumably faster) Eigen syntax --- gtsam/base/numericalDerivative.h | 26 ++++++++++++-------------- 1 file changed, 12 insertions(+), 14 deletions(-) diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index 429920e1c..053a89da8 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -32,8 +32,6 @@ #include #include - - namespace gtsam { /* @@ -106,8 +104,8 @@ namespace gtsam { for (size_t j=0;j Date: Thu, 6 Jun 2013 02:23:20 +0000 Subject: [PATCH 048/256] added documentation for noisemodel --- matlab/+gtsam/Contents.m | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/matlab/+gtsam/Contents.m b/matlab/+gtsam/Contents.m index 7d469d704..de7f97351 100644 --- a/matlab/+gtsam/Contents.m +++ b/matlab/+gtsam/Contents.m @@ -29,6 +29,11 @@ % GaussianBayesTreeClique - class GaussianBayesTreeClique, see Doxygen page for details % GaussianBayesTree - class GaussianBayesTree, see Doxygen page for details % GaussianISAM - class GaussianISAM, see Doxygen page for details +% noiseModel.Gaussian - class noiseModel.Gaussian, see Doxygen page for details +% noiseModel.Diagonal - class noiseModel.Diagonal, see Doxygen page for details +% noiseModel.Constrained - class noiseModel.Constrained, see Doxygen page for details +% noiseModel.Isotropic - class noiseModel.Isotropic, see Doxygen page for details +% noiseModel.Unit - class noiseModel.Unit, see Doxygen page for details % %% Linear Inference % GaussianSequentialSolver - class GaussianSequentialSolver, see Doxygen page for details From 43a0367a66d2a1ff6ef9afea9492e27651feaeed Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Thu, 6 Jun 2013 05:01:16 +0000 Subject: [PATCH 049/256] Commented out MATLAB wrap Rot3::retractCayley because it does not exist in quaternion mode --- gtsam.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam.h b/gtsam.h index 429cbc7d3..e211068ad 100644 --- a/gtsam.h +++ b/gtsam.h @@ -397,7 +397,7 @@ virtual class Rot3 : gtsam::Value { // Manifold static size_t Dim(); size_t dim() const; - gtsam::Rot3 retractCayley(Vector v) const; // FIXME, does not exist in both Matrix and Quaternion options + //gtsam::Rot3 retractCayley(Vector v) const; // FIXME, does not exist in both Matrix and Quaternion options gtsam::Rot3 retract(Vector v) const; Vector localCoordinates(const gtsam::Rot3& p) const; From ee21ef61a6cfbaf0c53dd059c73cba053b4748c4 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Thu, 6 Jun 2013 18:07:55 +0000 Subject: [PATCH 050/256] Added exists() to FactorGraph to allow for checking whether a factor exists at a given index. Necessary for matlab interface. --- gtsam.h | 5 ++++- gtsam/inference/FactorGraph.h | 3 +++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/gtsam.h b/gtsam.h index e211068ad..8ff9056f9 100644 --- a/gtsam.h +++ b/gtsam.h @@ -895,6 +895,7 @@ class SymbolicFactorGraph { void print(string s) const; bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const; size_t size() const; + bool exists(size_t i) const; // Standard interface // FIXME: Must wrap FastSet for this to work @@ -1282,6 +1283,7 @@ class GaussianFactorGraph { bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const; size_t size() const; gtsam::GaussianFactor* at(size_t idx) const; + bool exists(size_t idx) const; // Inference pair eliminateFrontals(size_t nFrontals) const; @@ -1508,7 +1510,8 @@ class NonlinearFactorGraph { bool empty() const; void remove(size_t i); size_t nrFactors() const; - gtsam::NonlinearFactor* at(size_t i) const; + gtsam::NonlinearFactor* at(size_t idx) const; + bool exists(size_t idx) const; void push_back(const gtsam::NonlinearFactorGraph& factors); // NonlinearFactorGraph diff --git a/gtsam/inference/FactorGraph.h b/gtsam/inference/FactorGraph.h index 70954152f..0d3b10e31 100644 --- a/gtsam/inference/FactorGraph.h +++ b/gtsam/inference/FactorGraph.h @@ -165,6 +165,9 @@ class VariableIndex; const sharedFactor operator[](size_t i) const { return at(i); } sharedFactor& operator[](size_t i) { return at(i); } + /** Checks whether a valid factor exists at the given index */ + inline bool exists(size_t i) const { return i Date: Fri, 7 Jun 2013 14:03:27 +0000 Subject: [PATCH 051/256] Used << --- gtsam/geometry/Point2.cpp | 2 +- gtsam/geometry/Point3.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/Point2.cpp b/gtsam/geometry/Point2.cpp index e188b2930..27a962e70 100644 --- a/gtsam/geometry/Point2.cpp +++ b/gtsam/geometry/Point2.cpp @@ -27,7 +27,7 @@ INSTANTIATE_LIE(Point2); /* ************************************************************************* */ void Point2::print(const string& s) const { - cout << s << "(" << x_ << ", " << y_ << ")" << endl; + cout << s << *this << endl; } /* ************************************************************************* */ diff --git a/gtsam/geometry/Point3.cpp b/gtsam/geometry/Point3.cpp index c8ee78565..df31f0803 100644 --- a/gtsam/geometry/Point3.cpp +++ b/gtsam/geometry/Point3.cpp @@ -32,7 +32,7 @@ bool Point3::equals(const Point3 & q, double tol) const { /* ************************************************************************* */ void Point3::print(const string& s) const { - cout << s << "(" << x_ << ", " << y_ << ", " << z_ << ")" << endl; + cout << s << *this << endl; } /* ************************************************************************* */ From b3748cf7c6724194413313ca40e49b4af8bbd352 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Mon, 10 Jun 2013 20:49:47 +0000 Subject: [PATCH 052/256] Added access functions to measurements and noisemodels for a variety of common nonlinear factors --- gtsam.h | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/gtsam.h b/gtsam.h index 8ff9056f9..20ea0bf8a 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1958,6 +1958,8 @@ class NonlinearISAM { template virtual class PriorFactor : gtsam::NonlinearFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); + T prior() const; + gtsam::noiseModel::Base* get_noiseModel() const; }; @@ -1965,6 +1967,8 @@ virtual class PriorFactor : gtsam::NonlinearFactor { template virtual class BetweenFactor : gtsam::NonlinearFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); + T measured() const; + gtsam::noiseModel::Base* get_noiseModel() const; }; @@ -1982,6 +1986,7 @@ virtual class NonlinearEquality : gtsam::NonlinearFactor { template virtual class RangeFactor : gtsam::NonlinearFactor { RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::RangeFactor RangeFactorPosePoint2; @@ -1998,6 +2003,7 @@ typedef gtsam::RangeFactor RangeFactor template virtual class BearingFactor : gtsam::NonlinearFactor { BearingFactor(size_t key1, size_t key2, const ROTATION& measured, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::BearingFactor BearingFactor2D; @@ -2007,6 +2013,7 @@ typedef gtsam::BearingFactor BearingFa template virtual class BearingRangeFactor : gtsam::NonlinearFactor { BearingRangeFactor(size_t poseKey, size_t pointKey, const ROTATION& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::BearingRangeFactor BearingRangeFactor2D; @@ -2030,6 +2037,7 @@ virtual class GenericProjectionFactor : gtsam::NonlinearFactor { CALIBRATION* calibration() const; bool verboseCheirality() const; bool throwCheirality() const; + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3_S2; typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3DS2; @@ -2058,6 +2066,7 @@ virtual class GenericStereoFactor : gtsam::NonlinearFactor { size_t poseKey, size_t landmarkKey, const gtsam::Cal3_S2Stereo* K); gtsam::StereoPoint2 measured() const; gtsam::Cal3_S2Stereo* calibration() const; + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::GenericStereoFactor GenericStereoFactor3D; @@ -2065,6 +2074,7 @@ typedef gtsam::GenericStereoFactor GenericStereoFac template virtual class PoseTranslationPrior : gtsam::NonlinearFactor { PoseTranslationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::PoseTranslationPrior PoseTranslationPrior2D; @@ -2074,6 +2084,7 @@ typedef gtsam::PoseTranslationPrior PoseTranslationPrior3D; template virtual class PoseRotationPrior : gtsam::NonlinearFactor { PoseRotationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); + gtsam::noiseModel::Base* get_noiseModel() const; }; typedef gtsam::PoseRotationPrior PoseRotationPrior2D; From 7b79cfc38c79dbddc6a48e2791568d47e43b264a Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 11 Jun 2013 14:35:22 +0000 Subject: [PATCH 053/256] Removed all non-test/timing cpp files from tests folder, small example now is header-only --- tests/CMakeLists.txt | 10 - tests/simulated2D.cpp | 49 ---- tests/simulated2D.h | 17 +- tests/simulated2DOriented.cpp | 39 --- tests/simulated2DOriented.h | 9 +- tests/simulated3D.cpp | 43 --- tests/simulated3D.h | 17 +- tests/smallExample.cpp | 502 -------------------------------- tests/smallExample.h | 534 ++++++++++++++++++++++++++++++++++ 9 files changed, 569 insertions(+), 651 deletions(-) delete mode 100644 tests/simulated2D.cpp delete mode 100644 tests/simulated2DOriented.cpp delete mode 100644 tests/simulated3D.cpp delete mode 100644 tests/smallExample.cpp diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 0ebada21e..021a7dd97 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -1,15 +1,5 @@ -# Build a library of example domains, just for tests -file(GLOB test_lib_srcs "*.cpp") -file(GLOB test_srcs "test*.cpp") -file(GLOB time_srcs "time*.cpp") -list(REMOVE_ITEM test_lib_srcs ${test_srcs}) -list(REMOVE_ITEM test_lib_srcs ${time_srcs}) -add_library(test_lib STATIC ${test_lib_srcs}) -target_link_libraries(test_lib ${gtsam-default}) - # Assemble local libraries set(tests_local_libs - test_lib slam nonlinear linear diff --git a/tests/simulated2D.cpp b/tests/simulated2D.cpp deleted file mode 100644 index 199a6756b..000000000 --- a/tests/simulated2D.cpp +++ /dev/null @@ -1,49 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file simulated2D.cpp - * @brief measurement functions and derivatives for simulated 2D robot - * @author Frank Dellaert - */ - -#include - -namespace simulated2D { - - static Matrix I = gtsam::eye(2); - - /* ************************************************************************* */ - Point2 prior(const Point2& x, boost::optional H) { - if (H) *H = I; - return x; - } - - /* ************************************************************************* */ - Point2 odo(const Point2& x1, const Point2& x2, boost::optional H1, - boost::optional H2) { - if (H1) *H1 = -I; - if (H2) *H2 = I; - return x2 - x1; - } - - /* ************************************************************************* */ - Point2 mea(const Point2& x, const Point2& l, boost::optional H1, - boost::optional H2) { - if (H1) *H1 = -I; - if (H2) *H2 = I; - return l - x; - } - -/* ************************************************************************* */ - -} // namespace simulated2D - diff --git a/tests/simulated2D.h b/tests/simulated2D.h index 3075d4a4a..f7a9a9284 100644 --- a/tests/simulated2D.h +++ b/tests/simulated2D.h @@ -90,7 +90,10 @@ namespace simulated2D { } /// Prior on a single pose, optionally returns derivative - Point2 prior(const Point2& x, boost::optional H = boost::none); + Point2 prior(const Point2& x, boost::optional H = boost::none) { + if (H) *H = gtsam::eye(2); + return x; + } /// odometry between two poses inline Point2 odo(const Point2& x1, const Point2& x2) { @@ -99,7 +102,11 @@ namespace simulated2D { /// odometry between two poses, optionally returns derivative Point2 odo(const Point2& x1, const Point2& x2, boost::optional H1 = - boost::none, boost::optional H2 = boost::none); + boost::none, boost::optional H2 = boost::none) { + if (H1) *H1 = -gtsam::eye(2); + if (H2) *H2 = gtsam::eye(2); + return x2 - x1; + } /// measurement between landmark and pose inline Point2 mea(const Point2& x, const Point2& l) { @@ -108,7 +115,11 @@ namespace simulated2D { /// measurement between landmark and pose, optionally returns derivative Point2 mea(const Point2& x, const Point2& l, boost::optional H1 = - boost::none, boost::optional H2 = boost::none); + boost::none, boost::optional H2 = boost::none) { + if (H1) *H1 = -gtsam::eye(2); + if (H2) *H2 = gtsam::eye(2); + return l - x; + } /** * Unary factor encoding a soft prior on a vector diff --git a/tests/simulated2DOriented.cpp b/tests/simulated2DOriented.cpp deleted file mode 100644 index c7d1d8469..000000000 --- a/tests/simulated2DOriented.cpp +++ /dev/null @@ -1,39 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file simulated2DOriented - * @brief measurement functions and derivatives for simulated 2D robot - * @author Frank Dellaert - */ - -#include - -namespace simulated2DOriented { - - static Matrix I = gtsam::eye(3); - - /* ************************************************************************* */ - Pose2 prior(const Pose2& x, boost::optional H) { - if (H) *H = I; - return x; - } - - /* ************************************************************************* */ - Pose2 odo(const Pose2& x1, const Pose2& x2, boost::optional H1, - boost::optional H2) { - return x1.between(x2, H1, H2); - } - -/* ************************************************************************* */ - -} // namespace simulated2DOriented - diff --git a/tests/simulated2DOriented.h b/tests/simulated2DOriented.h index a18ace2e3..b05fb45c1 100644 --- a/tests/simulated2DOriented.h +++ b/tests/simulated2DOriented.h @@ -62,7 +62,10 @@ namespace simulated2DOriented { } /// Prior on a single pose, optional derivative version - Pose2 prior(const Pose2& x, boost::optional H = boost::none); + Pose2 prior(const Pose2& x, boost::optional H = boost::none) { + if (H) *H = gtsam::eye(3); + return x; + } /// odometry between two poses inline Pose2 odo(const Pose2& x1, const Pose2& x2) { @@ -71,7 +74,9 @@ namespace simulated2DOriented { /// odometry between two poses, optional derivative version Pose2 odo(const Pose2& x1, const Pose2& x2, boost::optional H1 = - boost::none, boost::optional H2 = boost::none); + boost::none, boost::optional H2 = boost::none) { + return x1.between(x2, H1, H2); + } /// Unary factor encoding a soft prior on a vector template diff --git a/tests/simulated3D.cpp b/tests/simulated3D.cpp deleted file mode 100644 index c7ba2a9b0..000000000 --- a/tests/simulated3D.cpp +++ /dev/null @@ -1,43 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** -* @file Simulated3D.cpp -* @brief measurement functions and derivatives for simulated 3D robot -* @author Alex Cunningham -**/ - -#include - -namespace gtsam { - -namespace simulated3D { - -Point3 prior (const Point3& x, boost::optional H) { - if (H) *H = eye(3); - return x; -} - -Point3 odo(const Point3& x1, const Point3& x2, - boost::optional H1, boost::optional H2) { - if (H1) *H1 = -1 * eye(3); - if (H2) *H2 = eye(3); - return x2 - x1; -} - -Point3 mea(const Point3& x, const Point3& l, - boost::optional H1, boost::optional H2) { - if (H1) *H1 = -1 * eye(3); - if (H2) *H2 = eye(3); - return l - x; -} - -}} // namespace gtsam::simulated3D diff --git a/tests/simulated3D.h b/tests/simulated3D.h index 8aa0dc469..46945558a 100644 --- a/tests/simulated3D.h +++ b/tests/simulated3D.h @@ -38,21 +38,32 @@ namespace simulated3D { /** * Prior on a single pose */ -Point3 prior(const Point3& x, boost::optional H = boost::none); +Point3 prior(const Point3& x, boost::optional H = boost::none) { + if (H) *H = eye(3); + return x; +} /** * odometry between two poses */ Point3 odo(const Point3& x1, const Point3& x2, boost::optional H1 = boost::none, - boost::optional H2 = boost::none); + boost::optional H2 = boost::none) { + if (H1) *H1 = -1 * eye(3); + if (H2) *H2 = eye(3); + return x2 - x1; +} /** * measurement between landmark and pose */ Point3 mea(const Point3& x, const Point3& l, boost::optional H1 = boost::none, - boost::optional H2 = boost::none); + boost::optional H2 = boost::none) { + if (H1) *H1 = -1 * eye(3); + if (H2) *H2 = eye(3); + return l - x; +} /** * A prior factor on a single linear robot pose diff --git a/tests/smallExample.cpp b/tests/smallExample.cpp deleted file mode 100644 index 6074109a8..000000000 --- a/tests/smallExample.cpp +++ /dev/null @@ -1,502 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file smallExample.cpp - * @brief Create small example with two poses and one landmark - * @brief smallExample - * @author Carlos Nieto - * @author Frank dellaert - */ - -#include -#include -#include -#include -#include -#include - -#include - -#include -#include - -#include -#include - -using namespace std; - -namespace gtsam { -namespace example { - - using namespace gtsam::noiseModel; - - typedef boost::shared_ptr shared; - - static SharedDiagonal sigma1_0 = noiseModel::Isotropic::Sigma(2,1.0); - static SharedDiagonal sigma0_1 = noiseModel::Isotropic::Sigma(2,0.1); - static SharedDiagonal sigma0_2 = noiseModel::Isotropic::Sigma(2,0.2); - static SharedDiagonal constraintModel = noiseModel::Constrained::All(2); - - static const Index _l1_=0, _x1_=1, _x2_=2; - static const Index _x_=0, _y_=1, _z_=2; - - // Convenience for named keys - using symbol_shorthand::X; - using symbol_shorthand::L; - - /* ************************************************************************* */ - boost::shared_ptr sharedNonlinearFactorGraph() { - // Create - boost::shared_ptr nlfg( - new Graph); - - // prior on x1 - Point2 mu; - shared f1(new simulated2D::Prior(mu, sigma0_1, X(1))); - nlfg->push_back(f1); - - // odometry between x1 and x2 - Point2 z2(1.5, 0); - shared f2(new simulated2D::Odometry(z2, sigma0_1, X(1), X(2))); - nlfg->push_back(f2); - - // measurement between x1 and l1 - Point2 z3(0, -1); - shared f3(new simulated2D::Measurement(z3, sigma0_2, X(1), L(1))); - nlfg->push_back(f3); - - // measurement between x2 and l1 - Point2 z4(-1.5, -1.); - shared f4(new simulated2D::Measurement(z4, sigma0_2, X(2), L(1))); - nlfg->push_back(f4); - - return nlfg; - } - - /* ************************************************************************* */ - Graph createNonlinearFactorGraph() { - return *sharedNonlinearFactorGraph(); - } - - /* ************************************************************************* */ - Values createValues() { - Values c; - c.insert(X(1), Point2(0.0, 0.0)); - c.insert(X(2), Point2(1.5, 0.0)); - c.insert(L(1), Point2(0.0, -1.0)); - return c; - } - - /* ************************************************************************* */ - VectorValues createVectorValues() { - VectorValues c(vector(3, 2)); - c[_l1_] = Vector_(2, 0.0, -1.0); - c[_x1_] = Vector_(2, 0.0, 0.0); - c[_x2_] = Vector_(2, 1.5, 0.0); - return c; - } - - /* ************************************************************************* */ - boost::shared_ptr sharedNoisyValues() { - boost::shared_ptr c(new Values); - c->insert(X(1), Point2(0.1, 0.1)); - c->insert(X(2), Point2(1.4, 0.2)); - c->insert(L(1), Point2(0.1, -1.1)); - return c; - } - - /* ************************************************************************* */ - Values createNoisyValues() { - return *sharedNoisyValues(); - } - - /* ************************************************************************* */ - VectorValues createCorrectDelta(const Ordering& ordering) { - VectorValues c(vector(3,2)); - c[ordering[L(1)]] = Vector_(2, -0.1, 0.1); - c[ordering[X(1)]] = Vector_(2, -0.1, -0.1); - c[ordering[X(2)]] = Vector_(2, 0.1, -0.2); - return c; - } - - /* ************************************************************************* */ - VectorValues createZeroDelta(const Ordering& ordering) { - VectorValues c(vector(3,2)); - c[ordering[L(1)]] = zero(2); - c[ordering[X(1)]] = zero(2); - c[ordering[X(2)]] = zero(2); - return c; - } - - /* ************************************************************************* */ - GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering) { - // Create empty graph - GaussianFactorGraph fg; - - SharedDiagonal unit2 = noiseModel::Unit::Create(2); - - // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_] - fg.push_back(boost::make_shared(ordering[X(1)], 10*eye(2), -1.0*ones(2), unit2)); - - // odometry between x1 and x2: x2-x1=[0.2;-0.1] - fg.push_back(boost::make_shared(ordering[X(1)], -10*eye(2),ordering[X(2)], 10*eye(2), Vector_(2, 2.0, -1.0), unit2)); - - // measurement between x1 and l1: l1-x1=[0.0;0.2] - fg.push_back(boost::make_shared(ordering[X(1)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, 0.0, 1.0), unit2)); - - // measurement between x2 and l1: l1-x2=[-0.2;0.3] - fg.push_back(boost::make_shared(ordering[X(2)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, -1.0, 1.5), unit2)); - - return fg; - } - - /* ************************************************************************* */ - /** create small Chordal Bayes Net x <- y - * x y d - * 1 1 9 - * 1 5 - */ - GaussianBayesNet createSmallGaussianBayesNet() { - Matrix R11 = Matrix_(1, 1, 1.0), S12 = Matrix_(1, 1, 1.0); - Matrix R22 = Matrix_(1, 1, 1.0); - Vector d1(1), d2(1); - d1(0) = 9; - d2(0) = 5; - Vector tau(1); - tau(0) = 1.0; - - // define nodes and specify in reverse topological sort (i.e. parents last) - GaussianConditional::shared_ptr Px_y(new GaussianConditional(_x_, d1, R11, _y_, S12, tau)); - GaussianConditional::shared_ptr Py(new GaussianConditional(_y_, d2, R22, tau)); - GaussianBayesNet cbn; - cbn.push_back(Px_y); - cbn.push_back(Py); - - return cbn; - } - - /* ************************************************************************* */ - // Some nonlinear functions to optimize - /* ************************************************************************* */ - namespace smallOptimize { - - Point2 h(const Point2& v) { - return Point2(cos(v.x()), sin(v.y())); - } - - Matrix H(const Point2& v) { - return Matrix_(2, 2, - -sin(v.x()), 0.0, - 0.0, cos(v.y())); - } - - struct UnaryFactor: public gtsam::NoiseModelFactor1 { - - Point2 z_; - - UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) : - gtsam::NoiseModelFactor1(model, key), z_(z) { - } - - Vector evaluateError(const Point2& x, boost::optional A = boost::none) const { - if (A) *A = H(x); - return (h(x) - z_).vector(); - } - - }; - - } - - /* ************************************************************************* */ - boost::shared_ptr sharedReallyNonlinearFactorGraph() { - boost::shared_ptr fg(new Graph); - Vector z = Vector_(2, 1.0, 0.0); - double sigma = 0.1; - boost::shared_ptr factor( - new smallOptimize::UnaryFactor(z, noiseModel::Isotropic::Sigma(2,sigma), X(1))); - fg->push_back(factor); - return fg; - } - - Graph createReallyNonlinearFactorGraph() { - return *sharedReallyNonlinearFactorGraph(); - } - - /* ************************************************************************* */ - pair createNonlinearSmoother(int T) { - - // Create - Graph nlfg; - Values poses; - - // prior on x1 - Point2 x1(1.0, 0.0); - shared prior(new simulated2D::Prior(x1, sigma1_0, X(1))); - nlfg.push_back(prior); - poses.insert(X(1), x1); - - for (int t = 2; t <= T; t++) { - // odometry between x_t and x_{t-1} - Point2 odo(1.0, 0.0); - shared odometry(new simulated2D::Odometry(odo, sigma1_0, X(t - 1), X(t))); - nlfg.push_back(odometry); - - // measurement on x_t is like perfect GPS - Point2 xt(t, 0); - shared measurement(new simulated2D::Prior(xt, sigma1_0, X(t))); - nlfg.push_back(measurement); - - // initial estimate - poses.insert(X(t), xt); - } - - return make_pair(nlfg, poses); - } - - /* ************************************************************************* */ - pair, Ordering> createSmoother(int T, boost::optional ordering) { - Graph nlfg; - Values poses; - boost::tie(nlfg, poses) = createNonlinearSmoother(T); - - if(!ordering) ordering = *poses.orderingArbitrary(); - return make_pair(*nlfg.linearize(poses, *ordering), *ordering); - } - - /* ************************************************************************* */ - GaussianFactorGraph createSimpleConstraintGraph() { - // create unary factor - // prior on _x_, mean = [1,-1], sigma=0.1 - Matrix Ax = eye(2); - Vector b1(2); - b1(0) = 1.0; - b1(1) = -1.0; - JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, sigma0_1)); - - // create binary constraint factor - // between _x_ and _y_, that is going to be the only factor on _y_ - // |1 0||x_1| + |-1 0||y_1| = |0| - // |0 1||x_2| | 0 -1||y_2| |0| - Matrix Ax1 = eye(2); - Matrix Ay1 = eye(2) * -1; - Vector b2 = Vector_(2, 0.0, 0.0); - JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, - constraintModel)); - - // construct the graph - GaussianFactorGraph fg; - fg.push_back(f1); - fg.push_back(f2); - - return fg; - } - - /* ************************************************************************* */ - VectorValues createSimpleConstraintValues() { - VectorValues config(vector(2,2)); - Vector v = Vector_(2, 1.0, -1.0); - config[_x_] = v; - config[_y_] = v; - return config; - } - - /* ************************************************************************* */ - GaussianFactorGraph createSingleConstraintGraph() { - // create unary factor - // prior on _x_, mean = [1,-1], sigma=0.1 - Matrix Ax = eye(2); - Vector b1(2); - b1(0) = 1.0; - b1(1) = -1.0; - //GaussianFactor::shared_ptr f1(new JacobianFactor(_x_, sigma0_1->Whiten(Ax), sigma0_1->whiten(b1), sigma0_1)); - JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, sigma0_1)); - - // create binary constraint factor - // between _x_ and _y_, that is going to be the only factor on _y_ - // |1 2||x_1| + |10 0||y_1| = |1| - // |2 1||x_2| |0 10||y_2| |2| - Matrix Ax1(2, 2); - Ax1(0, 0) = 1.0; - Ax1(0, 1) = 2.0; - Ax1(1, 0) = 2.0; - Ax1(1, 1) = 1.0; - Matrix Ay1 = eye(2) * 10; - Vector b2 = Vector_(2, 1.0, 2.0); - JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, - constraintModel)); - - // construct the graph - GaussianFactorGraph fg; - fg.push_back(f1); - fg.push_back(f2); - - return fg; - } - - /* ************************************************************************* */ - VectorValues createSingleConstraintValues() { - VectorValues config(vector(2,2)); - config[_x_] = Vector_(2, 1.0, -1.0); - config[_y_] = Vector_(2, 0.2, 0.1); - return config; - } - - /* ************************************************************************* */ - GaussianFactorGraph createMultiConstraintGraph() { - // unary factor 1 - Matrix A = eye(2); - Vector b = Vector_(2, -2.0, 2.0); - JacobianFactor::shared_ptr lf1(new JacobianFactor(_x_, A, b, sigma0_1)); - - // constraint 1 - Matrix A11(2, 2); - A11(0, 0) = 1.0; - A11(0, 1) = 2.0; - A11(1, 0) = 2.0; - A11(1, 1) = 1.0; - - Matrix A12(2, 2); - A12(0, 0) = 10.0; - A12(0, 1) = 0.0; - A12(1, 0) = 0.0; - A12(1, 1) = 10.0; - - Vector b1(2); - b1(0) = 1.0; - b1(1) = 2.0; - JacobianFactor::shared_ptr lc1(new JacobianFactor(_x_, A11, _y_, A12, b1, - constraintModel)); - - // constraint 2 - Matrix A21(2, 2); - A21(0, 0) = 3.0; - A21(0, 1) = 4.0; - A21(1, 0) = -1.0; - A21(1, 1) = -2.0; - - Matrix A22(2, 2); - A22(0, 0) = 1.0; - A22(0, 1) = 1.0; - A22(1, 0) = 1.0; - A22(1, 1) = 2.0; - - Vector b2(2); - b2(0) = 3.0; - b2(1) = 4.0; - JacobianFactor::shared_ptr lc2(new JacobianFactor(_x_, A21, _z_, A22, b2, - constraintModel)); - - // construct the graph - GaussianFactorGraph fg; - fg.push_back(lf1); - fg.push_back(lc1); - fg.push_back(lc2); - - return fg; - } - - /* ************************************************************************* */ - VectorValues createMultiConstraintValues() { - VectorValues config(vector(3,2)); - config[_x_] = Vector_(2, -2.0, 2.0); - config[_y_] = Vector_(2, -0.1, 0.4); - config[_z_] = Vector_(2, -4.0, 5.0); - return config; - } - - - /* ************************************************************************* */ - // Create key for simulated planar graph - Symbol key(int x, int y) { - return X(1000*x+y); - } - - /* ************************************************************************* */ - boost::tuple planarGraph(size_t N) { - - // create empty graph - NonlinearFactorGraph nlfg; - - // Create almost hard constraint on x11, sigma=0 will work for PCG not for normal - shared constraint(new simulated2D::Prior(Point2(1.0, 1.0), Isotropic::Sigma(2,1e-3), key(1,1))); - nlfg.push_back(constraint); - - // Create horizontal constraints, 1...N*(N-1) - Point2 z1(1.0, 0.0); // move right - for (size_t x = 1; x < N; x++) - for (size_t y = 1; y <= N; y++) { - shared f(new simulated2D::Odometry(z1, Isotropic::Sigma(2,0.01), key(x, y), key(x + 1, y))); - nlfg.push_back(f); - } - - // Create vertical constraints, N*(N-1)+1..2*N*(N-1) - Point2 z2(0.0, 1.0); // move up - for (size_t x = 1; x <= N; x++) - for (size_t y = 1; y < N; y++) { - shared f(new simulated2D::Odometry(z2, Isotropic::Sigma(2,0.01), key(x, y), key(x, y + 1))); - nlfg.push_back(f); - } - - // Create linearization and ground xtrue config - Values zeros; - for (size_t x = 1; x <= N; x++) - for (size_t y = 1; y <= N; y++) - zeros.insert(key(x, y), Point2()); - Ordering ordering(planarOrdering(N)); - VectorValues xtrue(zeros.dims(ordering)); - for (size_t x = 1; x <= N; x++) - for (size_t y = 1; y <= N; y++) - xtrue[ordering[key(x, y)]] = Point2(x,y).vector(); - - // linearize around zero - boost::shared_ptr gfg = nlfg.linearize(zeros, ordering); - return boost::make_tuple(*gfg, xtrue); - } - - /* ************************************************************************* */ - Ordering planarOrdering(size_t N) { - Ordering ordering; - for (size_t y = N; y >= 1; y--) - for (size_t x = N; x >= 1; x--) - ordering.push_back(key(x, y)); - return ordering; - } - - /* ************************************************************************* */ - pair splitOffPlanarTree(size_t N, - const GaussianFactorGraph& original) { - GaussianFactorGraph T, C; - - // Add the x11 constraint to the tree - T.push_back(original[0]); - - // Add all horizontal constraints to the tree - size_t i = 1; - for (size_t x = 1; x < N; x++) - for (size_t y = 1; y <= N; y++, i++) - T.push_back(original[i]); - - // Add first vertical column of constraints to T, others to C - for (size_t x = 1; x <= N; x++) - for (size_t y = 1; y < N; y++, i++) - if (x == 1) - T.push_back(original[i]); - else - C.push_back(original[i]); - - return make_pair(T, C); - } - -/* ************************************************************************* */ - -} // example -} // namespace gtsam diff --git a/tests/smallExample.h b/tests/smallExample.h index 7652d96aa..595211180 100644 --- a/tests/smallExample.h +++ b/tests/smallExample.h @@ -25,6 +25,19 @@ #include #include +#include +//#include +//#include +//#include +//#include +//#include +// +//#include +//#include +// +//#include +//#include + namespace gtsam { namespace example { @@ -151,3 +164,524 @@ namespace gtsam { } // example } // gtsam + + +// Implementations +namespace gtsam { +namespace example { + +// using namespace gtsam::noiseModel; + +namespace impl { + typedef boost::shared_ptr shared_nlf; + + static SharedDiagonal sigma1_0 = noiseModel::Isotropic::Sigma(2,1.0); + static SharedDiagonal sigma0_1 = noiseModel::Isotropic::Sigma(2,0.1); + static SharedDiagonal sigma0_2 = noiseModel::Isotropic::Sigma(2,0.2); + static SharedDiagonal constraintModel = noiseModel::Constrained::All(2); + + static const Index _l1_=0, _x1_=1, _x2_=2; + static const Index _x_=0, _y_=1, _z_=2; +} // \namespace impl + + + /* ************************************************************************* */ + boost::shared_ptr sharedNonlinearFactorGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // Create + boost::shared_ptr nlfg( + new Graph); + + // prior on x1 + Point2 mu; + shared_nlf f1(new simulated2D::Prior(mu, sigma0_1, X(1))); + nlfg->push_back(f1); + + // odometry between x1 and x2 + Point2 z2(1.5, 0); + shared_nlf f2(new simulated2D::Odometry(z2, sigma0_1, X(1), X(2))); + nlfg->push_back(f2); + + // measurement between x1 and l1 + Point2 z3(0, -1); + shared_nlf f3(new simulated2D::Measurement(z3, sigma0_2, X(1), L(1))); + nlfg->push_back(f3); + + // measurement between x2 and l1 + Point2 z4(-1.5, -1.); + shared_nlf f4(new simulated2D::Measurement(z4, sigma0_2, X(2), L(1))); + nlfg->push_back(f4); + + return nlfg; + } + + /* ************************************************************************* */ + Graph createNonlinearFactorGraph() { + return *sharedNonlinearFactorGraph(); + } + + /* ************************************************************************* */ + Values createValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + Values c; + c.insert(X(1), Point2(0.0, 0.0)); + c.insert(X(2), Point2(1.5, 0.0)); + c.insert(L(1), Point2(0.0, -1.0)); + return c; + } + + /* ************************************************************************* */ + VectorValues createVectorValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues c(std::vector(3, 2)); + c[_l1_] = Vector_(2, 0.0, -1.0); + c[_x1_] = Vector_(2, 0.0, 0.0); + c[_x2_] = Vector_(2, 1.5, 0.0); + return c; + } + + /* ************************************************************************* */ + boost::shared_ptr sharedNoisyValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + boost::shared_ptr c(new Values); + c->insert(X(1), Point2(0.1, 0.1)); + c->insert(X(2), Point2(1.4, 0.2)); + c->insert(L(1), Point2(0.1, -1.1)); + return c; + } + + /* ************************************************************************* */ + Values createNoisyValues() { + return *sharedNoisyValues(); + } + + /* ************************************************************************* */ + VectorValues createCorrectDelta(const Ordering& ordering) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues c(std::vector(3,2)); + c[ordering[L(1)]] = Vector_(2, -0.1, 0.1); + c[ordering[X(1)]] = Vector_(2, -0.1, -0.1); + c[ordering[X(2)]] = Vector_(2, 0.1, -0.2); + return c; + } + + /* ************************************************************************* */ + VectorValues createZeroDelta(const Ordering& ordering) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues c(std::vector(3,2)); + c[ordering[L(1)]] = zero(2); + c[ordering[X(1)]] = zero(2); + c[ordering[X(2)]] = zero(2); + return c; + } + + /* ************************************************************************* */ + GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // Create empty graph + GaussianFactorGraph fg; + + SharedDiagonal unit2 = noiseModel::Unit::Create(2); + + // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_] + fg.push_back(boost::make_shared(ordering[X(1)], 10*eye(2), -1.0*ones(2), unit2)); + + // odometry between x1 and x2: x2-x1=[0.2;-0.1] + fg.push_back(boost::make_shared(ordering[X(1)], -10*eye(2),ordering[X(2)], 10*eye(2), Vector_(2, 2.0, -1.0), unit2)); + + // measurement between x1 and l1: l1-x1=[0.0;0.2] + fg.push_back(boost::make_shared(ordering[X(1)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, 0.0, 1.0), unit2)); + + // measurement between x2 and l1: l1-x2=[-0.2;0.3] + fg.push_back(boost::make_shared(ordering[X(2)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, -1.0, 1.5), unit2)); + + return fg; + } + + /* ************************************************************************* */ + /** create small Chordal Bayes Net x <- y + * x y d + * 1 1 9 + * 1 5 + */ + GaussianBayesNet createSmallGaussianBayesNet() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + Matrix R11 = Matrix_(1, 1, 1.0), S12 = Matrix_(1, 1, 1.0); + Matrix R22 = Matrix_(1, 1, 1.0); + Vector d1(1), d2(1); + d1(0) = 9; + d2(0) = 5; + Vector tau(1); + tau(0) = 1.0; + + // define nodes and specify in reverse topological sort (i.e. parents last) + GaussianConditional::shared_ptr Px_y(new GaussianConditional(_x_, d1, R11, _y_, S12, tau)); + GaussianConditional::shared_ptr Py(new GaussianConditional(_y_, d2, R22, tau)); + GaussianBayesNet cbn; + cbn.push_back(Px_y); + cbn.push_back(Py); + + return cbn; + } + + /* ************************************************************************* */ + // Some nonlinear functions to optimize + /* ************************************************************************* */ + namespace smallOptimize { + + Point2 h(const Point2& v) { + return Point2(cos(v.x()), sin(v.y())); + } + + Matrix H(const Point2& v) { + return Matrix_(2, 2, + -sin(v.x()), 0.0, + 0.0, cos(v.y())); + } + + struct UnaryFactor: public gtsam::NoiseModelFactor1 { + + Point2 z_; + + UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) : + gtsam::NoiseModelFactor1(model, key), z_(z) { + } + + Vector evaluateError(const Point2& x, boost::optional A = boost::none) const { + if (A) *A = H(x); + return (h(x) - z_).vector(); + } + + }; + + } + + /* ************************************************************************* */ + boost::shared_ptr sharedReallyNonlinearFactorGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + boost::shared_ptr fg(new Graph); + Vector z = Vector_(2, 1.0, 0.0); + double sigma = 0.1; + boost::shared_ptr factor( + new smallOptimize::UnaryFactor(z, noiseModel::Isotropic::Sigma(2,sigma), X(1))); + fg->push_back(factor); + return fg; + } + + Graph createReallyNonlinearFactorGraph() { + return *sharedReallyNonlinearFactorGraph(); + } + + /* ************************************************************************* */ + std::pair createNonlinearSmoother(int T) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + + // Create + Graph nlfg; + Values poses; + + // prior on x1 + Point2 x1(1.0, 0.0); + shared_nlf prior(new simulated2D::Prior(x1, sigma1_0, X(1))); + nlfg.push_back(prior); + poses.insert(X(1), x1); + + for (int t = 2; t <= T; t++) { + // odometry between x_t and x_{t-1} + Point2 odo(1.0, 0.0); + shared_nlf odometry(new simulated2D::Odometry(odo, sigma1_0, X(t - 1), X(t))); + nlfg.push_back(odometry); + + // measurement on x_t is like perfect GPS + Point2 xt(t, 0); + shared_nlf measurement(new simulated2D::Prior(xt, sigma1_0, X(t))); + nlfg.push_back(measurement); + + // initial estimate + poses.insert(X(t), xt); + } + + return std::make_pair(nlfg, poses); + } + + /* ************************************************************************* */ + std::pair, Ordering> createSmoother(int T, boost::optional ordering) { + Graph nlfg; + Values poses; + boost::tie(nlfg, poses) = createNonlinearSmoother(T); + + if(!ordering) ordering = *poses.orderingArbitrary(); + return std::make_pair(*nlfg.linearize(poses, *ordering), *ordering); + } + + /* ************************************************************************* */ + GaussianFactorGraph createSimpleConstraintGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // create unary factor + // prior on _x_, mean = [1,-1], sigma=0.1 + Matrix Ax = eye(2); + Vector b1(2); + b1(0) = 1.0; + b1(1) = -1.0; + JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, sigma0_1)); + + // create binary constraint factor + // between _x_ and _y_, that is going to be the only factor on _y_ + // |1 0||x_1| + |-1 0||y_1| = |0| + // |0 1||x_2| | 0 -1||y_2| |0| + Matrix Ax1 = eye(2); + Matrix Ay1 = eye(2) * -1; + Vector b2 = Vector_(2, 0.0, 0.0); + JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, + constraintModel)); + + // construct the graph + GaussianFactorGraph fg; + fg.push_back(f1); + fg.push_back(f2); + + return fg; + } + + /* ************************************************************************* */ + VectorValues createSimpleConstraintValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues config(std::vector(2,2)); + Vector v = Vector_(2, 1.0, -1.0); + config[_x_] = v; + config[_y_] = v; + return config; + } + + /* ************************************************************************* */ + GaussianFactorGraph createSingleConstraintGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // create unary factor + // prior on _x_, mean = [1,-1], sigma=0.1 + Matrix Ax = eye(2); + Vector b1(2); + b1(0) = 1.0; + b1(1) = -1.0; + //GaussianFactor::shared_ptr f1(new JacobianFactor(_x_, sigma0_1->Whiten(Ax), sigma0_1->whiten(b1), sigma0_1)); + JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, sigma0_1)); + + // create binary constraint factor + // between _x_ and _y_, that is going to be the only factor on _y_ + // |1 2||x_1| + |10 0||y_1| = |1| + // |2 1||x_2| |0 10||y_2| |2| + Matrix Ax1(2, 2); + Ax1(0, 0) = 1.0; + Ax1(0, 1) = 2.0; + Ax1(1, 0) = 2.0; + Ax1(1, 1) = 1.0; + Matrix Ay1 = eye(2) * 10; + Vector b2 = Vector_(2, 1.0, 2.0); + JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, + constraintModel)); + + // construct the graph + GaussianFactorGraph fg; + fg.push_back(f1); + fg.push_back(f2); + + return fg; + } + + /* ************************************************************************* */ + VectorValues createSingleConstraintValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues config(std::vector(2,2)); + config[_x_] = Vector_(2, 1.0, -1.0); + config[_y_] = Vector_(2, 0.2, 0.1); + return config; + } + + /* ************************************************************************* */ + GaussianFactorGraph createMultiConstraintGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // unary factor 1 + Matrix A = eye(2); + Vector b = Vector_(2, -2.0, 2.0); + JacobianFactor::shared_ptr lf1(new JacobianFactor(_x_, A, b, sigma0_1)); + + // constraint 1 + Matrix A11(2, 2); + A11(0, 0) = 1.0; + A11(0, 1) = 2.0; + A11(1, 0) = 2.0; + A11(1, 1) = 1.0; + + Matrix A12(2, 2); + A12(0, 0) = 10.0; + A12(0, 1) = 0.0; + A12(1, 0) = 0.0; + A12(1, 1) = 10.0; + + Vector b1(2); + b1(0) = 1.0; + b1(1) = 2.0; + JacobianFactor::shared_ptr lc1(new JacobianFactor(_x_, A11, _y_, A12, b1, + constraintModel)); + + // constraint 2 + Matrix A21(2, 2); + A21(0, 0) = 3.0; + A21(0, 1) = 4.0; + A21(1, 0) = -1.0; + A21(1, 1) = -2.0; + + Matrix A22(2, 2); + A22(0, 0) = 1.0; + A22(0, 1) = 1.0; + A22(1, 0) = 1.0; + A22(1, 1) = 2.0; + + Vector b2(2); + b2(0) = 3.0; + b2(1) = 4.0; + JacobianFactor::shared_ptr lc2(new JacobianFactor(_x_, A21, _z_, A22, b2, + constraintModel)); + + // construct the graph + GaussianFactorGraph fg; + fg.push_back(lf1); + fg.push_back(lc1); + fg.push_back(lc2); + + return fg; + } + + /* ************************************************************************* */ + VectorValues createMultiConstraintValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues config(std::vector(3,2)); + config[_x_] = Vector_(2, -2.0, 2.0); + config[_y_] = Vector_(2, -0.1, 0.4); + config[_z_] = Vector_(2, -4.0, 5.0); + return config; + } + + /* ************************************************************************* */ + // Create key for simulated planar graph + namespace impl { + Symbol key(int x, int y) { + using symbol_shorthand::X; + return X(1000*x+y); + } + } // \namespace impl + + /* ************************************************************************* */ + boost::tuple planarGraph(size_t N) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + + // create empty graph + NonlinearFactorGraph nlfg; + + // Create almost hard constraint on x11, sigma=0 will work for PCG not for normal + shared_nlf constraint(new simulated2D::Prior(Point2(1.0, 1.0), noiseModel::Isotropic::Sigma(2,1e-3), key(1,1))); + nlfg.push_back(constraint); + + // Create horizontal constraints, 1...N*(N-1) + Point2 z1(1.0, 0.0); // move right + for (size_t x = 1; x < N; x++) + for (size_t y = 1; y <= N; y++) { + shared_nlf f(new simulated2D::Odometry(z1, noiseModel::Isotropic::Sigma(2,0.01), key(x, y), key(x + 1, y))); + nlfg.push_back(f); + } + + // Create vertical constraints, N*(N-1)+1..2*N*(N-1) + Point2 z2(0.0, 1.0); // move up + for (size_t x = 1; x <= N; x++) + for (size_t y = 1; y < N; y++) { + shared_nlf f(new simulated2D::Odometry(z2, noiseModel::Isotropic::Sigma(2,0.01), key(x, y), key(x, y + 1))); + nlfg.push_back(f); + } + + // Create linearization and ground xtrue config + Values zeros; + for (size_t x = 1; x <= N; x++) + for (size_t y = 1; y <= N; y++) + zeros.insert(key(x, y), Point2()); + Ordering ordering(planarOrdering(N)); + VectorValues xtrue(zeros.dims(ordering)); + for (size_t x = 1; x <= N; x++) + for (size_t y = 1; y <= N; y++) + xtrue[ordering[key(x, y)]] = Point2(x,y).vector(); + + // linearize around zero + boost::shared_ptr gfg = nlfg.linearize(zeros, ordering); + return boost::make_tuple(*gfg, xtrue); + } + + /* ************************************************************************* */ + Ordering planarOrdering(size_t N) { + Ordering ordering; + for (size_t y = N; y >= 1; y--) + for (size_t x = N; x >= 1; x--) + ordering.push_back(impl::key(x, y)); + return ordering; + } + + /* ************************************************************************* */ + std::pair splitOffPlanarTree(size_t N, + const GaussianFactorGraph& original) { + GaussianFactorGraph T, C; + + // Add the x11 constraint to the tree + T.push_back(original[0]); + + // Add all horizontal constraints to the tree + size_t i = 1; + for (size_t x = 1; x < N; x++) + for (size_t y = 1; y <= N; y++, i++) + T.push_back(original[i]); + + // Add first vertical column of constraints to T, others to C + for (size_t x = 1; x <= N; x++) + for (size_t y = 1; y < N; y++, i++) + if (x == 1) + T.push_back(original[i]); + else + C.push_back(original[i]); + + return std::make_pair(T, C); + } + +/* ************************************************************************* */ + +} // \namespace example +} // \namespace gtsam From 37f936d41cec672af8ef68c30c26d4bb9a39f86e Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 11 Jun 2013 14:36:50 +0000 Subject: [PATCH 054/256] Cleanup, whitespace --- tests/smallExample.h | 1146 +++++++++++++++++++++--------------------- 1 file changed, 567 insertions(+), 579 deletions(-) diff --git a/tests/smallExample.h b/tests/smallExample.h index 595211180..e048ed0a2 100644 --- a/tests/smallExample.h +++ b/tests/smallExample.h @@ -22,147 +22,135 @@ #pragma once #include +#include #include #include -#include -//#include -//#include -//#include -//#include -//#include -// -//#include -//#include -// -//#include -//#include - namespace gtsam { - namespace example { +namespace example { - typedef NonlinearFactorGraph Graph; +typedef NonlinearFactorGraph Graph; - /** - * Create small example for non-linear factor graph - */ - boost::shared_ptr sharedNonlinearFactorGraph(); - Graph createNonlinearFactorGraph(); +/** + * Create small example for non-linear factor graph + */ +boost::shared_ptr sharedNonlinearFactorGraph(); +Graph createNonlinearFactorGraph(); - /** - * Create values structure to go with it - * The ground truth values structure for the example above - */ - Values createValues(); +/** + * Create values structure to go with it + * The ground truth values structure for the example above + */ +Values createValues(); - /** Vector Values equivalent */ - VectorValues createVectorValues(); +/** Vector Values equivalent */ +VectorValues createVectorValues(); - /** - * create a noisy values structure for a nonlinear factor graph - */ - boost::shared_ptr sharedNoisyValues(); - Values createNoisyValues(); +/** + * create a noisy values structure for a nonlinear factor graph + */ +boost::shared_ptr sharedNoisyValues(); +Values createNoisyValues(); - /** - * Zero delta config - */ - VectorValues createZeroDelta(const Ordering& ordering); +/** + * Zero delta config + */ +VectorValues createZeroDelta(const Ordering& ordering); - /** - * Delta config that, when added to noisyValues, returns the ground truth - */ - VectorValues createCorrectDelta(const Ordering& ordering); +/** + * Delta config that, when added to noisyValues, returns the ground truth + */ +VectorValues createCorrectDelta(const Ordering& ordering); - /** - * create a linear factor graph - * The non-linear graph above evaluated at NoisyValues - */ - GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering); +/** + * create a linear factor graph + * The non-linear graph above evaluated at NoisyValues + */ +GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering); - /** - * create small Chordal Bayes Net x <- y - */ - GaussianBayesNet createSmallGaussianBayesNet(); +/** + * create small Chordal Bayes Net x <- y + */ +GaussianBayesNet createSmallGaussianBayesNet(); - /** - * Create really non-linear factor graph (cos/sin) - */ - boost::shared_ptr - sharedReallyNonlinearFactorGraph(); - Graph createReallyNonlinearFactorGraph(); +/** + * Create really non-linear factor graph (cos/sin) + */ +boost::shared_ptr +sharedReallyNonlinearFactorGraph(); +Graph createReallyNonlinearFactorGraph(); - /** - * Create a full nonlinear smoother - * @param T number of time-steps - */ - std::pair createNonlinearSmoother(int T); +/** + * Create a full nonlinear smoother + * @param T number of time-steps + */ +std::pair createNonlinearSmoother(int T); - /** - * Create a Kalman smoother by linearizing a non-linear factor graph - * @param T number of time-steps - */ - std::pair, Ordering> createSmoother(int T, boost::optional ordering = boost::none); +/** + * Create a Kalman smoother by linearizing a non-linear factor graph + * @param T number of time-steps + */ +std::pair, Ordering> createSmoother(int T, boost::optional ordering = boost::none); - /* ******************************************************* */ - // Linear Constrained Examples - /* ******************************************************* */ +/* ******************************************************* */ +// Linear Constrained Examples +/* ******************************************************* */ - /** - * Creates a simple constrained graph with one linear factor and - * one binary equality constraint that sets x = y - */ - GaussianFactorGraph createSimpleConstraintGraph(); - VectorValues createSimpleConstraintValues(); +/** + * Creates a simple constrained graph with one linear factor and + * one binary equality constraint that sets x = y + */ +GaussianFactorGraph createSimpleConstraintGraph(); +VectorValues createSimpleConstraintValues(); - /** - * Creates a simple constrained graph with one linear factor and - * one binary constraint. - */ - GaussianFactorGraph createSingleConstraintGraph(); - VectorValues createSingleConstraintValues(); +/** + * Creates a simple constrained graph with one linear factor and + * one binary constraint. + */ +GaussianFactorGraph createSingleConstraintGraph(); +VectorValues createSingleConstraintValues(); - /** - * Creates a constrained graph with a linear factor and two - * binary constraints that share a node - */ - GaussianFactorGraph createMultiConstraintGraph(); - VectorValues createMultiConstraintValues(); +/** + * Creates a constrained graph with a linear factor and two + * binary constraints that share a node + */ +GaussianFactorGraph createMultiConstraintGraph(); +VectorValues createMultiConstraintValues(); - /* ******************************************************* */ - // Planar graph with easy subtree for SubgraphPreconditioner - /* ******************************************************* */ +/* ******************************************************* */ +// Planar graph with easy subtree for SubgraphPreconditioner +/* ******************************************************* */ - /* - * Create factor graph with N^2 nodes, for example for N=3 - * x13-x23-x33 - * | | | - * x12-x22-x32 - * | | | - * -x11-x21-x31 - * with x11 clamped at (1,1), and others related by 2D odometry. - */ - boost::tuple planarGraph(size_t N); +/* + * Create factor graph with N^2 nodes, for example for N=3 + * x13-x23-x33 + * | | | + * x12-x22-x32 + * | | | + * -x11-x21-x31 + * with x11 clamped at (1,1), and others related by 2D odometry. + */ +boost::tuple planarGraph(size_t N); - /* - * Create canonical ordering for planar graph that also works for tree - * With x11 the root, e.g. for N=3 - * x33 x23 x13 x32 x22 x12 x31 x21 x11 - */ - Ordering planarOrdering(size_t N); +/* + * Create canonical ordering for planar graph that also works for tree + * With x11 the root, e.g. for N=3 + * x33 x23 x13 x32 x22 x12 x31 x21 x11 + */ +Ordering planarOrdering(size_t N); - /* - * Split graph into tree and loop closing constraints, e.g., with N=3 - * x13-x23-x33 - * | - * x12-x22-x32 - * | - * -x11-x21-x31 - */ - std::pair splitOffPlanarTree( - size_t N, const GaussianFactorGraph& original); +/* + * Split graph into tree and loop closing constraints, e.g., with N=3 + * x13-x23-x33 + * | + * x12-x22-x32 + * | + * -x11-x21-x31 + */ +std::pair splitOffPlanarTree( + size_t N, const GaussianFactorGraph& original); - } // example +} // example } // gtsam @@ -173,513 +161,513 @@ namespace example { // using namespace gtsam::noiseModel; namespace impl { - typedef boost::shared_ptr shared_nlf; +typedef boost::shared_ptr shared_nlf; - static SharedDiagonal sigma1_0 = noiseModel::Isotropic::Sigma(2,1.0); - static SharedDiagonal sigma0_1 = noiseModel::Isotropic::Sigma(2,0.1); - static SharedDiagonal sigma0_2 = noiseModel::Isotropic::Sigma(2,0.2); - static SharedDiagonal constraintModel = noiseModel::Constrained::All(2); +static SharedDiagonal sigma1_0 = noiseModel::Isotropic::Sigma(2,1.0); +static SharedDiagonal sigma0_1 = noiseModel::Isotropic::Sigma(2,0.1); +static SharedDiagonal sigma0_2 = noiseModel::Isotropic::Sigma(2,0.2); +static SharedDiagonal constraintModel = noiseModel::Constrained::All(2); - static const Index _l1_=0, _x1_=1, _x2_=2; - static const Index _x_=0, _y_=1, _z_=2; +static const Index _l1_=0, _x1_=1, _x2_=2; +static const Index _x_=0, _y_=1, _z_=2; } // \namespace impl - /* ************************************************************************* */ - boost::shared_ptr sharedNonlinearFactorGraph() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - // Create - boost::shared_ptr nlfg( - new Graph); +/* ************************************************************************* */ +boost::shared_ptr sharedNonlinearFactorGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // Create + boost::shared_ptr nlfg( + new Graph); - // prior on x1 - Point2 mu; - shared_nlf f1(new simulated2D::Prior(mu, sigma0_1, X(1))); - nlfg->push_back(f1); + // prior on x1 + Point2 mu; + shared_nlf f1(new simulated2D::Prior(mu, sigma0_1, X(1))); + nlfg->push_back(f1); - // odometry between x1 and x2 - Point2 z2(1.5, 0); - shared_nlf f2(new simulated2D::Odometry(z2, sigma0_1, X(1), X(2))); - nlfg->push_back(f2); + // odometry between x1 and x2 + Point2 z2(1.5, 0); + shared_nlf f2(new simulated2D::Odometry(z2, sigma0_1, X(1), X(2))); + nlfg->push_back(f2); - // measurement between x1 and l1 - Point2 z3(0, -1); - shared_nlf f3(new simulated2D::Measurement(z3, sigma0_2, X(1), L(1))); - nlfg->push_back(f3); + // measurement between x1 and l1 + Point2 z3(0, -1); + shared_nlf f3(new simulated2D::Measurement(z3, sigma0_2, X(1), L(1))); + nlfg->push_back(f3); - // measurement between x2 and l1 - Point2 z4(-1.5, -1.); - shared_nlf f4(new simulated2D::Measurement(z4, sigma0_2, X(2), L(1))); - nlfg->push_back(f4); + // measurement between x2 and l1 + Point2 z4(-1.5, -1.); + shared_nlf f4(new simulated2D::Measurement(z4, sigma0_2, X(2), L(1))); + nlfg->push_back(f4); - return nlfg; + return nlfg; +} + +/* ************************************************************************* */ +Graph createNonlinearFactorGraph() { + return *sharedNonlinearFactorGraph(); +} + +/* ************************************************************************* */ +Values createValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + Values c; + c.insert(X(1), Point2(0.0, 0.0)); + c.insert(X(2), Point2(1.5, 0.0)); + c.insert(L(1), Point2(0.0, -1.0)); + return c; +} + +/* ************************************************************************* */ +VectorValues createVectorValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues c(std::vector(3, 2)); + c[_l1_] = Vector_(2, 0.0, -1.0); + c[_x1_] = Vector_(2, 0.0, 0.0); + c[_x2_] = Vector_(2, 1.5, 0.0); + return c; +} + +/* ************************************************************************* */ +boost::shared_ptr sharedNoisyValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + boost::shared_ptr c(new Values); + c->insert(X(1), Point2(0.1, 0.1)); + c->insert(X(2), Point2(1.4, 0.2)); + c->insert(L(1), Point2(0.1, -1.1)); + return c; +} + +/* ************************************************************************* */ +Values createNoisyValues() { + return *sharedNoisyValues(); +} + +/* ************************************************************************* */ +VectorValues createCorrectDelta(const Ordering& ordering) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues c(std::vector(3,2)); + c[ordering[L(1)]] = Vector_(2, -0.1, 0.1); + c[ordering[X(1)]] = Vector_(2, -0.1, -0.1); + c[ordering[X(2)]] = Vector_(2, 0.1, -0.2); + return c; +} + +/* ************************************************************************* */ +VectorValues createZeroDelta(const Ordering& ordering) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues c(std::vector(3,2)); + c[ordering[L(1)]] = zero(2); + c[ordering[X(1)]] = zero(2); + c[ordering[X(2)]] = zero(2); + return c; +} + +/* ************************************************************************* */ +GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // Create empty graph + GaussianFactorGraph fg; + + SharedDiagonal unit2 = noiseModel::Unit::Create(2); + + // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_] + fg.push_back(boost::make_shared(ordering[X(1)], 10*eye(2), -1.0*ones(2), unit2)); + + // odometry between x1 and x2: x2-x1=[0.2;-0.1] + fg.push_back(boost::make_shared(ordering[X(1)], -10*eye(2),ordering[X(2)], 10*eye(2), Vector_(2, 2.0, -1.0), unit2)); + + // measurement between x1 and l1: l1-x1=[0.0;0.2] + fg.push_back(boost::make_shared(ordering[X(1)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, 0.0, 1.0), unit2)); + + // measurement between x2 and l1: l1-x2=[-0.2;0.3] + fg.push_back(boost::make_shared(ordering[X(2)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, -1.0, 1.5), unit2)); + + return fg; +} + +/* ************************************************************************* */ +/** create small Chordal Bayes Net x <- y + * x y d + * 1 1 9 + * 1 5 + */ +GaussianBayesNet createSmallGaussianBayesNet() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + Matrix R11 = Matrix_(1, 1, 1.0), S12 = Matrix_(1, 1, 1.0); + Matrix R22 = Matrix_(1, 1, 1.0); + Vector d1(1), d2(1); + d1(0) = 9; + d2(0) = 5; + Vector tau(1); + tau(0) = 1.0; + + // define nodes and specify in reverse topological sort (i.e. parents last) + GaussianConditional::shared_ptr Px_y(new GaussianConditional(_x_, d1, R11, _y_, S12, tau)); + GaussianConditional::shared_ptr Py(new GaussianConditional(_y_, d2, R22, tau)); + GaussianBayesNet cbn; + cbn.push_back(Px_y); + cbn.push_back(Py); + + return cbn; +} + +/* ************************************************************************* */ +// Some nonlinear functions to optimize +/* ************************************************************************* */ +namespace smallOptimize { + +Point2 h(const Point2& v) { + return Point2(cos(v.x()), sin(v.y())); +} + +Matrix H(const Point2& v) { + return Matrix_(2, 2, + -sin(v.x()), 0.0, + 0.0, cos(v.y())); +} + +struct UnaryFactor: public gtsam::NoiseModelFactor1 { + + Point2 z_; + + UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) : + gtsam::NoiseModelFactor1(model, key), z_(z) { } - /* ************************************************************************* */ - Graph createNonlinearFactorGraph() { - return *sharedNonlinearFactorGraph(); + Vector evaluateError(const Point2& x, boost::optional A = boost::none) const { + if (A) *A = H(x); + return (h(x) - z_).vector(); } - /* ************************************************************************* */ - Values createValues() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - Values c; - c.insert(X(1), Point2(0.0, 0.0)); - c.insert(X(2), Point2(1.5, 0.0)); - c.insert(L(1), Point2(0.0, -1.0)); - return c; +}; + +} + +/* ************************************************************************* */ +boost::shared_ptr sharedReallyNonlinearFactorGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + boost::shared_ptr fg(new Graph); + Vector z = Vector_(2, 1.0, 0.0); + double sigma = 0.1; + boost::shared_ptr factor( + new smallOptimize::UnaryFactor(z, noiseModel::Isotropic::Sigma(2,sigma), X(1))); + fg->push_back(factor); + return fg; +} + +Graph createReallyNonlinearFactorGraph() { + return *sharedReallyNonlinearFactorGraph(); +} + +/* ************************************************************************* */ +std::pair createNonlinearSmoother(int T) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + + // Create + Graph nlfg; + Values poses; + + // prior on x1 + Point2 x1(1.0, 0.0); + shared_nlf prior(new simulated2D::Prior(x1, sigma1_0, X(1))); + nlfg.push_back(prior); + poses.insert(X(1), x1); + + for (int t = 2; t <= T; t++) { + // odometry between x_t and x_{t-1} + Point2 odo(1.0, 0.0); + shared_nlf odometry(new simulated2D::Odometry(odo, sigma1_0, X(t - 1), X(t))); + nlfg.push_back(odometry); + + // measurement on x_t is like perfect GPS + Point2 xt(t, 0); + shared_nlf measurement(new simulated2D::Prior(xt, sigma1_0, X(t))); + nlfg.push_back(measurement); + + // initial estimate + poses.insert(X(t), xt); } - /* ************************************************************************* */ - VectorValues createVectorValues() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - VectorValues c(std::vector(3, 2)); - c[_l1_] = Vector_(2, 0.0, -1.0); - c[_x1_] = Vector_(2, 0.0, 0.0); - c[_x2_] = Vector_(2, 1.5, 0.0); - return c; - } + return std::make_pair(nlfg, poses); +} - /* ************************************************************************* */ - boost::shared_ptr sharedNoisyValues() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - boost::shared_ptr c(new Values); - c->insert(X(1), Point2(0.1, 0.1)); - c->insert(X(2), Point2(1.4, 0.2)); - c->insert(L(1), Point2(0.1, -1.1)); - return c; - } +/* ************************************************************************* */ +std::pair, Ordering> createSmoother(int T, boost::optional ordering) { + Graph nlfg; + Values poses; + boost::tie(nlfg, poses) = createNonlinearSmoother(T); - /* ************************************************************************* */ - Values createNoisyValues() { - return *sharedNoisyValues(); - } + if(!ordering) ordering = *poses.orderingArbitrary(); + return std::make_pair(*nlfg.linearize(poses, *ordering), *ordering); +} - /* ************************************************************************* */ - VectorValues createCorrectDelta(const Ordering& ordering) { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - VectorValues c(std::vector(3,2)); - c[ordering[L(1)]] = Vector_(2, -0.1, 0.1); - c[ordering[X(1)]] = Vector_(2, -0.1, -0.1); - c[ordering[X(2)]] = Vector_(2, 0.1, -0.2); - return c; - } +/* ************************************************************************* */ +GaussianFactorGraph createSimpleConstraintGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // create unary factor + // prior on _x_, mean = [1,-1], sigma=0.1 + Matrix Ax = eye(2); + Vector b1(2); + b1(0) = 1.0; + b1(1) = -1.0; + JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, sigma0_1)); - /* ************************************************************************* */ - VectorValues createZeroDelta(const Ordering& ordering) { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - VectorValues c(std::vector(3,2)); - c[ordering[L(1)]] = zero(2); - c[ordering[X(1)]] = zero(2); - c[ordering[X(2)]] = zero(2); - return c; - } + // create binary constraint factor + // between _x_ and _y_, that is going to be the only factor on _y_ + // |1 0||x_1| + |-1 0||y_1| = |0| + // |0 1||x_2| | 0 -1||y_2| |0| + Matrix Ax1 = eye(2); + Matrix Ay1 = eye(2) * -1; + Vector b2 = Vector_(2, 0.0, 0.0); + JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, + constraintModel)); - /* ************************************************************************* */ - GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering) { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - // Create empty graph - GaussianFactorGraph fg; + // construct the graph + GaussianFactorGraph fg; + fg.push_back(f1); + fg.push_back(f2); - SharedDiagonal unit2 = noiseModel::Unit::Create(2); + return fg; +} - // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_] - fg.push_back(boost::make_shared(ordering[X(1)], 10*eye(2), -1.0*ones(2), unit2)); +/* ************************************************************************* */ +VectorValues createSimpleConstraintValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues config(std::vector(2,2)); + Vector v = Vector_(2, 1.0, -1.0); + config[_x_] = v; + config[_y_] = v; + return config; +} - // odometry between x1 and x2: x2-x1=[0.2;-0.1] - fg.push_back(boost::make_shared(ordering[X(1)], -10*eye(2),ordering[X(2)], 10*eye(2), Vector_(2, 2.0, -1.0), unit2)); +/* ************************************************************************* */ +GaussianFactorGraph createSingleConstraintGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // create unary factor + // prior on _x_, mean = [1,-1], sigma=0.1 + Matrix Ax = eye(2); + Vector b1(2); + b1(0) = 1.0; + b1(1) = -1.0; + //GaussianFactor::shared_ptr f1(new JacobianFactor(_x_, sigma0_1->Whiten(Ax), sigma0_1->whiten(b1), sigma0_1)); + JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, sigma0_1)); - // measurement between x1 and l1: l1-x1=[0.0;0.2] - fg.push_back(boost::make_shared(ordering[X(1)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, 0.0, 1.0), unit2)); + // create binary constraint factor + // between _x_ and _y_, that is going to be the only factor on _y_ + // |1 2||x_1| + |10 0||y_1| = |1| + // |2 1||x_2| |0 10||y_2| |2| + Matrix Ax1(2, 2); + Ax1(0, 0) = 1.0; + Ax1(0, 1) = 2.0; + Ax1(1, 0) = 2.0; + Ax1(1, 1) = 1.0; + Matrix Ay1 = eye(2) * 10; + Vector b2 = Vector_(2, 1.0, 2.0); + JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, + constraintModel)); - // measurement between x2 and l1: l1-x2=[-0.2;0.3] - fg.push_back(boost::make_shared(ordering[X(2)], -5*eye(2), ordering[L(1)], 5*eye(2), Vector_(2, -1.0, 1.5), unit2)); + // construct the graph + GaussianFactorGraph fg; + fg.push_back(f1); + fg.push_back(f2); - return fg; - } + return fg; +} - /* ************************************************************************* */ - /** create small Chordal Bayes Net x <- y - * x y d - * 1 1 9 - * 1 5 - */ - GaussianBayesNet createSmallGaussianBayesNet() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - Matrix R11 = Matrix_(1, 1, 1.0), S12 = Matrix_(1, 1, 1.0); - Matrix R22 = Matrix_(1, 1, 1.0); - Vector d1(1), d2(1); - d1(0) = 9; - d2(0) = 5; - Vector tau(1); - tau(0) = 1.0; +/* ************************************************************************* */ +VectorValues createSingleConstraintValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues config(std::vector(2,2)); + config[_x_] = Vector_(2, 1.0, -1.0); + config[_y_] = Vector_(2, 0.2, 0.1); + return config; +} - // define nodes and specify in reverse topological sort (i.e. parents last) - GaussianConditional::shared_ptr Px_y(new GaussianConditional(_x_, d1, R11, _y_, S12, tau)); - GaussianConditional::shared_ptr Py(new GaussianConditional(_y_, d2, R22, tau)); - GaussianBayesNet cbn; - cbn.push_back(Px_y); - cbn.push_back(Py); +/* ************************************************************************* */ +GaussianFactorGraph createMultiConstraintGraph() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + // unary factor 1 + Matrix A = eye(2); + Vector b = Vector_(2, -2.0, 2.0); + JacobianFactor::shared_ptr lf1(new JacobianFactor(_x_, A, b, sigma0_1)); - return cbn; - } + // constraint 1 + Matrix A11(2, 2); + A11(0, 0) = 1.0; + A11(0, 1) = 2.0; + A11(1, 0) = 2.0; + A11(1, 1) = 1.0; - /* ************************************************************************* */ - // Some nonlinear functions to optimize - /* ************************************************************************* */ - namespace smallOptimize { + Matrix A12(2, 2); + A12(0, 0) = 10.0; + A12(0, 1) = 0.0; + A12(1, 0) = 0.0; + A12(1, 1) = 10.0; - Point2 h(const Point2& v) { - return Point2(cos(v.x()), sin(v.y())); + Vector b1(2); + b1(0) = 1.0; + b1(1) = 2.0; + JacobianFactor::shared_ptr lc1(new JacobianFactor(_x_, A11, _y_, A12, b1, + constraintModel)); + + // constraint 2 + Matrix A21(2, 2); + A21(0, 0) = 3.0; + A21(0, 1) = 4.0; + A21(1, 0) = -1.0; + A21(1, 1) = -2.0; + + Matrix A22(2, 2); + A22(0, 0) = 1.0; + A22(0, 1) = 1.0; + A22(1, 0) = 1.0; + A22(1, 1) = 2.0; + + Vector b2(2); + b2(0) = 3.0; + b2(1) = 4.0; + JacobianFactor::shared_ptr lc2(new JacobianFactor(_x_, A21, _z_, A22, b2, + constraintModel)); + + // construct the graph + GaussianFactorGraph fg; + fg.push_back(lf1); + fg.push_back(lc1); + fg.push_back(lc2); + + return fg; +} + +/* ************************************************************************* */ +VectorValues createMultiConstraintValues() { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + VectorValues config(std::vector(3,2)); + config[_x_] = Vector_(2, -2.0, 2.0); + config[_y_] = Vector_(2, -0.1, 0.4); + config[_z_] = Vector_(2, -4.0, 5.0); + return config; +} + +/* ************************************************************************* */ +// Create key for simulated planar graph +namespace impl { +Symbol key(int x, int y) { + using symbol_shorthand::X; + return X(1000*x+y); +} +} // \namespace impl + +/* ************************************************************************* */ +boost::tuple planarGraph(size_t N) { + using namespace impl; + using symbol_shorthand::X; + using symbol_shorthand::L; + + // create empty graph + NonlinearFactorGraph nlfg; + + // Create almost hard constraint on x11, sigma=0 will work for PCG not for normal + shared_nlf constraint(new simulated2D::Prior(Point2(1.0, 1.0), noiseModel::Isotropic::Sigma(2,1e-3), key(1,1))); + nlfg.push_back(constraint); + + // Create horizontal constraints, 1...N*(N-1) + Point2 z1(1.0, 0.0); // move right + for (size_t x = 1; x < N; x++) + for (size_t y = 1; y <= N; y++) { + shared_nlf f(new simulated2D::Odometry(z1, noiseModel::Isotropic::Sigma(2,0.01), key(x, y), key(x + 1, y))); + nlfg.push_back(f); } - Matrix H(const Point2& v) { - return Matrix_(2, 2, - -sin(v.x()), 0.0, - 0.0, cos(v.y())); + // Create vertical constraints, N*(N-1)+1..2*N*(N-1) + Point2 z2(0.0, 1.0); // move up + for (size_t x = 1; x <= N; x++) + for (size_t y = 1; y < N; y++) { + shared_nlf f(new simulated2D::Odometry(z2, noiseModel::Isotropic::Sigma(2,0.01), key(x, y), key(x, y + 1))); + nlfg.push_back(f); } - struct UnaryFactor: public gtsam::NoiseModelFactor1 { + // Create linearization and ground xtrue config + Values zeros; + for (size_t x = 1; x <= N; x++) + for (size_t y = 1; y <= N; y++) + zeros.insert(key(x, y), Point2()); + Ordering ordering(planarOrdering(N)); + VectorValues xtrue(zeros.dims(ordering)); + for (size_t x = 1; x <= N; x++) + for (size_t y = 1; y <= N; y++) + xtrue[ordering[key(x, y)]] = Point2(x,y).vector(); - Point2 z_; + // linearize around zero + boost::shared_ptr gfg = nlfg.linearize(zeros, ordering); + return boost::make_tuple(*gfg, xtrue); +} - UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) : - gtsam::NoiseModelFactor1(model, key), z_(z) { - } +/* ************************************************************************* */ +Ordering planarOrdering(size_t N) { + Ordering ordering; + for (size_t y = N; y >= 1; y--) + for (size_t x = N; x >= 1; x--) + ordering.push_back(impl::key(x, y)); + return ordering; +} - Vector evaluateError(const Point2& x, boost::optional A = boost::none) const { - if (A) *A = H(x); - return (h(x) - z_).vector(); - } +/* ************************************************************************* */ +std::pair splitOffPlanarTree(size_t N, + const GaussianFactorGraph& original) { + GaussianFactorGraph T, C; - }; + // Add the x11 constraint to the tree + T.push_back(original[0]); - } + // Add all horizontal constraints to the tree + size_t i = 1; + for (size_t x = 1; x < N; x++) + for (size_t y = 1; y <= N; y++, i++) + T.push_back(original[i]); - /* ************************************************************************* */ - boost::shared_ptr sharedReallyNonlinearFactorGraph() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - boost::shared_ptr fg(new Graph); - Vector z = Vector_(2, 1.0, 0.0); - double sigma = 0.1; - boost::shared_ptr factor( - new smallOptimize::UnaryFactor(z, noiseModel::Isotropic::Sigma(2,sigma), X(1))); - fg->push_back(factor); - return fg; - } - - Graph createReallyNonlinearFactorGraph() { - return *sharedReallyNonlinearFactorGraph(); - } - - /* ************************************************************************* */ - std::pair createNonlinearSmoother(int T) { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - - // Create - Graph nlfg; - Values poses; - - // prior on x1 - Point2 x1(1.0, 0.0); - shared_nlf prior(new simulated2D::Prior(x1, sigma1_0, X(1))); - nlfg.push_back(prior); - poses.insert(X(1), x1); - - for (int t = 2; t <= T; t++) { - // odometry between x_t and x_{t-1} - Point2 odo(1.0, 0.0); - shared_nlf odometry(new simulated2D::Odometry(odo, sigma1_0, X(t - 1), X(t))); - nlfg.push_back(odometry); - - // measurement on x_t is like perfect GPS - Point2 xt(t, 0); - shared_nlf measurement(new simulated2D::Prior(xt, sigma1_0, X(t))); - nlfg.push_back(measurement); - - // initial estimate - poses.insert(X(t), xt); - } - - return std::make_pair(nlfg, poses); - } - - /* ************************************************************************* */ - std::pair, Ordering> createSmoother(int T, boost::optional ordering) { - Graph nlfg; - Values poses; - boost::tie(nlfg, poses) = createNonlinearSmoother(T); - - if(!ordering) ordering = *poses.orderingArbitrary(); - return std::make_pair(*nlfg.linearize(poses, *ordering), *ordering); - } - - /* ************************************************************************* */ - GaussianFactorGraph createSimpleConstraintGraph() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - // create unary factor - // prior on _x_, mean = [1,-1], sigma=0.1 - Matrix Ax = eye(2); - Vector b1(2); - b1(0) = 1.0; - b1(1) = -1.0; - JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, sigma0_1)); - - // create binary constraint factor - // between _x_ and _y_, that is going to be the only factor on _y_ - // |1 0||x_1| + |-1 0||y_1| = |0| - // |0 1||x_2| | 0 -1||y_2| |0| - Matrix Ax1 = eye(2); - Matrix Ay1 = eye(2) * -1; - Vector b2 = Vector_(2, 0.0, 0.0); - JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, - constraintModel)); - - // construct the graph - GaussianFactorGraph fg; - fg.push_back(f1); - fg.push_back(f2); - - return fg; - } - - /* ************************************************************************* */ - VectorValues createSimpleConstraintValues() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - VectorValues config(std::vector(2,2)); - Vector v = Vector_(2, 1.0, -1.0); - config[_x_] = v; - config[_y_] = v; - return config; - } - - /* ************************************************************************* */ - GaussianFactorGraph createSingleConstraintGraph() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - // create unary factor - // prior on _x_, mean = [1,-1], sigma=0.1 - Matrix Ax = eye(2); - Vector b1(2); - b1(0) = 1.0; - b1(1) = -1.0; - //GaussianFactor::shared_ptr f1(new JacobianFactor(_x_, sigma0_1->Whiten(Ax), sigma0_1->whiten(b1), sigma0_1)); - JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, sigma0_1)); - - // create binary constraint factor - // between _x_ and _y_, that is going to be the only factor on _y_ - // |1 2||x_1| + |10 0||y_1| = |1| - // |2 1||x_2| |0 10||y_2| |2| - Matrix Ax1(2, 2); - Ax1(0, 0) = 1.0; - Ax1(0, 1) = 2.0; - Ax1(1, 0) = 2.0; - Ax1(1, 1) = 1.0; - Matrix Ay1 = eye(2) * 10; - Vector b2 = Vector_(2, 1.0, 2.0); - JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, - constraintModel)); - - // construct the graph - GaussianFactorGraph fg; - fg.push_back(f1); - fg.push_back(f2); - - return fg; - } - - /* ************************************************************************* */ - VectorValues createSingleConstraintValues() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - VectorValues config(std::vector(2,2)); - config[_x_] = Vector_(2, 1.0, -1.0); - config[_y_] = Vector_(2, 0.2, 0.1); - return config; - } - - /* ************************************************************************* */ - GaussianFactorGraph createMultiConstraintGraph() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - // unary factor 1 - Matrix A = eye(2); - Vector b = Vector_(2, -2.0, 2.0); - JacobianFactor::shared_ptr lf1(new JacobianFactor(_x_, A, b, sigma0_1)); - - // constraint 1 - Matrix A11(2, 2); - A11(0, 0) = 1.0; - A11(0, 1) = 2.0; - A11(1, 0) = 2.0; - A11(1, 1) = 1.0; - - Matrix A12(2, 2); - A12(0, 0) = 10.0; - A12(0, 1) = 0.0; - A12(1, 0) = 0.0; - A12(1, 1) = 10.0; - - Vector b1(2); - b1(0) = 1.0; - b1(1) = 2.0; - JacobianFactor::shared_ptr lc1(new JacobianFactor(_x_, A11, _y_, A12, b1, - constraintModel)); - - // constraint 2 - Matrix A21(2, 2); - A21(0, 0) = 3.0; - A21(0, 1) = 4.0; - A21(1, 0) = -1.0; - A21(1, 1) = -2.0; - - Matrix A22(2, 2); - A22(0, 0) = 1.0; - A22(0, 1) = 1.0; - A22(1, 0) = 1.0; - A22(1, 1) = 2.0; - - Vector b2(2); - b2(0) = 3.0; - b2(1) = 4.0; - JacobianFactor::shared_ptr lc2(new JacobianFactor(_x_, A21, _z_, A22, b2, - constraintModel)); - - // construct the graph - GaussianFactorGraph fg; - fg.push_back(lf1); - fg.push_back(lc1); - fg.push_back(lc2); - - return fg; - } - - /* ************************************************************************* */ - VectorValues createMultiConstraintValues() { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - VectorValues config(std::vector(3,2)); - config[_x_] = Vector_(2, -2.0, 2.0); - config[_y_] = Vector_(2, -0.1, 0.4); - config[_z_] = Vector_(2, -4.0, 5.0); - return config; - } - - /* ************************************************************************* */ - // Create key for simulated planar graph - namespace impl { - Symbol key(int x, int y) { - using symbol_shorthand::X; - return X(1000*x+y); - } - } // \namespace impl - - /* ************************************************************************* */ - boost::tuple planarGraph(size_t N) { - using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; - - // create empty graph - NonlinearFactorGraph nlfg; - - // Create almost hard constraint on x11, sigma=0 will work for PCG not for normal - shared_nlf constraint(new simulated2D::Prior(Point2(1.0, 1.0), noiseModel::Isotropic::Sigma(2,1e-3), key(1,1))); - nlfg.push_back(constraint); - - // Create horizontal constraints, 1...N*(N-1) - Point2 z1(1.0, 0.0); // move right - for (size_t x = 1; x < N; x++) - for (size_t y = 1; y <= N; y++) { - shared_nlf f(new simulated2D::Odometry(z1, noiseModel::Isotropic::Sigma(2,0.01), key(x, y), key(x + 1, y))); - nlfg.push_back(f); - } - - // Create vertical constraints, N*(N-1)+1..2*N*(N-1) - Point2 z2(0.0, 1.0); // move up - for (size_t x = 1; x <= N; x++) - for (size_t y = 1; y < N; y++) { - shared_nlf f(new simulated2D::Odometry(z2, noiseModel::Isotropic::Sigma(2,0.01), key(x, y), key(x, y + 1))); - nlfg.push_back(f); - } - - // Create linearization and ground xtrue config - Values zeros; - for (size_t x = 1; x <= N; x++) - for (size_t y = 1; y <= N; y++) - zeros.insert(key(x, y), Point2()); - Ordering ordering(planarOrdering(N)); - VectorValues xtrue(zeros.dims(ordering)); - for (size_t x = 1; x <= N; x++) - for (size_t y = 1; y <= N; y++) - xtrue[ordering[key(x, y)]] = Point2(x,y).vector(); - - // linearize around zero - boost::shared_ptr gfg = nlfg.linearize(zeros, ordering); - return boost::make_tuple(*gfg, xtrue); - } - - /* ************************************************************************* */ - Ordering planarOrdering(size_t N) { - Ordering ordering; - for (size_t y = N; y >= 1; y--) - for (size_t x = N; x >= 1; x--) - ordering.push_back(impl::key(x, y)); - return ordering; - } - - /* ************************************************************************* */ - std::pair splitOffPlanarTree(size_t N, - const GaussianFactorGraph& original) { - GaussianFactorGraph T, C; - - // Add the x11 constraint to the tree - T.push_back(original[0]); - - // Add all horizontal constraints to the tree - size_t i = 1; - for (size_t x = 1; x < N; x++) - for (size_t y = 1; y <= N; y++, i++) + // Add first vertical column of constraints to T, others to C + for (size_t x = 1; x <= N; x++) + for (size_t y = 1; y < N; y++, i++) + if (x == 1) T.push_back(original[i]); + else + C.push_back(original[i]); - // Add first vertical column of constraints to T, others to C - for (size_t x = 1; x <= N; x++) - for (size_t y = 1; y < N; y++, i++) - if (x == 1) - T.push_back(original[i]); - else - C.push_back(original[i]); - - return std::make_pair(T, C); - } + return std::make_pair(T, C); +} /* ************************************************************************* */ From 0c7182b713e9acb47bb96a2258cb9ac02e3db727 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 11 Jun 2013 14:36:50 +0000 Subject: [PATCH 055/256] Removed unnecessary using statements --- tests/smallExample.h | 22 ---------------------- 1 file changed, 22 deletions(-) diff --git a/tests/smallExample.h b/tests/smallExample.h index e048ed0a2..ea9f30b54 100644 --- a/tests/smallExample.h +++ b/tests/smallExample.h @@ -212,7 +212,6 @@ Graph createNonlinearFactorGraph() { /* ************************************************************************* */ Values createValues() { - using namespace impl; using symbol_shorthand::X; using symbol_shorthand::L; Values c; @@ -225,8 +224,6 @@ Values createValues() { /* ************************************************************************* */ VectorValues createVectorValues() { using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; VectorValues c(std::vector(3, 2)); c[_l1_] = Vector_(2, 0.0, -1.0); c[_x1_] = Vector_(2, 0.0, 0.0); @@ -236,7 +233,6 @@ VectorValues createVectorValues() { /* ************************************************************************* */ boost::shared_ptr sharedNoisyValues() { - using namespace impl; using symbol_shorthand::X; using symbol_shorthand::L; boost::shared_ptr c(new Values); @@ -253,7 +249,6 @@ Values createNoisyValues() { /* ************************************************************************* */ VectorValues createCorrectDelta(const Ordering& ordering) { - using namespace impl; using symbol_shorthand::X; using symbol_shorthand::L; VectorValues c(std::vector(3,2)); @@ -265,7 +260,6 @@ VectorValues createCorrectDelta(const Ordering& ordering) { /* ************************************************************************* */ VectorValues createZeroDelta(const Ordering& ordering) { - using namespace impl; using symbol_shorthand::X; using symbol_shorthand::L; VectorValues c(std::vector(3,2)); @@ -277,7 +271,6 @@ VectorValues createZeroDelta(const Ordering& ordering) { /* ************************************************************************* */ GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering) { - using namespace impl; using symbol_shorthand::X; using symbol_shorthand::L; // Create empty graph @@ -308,8 +301,6 @@ GaussianFactorGraph createGaussianFactorGraph(const Ordering& ordering) { */ GaussianBayesNet createSmallGaussianBayesNet() { using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; Matrix R11 = Matrix_(1, 1, 1.0), S12 = Matrix_(1, 1, 1.0); Matrix R22 = Matrix_(1, 1, 1.0); Vector d1(1), d2(1); @@ -362,7 +353,6 @@ struct UnaryFactor: public gtsam::NoiseModelFactor1 { /* ************************************************************************* */ boost::shared_ptr sharedReallyNonlinearFactorGraph() { - using namespace impl; using symbol_shorthand::X; using symbol_shorthand::L; boost::shared_ptr fg(new Graph); @@ -425,8 +415,6 @@ std::pair, Ordering> createSmoother(int T, boost::op /* ************************************************************************* */ GaussianFactorGraph createSimpleConstraintGraph() { using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; // create unary factor // prior on _x_, mean = [1,-1], sigma=0.1 Matrix Ax = eye(2); @@ -468,8 +456,6 @@ VectorValues createSimpleConstraintValues() { /* ************************************************************************* */ GaussianFactorGraph createSingleConstraintGraph() { using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; // create unary factor // prior on _x_, mean = [1,-1], sigma=0.1 Matrix Ax = eye(2); @@ -504,8 +490,6 @@ GaussianFactorGraph createSingleConstraintGraph() { /* ************************************************************************* */ VectorValues createSingleConstraintValues() { using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; VectorValues config(std::vector(2,2)); config[_x_] = Vector_(2, 1.0, -1.0); config[_y_] = Vector_(2, 0.2, 0.1); @@ -515,8 +499,6 @@ VectorValues createSingleConstraintValues() { /* ************************************************************************* */ GaussianFactorGraph createMultiConstraintGraph() { using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; // unary factor 1 Matrix A = eye(2); Vector b = Vector_(2, -2.0, 2.0); @@ -572,8 +554,6 @@ GaussianFactorGraph createMultiConstraintGraph() { /* ************************************************************************* */ VectorValues createMultiConstraintValues() { using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; VectorValues config(std::vector(3,2)); config[_x_] = Vector_(2, -2.0, 2.0); config[_y_] = Vector_(2, -0.1, 0.4); @@ -593,8 +573,6 @@ Symbol key(int x, int y) { /* ************************************************************************* */ boost::tuple planarGraph(size_t N) { using namespace impl; - using symbol_shorthand::X; - using symbol_shorthand::L; // create empty graph NonlinearFactorGraph nlfg; From 361682c485fb2a45556def95528447d9bbdf0a82 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 11 Jun 2013 14:36:51 +0000 Subject: [PATCH 056/256] Working on a test for liquefy --- .cproject | 362 +++++++++--------- .../linear/tests/testBayesTreeOperations.cpp | 113 +++++- 2 files changed, 301 insertions(+), 174 deletions(-) diff --git a/.cproject b/.cproject index 872909c06..2145af336 100644 --- a/.cproject +++ b/.cproject @@ -1,7 +1,5 @@ - - - + @@ -309,14 +307,6 @@ true true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j2 @@ -343,6 +333,7 @@ make + tests/testBayesTree.run true false @@ -350,6 +341,7 @@ make + testBinaryBayesNet.run true false @@ -397,6 +389,7 @@ make + testSymbolicBayesNet.run true false @@ -404,6 +397,7 @@ make + tests/testSymbolicFactor.run true false @@ -411,6 +405,7 @@ make + testSymbolicFactorGraph.run true false @@ -426,11 +421,20 @@ make + tests/testBayesTree true false true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j5 @@ -527,22 +531,6 @@ false true - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - make -j2 @@ -559,6 +547,22 @@ true true + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + make -j2 @@ -583,34 +587,26 @@ true true - + make - -j5 - testValues.run + -j2 + all true true true - + make - -j5 - testOrdering.run + -j2 + check true true true - + make - -j5 - testKey.run - true - true - true - - - make - -j5 - testLinearContainerFactor.run + -j2 + clean true true true @@ -695,26 +691,34 @@ true true - + make - -j2 - all + -j5 + testValues.run true true true - + make - -j2 - check + -j5 + testOrdering.run true true true - + make - -j2 - clean + -j5 + testKey.run + true + true + true + + + make + -j5 + testLinearContainerFactor.run true true true @@ -919,6 +923,14 @@ true true + + make + -j5 + testBayesTreeOperations.run + true + true + true + make -j5 @@ -1073,6 +1085,7 @@ make + testGraph.run true false @@ -1080,6 +1093,7 @@ make + testJunctionTree.run true false @@ -1087,6 +1101,7 @@ make + testSymbolicBayesNetB.run true false @@ -1254,6 +1269,7 @@ make + testErrors.run true false @@ -1299,14 +1315,6 @@ true true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j2 @@ -1387,6 +1395,14 @@ true true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j2 @@ -1701,7 +1717,6 @@ make - testSimulated2DOriented.run true false @@ -1741,7 +1756,6 @@ make - testSimulated2D.run true false @@ -1749,7 +1763,6 @@ make - testSimulated3D.run true false @@ -1949,7 +1962,6 @@ make - tests/testGaussianISAM2 true false @@ -1971,102 +1983,6 @@ true true - - make - -j2 - testRot3.run - true - true - true - - - make - -j2 - testRot2.run - true - true - true - - - make - -j2 - testPose3.run - true - true - true - - - make - -j2 - timeRot3.run - true - true - true - - - make - -j2 - testPose2.run - true - true - true - - - make - -j2 - testCal3_S2.run - true - true - true - - - make - -j2 - testSimpleCamera.run - true - true - true - - - make - -j2 - testHomography2.run - true - true - true - - - make - -j2 - testCalibratedCamera.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testPoint2.run - true - true - true - make -j3 @@ -2268,6 +2184,7 @@ cpack + -G DEB true false @@ -2275,6 +2192,7 @@ cpack + -G RPM true false @@ -2282,6 +2200,7 @@ cpack + -G TGZ true false @@ -2289,6 +2208,7 @@ cpack + --config CPackSourceConfig.cmake true false @@ -2430,34 +2350,98 @@ true true - + make - -j5 - testSpirit.run + -j2 + testRot3.run true true true - + make - -j5 - testWrap.run + -j2 + testRot2.run true true true - + make - -j5 - check.wrap + -j2 + testPose3.run true true true - + make - -j5 - wrap + -j2 + timeRot3.run + true + true + true + + + make + -j2 + testPose2.run + true + true + true + + + make + -j2 + testCal3_S2.run + true + true + true + + + make + -j2 + testSimpleCamera.run + true + true + true + + + make + -j2 + testHomography2.run + true + true + true + + + make + -j2 + testCalibratedCamera.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPoint2.run true true true @@ -2501,6 +2485,38 @@ false true + + make + -j5 + testSpirit.run + true + true + true + + + make + -j5 + testWrap.run + true + true + true + + + make + -j5 + check.wrap + true + true + true + + + make + -j5 + wrap + true + true + true + diff --git a/gtsam_unstable/linear/tests/testBayesTreeOperations.cpp b/gtsam_unstable/linear/tests/testBayesTreeOperations.cpp index b1c833f2c..cccd47aac 100644 --- a/gtsam_unstable/linear/tests/testBayesTreeOperations.cpp +++ b/gtsam_unstable/linear/tests/testBayesTreeOperations.cpp @@ -10,6 +10,9 @@ #include #include +#include + +#include using namespace gtsam; @@ -17,8 +20,15 @@ SharedDiagonal model2 = noiseModel::Diagonal::Sigmas(ones(2)); SharedDiagonal model4 = noiseModel::Diagonal::Sigmas(ones(4)); SharedDiagonal model6 = noiseModel::Diagonal::Sigmas(ones(6)); +using namespace std; + +using symbol_shorthand::X; +using symbol_shorthand::L; + +static const double tol = 1e-4; + /* ************************************************************************* */ -TEST( testLinearTools, splitFactor ) { +TEST( testBayesTreeOperations, splitFactor ) { // Build upper-triangular system JacobianFactor initFactor( @@ -120,6 +130,107 @@ TEST_UNSAFE( testLinearTools, splitFactor2 ) { EXPECT(assert_equal(expSplit, actSplit)); } +/* ************************************************************************* */ +// Some numbers that should be consistent among all smoother tests + +//static double sigmax1 = 0.786153, /*sigmax2 = 1.0/1.47292,*/ sigmax3 = 0.671512, sigmax4 = +// 0.669534 /*, sigmax5 = sigmax3, sigmax6 = sigmax2*/, sigmax7 = sigmax1; + +/* ************************************************************************* */ +TEST( testBayesTreeOperations, liquefy ) { + using namespace example; + + // Create smoother with 7 nodes + Ordering ordering; + ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4); + GaussianFactorGraph smoother = createSmoother(7, ordering).first; + + // Create the Bayes tree + GaussianBayesTree bayesTree = *GaussianMultifrontalSolver(smoother).eliminate(); +// bayesTree.print("Full tree"); + + SharedDiagonal unit6 = noiseModel::Diagonal::Sigmas(Vector_(ones(6))); + SharedDiagonal unit4 = noiseModel::Diagonal::Sigmas(Vector_(ones(4))); + SharedDiagonal unit2 = noiseModel::Diagonal::Sigmas(Vector_(ones(2))); + + // Liquefy the tree back into a graph + { + GaussianFactorGraph actGraph = liquefy(bayesTree, false); // Doesn't split conditionals + GaussianFactorGraph expGraph; + + Matrix A12 = Matrix_(6, 2, + 1.73205081, 0.0, + 0.0, 1.73205081, + 0.0, 0.0, + 0.0, 0.0, + 0.0, 0.0, + 0.0, 0.0); + + Matrix A15 = Matrix_(6, 2, + -0.577350269, 0.0, + 0.0, -0.577350269, + 1.47196014, 0.0, + 0.0, 1.47196014, + 0.0, 0.0, + 0.0, 0.0); + + Matrix A16 = Matrix_(6, 2, + -0.577350269, 0.0, + 0.0, -0.577350269, + -0.226455407, 0.0, + 0.0, -0.226455407, + 1.49357599, 0.0, + 0.0, 1.49357599); + expGraph.add(2, A12, 5, A15, 6, A16, zeros(6,1), unit6); + + Matrix A21 = Matrix_(4, 2, + 1.73205081, 0.0, + 0.0, 1.73205081, + 0.0, 0.0, + 0.0, 0.0); + + Matrix A24 = Matrix_(4, 2, + -0.577350269, 0.0, + 0.0, -0.577350269, + 1.47196014, 0.0, + 0.0, 1.47196014); + + Matrix A26 = Matrix_(4, 2, + -0.577350269, 0.0, + 0.0, -0.577350269, + -0.226455407, 0.0, + 0.0, -0.226455407); + + expGraph.add(1, A21, 4, A24, 6, A26, zeros(4,1), unit4); + + Matrix A30 = Matrix_(2, 2, + 1.41421356, 0.0, + 0.0, 1.41421356); + + Matrix A34 = Matrix_(2, 2, + -0.707106781, 0.0, + 0.0, -0.707106781); + + expGraph.add(0, A30, 4, A34, zeros(2,1), unit2); + + Matrix A43 = Matrix_(2, 2, + 1.41421356, 0.0, + 0.0, 1.41421356); + Matrix A45 = Matrix_(2, 2, + -0.707106781, 0.0, + 0.0, -0.707106781); + + expGraph.add(3, A43, 5, A45, zeros(2,1), unit2); + + EXPECT(assert_equal(expGraph, actGraph)); + LONGS_EQUAL(4, actGraph.size()); + EXPECT(assert_equal(*expGraph.at(0), *actGraph.at(0))); + EXPECT(assert_equal(*expGraph.at(1), *actGraph.at(1))); + EXPECT(assert_equal(*expGraph.at(2), *actGraph.at(2))); + EXPECT(assert_equal(*expGraph.at(3), *actGraph.at(3))); + } +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ From 83a1483e9f686c7e59586fc8dcb13b41e420d076 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 11 Jun 2013 14:36:52 +0000 Subject: [PATCH 057/256] Adding unit tests and a bugfix for liquefying bayes tree function --- gtsam_unstable/linear/bayesTreeOperations.cpp | 2 +- .../linear/tests/testBayesTreeOperations.cpp | 154 +++++++++++++++++- 2 files changed, 147 insertions(+), 9 deletions(-) diff --git a/gtsam_unstable/linear/bayesTreeOperations.cpp b/gtsam_unstable/linear/bayesTreeOperations.cpp index e889b3cbb..99daa1bb4 100644 --- a/gtsam_unstable/linear/bayesTreeOperations.cpp +++ b/gtsam_unstable/linear/bayesTreeOperations.cpp @@ -48,7 +48,7 @@ GaussianFactorGraph splitFactor(const GaussianFactor::shared_ptr& factor) { JacobianFactor::const_iterator rowIt, colIt; const size_t totalRows = jf->rows(); size_t rowsRemaining = totalRows; - for (rowIt = jf->begin(); rowIt != jf->end(); ++rowIt) { + for (rowIt = jf->begin(); rowIt != jf->end() && rowsRemaining > 0; ++rowIt) { // get dim of current variable size_t varDim = jf->getDim(rowIt); size_t startRow = totalRows - rowsRemaining; diff --git a/gtsam_unstable/linear/tests/testBayesTreeOperations.cpp b/gtsam_unstable/linear/tests/testBayesTreeOperations.cpp index cccd47aac..efc5bba55 100644 --- a/gtsam_unstable/linear/tests/testBayesTreeOperations.cpp +++ b/gtsam_unstable/linear/tests/testBayesTreeOperations.cpp @@ -28,7 +28,7 @@ using symbol_shorthand::L; static const double tol = 1e-4; /* ************************************************************************* */ -TEST( testBayesTreeOperations, splitFactor ) { +TEST( testBayesTreeOperations, splitFactor1 ) { // Build upper-triangular system JacobianFactor initFactor( @@ -68,7 +68,7 @@ TEST( testBayesTreeOperations, splitFactor ) { } /* ************************************************************************* */ -TEST_UNSAFE( testLinearTools, splitFactor2 ) { +TEST( testBayesTreeOperations, splitFactor2 ) { // Build upper-triangular system JacobianFactor initFactor( @@ -130,6 +130,57 @@ TEST_UNSAFE( testLinearTools, splitFactor2 ) { EXPECT(assert_equal(expSplit, actSplit)); } +/* ************************************************************************* */ +TEST( testBayesTreeOperations, splitFactor3 ) { + + // Build upper-triangular system + JacobianFactor initFactor( + 0,Matrix_(4, 2, + 1.0, 2.0, + 0.0, 3.0, + 0.0, 0.0, + 0.0, 0.0), + 1,Matrix_(4, 2, + 1.0, 2.0, + 9.0, 3.0, + 6.0, 8.0, + 0.0, 7.0), + 2,Matrix_(4, 2, + 1.1, 2.2, + 9.1, 3.2, + 6.1, 8.2, + 0.1, 7.2), + Vector_(4, 0.1, 0.2, 0.3, 0.4), + model4); + + GaussianFactorGraph actSplit = splitFactor(initFactor.clone()); + GaussianFactorGraph expSplit; + + expSplit.add( + 0,Matrix_(2, 2, + 1.0, 2.0, + 0.0, 3.0), + 1,Matrix_(2, 2, + 1.0, 2.0, + 9.0, 3.0), + 2,Matrix_(2, 2, + 1.1, 2.2, + 9.1, 3.2), + Vector_(2, 0.1, 0.2), + model2); + expSplit.add( + 1,Matrix_(2, 2, + 6.0, 8.0, + 0.0, 7.0), + 2,Matrix_(2, 2, + 6.1, 8.2, + 0.1, 7.2), + Vector_(2, 0.3, 0.4), + model2); + + EXPECT(assert_equal(expSplit, actSplit)); +} + /* ************************************************************************* */ // Some numbers that should be consistent among all smoother tests @@ -222,12 +273,99 @@ TEST( testBayesTreeOperations, liquefy ) { expGraph.add(3, A43, 5, A45, zeros(2,1), unit2); - EXPECT(assert_equal(expGraph, actGraph)); - LONGS_EQUAL(4, actGraph.size()); - EXPECT(assert_equal(*expGraph.at(0), *actGraph.at(0))); - EXPECT(assert_equal(*expGraph.at(1), *actGraph.at(1))); - EXPECT(assert_equal(*expGraph.at(2), *actGraph.at(2))); - EXPECT(assert_equal(*expGraph.at(3), *actGraph.at(3))); + EXPECT(assert_equal(expGraph, actGraph, tol)); + } + + // Liquefy the tree back into a graph, splitting factors + { + GaussianFactorGraph actGraph = liquefy(bayesTree, true); + GaussianFactorGraph expGraph; + + // Conditional 1 + { + Matrix A12 = Matrix_(2, 2, + 1.73205081, 0.0, + 0.0, 1.73205081); + + Matrix A15 = Matrix_(2, 2, + -0.577350269, 0.0, + 0.0, -0.577350269); + + Matrix A16 = Matrix_(2, 2, + -0.577350269, 0.0, + 0.0, -0.577350269); + expGraph.add(2, A12, 5, A15, 6, A16, zeros(2,1), unit2); + } + + { + Matrix A15 = Matrix_(2, 2, + 1.47196014, 0.0, + 0.0, 1.47196014); + + Matrix A16 = Matrix_(2, 2, + -0.226455407, 0.0, + 0.0, -0.226455407); + expGraph.add(5, A15, 6, A16, zeros(2,1), unit2); + } + + { + Matrix A16 = Matrix_(2, 2, + 1.49357599, 0.0, + 0.0, 1.49357599); + expGraph.add(6, A16, zeros(2,1), unit2); + } + + // Conditional 2 + { + Matrix A21 = Matrix_(2, 2, + 1.73205081, 0.0, + 0.0, 1.73205081); + + Matrix A24 = Matrix_(2, 2, + -0.577350269, 0.0, + 0.0, -0.577350269); + + Matrix A26 = Matrix_(2, 2, + -0.577350269, 0.0, + 0.0, -0.577350269); + + expGraph.add(1, A21, 4, A24, 6, A26, zeros(2,1), unit2); + } + + { + Matrix A24 = Matrix_(2, 2, + 1.47196014, 0.0, + 0.0, 1.47196014); + + Matrix A26 = Matrix_(2, 2, + -0.226455407, 0.0, + 0.0, -0.226455407); + + expGraph.add(4, A24, 6, A26, zeros(2,1), unit2); + } + + // Conditional 3 + Matrix A30 = Matrix_(2, 2, + 1.41421356, 0.0, + 0.0, 1.41421356); + + Matrix A34 = Matrix_(2, 2, + -0.707106781, 0.0, + 0.0, -0.707106781); + + expGraph.add(0, A30, 4, A34, zeros(2,1), unit2); + + // Conditional 4 + Matrix A43 = Matrix_(2, 2, + 1.41421356, 0.0, + 0.0, 1.41421356); + Matrix A45 = Matrix_(2, 2, + -0.707106781, 0.0, + 0.0, -0.707106781); + + expGraph.add(3, A43, 5, A45, zeros(2,1), unit2); + + EXPECT(assert_equal(expGraph, actGraph, tol)); } } From 083e0c849e0c1b4d4a6cce104bc0a367355abc6c Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 11 Jun 2013 14:36:53 +0000 Subject: [PATCH 058/256] Switched to templated version of liquefy() to allow for use with non-default clique types --- gtsam_unstable/linear/bayesTreeOperations.cpp | 20 ------------- gtsam_unstable/linear/bayesTreeOperations.h | 28 ++++++++++++++++--- 2 files changed, 24 insertions(+), 24 deletions(-) diff --git a/gtsam_unstable/linear/bayesTreeOperations.cpp b/gtsam_unstable/linear/bayesTreeOperations.cpp index 99daa1bb4..c2e84dec3 100644 --- a/gtsam_unstable/linear/bayesTreeOperations.cpp +++ b/gtsam_unstable/linear/bayesTreeOperations.cpp @@ -127,26 +127,6 @@ findPathCliques(const GaussianBayesTree::sharedClique& initial) { return result; } -/* ************************************************************************* */ -GaussianFactorGraph liquefy(const GaussianBayesTree::sharedClique& root, bool splitConditionals) { - GaussianFactorGraph result; - if (root && root->conditional()) { - GaussianConditional::shared_ptr conditional = root->conditional(); - if (!splitConditionals) - result.push_back(conditional->toFactor()); - else - result.push_back(splitFactor(conditional->toFactor())); - } - BOOST_FOREACH(const GaussianBayesTree::sharedClique& child, root->children()) - result.push_back(liquefy(child, splitConditionals)); - return result; -} - -/* ************************************************************************* */ -GaussianFactorGraph liquefy(const GaussianBayesTree& bayesTree, bool splitConditionals) { - return liquefy(bayesTree.root(), splitConditionals); -} - /* ************************************************************************* */ } // \namespace gtsam diff --git a/gtsam_unstable/linear/bayesTreeOperations.h b/gtsam_unstable/linear/bayesTreeOperations.h index 471b38376..453678611 100644 --- a/gtsam_unstable/linear/bayesTreeOperations.h +++ b/gtsam_unstable/linear/bayesTreeOperations.h @@ -67,13 +67,33 @@ GTSAM_UNSTABLE_EXPORT std::deque findPathCliques(const GaussianBayesTree::sharedClique& initial); /** - * Liquefies a GaussianBayesTree into a GaussianFactorGraph recursively, given either a - * root clique or a full bayes tree. + * Liquefies a BayesTree into a GaussianFactorGraph recursively, given a + * root clique * * @param splitConditionals flag enables spliting multi-frontal conditionals into separate factors */ -GTSAM_UNSTABLE_EXPORT GaussianFactorGraph liquefy(const GaussianBayesTree::sharedClique& root, bool splitConditionals = false); -GTSAM_UNSTABLE_EXPORT GaussianFactorGraph liquefy(const GaussianBayesTree& bayesTree, bool splitConditionals = false); +template +GaussianFactorGraph liquefy(const typename BAYESTREE::sharedClique& root, bool splitConditionals = false) { + GaussianFactorGraph result; + if (root && root->conditional()) { + GaussianConditional::shared_ptr conditional = root->conditional(); + if (!splitConditionals) + result.push_back(conditional->toFactor()); + else + result.push_back(splitFactor(conditional->toFactor())); + } + BOOST_FOREACH(const typename BAYESTREE::sharedClique& child, root->children()) + result.push_back(liquefy(child, splitConditionals)); + return result; +} + +/** + * Liquefies a BayesTree into a GaussianFactorGraph recursively, from a full bayes tree. + */ +template +GaussianFactorGraph liquefy(const BAYESTREE& bayesTree, bool splitConditionals = false) { + return liquefy(bayesTree.root(), splitConditionals); +} } // \namespace gtsam From 9e3bfdc4f8f82d095a4a4aae216bb8b5c7ee291c Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 11 Jun 2013 14:36:54 +0000 Subject: [PATCH 059/256] comments only --- gtsam_unstable/linear/bayesTreeOperations.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam_unstable/linear/bayesTreeOperations.h b/gtsam_unstable/linear/bayesTreeOperations.h index 453678611..3f85dc12c 100644 --- a/gtsam_unstable/linear/bayesTreeOperations.h +++ b/gtsam_unstable/linear/bayesTreeOperations.h @@ -89,6 +89,8 @@ GaussianFactorGraph liquefy(const typename BAYESTREE::sharedClique& root, bool s /** * Liquefies a BayesTree into a GaussianFactorGraph recursively, from a full bayes tree. + * + * @param splitConditionals flag enables spliting multi-frontal conditionals into separate factors */ template GaussianFactorGraph liquefy(const BAYESTREE& bayesTree, bool splitConditionals = false) { From 23b326824a4783fae9e35e5795c931704d46aa66 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 11 Jun 2013 20:26:34 +0000 Subject: [PATCH 060/256] Added actual check to a test --- gtsam/inference/tests/testPermutation.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/inference/tests/testPermutation.cpp b/gtsam/inference/tests/testPermutation.cpp index 98e94b4f7..5aa83422f 100644 --- a/gtsam/inference/tests/testPermutation.cpp +++ b/gtsam/inference/tests/testPermutation.cpp @@ -125,6 +125,7 @@ TEST(Reduction, CreateFromPartialPermutation) { expected.insert(make_pair(6,4)); internal::Reduction actual = internal::Reduction::CreateFromPartialPermutation(selector, p); + EXPECT(assert_equal(expected, actual)); } /* ************************************************************************* */ From 219695318830f2bac97e277f64e7b2f6f38ae92c Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 11 Jun 2013 20:26:34 +0000 Subject: [PATCH 061/256] Removed reference to nonexistant test_lib --- tests/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 021a7dd97..3afbf222a 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -34,7 +34,7 @@ if (GTSAM_BUILD_TESTS) # Build grouped tests gtsam_add_grouped_scripts("tests" # Use subdirectory as group label "test*.cpp" check "Test" # Standard for all tests - "${tests_local_libs}" "${gtsam-default};CppUnitLite;test_lib" "${tests_exclude}" # Pass in linking and exclusion lists + "${tests_local_libs}" "${gtsam-default};CppUnitLite" "${tests_exclude}" # Pass in linking and exclusion lists ${is_test}) # Set all as tests endif (GTSAM_BUILD_TESTS) @@ -47,6 +47,6 @@ if (GTSAM_BUILD_TIMING) # Build grouped benchmarks gtsam_add_grouped_scripts("tests" # Use subdirectory as group label "time*.cpp" timing "Timing Benchmark" # Standard for all timing scripts - "${tests_local_libs}" "${gtsam-default};CppUnitLite;test_lib" "${tests_exclude}" # Pass in linking and exclusion lists + "${tests_local_libs}" "${gtsam-default};CppUnitLite" "${tests_exclude}" # Pass in linking and exclusion lists ${is_test}) endif (GTSAM_BUILD_TIMING) From 19f7da62dd1b072f390c2f875524581eaceaba7f Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 12 Jun 2013 19:30:20 +0000 Subject: [PATCH 062/256] Refactored existing serialization functionality, added exposed interface for serialization --- .cproject | 72 ++----- gtsam/base/serialization.h | 92 +++++++++ gtsam/base/serializationTestHelpers.h | 74 +------ gtsam/slam/serialization.cpp | 257 +++++++++++++++++++++++++ gtsam/slam/serialization.h | 40 ++++ gtsam/slam/tests/testSerialization.cpp | 75 ++++++++ tests/testSerializationSLAM.cpp | 25 ++- 7 files changed, 503 insertions(+), 132 deletions(-) create mode 100644 gtsam/base/serialization.h create mode 100644 gtsam/slam/serialization.cpp create mode 100644 gtsam/slam/serialization.h create mode 100644 gtsam/slam/tests/testSerialization.cpp diff --git a/.cproject b/.cproject index 2145af336..46f9a60fb 100644 --- a/.cproject +++ b/.cproject @@ -619,54 +619,6 @@ true true - - make - -j5 - testPlanarSLAM.run - true - true - true - - - make - -j5 - testPose2SLAM.run - true - true - true - - - make - -j5 - testPose3SLAM.run - true - true - true - - - make - -j5 - testSimulated2D.run - true - true - true - - - make - -j5 - testSimulated2DOriented.run - true - true - true - - - make - -j5 - testVisualSLAM.run - true - true - true - make -j5 @@ -675,14 +627,6 @@ true true - - make - -j5 - testSerializationSLAM.run - true - true - true - make -j5 @@ -691,6 +635,14 @@ true true + + make + -j5 + testSerialization.run + true + true + true + make -j5 @@ -1163,6 +1115,14 @@ true true + + make + -j5 + testSerializationSLAM.run + true + true + true + make -j5 diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h new file mode 100644 index 000000000..8089de814 --- /dev/null +++ b/gtsam/base/serialization.h @@ -0,0 +1,92 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file serialization.h + * @brief Convenience functions for serializing data structures via boost.serialization + * @author Alex Cunningham + * @author Richard Roberts + * @date Feb 7, 2012 + */ + +#pragma once + +#include +#include + +// includes for standard serialization types +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace gtsam { + +// Serialization directly to strings in compressed format +template +std::string serialize(const T& input) { + std::ostringstream out_archive_stream; + boost::archive::text_oarchive out_archive(out_archive_stream); + out_archive << input; + return out_archive_stream.str(); +} + +template +void deserialize(const std::string& serialized, T& output) { + std::istringstream in_archive_stream(serialized); + boost::archive::text_iarchive in_archive(in_archive_stream); + in_archive >> output; +} + +// Serialization to XML format with named structures +template +std::string serializeXML(const T& input, const std::string& name="data") { + std::ostringstream out_archive_stream; + boost::archive::xml_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input); + return out_archive_stream.str(); +} + +template +void deserializeXML(const std::string& serialized, T& output, const std::string& name="data") { + std::istringstream in_archive_stream(serialized); + boost::archive::xml_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); +} + +// Serialization to binary format with named structures +template +std::string serializeBinary(const T& input, const std::string& name="data") { + std::ostringstream out_archive_stream; + boost::archive::binary_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input); + return out_archive_stream.str(); +} + +template +void deserializeBinary(const std::string& serialized, T& output, const std::string& name="data") { + std::istringstream in_archive_stream(serialized); + boost::archive::binary_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); +} + +} // \namespace gtsam diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 3d5bf4d71..b6593bd9f 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -22,46 +22,14 @@ #include #include -// includes for standard serialization types -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include +#include // whether to print the serialized text to stdout const bool verbose = false; -namespace gtsam { namespace serializationTestHelpers { +namespace gtsam { +namespace serializationTestHelpers { - /* ************************************************************************* */ - // Serialization testing code. - /* ************************************************************************* */ - -template -std::string serialize(const T& input) { - std::ostringstream out_archive_stream; - boost::archive::text_oarchive out_archive(out_archive_stream); - out_archive << input; - return out_archive_stream.str(); -} - -template -void deserialize(const std::string& serialized, T& output) { - std::istringstream in_archive_stream(serialized); - boost::archive::text_iarchive in_archive(in_archive_stream); - in_archive >> output; -} // Templated round-trip serialization template @@ -97,22 +65,6 @@ bool equalsDereferenced(const T& input) { return input->equals(*output); } -/* ************************************************************************* */ -template -std::string serializeXML(const T& input) { - std::ostringstream out_archive_stream; - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp("data", input); - return out_archive_stream.str(); -} - -template -void deserializeXML(const std::string& serialized, T& output) { - std::istringstream in_archive_stream(serialized); - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp("data", output); -} - // Templated round-trip serialization using XML template void roundtripXML(const T& input, T& output) { @@ -148,22 +100,6 @@ bool equalsDereferencedXML(const T& input = T()) { return input->equals(*output); } -/* ************************************************************************* */ -template -std::string serializeBinary(const T& input) { - std::ostringstream out_archive_stream; - boost::archive::binary_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp("data", input); - return out_archive_stream.str(); -} - -template -void deserializeBinary(const std::string& serialized, T& output) { - std::istringstream in_archive_stream(serialized); - boost::archive::binary_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp("data", output); -} - // Templated round-trip serialization using XML template void roundtripBinary(const T& input, T& output) { @@ -199,4 +135,6 @@ bool equalsDereferencedBinary(const T& input = T()) { return input->equals(*output); } -} } +} // \namespace serializationTestHelpers +} // \namespace gtsam + diff --git a/gtsam/slam/serialization.cpp b/gtsam/slam/serialization.cpp new file mode 100644 index 000000000..a57d82add --- /dev/null +++ b/gtsam/slam/serialization.cpp @@ -0,0 +1,257 @@ +/** + * @file serialization.cpp + * + * @date Jun 12, 2013 + * @author Alex Cunningham + */ + +#include +#include + +//#include +#include +#include +#include +//#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +//#include +#include +#include +#include +//#include + +using namespace gtsam; + +// Creating as many permutations of factors as possible +typedef PriorFactor PriorFactorLieVector; +typedef PriorFactor PriorFactorLieMatrix; +typedef PriorFactor PriorFactorPoint2; +typedef PriorFactor PriorFactorStereoPoint2; +typedef PriorFactor PriorFactorPoint3; +typedef PriorFactor PriorFactorRot2; +typedef PriorFactor PriorFactorRot3; +typedef PriorFactor PriorFactorPose2; +typedef PriorFactor PriorFactorPose3; +typedef PriorFactor PriorFactorCal3_S2; +typedef PriorFactor PriorFactorCal3DS2; +typedef PriorFactor PriorFactorCalibratedCamera; +typedef PriorFactor PriorFactorSimpleCamera; +typedef PriorFactor PriorFactorStereoCamera; + +typedef BetweenFactor BetweenFactorLieVector; +typedef BetweenFactor BetweenFactorLieMatrix; +typedef BetweenFactor BetweenFactorPoint2; +typedef BetweenFactor BetweenFactorPoint3; +typedef BetweenFactor BetweenFactorRot2; +typedef BetweenFactor BetweenFactorRot3; +typedef BetweenFactor BetweenFactorPose2; +typedef BetweenFactor BetweenFactorPose3; + +typedef NonlinearEquality NonlinearEqualityLieVector; +typedef NonlinearEquality NonlinearEqualityLieMatrix; +typedef NonlinearEquality NonlinearEqualityPoint2; +typedef NonlinearEquality NonlinearEqualityStereoPoint2; +typedef NonlinearEquality NonlinearEqualityPoint3; +typedef NonlinearEquality NonlinearEqualityRot2; +typedef NonlinearEquality NonlinearEqualityRot3; +typedef NonlinearEquality NonlinearEqualityPose2; +typedef NonlinearEquality NonlinearEqualityPose3; +typedef NonlinearEquality NonlinearEqualityCal3_S2; +typedef NonlinearEquality NonlinearEqualityCal3DS2; +typedef NonlinearEquality NonlinearEqualityCalibratedCamera; +typedef NonlinearEquality NonlinearEqualitySimpleCamera; +typedef NonlinearEquality NonlinearEqualityStereoCamera; + +typedef RangeFactor RangeFactorPosePoint2; +typedef RangeFactor RangeFactorPosePoint3; +typedef RangeFactor RangeFactorPose2; +typedef RangeFactor RangeFactorPose3; +typedef RangeFactor RangeFactorCalibratedCameraPoint; +typedef RangeFactor RangeFactorSimpleCameraPoint; +typedef RangeFactor RangeFactorCalibratedCamera; +typedef RangeFactor RangeFactorSimpleCamera; + +typedef BearingFactor BearingFactor2D; +typedef BearingFactor BearingFactor3D; + +typedef BearingRangeFactor BearingRangeFactor2D; +typedef BearingRangeFactor BearingRangeFactor3D; + +typedef GenericProjectionFactor GenericProjectionFactorCal3_S2; +typedef GenericProjectionFactor GenericProjectionFactorCal3DS2; + +typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; +//typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; + +typedef gtsam::GeneralSFMFactor2 GeneralSFMFactor2Cal3_S2; + +typedef gtsam::GenericStereoFactor GenericStereoFactor3D; + + +/* Create GUIDs for Noisemodels */ +/* ************************************************************************* */ +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); + +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Base , "gtsam_noiseModel_mEstimator_Base"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Null , "gtsam_noiseModel_mEstimator_Null"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Fair , "gtsam_noiseModel_mEstimator_Fair"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Huber, "gtsam_noiseModel_mEstimator_Huber"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Tukey, "gtsam_noiseModel_mEstimator_Tukey"); + +BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); + +/* Create GUIDs for geometry */ +/* ************************************************************************* */ +BOOST_CLASS_EXPORT(gtsam::LieVector); +BOOST_CLASS_EXPORT(gtsam::LieMatrix); +BOOST_CLASS_EXPORT(gtsam::Point2); +BOOST_CLASS_EXPORT(gtsam::StereoPoint2); +BOOST_CLASS_EXPORT(gtsam::Point3); +BOOST_CLASS_EXPORT(gtsam::Rot2); +BOOST_CLASS_EXPORT(gtsam::Rot3); +BOOST_CLASS_EXPORT(gtsam::Pose2); +BOOST_CLASS_EXPORT(gtsam::Pose3); +BOOST_CLASS_EXPORT(gtsam::Cal3_S2); +BOOST_CLASS_EXPORT(gtsam::Cal3DS2); +BOOST_CLASS_EXPORT(gtsam::Cal3_S2Stereo); +BOOST_CLASS_EXPORT(gtsam::CalibratedCamera); +BOOST_CLASS_EXPORT(gtsam::SimpleCamera); +BOOST_CLASS_EXPORT(gtsam::StereoCamera); + +/* Create GUIDs for factors */ +/* ************************************************************************* */ +BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor"); +BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactor , "gtsam::HessianFactor"); + +BOOST_CLASS_EXPORT_GUID(PriorFactorLieVector, "gtsam::PriorFactorLieVector"); +BOOST_CLASS_EXPORT_GUID(PriorFactorLieMatrix, "gtsam::PriorFactorLieMatrix"); +BOOST_CLASS_EXPORT_GUID(PriorFactorPoint2, "gtsam::PriorFactorPoint2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorStereoPoint2, "gtsam::PriorFactorStereoPoint2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorPoint3, "gtsam::PriorFactorPoint3"); +BOOST_CLASS_EXPORT_GUID(PriorFactorRot2, "gtsam::PriorFactorRot2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorRot3, "gtsam::PriorFactorRot3"); +BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsam::PriorFactorPose2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorPose3, "gtsam::PriorFactorPose3"); +BOOST_CLASS_EXPORT_GUID(PriorFactorCal3_S2, "gtsam::PriorFactorCal3_S2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorCal3DS2, "gtsam::PriorFactorCal3DS2"); +BOOST_CLASS_EXPORT_GUID(PriorFactorCalibratedCamera, "gtsam::PriorFactorCalibratedCamera"); +BOOST_CLASS_EXPORT_GUID(PriorFactorSimpleCamera, "gtsam::PriorFactorSimpleCamera"); +BOOST_CLASS_EXPORT_GUID(PriorFactorStereoCamera, "gtsam::PriorFactorStereoCamera"); + +BOOST_CLASS_EXPORT_GUID(BetweenFactorLieVector, "gtsam::BetweenFactorLieVector"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorLieMatrix, "gtsam::BetweenFactorLieMatrix"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint2, "gtsam::BetweenFactorPoint2"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint3, "gtsam::BetweenFactorPoint3"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorRot2, "gtsam::BetweenFactorRot2"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorRot3, "gtsam::BetweenFactorRot3"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorPose2, "gtsam::BetweenFactorPose2"); +BOOST_CLASS_EXPORT_GUID(BetweenFactorPose3, "gtsam::BetweenFactorPose3"); + +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieVector, "gtsam::NonlinearEqualityLieVector"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieMatrix, "gtsam::NonlinearEqualityLieMatrix"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint2, "gtsam::NonlinearEqualityPoint2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoPoint2, "gtsam::NonlinearEqualityStereoPoint2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint3, "gtsam::NonlinearEqualityPoint3"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot2, "gtsam::NonlinearEqualityRot2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot3, "gtsam::NonlinearEqualityRot3"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose2, "gtsam::NonlinearEqualityPose2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose3, "gtsam::NonlinearEqualityPose3"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3_S2, "gtsam::NonlinearEqualityCal3_S2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3DS2, "gtsam::NonlinearEqualityCal3DS2"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCalibratedCamera, "gtsam::NonlinearEqualityCalibratedCamera"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualitySimpleCamera, "gtsam::NonlinearEqualitySimpleCamera"); +BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoCamera, "gtsam::NonlinearEqualityStereoCamera"); + +BOOST_CLASS_EXPORT_GUID(RangeFactorPosePoint2, "gtsam::RangeFactorPosePoint2"); +BOOST_CLASS_EXPORT_GUID(RangeFactorPosePoint3, "gtsam::RangeFactorPosePoint3"); +BOOST_CLASS_EXPORT_GUID(RangeFactorPose2, "gtsam::RangeFactorPose2"); +BOOST_CLASS_EXPORT_GUID(RangeFactorPose3, "gtsam::RangeFactorPose3"); +BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCameraPoint, "gtsam::RangeFactorCalibratedCameraPoint"); +BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleCameraPoint"); +BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCamera, "gtsam::RangeFactorCalibratedCamera"); +BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera"); + +BOOST_CLASS_EXPORT_GUID(BearingFactor2D, "gtsam::BearingFactor2D"); + +BOOST_CLASS_EXPORT_GUID(BearingRangeFactor2D, "gtsam::BearingRangeFactor2D"); + +BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectionFactorCal3_S2"); +BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3DS2, "gtsam::GenericProjectionFactorCal3DS2"); + +BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3_S2, "gtsam::GeneralSFMFactorCal3_S2"); +//BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2"); + +BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_S2"); + +BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D"); + +/* ************************************************************************* */ +// Actual implementations of functions +/* ************************************************************************* */ +std::string gtsam::serializeGraph(const NonlinearFactorGraph& graph) { + return serialize(graph); +} + +/* ************************************************************************* */ +NonlinearFactorGraph gtsam::deserializeGraph(const std::string& serialized_graph) { + NonlinearFactorGraph result; + deserialize(serialized_graph, result); + return result; +} + +/* ************************************************************************* */ +std::string gtsam::serializeGraphXML(const NonlinearFactorGraph& graph, const std::string& name) { + return serializeXML(graph, name); +} + +/* ************************************************************************* */ +NonlinearFactorGraph gtsam::deserializeGraphXML(const std::string& serialized_graph, + const std::string& name) { + NonlinearFactorGraph result; + deserializeXML(serialized_graph, result, name); + return result; +} + +/* ************************************************************************* */ +std::string gtsam::serializeValues(const Values& values) { + return serialize(values); +} + +/* ************************************************************************* */ +Values gtsam::deserializeValues(const std::string& serialized_values) { + Values result; + deserialize(serialized_values, result); + return result; +} + +/* ************************************************************************* */ +std::string gtsam::serializeValuesXML(const Values& values, const std::string& name) { + return serializeXML(values, name); +} + +/* ************************************************************************* */ +Values gtsam::deserializeValuesXML(const std::string& serialized_values, + const std::string& name) { + Values result; + deserializeXML(serialized_values, result, name); + return result; +} + +/* ************************************************************************* */ + + diff --git a/gtsam/slam/serialization.h b/gtsam/slam/serialization.h new file mode 100644 index 000000000..ceb237686 --- /dev/null +++ b/gtsam/slam/serialization.h @@ -0,0 +1,40 @@ +/** + * @file serialization.h + * + * @brief Global functions for performing serialization, designed for use with matlab + * + * @date Jun 12, 2013 + * @author Alex Cunningham + */ + +#pragma once + +#include + +namespace gtsam { + +// Serialize/Deserialize a NonlinearFactorGraph +std::string serializeGraph(const NonlinearFactorGraph& graph); + +NonlinearFactorGraph deserializeGraph(const std::string& serialized_graph); + +std::string serializeGraphXML(const NonlinearFactorGraph& graph, + const std::string& name = "graph"); + +NonlinearFactorGraph deserializeGraphXML(const std::string& serialized_graph, + const std::string& name = "graph"); + + +// Serialize/Deserialize a Values +std::string serializeValues(const Values& values); + +Values deserializeValues(const std::string& serialized_values); + +std::string serializeValuesXML(const Values& values, const std::string& name = "values"); + +Values deserializeValuesXML(const std::string& serialized_values, + const std::string& name = "values"); + +} // \namespace gtsam + + diff --git a/gtsam/slam/tests/testSerialization.cpp b/gtsam/slam/tests/testSerialization.cpp new file mode 100644 index 000000000..64d5504da --- /dev/null +++ b/gtsam/slam/tests/testSerialization.cpp @@ -0,0 +1,75 @@ +/** + * @file testSerialization.cpp + * + * @brief Tests for serialization global functions using boost.serialization + * + * @date Jun 12, 2013 + * @author Alex Cunningham + */ + +#include + +#include + +#include +#include + +#include +#include + +using namespace std; +using namespace gtsam; + +Values exampleValues() { + Values result; + result.insert(234, gtsam::Rot2::fromAngle(0.1)); + result.insert(123, gtsam::Point2(1.0, 2.0)); + result.insert(254, gtsam::Pose2(1.0, 2.0, 0.3)); + result.insert(678, gtsam::Rot3::Rx(0.1)); + result.insert(498, gtsam::Point3(1.0, 2.0, 3.0)); + result.insert(345, gtsam::Pose3(Rot3::Rx(0.1), Point3(1.0, 2.0, 3.0))); + return result; +} + +NonlinearFactorGraph exampleGraph() { + NonlinearFactorGraph graph; + graph.add(PriorFactor(234, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3)))); + graph.add(BetweenFactor(234, 567, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3)))); + return graph; +} + +/* ************************************************************************* */ +TEST( testSerialization, text_graph_serialization ) { + NonlinearFactorGraph graph = exampleGraph(); + string serialized = serializeGraph(graph); + NonlinearFactorGraph actGraph = deserializeGraph(serialized); + EXPECT(assert_equal(graph, actGraph)); +} + +/* ************************************************************************* */ +TEST( testSerialization, xml_graph_serialization ) { + NonlinearFactorGraph graph = exampleGraph(); + string serialized = serializeGraphXML(graph, "graph1"); + NonlinearFactorGraph actGraph = deserializeGraphXML(serialized, "graph1"); + EXPECT(assert_equal(graph, actGraph)); +} + +/* ************************************************************************* */ +TEST( testSerialization, text_values_serialization ) { + Values values = exampleValues(); + string serialized = serializeValues(values); + Values actValues = deserializeValues(serialized); + EXPECT(assert_equal(values, actValues)); +} + +/* ************************************************************************* */ +TEST( testSerialization, xml_values_serialization ) { + Values values = exampleValues(); + string serialized = serializeValuesXML(values, "values1"); + Values actValues = deserializeValuesXML(serialized, "values1"); + EXPECT(assert_equal(values, actValues, 1e-5)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ diff --git a/tests/testSerializationSLAM.cpp b/tests/testSerializationSLAM.cpp index f9229eac6..57a1e5cb3 100644 --- a/tests/testSerializationSLAM.cpp +++ b/tests/testSerializationSLAM.cpp @@ -133,6 +133,13 @@ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal" BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Robust, "gtsam_noiseModel_Robust"); + +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Base , "gtsam_noiseModel_mEstimator_Base"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Null , "gtsam_noiseModel_mEstimator_Null"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Fair , "gtsam_noiseModel_mEstimator_Fair"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Huber, "gtsam_noiseModel_mEstimator_Huber"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Tukey, "gtsam_noiseModel_mEstimator_Tukey"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); @@ -155,7 +162,6 @@ BOOST_CLASS_EXPORT(gtsam::CalibratedCamera); BOOST_CLASS_EXPORT(gtsam::SimpleCamera); BOOST_CLASS_EXPORT(gtsam::StereoCamera); - /* Create GUIDs for factors */ /* ************************************************************************* */ BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor"); @@ -225,7 +231,7 @@ BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D"); /* ************************************************************************* */ -TEST (Serialization, smallExample_linear) { +TEST (testSerializationSLAM, smallExample_linear) { using namespace example; Ordering ordering; ordering += X(1),X(2),L(1); @@ -245,7 +251,7 @@ TEST (Serialization, smallExample_linear) { } /* ************************************************************************* */ -TEST (Serialization, gaussianISAM) { +TEST (testSerializationSLAM, gaussianISAM) { using namespace example; Ordering ordering; GaussianFactorGraph smoother; @@ -265,7 +271,7 @@ BOOST_CLASS_EXPORT_GUID(simulated2D::Odometry, "gtsam::simulated2D::Odometry" BOOST_CLASS_EXPORT_GUID(simulated2D::Measurement, "gtsam::simulated2D::Measurement") /* ************************************************************************* */ -TEST (Serialization, smallExample_nonlinear) { +TEST (testSerializationSLAM, smallExample_nonlinear) { using namespace example; NonlinearFactorGraph nfg = createNonlinearFactorGraph(); Values c1 = createValues(); @@ -279,7 +285,7 @@ TEST (Serialization, smallExample_nonlinear) { } /* ************************************************************************* */ -TEST (Serialization, factors) { +TEST (testSerializationSLAM, factors) { LieVector lieVector(4, 1.0, 2.0, 3.0, 4.0); LieMatrix lieMatrix(2, 3, 1.0, 2.0, 3.0, 4.0, 5.0 ,6.0); @@ -331,7 +337,13 @@ TEST (Serialization, factors) { SharedNoiseModel model9 = noiseModel::Isotropic::Sigma(9, 0.3); SharedNoiseModel model11 = noiseModel::Isotropic::Sigma(11, 0.3); + SharedNoiseModel robust1 = noiseModel::Robust::Create( + noiseModel::mEstimator::Huber::Create(10.0, noiseModel::mEstimator::Huber::Scalar), + noiseModel::Unit::Create(2)); + EXPECT(equalsDereferenced(robust1)); + EXPECT(equalsDereferencedXML(robust1)); + EXPECT(equalsDereferencedBinary(robust1)); PriorFactorLieVector priorFactorLieVector(a01, lieVector, model4); PriorFactorLieMatrix priorFactorLieMatrix(a02, lieMatrix, model6); @@ -660,11 +672,8 @@ TEST (Serialization, factors) { EXPECT(equalsBinary(generalSFMFactor2Cal3_S2)); EXPECT(equalsBinary(genericStereoFactor3D)); - } - - /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ From 666e30a59b136521f1168971a053b55c58fdb536 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 12 Jun 2013 19:30:21 +0000 Subject: [PATCH 063/256] Changed serialization interface to return shared versions of graph/values to avoid copies in matlab --- gtsam/slam/serialization.cpp | 24 ++++++++++++------------ gtsam/slam/serialization.h | 8 ++++---- gtsam/slam/tests/testSerialization.cpp | 8 ++++---- 3 files changed, 20 insertions(+), 20 deletions(-) diff --git a/gtsam/slam/serialization.cpp b/gtsam/slam/serialization.cpp index a57d82add..d8a1cce06 100644 --- a/gtsam/slam/serialization.cpp +++ b/gtsam/slam/serialization.cpp @@ -208,9 +208,9 @@ std::string gtsam::serializeGraph(const NonlinearFactorGraph& graph) { } /* ************************************************************************* */ -NonlinearFactorGraph gtsam::deserializeGraph(const std::string& serialized_graph) { - NonlinearFactorGraph result; - deserialize(serialized_graph, result); +NonlinearFactorGraph::shared_ptr gtsam::deserializeGraph(const std::string& serialized_graph) { + NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph()); + deserialize(serialized_graph, *result); return result; } @@ -220,10 +220,10 @@ std::string gtsam::serializeGraphXML(const NonlinearFactorGraph& graph, const st } /* ************************************************************************* */ -NonlinearFactorGraph gtsam::deserializeGraphXML(const std::string& serialized_graph, +NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphXML(const std::string& serialized_graph, const std::string& name) { - NonlinearFactorGraph result; - deserializeXML(serialized_graph, result, name); + NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph()); + deserializeXML(serialized_graph, *result, name); return result; } @@ -233,9 +233,9 @@ std::string gtsam::serializeValues(const Values& values) { } /* ************************************************************************* */ -Values gtsam::deserializeValues(const std::string& serialized_values) { - Values result; - deserialize(serialized_values, result); +Values::shared_ptr gtsam::deserializeValues(const std::string& serialized_values) { + Values::shared_ptr result(new Values()); + deserialize(serialized_values, *result); return result; } @@ -245,10 +245,10 @@ std::string gtsam::serializeValuesXML(const Values& values, const std::string& n } /* ************************************************************************* */ -Values gtsam::deserializeValuesXML(const std::string& serialized_values, +Values::shared_ptr gtsam::deserializeValuesXML(const std::string& serialized_values, const std::string& name) { - Values result; - deserializeXML(serialized_values, result, name); + Values::shared_ptr result(new Values()); + deserializeXML(serialized_values, *result, name); return result; } diff --git a/gtsam/slam/serialization.h b/gtsam/slam/serialization.h index ceb237686..0dde72a8c 100644 --- a/gtsam/slam/serialization.h +++ b/gtsam/slam/serialization.h @@ -16,23 +16,23 @@ namespace gtsam { // Serialize/Deserialize a NonlinearFactorGraph std::string serializeGraph(const NonlinearFactorGraph& graph); -NonlinearFactorGraph deserializeGraph(const std::string& serialized_graph); +NonlinearFactorGraph::shared_ptr deserializeGraph(const std::string& serialized_graph); std::string serializeGraphXML(const NonlinearFactorGraph& graph, const std::string& name = "graph"); -NonlinearFactorGraph deserializeGraphXML(const std::string& serialized_graph, +NonlinearFactorGraph::shared_ptr deserializeGraphXML(const std::string& serialized_graph, const std::string& name = "graph"); // Serialize/Deserialize a Values std::string serializeValues(const Values& values); -Values deserializeValues(const std::string& serialized_values); +Values::shared_ptr deserializeValues(const std::string& serialized_values); std::string serializeValuesXML(const Values& values, const std::string& name = "values"); -Values deserializeValuesXML(const std::string& serialized_values, +Values::shared_ptr deserializeValuesXML(const std::string& serialized_values, const std::string& name = "values"); } // \namespace gtsam diff --git a/gtsam/slam/tests/testSerialization.cpp b/gtsam/slam/tests/testSerialization.cpp index 64d5504da..91b938ad0 100644 --- a/gtsam/slam/tests/testSerialization.cpp +++ b/gtsam/slam/tests/testSerialization.cpp @@ -42,7 +42,7 @@ NonlinearFactorGraph exampleGraph() { TEST( testSerialization, text_graph_serialization ) { NonlinearFactorGraph graph = exampleGraph(); string serialized = serializeGraph(graph); - NonlinearFactorGraph actGraph = deserializeGraph(serialized); + NonlinearFactorGraph actGraph = *deserializeGraph(serialized); EXPECT(assert_equal(graph, actGraph)); } @@ -50,7 +50,7 @@ TEST( testSerialization, text_graph_serialization ) { TEST( testSerialization, xml_graph_serialization ) { NonlinearFactorGraph graph = exampleGraph(); string serialized = serializeGraphXML(graph, "graph1"); - NonlinearFactorGraph actGraph = deserializeGraphXML(serialized, "graph1"); + NonlinearFactorGraph actGraph = *deserializeGraphXML(serialized, "graph1"); EXPECT(assert_equal(graph, actGraph)); } @@ -58,7 +58,7 @@ TEST( testSerialization, xml_graph_serialization ) { TEST( testSerialization, text_values_serialization ) { Values values = exampleValues(); string serialized = serializeValues(values); - Values actValues = deserializeValues(serialized); + Values actValues = *deserializeValues(serialized); EXPECT(assert_equal(values, actValues)); } @@ -66,7 +66,7 @@ TEST( testSerialization, text_values_serialization ) { TEST( testSerialization, xml_values_serialization ) { Values values = exampleValues(); string serialized = serializeValuesXML(values, "values1"); - Values actValues = deserializeValuesXML(serialized, "values1"); + Values actValues = *deserializeValuesXML(serialized, "values1"); EXPECT(assert_equal(values, actValues, 1e-5)); } From e69af84c36970fbbeb3de209e3bfe06cb034de69 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 12 Jun 2013 19:30:22 +0000 Subject: [PATCH 064/256] Added wrapping for graph/values serialization with tests in Matlab. Values serializes correctly, but graphs do not in either case. --- gtsam.h | 27 ++++++++++++++++++++++ matlab/gtsam_tests/testPlanarSLAMExample.m | 8 +++++++ matlab/gtsam_tests/testPose2SLAMExample.m | 9 ++++++++ 3 files changed, 44 insertions(+) diff --git a/gtsam.h b/gtsam.h index 20ea0bf8a..64270b133 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2102,6 +2102,33 @@ pair load2D(string filename, pair load2D_robust(string filename, gtsam::noiseModel::Base* model); +//************************************************************************* +// Serialization +//************************************************************************* +#include + +// Serialize/Deserialize a NonlinearFactorGraph +string serializeGraph(const gtsam::NonlinearFactorGraph& graph); + +gtsam::NonlinearFactorGraph* deserializeGraph(string serialized_graph); + +string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph); +string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph, string name); + +gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph); +gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph, string name); + +// Serialize/Deserialize a Values +string serializeValues(const gtsam::Values& values); + +gtsam::Values* deserializeValues(string serialized_values); + +string serializeValuesXML(const gtsam::Values& values); +string serializeValuesXML(const gtsam::Values& values, string name); + +gtsam::Values* deserializeValuesXML(string serialized_values); +gtsam::Values* deserializeValuesXML(string serialized_values, string name); + //************************************************************************* // Utilities //************************************************************************* diff --git a/matlab/gtsam_tests/testPlanarSLAMExample.m b/matlab/gtsam_tests/testPlanarSLAMExample.m index 2a736a710..584b86345 100644 --- a/matlab/gtsam_tests/testPlanarSLAMExample.m +++ b/matlab/gtsam_tests/testPlanarSLAMExample.m @@ -68,4 +68,12 @@ point_1 = result.at(symbol('l',1)); marginals.marginalCovariance(symbol('l',1)); CHECK('point_1.equals(Point2(2,2),1e-4)',point_1.equals(Point2(2,2),1e-4)); +%% Check that serialization works properly +serialized_values = serializeValues(initialEstimate); +deserializedValues = deserializeValues(serialized_values); +CHECK('initialEstimate.equals(deserializedValues)',initialEstimate.equals(deserializedValues,1e-9)); +% FAILS: unregistered class? +% serialized_graph = serializeGraph(graph); +% deserializedGraph = deserializeGraph(serialized_graph); +% CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9)); \ No newline at end of file diff --git a/matlab/gtsam_tests/testPose2SLAMExample.m b/matlab/gtsam_tests/testPose2SLAMExample.m index 127bcd41c..2ac354955 100644 --- a/matlab/gtsam_tests/testPose2SLAMExample.m +++ b/matlab/gtsam_tests/testPose2SLAMExample.m @@ -61,3 +61,12 @@ pose_1 = result.at(1); CHECK('pose_1.equals(Pose2,1e-4)',pose_1.equals(Pose2,1e-4)); +%% Check that serialization works properly +serialized_values = serializeValues(initialEstimate); +deserializedValues = deserializeValues(serialized_values); +CHECK('initialEstimate.equals(deserializedValues)',initialEstimate.equals(deserializedValues,1e-9)); + +% FAILS: unregistered class? +% serialized_graph = serializeGraph(graph); +% deserializedGraph = deserializeGraph(serialized_graph); +% CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9)); From 527ea5e5114220a663c8a14192a49ade6278d762 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 12 Jun 2013 20:01:59 +0000 Subject: [PATCH 065/256] Moved serialization tests over to a single test scenario - factors don't appear to work at the moment --- .../testGraphValuesSerialization.m | 56 +++++++++++++++++++ matlab/gtsam_tests/testPlanarSLAMExample.m | 10 ---- matlab/gtsam_tests/testPose2SLAMExample.m | 10 ---- matlab/gtsam_tests/test_gtsam.m | 3 + 4 files changed, 59 insertions(+), 20 deletions(-) create mode 100644 matlab/gtsam_tests/testGraphValuesSerialization.m diff --git a/matlab/gtsam_tests/testGraphValuesSerialization.m b/matlab/gtsam_tests/testGraphValuesSerialization.m new file mode 100644 index 000000000..1d4066c82 --- /dev/null +++ b/matlab/gtsam_tests/testGraphValuesSerialization.m @@ -0,0 +1,56 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% GTSAM Copyright 2010, Georgia Tech Research Corporation, +% Atlanta, Georgia 30332-0415 +% All Rights Reserved +% Authors: Frank Dellaert, et al. (see THANKS for the full author list) +% +% See LICENSE for the license information +% +% @brief Simple robotics example using the pre-built planar SLAM domain +% @author Alex Cunningham +% @author Frank Dellaert +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +import gtsam.* + +%% Create keys for variables +i1 = symbol('x',1); i2 = symbol('x',2); i3 = symbol('x',3); +j1 = symbol('l',1); j2 = symbol('l',2); + +%% Create graph and factors +graph = NonlinearFactorGraph; + +% Prior factor - FAIL: unregistered class +priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin +priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); +graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph + +% Between Factors - FAIL: unregistered class +odometry = Pose2(2.0, 0.0, 0.0); +odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); +graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); + +% BearingRange Factors - FAIL: unregistered class +degrees = pi/180; +brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); +graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(4+4), brNoise)); +graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise)); +graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise)); + +%% Create Values +values = Values; +values.insert(i1, Pose2(0.5, 0.0, 0.2)); +values.insert(i2, Pose2(2.3, 0.1,-0.2)); +values.insert(i3, Pose2(4.1, 0.1, 0.1)); +values.insert(j1, Point2(1.8, 2.1)); +values.insert(j2, Point2(4.1, 1.8)); + +%% Check that serialization works properly +serialized_values = serializeValues(values); % returns a string +deserializedValues = deserializeValues(serialized_values); % returns a new values +CHECK('values.equals(deserializedValues)',values.equals(deserializedValues,1e-9)); + +serialized_graph = serializeGraph(graph); % returns a string +deserializedGraph = deserializeGraph(serialized_graph); % returns a new graph +CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9)); \ No newline at end of file diff --git a/matlab/gtsam_tests/testPlanarSLAMExample.m b/matlab/gtsam_tests/testPlanarSLAMExample.m index 584b86345..7694a1a0b 100644 --- a/matlab/gtsam_tests/testPlanarSLAMExample.m +++ b/matlab/gtsam_tests/testPlanarSLAMExample.m @@ -67,13 +67,3 @@ CHECK('pose_1.equals(Pose2,1e-4)',pose_1.equals(Pose2,1e-4)); point_1 = result.at(symbol('l',1)); marginals.marginalCovariance(symbol('l',1)); CHECK('point_1.equals(Point2(2,2),1e-4)',point_1.equals(Point2(2,2),1e-4)); - -%% Check that serialization works properly -serialized_values = serializeValues(initialEstimate); -deserializedValues = deserializeValues(serialized_values); -CHECK('initialEstimate.equals(deserializedValues)',initialEstimate.equals(deserializedValues,1e-9)); - -% FAILS: unregistered class? -% serialized_graph = serializeGraph(graph); -% deserializedGraph = deserializeGraph(serialized_graph); -% CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9)); \ No newline at end of file diff --git a/matlab/gtsam_tests/testPose2SLAMExample.m b/matlab/gtsam_tests/testPose2SLAMExample.m index 2ac354955..8c70c27e7 100644 --- a/matlab/gtsam_tests/testPose2SLAMExample.m +++ b/matlab/gtsam_tests/testPose2SLAMExample.m @@ -60,13 +60,3 @@ P = marginals.marginalCovariance(1); pose_1 = result.at(1); CHECK('pose_1.equals(Pose2,1e-4)',pose_1.equals(Pose2,1e-4)); - -%% Check that serialization works properly -serialized_values = serializeValues(initialEstimate); -deserializedValues = deserializeValues(serialized_values); -CHECK('initialEstimate.equals(deserializedValues)',initialEstimate.equals(deserializedValues,1e-9)); - -% FAILS: unregistered class? -% serialized_graph = serializeGraph(graph); -% deserializedGraph = deserializeGraph(serialized_graph); -% CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9)); diff --git a/matlab/gtsam_tests/test_gtsam.m b/matlab/gtsam_tests/test_gtsam.m index 113e594fd..1f8125b81 100644 --- a/matlab/gtsam_tests/test_gtsam.m +++ b/matlab/gtsam_tests/test_gtsam.m @@ -30,5 +30,8 @@ testStereoVOExample display 'Starting: testVisualISAMExample' testVisualISAMExample +display 'Starting: testGraphValuesSerialization' +testVisualISAMExample + % end of tests display 'Tests complete!' From e1fc90ad14f319d9ce91bafafb5c77c3f1645aff Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Thu, 13 Jun 2013 14:29:31 +0000 Subject: [PATCH 066/256] Added direct saving to/from files for graph/values serialization --- gtsam/base/serialization.h | 67 ++++++++++++++++++++++++++ gtsam/slam/serialization.cpp | 56 +++++++++++++++++++++ gtsam/slam/serialization.h | 22 +++++++++ gtsam/slam/tests/testSerialization.cpp | 47 ++++++++++++++++++ 4 files changed, 192 insertions(+) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 8089de814..a41182f47 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -20,6 +20,7 @@ #pragma once #include +#include #include // includes for standard serialization types @@ -57,6 +58,28 @@ void deserialize(const std::string& serialized, T& output) { in_archive >> output; } +template +bool serializeToFile(const T& input, const std::string& filename) { + std::ofstream out_archive_stream(filename.c_str()); + if (!out_archive_stream.is_open()) + return false; + boost::archive::text_oarchive out_archive(out_archive_stream); + out_archive << input; + out_archive_stream.close(); + return true; +} + +template +bool deserializeFromFile(const std::string& filename, T& output) { + std::ifstream in_archive_stream(filename.c_str()); + if (!in_archive_stream.is_open()) + return false; + boost::archive::text_iarchive in_archive(in_archive_stream); + in_archive >> output; + in_archive_stream.close(); + return true; +} + // Serialization to XML format with named structures template std::string serializeXML(const T& input, const std::string& name="data") { @@ -73,6 +96,28 @@ void deserializeXML(const std::string& serialized, T& output, const std::string& in_archive >> boost::serialization::make_nvp(name.c_str(), output); } +template +bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name="data") { + std::ofstream out_archive_stream(filename.c_str()); + if (!out_archive_stream.is_open()) + return false; + boost::archive::xml_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input);; + out_archive_stream.close(); + return true; +} + +template +bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name="data") { + std::ifstream in_archive_stream(filename.c_str()); + if (!in_archive_stream.is_open()) + return false; + boost::archive::xml_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); + in_archive_stream.close(); + return true; +} + // Serialization to binary format with named structures template std::string serializeBinary(const T& input, const std::string& name="data") { @@ -89,4 +134,26 @@ void deserializeBinary(const std::string& serialized, T& output, const std::stri in_archive >> boost::serialization::make_nvp(name.c_str(), output); } +template +bool deserializeToBinaryFile(const T& input, const std::string& filename, const std::string& name="data") { + std::ofstream out_archive_stream(filename.c_str()); + if (!out_archive_stream.is_open()) + return false; + boost::archive::binary_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input);; + out_archive_stream.close(); + return true; +} + +template +bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name="data") { + std::ifstream in_archive_stream(filename.c_str()); + if (!in_archive_stream.is_open()) + return false; + boost::archive::binary_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); + in_archive_stream.close(); + return true; +} + } // \namespace gtsam diff --git a/gtsam/slam/serialization.cpp b/gtsam/slam/serialization.cpp index d8a1cce06..e601a5e81 100644 --- a/gtsam/slam/serialization.cpp +++ b/gtsam/slam/serialization.cpp @@ -253,5 +253,61 @@ Values::shared_ptr gtsam::deserializeValuesXML(const std::string& serialized_val } /* ************************************************************************* */ +bool gtsam::serializeGraphToFile(const NonlinearFactorGraph& graph, const std::string& fname) { + return serializeToFile(graph, fname); +} + +/* ************************************************************************* */ +bool gtsam::serializeGraphToXMLFile(const NonlinearFactorGraph& graph, + const std::string& fname, const std::string& name) { + return serializeToXMLFile(graph, fname, name); +} + +/* ************************************************************************* */ +bool gtsam::serializeValuesToFile(const Values& values, const std::string& fname) { + return serializeToFile(values, fname); +} + +/* ************************************************************************* */ +bool gtsam::serializeValuesToXMLFile(const Values& values, + const std::string& fname, const std::string& name) { + return serializeToXMLFile(values, fname, name); +} + +/* ************************************************************************* */ +NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToFile(const std::string& fname) { + NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph()); + if (!deserializeFromFile(fname, *result)) + throw std::invalid_argument("Failed to open file" + fname); + return result; +} + +/* ************************************************************************* */ +NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToXMLFile(const std::string& fname, + const std::string& name) { + NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph()); + if (!deserializeFromXMLFile(fname, *result, name)) + throw std::invalid_argument("Failed to open file" + fname); + return result; +} + +/* ************************************************************************* */ +Values::shared_ptr gtsam::deserializeValuesToFile(const std::string& fname) { + Values::shared_ptr result(new Values()); + if (!deserializeFromFile(fname, *result)) + throw std::invalid_argument("Failed to open file" + fname); + return result; +} + +/* ************************************************************************* */ +Values::shared_ptr gtsam::deserializeValuesToXMLFile(const std::string& fname, + const std::string& name) { + Values::shared_ptr result(new Values()); + if (!deserializeFromXMLFile(fname, *result, name)) + throw std::invalid_argument("Failed to open file" + fname); + return result; +} + +/* ************************************************************************* */ diff --git a/gtsam/slam/serialization.h b/gtsam/slam/serialization.h index 0dde72a8c..5d75f160c 100644 --- a/gtsam/slam/serialization.h +++ b/gtsam/slam/serialization.h @@ -35,6 +35,28 @@ std::string serializeValuesXML(const Values& values, const std::string& name = " Values::shared_ptr deserializeValuesXML(const std::string& serialized_values, const std::string& name = "values"); +// Serialize to/from files +// serialize functions return true if successful +// Filename arguments include path + +// Serialize +bool serializeGraphToFile(const NonlinearFactorGraph& graph, const std::string& fname); +bool serializeGraphToXMLFile(const NonlinearFactorGraph& graph, + const std::string& fname, const std::string& name = "graph"); + +bool serializeValuesToFile(const Values& values, const std::string& fname); +bool serializeValuesToXMLFile(const Values& values, + const std::string& fname, const std::string& name = "values"); + +// Deserialize +NonlinearFactorGraph::shared_ptr deserializeGraphToFile(const std::string& fname); +NonlinearFactorGraph::shared_ptr deserializeGraphToXMLFile(const std::string& fname, + const std::string& name = "graph"); + +Values::shared_ptr deserializeValuesToFile(const std::string& fname); +Values::shared_ptr deserializeValuesToXMLFile(const std::string& fname, + const std::string& name = "values"); + } // \namespace gtsam diff --git a/gtsam/slam/tests/testSerialization.cpp b/gtsam/slam/tests/testSerialization.cpp index 91b938ad0..aad89d4a0 100644 --- a/gtsam/slam/tests/testSerialization.cpp +++ b/gtsam/slam/tests/testSerialization.cpp @@ -16,9 +16,23 @@ #include #include +#include + +#include +#include +#include +#include +#include using namespace std; using namespace gtsam; +using namespace boost::assign; +namespace fs = boost::filesystem; +#ifdef TOPSRCDIR +static string topdir = TOPSRCDIR; +#else +static string topdir = "TOPSRCDIR_NOT_CONFIGURED"; // If TOPSRCDIR is not defined, we error +#endif Values exampleValues() { Values result; @@ -35,6 +49,7 @@ NonlinearFactorGraph exampleGraph() { NonlinearFactorGraph graph; graph.add(PriorFactor(234, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3)))); graph.add(BetweenFactor(234, 567, Pose2(1.0, 2.0, 0.3), noiseModel::Diagonal::Sigmas(ones(3)))); + graph.add(BearingRangeFactor(234, 567, Rot2::fromAngle(0.3), 2.0, noiseModel::Diagonal::Sigmas(ones(2)))); return graph; } @@ -70,6 +85,38 @@ TEST( testSerialization, xml_values_serialization ) { EXPECT(assert_equal(values, actValues, 1e-5)); } +/* ************************************************************************* */ +TEST( testSerialization, serialization_file ) { + // Create files in folder in build folder + fs::remove_all("actual"); + fs::create_directory("actual"); + string path = "actual/"; + + NonlinearFactorGraph graph = exampleGraph(); + Values values = exampleValues(); + + // Serialize objects using each configuration + EXPECT(serializeGraphToFile(graph, path + "graph.dat")); + EXPECT(serializeGraphToXMLFile(graph, path + "graph.xml", "graph1")); + + EXPECT(serializeValuesToFile(values, path + "values.dat")); + EXPECT(serializeValuesToXMLFile(values, path + "values.xml", "values1")); + + // Deserialize + NonlinearFactorGraph actGraph = *deserializeGraphToFile(path + "graph.dat"); + NonlinearFactorGraph actGraphXML = *deserializeGraphToXMLFile(path + "graph.xml", "graph1"); + + Values actValues = *deserializeValuesToFile(path + "values.dat"); + Values actValuesXML = *deserializeValuesToXMLFile(path + "values.xml", "values1"); + + // Verify + EXPECT(assert_equal(graph, actGraph)); + EXPECT(assert_equal(graph, actGraphXML)); + + EXPECT(assert_equal(values, actValues)); + EXPECT(assert_equal(values, actValuesXML)); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ From cabcb3efc8d8b3ed286b469fc8e819e0384b6ae2 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Thu, 13 Jun 2013 14:29:32 +0000 Subject: [PATCH 067/256] Added wrapping for serialization to/from file functions --- gtsam.h | 27 +++++++++++++++++++++++++-- 1 file changed, 25 insertions(+), 2 deletions(-) diff --git a/gtsam.h b/gtsam.h index 64270b133..40806c3a2 100644 --- a/gtsam.h +++ b/gtsam.h @@ -62,7 +62,7 @@ * of using the copy constructor (which is used for non-virtual objects). * - Signature of clone function - will be called virtually, so must appear at least at the top of the inheritance tree * virtual boost::shared_ptr clone() const; - * Templates + * Class Templates * - Basic templates are supported either with an explicit list of types to instantiate, * e.g. template class Class1 { ... }; * or with typedefs, e.g. @@ -81,7 +81,12 @@ /** * Status: * - TODO: default values for arguments + * - WORKAROUND: make multiple versions of the same function for different configurations of default arguments * - TODO: Handle gtsam::Rot3M conversions to quaternions + * - TODO: Parse return of const ref arguments + * - TODO: Parse std::string variants and convert directly to special string + * - TODO: Add enum support + * - TODO: Add generalized serialization support via boost.serialization with hooks to matlab save/load */ namespace std { @@ -98,7 +103,7 @@ namespace std { bool empty() const; void reserve(size_t n); - //Element acces + //Element access T* at(size_t n); T* front(); T* back(); @@ -2129,6 +2134,24 @@ string serializeValuesXML(const gtsam::Values& values, string name); gtsam::Values* deserializeValuesXML(string serialized_values); gtsam::Values* deserializeValuesXML(string serialized_values, string name); +// Serialize +bool serializeGraphToFile(const gtsam::NonlinearFactorGraph& graph, string fname); +bool serializeGraphToXMLFile(const gtsam::NonlinearFactorGraph& graph, string fname); +bool serializeGraphToXMLFile(const gtsam::NonlinearFactorGraph& graph, string fname, string name); + +bool serializeValuesToFile(const gtsam::Values& values, string fname); +bool serializeValuesToXMLFile(const gtsam::Values& values, string fname); +bool serializeValuesToXMLFile(const gtsam::Values& values, string fname, string name); + +// Deserialize +gtsam::NonlinearFactorGraph* deserializeGraphToFile(string fname); +gtsam::NonlinearFactorGraph* deserializeGraphToXMLFile(string fname); +gtsam::NonlinearFactorGraph* deserializeGraphToXMLFile(string fname, string name); + +gtsam::Values* deserializeValuesToFile(string fname); +gtsam::Values* deserializeValuesToXMLFile(string fname); +gtsam::Values* deserializeValuesToXMLFile(string fname, string name); + //************************************************************************* // Utilities //************************************************************************* From a8199f2ed0e6ac9fec89bbf3cd5d0e635fb5369a Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Thu, 13 Jun 2013 14:46:53 +0000 Subject: [PATCH 068/256] Changed naming convention for deserialization functions --- gtsam.h | 12 ++++++------ gtsam/slam/serialization.cpp | 8 ++++---- gtsam/slam/serialization.h | 8 ++++---- gtsam/slam/tests/testSerialization.cpp | 8 ++++---- 4 files changed, 18 insertions(+), 18 deletions(-) diff --git a/gtsam.h b/gtsam.h index 40806c3a2..36a2a9304 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2144,13 +2144,13 @@ bool serializeValuesToXMLFile(const gtsam::Values& values, string fname); bool serializeValuesToXMLFile(const gtsam::Values& values, string fname, string name); // Deserialize -gtsam::NonlinearFactorGraph* deserializeGraphToFile(string fname); -gtsam::NonlinearFactorGraph* deserializeGraphToXMLFile(string fname); -gtsam::NonlinearFactorGraph* deserializeGraphToXMLFile(string fname, string name); +gtsam::NonlinearFactorGraph* deserializeGraphFromFile(string fname); +gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname); +gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname, string name); -gtsam::Values* deserializeValuesToFile(string fname); -gtsam::Values* deserializeValuesToXMLFile(string fname); -gtsam::Values* deserializeValuesToXMLFile(string fname, string name); +gtsam::Values* deserializeValuesFromFile(string fname); +gtsam::Values* deserializeValuesFromXMLFile(string fname); +gtsam::Values* deserializeValuesFromXMLFile(string fname, string name); //************************************************************************* // Utilities diff --git a/gtsam/slam/serialization.cpp b/gtsam/slam/serialization.cpp index e601a5e81..304b10b6d 100644 --- a/gtsam/slam/serialization.cpp +++ b/gtsam/slam/serialization.cpp @@ -275,7 +275,7 @@ bool gtsam::serializeValuesToXMLFile(const Values& values, } /* ************************************************************************* */ -NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToFile(const std::string& fname) { +NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphFromFile(const std::string& fname) { NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph()); if (!deserializeFromFile(fname, *result)) throw std::invalid_argument("Failed to open file" + fname); @@ -283,7 +283,7 @@ NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToFile(const std::string } /* ************************************************************************* */ -NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToXMLFile(const std::string& fname, +NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphFromXMLFile(const std::string& fname, const std::string& name) { NonlinearFactorGraph::shared_ptr result(new NonlinearFactorGraph()); if (!deserializeFromXMLFile(fname, *result, name)) @@ -292,7 +292,7 @@ NonlinearFactorGraph::shared_ptr gtsam::deserializeGraphToXMLFile(const std::str } /* ************************************************************************* */ -Values::shared_ptr gtsam::deserializeValuesToFile(const std::string& fname) { +Values::shared_ptr gtsam::deserializeValuesFromFile(const std::string& fname) { Values::shared_ptr result(new Values()); if (!deserializeFromFile(fname, *result)) throw std::invalid_argument("Failed to open file" + fname); @@ -300,7 +300,7 @@ Values::shared_ptr gtsam::deserializeValuesToFile(const std::string& fname) { } /* ************************************************************************* */ -Values::shared_ptr gtsam::deserializeValuesToXMLFile(const std::string& fname, +Values::shared_ptr gtsam::deserializeValuesFromXMLFile(const std::string& fname, const std::string& name) { Values::shared_ptr result(new Values()); if (!deserializeFromXMLFile(fname, *result, name)) diff --git a/gtsam/slam/serialization.h b/gtsam/slam/serialization.h index 5d75f160c..08451fa0c 100644 --- a/gtsam/slam/serialization.h +++ b/gtsam/slam/serialization.h @@ -49,12 +49,12 @@ bool serializeValuesToXMLFile(const Values& values, const std::string& fname, const std::string& name = "values"); // Deserialize -NonlinearFactorGraph::shared_ptr deserializeGraphToFile(const std::string& fname); -NonlinearFactorGraph::shared_ptr deserializeGraphToXMLFile(const std::string& fname, +NonlinearFactorGraph::shared_ptr deserializeGraphFromFile(const std::string& fname); +NonlinearFactorGraph::shared_ptr deserializeGraphFromXMLFile(const std::string& fname, const std::string& name = "graph"); -Values::shared_ptr deserializeValuesToFile(const std::string& fname); -Values::shared_ptr deserializeValuesToXMLFile(const std::string& fname, +Values::shared_ptr deserializeValuesFromFile(const std::string& fname); +Values::shared_ptr deserializeValuesFromXMLFile(const std::string& fname, const std::string& name = "values"); } // \namespace gtsam diff --git a/gtsam/slam/tests/testSerialization.cpp b/gtsam/slam/tests/testSerialization.cpp index aad89d4a0..616b5b6b7 100644 --- a/gtsam/slam/tests/testSerialization.cpp +++ b/gtsam/slam/tests/testSerialization.cpp @@ -103,11 +103,11 @@ TEST( testSerialization, serialization_file ) { EXPECT(serializeValuesToXMLFile(values, path + "values.xml", "values1")); // Deserialize - NonlinearFactorGraph actGraph = *deserializeGraphToFile(path + "graph.dat"); - NonlinearFactorGraph actGraphXML = *deserializeGraphToXMLFile(path + "graph.xml", "graph1"); + NonlinearFactorGraph actGraph = *deserializeGraphFromFile(path + "graph.dat"); + NonlinearFactorGraph actGraphXML = *deserializeGraphFromXMLFile(path + "graph.xml", "graph1"); - Values actValues = *deserializeValuesToFile(path + "values.dat"); - Values actValuesXML = *deserializeValuesToXMLFile(path + "values.xml", "values1"); + Values actValues = *deserializeValuesFromFile(path + "values.dat"); + Values actValuesXML = *deserializeValuesFromXMLFile(path + "values.xml", "values1"); // Verify EXPECT(assert_equal(graph, actGraph)); From 46ea1d229df7435edc99ec00411f2193576a6bb3 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Thu, 13 Jun 2013 14:53:18 +0000 Subject: [PATCH 069/256] Added test for serializing to file in matlab, graph still fails --- matlab/gtsam_tests/testGraphValuesSerialization.m | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/matlab/gtsam_tests/testGraphValuesSerialization.m b/matlab/gtsam_tests/testGraphValuesSerialization.m index 1d4066c82..5583dde76 100644 --- a/matlab/gtsam_tests/testGraphValuesSerialization.m +++ b/matlab/gtsam_tests/testGraphValuesSerialization.m @@ -51,6 +51,15 @@ serialized_values = serializeValues(values); % returns a string deserializedValues = deserializeValues(serialized_values); % returns a new values CHECK('values.equals(deserializedValues)',values.equals(deserializedValues,1e-9)); -serialized_graph = serializeGraph(graph); % returns a string -deserializedGraph = deserializeGraph(serialized_graph); % returns a new graph -CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9)); \ No newline at end of file +CHECK('serializeValuesToFile(values, values.dat)', serializeValuesToFile(values, 'values.dat')); +deserializedValuesFile = deserializeValuesFromFile('values.dat'); % returns a new values +CHECK('values.equals(deserializedValuesFile)',values.equals(deserializedValuesFile,1e-9)); + +% % FAIL: unregistered class - derived class not registered or exported +% serialized_graph = serializeGraph(graph); % returns a string +% deserializedGraph = deserializeGraph(serialized_graph); % returns a new graph +% CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9)); +% +% CHECK('serializeGraphToFile(graph, graph.dat)', serializeGraphToFile(graph, 'graph.dat')); +% deserializedGraphFile = deserializeGraphFromFile('graph.dat'); % returns a new graph +% CHECK('graph.equals(deserializedGraphFile)',graph.equals(deserializedGraphFile,1e-9)); \ No newline at end of file From fd42854222323a4f291f7652e5a529f5669f6544 Mon Sep 17 00:00:00 2001 From: Vadim Indelman Date: Thu, 13 Jun 2013 21:17:21 +0000 Subject: [PATCH 070/256] Enabled R matrix in noise model. --- gtsam.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam.h b/gtsam.h index 36a2a9304..45c701ee1 100644 --- a/gtsam.h +++ b/gtsam.h @@ -985,7 +985,7 @@ virtual class Base { virtual class Gaussian : gtsam::noiseModel::Base { static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R); static gtsam::noiseModel::Gaussian* Covariance(Matrix R); - //Matrix R() const; // FIXME: cannot parse!!! + Matrix R() const; bool equals(gtsam::noiseModel::Base& expected, double tol); void print(string s) const; }; @@ -994,7 +994,7 @@ virtual class Diagonal : gtsam::noiseModel::Gaussian { static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas); static gtsam::noiseModel::Diagonal* Variances(Vector variances); static gtsam::noiseModel::Diagonal* Precisions(Vector precisions); -// Matrix R() const; // FIXME: cannot parse!!! + Matrix R() const; void print(string s) const; }; From d85c773f7cbc1eddd6c2640a8791a77387276726 Mon Sep 17 00:00:00 2001 From: Kyel Ok Date: Fri, 14 Jun 2013 21:18:22 +0000 Subject: [PATCH 071/256] Changes in AHRS - flat trim initialization added, some comments by Frank, aidingAvailablitiy function --- gtsam_unstable/slam/AHRS.cpp | 23 +++++++++++++-- gtsam_unstable/slam/AHRS.h | 5 +++- gtsam_unstable/slam/Mechanization_bRn2.cpp | 34 +++++++++++++--------- gtsam_unstable/slam/Mechanization_bRn2.h | 7 +++-- 4 files changed, 50 insertions(+), 19 deletions(-) diff --git a/gtsam_unstable/slam/AHRS.cpp b/gtsam_unstable/slam/AHRS.cpp index cbd1096a9..002c9e3e6 100644 --- a/gtsam_unstable/slam/AHRS.cpp +++ b/gtsam_unstable/slam/AHRS.cpp @@ -24,11 +24,12 @@ Matrix I3 = eye(3); Matrix Z3 = zeros(3, 3); /* ************************************************************************* */ -AHRS::AHRS(const Matrix& stationaryU, const Matrix& stationaryF, double g_e) : +AHRS::AHRS(const Matrix& stationaryU, const Matrix& stationaryF, double g_e, + bool flat) : KF_(9) { // Initial state - mech0_ = Mechanization_bRn2::initialize(stationaryU, stationaryF, g_e); + mech0_ = Mechanization_bRn2::initialize(stationaryU, stationaryF, g_e, flat); size_t T = stationaryU.cols(); @@ -145,6 +146,18 @@ std::pair AHRS::integrate( return make_pair(newMech, newState); } +/* ************************************************************************* */ +bool AHRS::isAidingAvailable(const Mechanization_bRn2& mech, + const gtsam::Vector& f, const gtsam::Vector& u, double ge) { + + // Subtract the biases + Vector f_ = f - mech.x_a(); + Vector u_ = u - mech.x_g(); + + double mu_f = f_.norm() - ge; + double mu_u = u_.norm(); + return (fabs(mu_f)<0.5 && mu_u < 5.0 / 180.0 * 3.1415926); +} /* ************************************************************************* */ std::pair AHRS::aid( @@ -169,10 +182,14 @@ std::pair AHRS::aid( // F(:,k) = mech.x_a + dx_a - bRn*n_g; // F(:,k) = mech.x_a + dx_a - bRn*(I+P)*n_g; // F(:,k) = mech.x_a + dx_a - b_g - bRn*(rho x n_g); // P = [rho]_x - // b_g - (mech.x_a - F(:,k)) = dx_a + bRn*(n_g x rho); + // Hence, the measurement z = b_g - (mech.x_a - F(:,k)) is predicted + // from the filter state (dx_a, rho) as dx_a + bRn*(n_g x rho) + // z = b_g - (mech.x_a - F(:,k)) = dx_a + bRn*(n_g x rho) z = bRn * n_g_ - measured_b_g; + // Now the Jacobian H Matrix b_g = bRn * n_g_cross_; H = collect(3, &b_g, &Z3, &I3); + // And the measurement noise, TODO: should be created once where sigmas_v_a is given R = diag(emul(sigmas_v_a_, sigmas_v_a_)); } diff --git a/gtsam_unstable/slam/AHRS.h b/gtsam_unstable/slam/AHRS.h index 01c61704b..1d7eb85f5 100644 --- a/gtsam_unstable/slam/AHRS.h +++ b/gtsam_unstable/slam/AHRS.h @@ -43,7 +43,7 @@ public: * @param stationaryF initial interval of accelerator measurements, 3xn matrix * @param g_e if given, initializes gravity with correct value g_e */ - AHRS(const Matrix& stationaryU, const Matrix& stationaryF, double g_e); + AHRS(const Matrix& stationaryU, const Matrix& stationaryF, double g_e, bool flat=false); std::pair initialize(double g_e); @@ -51,6 +51,9 @@ public: const Mechanization_bRn2& mech, KalmanFilter::State state, const Vector& u, double dt); + bool isAidingAvailable(const Mechanization_bRn2& mech, + const Vector& f, const Vector& u, double ge); + std::pair aid( const Mechanization_bRn2& mech, KalmanFilter::State state, const Vector& f, bool Farrell=0); diff --git a/gtsam_unstable/slam/Mechanization_bRn2.cpp b/gtsam_unstable/slam/Mechanization_bRn2.cpp index ca95843af..312814d15 100644 --- a/gtsam_unstable/slam/Mechanization_bRn2.cpp +++ b/gtsam_unstable/slam/Mechanization_bRn2.cpp @@ -12,35 +12,43 @@ namespace gtsam { /* ************************************************************************* */ Mechanization_bRn2 Mechanization_bRn2::initializeVector(const std::list& U, - const std::list& F, const double g_e) { + const std::list& F, const double g_e, bool flat) { Matrix Umat = Matrix_(3,U.size(), concatVectors(U)); Matrix Fmat = Matrix_(3,F.size(), concatVectors(F)); - return initialize(Umat, Fmat, g_e); + return initialize(Umat, Fmat, g_e, flat); } /* ************************************************************************* */ Mechanization_bRn2 Mechanization_bRn2::initialize(const Matrix& U, - const Matrix& F, const double g_e) { + const Matrix& F, const double g_e, bool flat) { // estimate gyro bias by averaging gyroscope readings (10.62) Vector x_g = U.rowwise().mean(); - Vector meanF = -F.rowwise().mean(); + Vector meanF = F.rowwise().mean(); - Vector b_g, x_a; + // estimate gravity + Vector b_g; if(g_e == 0) { - // estimate gravity in body frame from accelerometer (10.13) - b_g = meanF; - // estimate accelerometer bias as zero (10.65) - x_a = zero(3); - + if (flat) + // acceleration measured is along the z-axis. + b_g = Vector_(3, 0.0, 0.0, norm_2(meanF)); + else + // acceleration measured is the opposite of gravity (10.13) + b_g = -meanF; } else { - // normalize b_g and attribute remainder to biases - b_g = g_e * meanF/meanF.norm(); - x_a = -(meanF - b_g); + if (flat) + // gravity is downward along the z-axis since we are flat on the ground + b_g = Vector_(3,0.0,0.0,g_e); + else + // normalize b_g and attribute remainder to biases + b_g = - g_e * meanF/meanF.norm(); } + // estimate accelerometer bias + Vector x_a = meanF + b_g; + // initialize roll, pitch (eqns. 10.14, 10.15) double g1=b_g(0); double g2=b_g(1); diff --git a/gtsam_unstable/slam/Mechanization_bRn2.h b/gtsam_unstable/slam/Mechanization_bRn2.h index b81e685d4..711a44bf9 100644 --- a/gtsam_unstable/slam/Mechanization_bRn2.h +++ b/gtsam_unstable/slam/Mechanization_bRn2.h @@ -47,12 +47,15 @@ public: * Initialize the first Mechanization state * @param U a list of gyro measurement vectors * @param F a list of accelerometer measurement vectors + * @param g_e gravity magnitude + * @param flat flag saying whether this is a flat trim init */ static Mechanization_bRn2 initializeVector(const std::list& U, - const std::list& F, const double g_e = 0); + const std::list& F, const double g_e = 0, bool flat=false); + /// Matrix version of initialize static Mechanization_bRn2 initialize(const Matrix& U, - const Matrix& F, const double g_e = 0); + const Matrix& F, const double g_e = 0, bool flat=false); /** * Correct AHRS full state given error state dx From cf5a43a6c6cea7cabdfe120cdb725924d8bb7bc1 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 18 Jun 2013 04:37:46 +0000 Subject: [PATCH 072/256] WhiteNoiseFactor was defunct but now compiles and has at least one (simple) test. Shame on whomever moved this to GTSAM for not adding a test. --- .cproject | 362 +++++++++--------- gtsam/nonlinear/WhiteNoiseFactor.h | 43 ++- .../nonlinear/tests/testWhiteNoiseFactor.cpp | 38 ++ 3 files changed, 241 insertions(+), 202 deletions(-) create mode 100644 gtsam/nonlinear/tests/testWhiteNoiseFactor.cpp diff --git a/.cproject b/.cproject index 46f9a60fb..56b3a0cae 100644 --- a/.cproject +++ b/.cproject @@ -1,5 +1,7 @@ - + + + @@ -307,6 +309,14 @@ true true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j2 @@ -333,7 +343,6 @@ make - tests/testBayesTree.run true false @@ -341,7 +350,6 @@ make - testBinaryBayesNet.run true false @@ -389,7 +397,6 @@ make - testSymbolicBayesNet.run true false @@ -397,7 +404,6 @@ make - tests/testSymbolicFactor.run true false @@ -405,7 +411,6 @@ make - testSymbolicFactorGraph.run true false @@ -421,20 +426,11 @@ make - tests/testBayesTree true false true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j5 @@ -531,22 +527,6 @@ false true - - make - -j2 - tests/testPose2.run - true - true - true - - - make - -j2 - tests/testPose3.run - true - true - true - make -j2 @@ -563,6 +543,22 @@ true true + + make + -j2 + tests/testPose2.run + true + true + true + + + make + -j2 + tests/testPose3.run + true + true + true + make -j2 @@ -587,26 +583,42 @@ true true - + make - -j2 - all + -j5 + testValues.run true true true - + make - -j2 - check + -j5 + testOrdering.run true true true - + make - -j2 - clean + -j5 + testKey.run + true + true + true + + + make + -j5 + testLinearContainerFactor.run + true + true + true + + + make + -j5 + testWhiteNoiseFactor.run true true true @@ -643,34 +655,26 @@ true true - + make - -j5 - testValues.run + -j2 + all true true true - + make - -j5 - testOrdering.run + -j2 + check true true true - + make - -j5 - testKey.run - true - true - true - - - make - -j5 - testLinearContainerFactor.run + -j2 + clean true true true @@ -1037,7 +1041,6 @@ make - testGraph.run true false @@ -1045,7 +1048,6 @@ make - testJunctionTree.run true false @@ -1053,7 +1055,6 @@ make - testSymbolicBayesNetB.run true false @@ -1229,7 +1230,6 @@ make - testErrors.run true false @@ -1275,6 +1275,14 @@ true true + + make + -j2 + testGaussianFactor.run + true + true + true + make -j2 @@ -1355,14 +1363,6 @@ true true - - make - -j2 - testGaussianFactor.run - true - true - true - make -j2 @@ -1677,6 +1677,7 @@ make + testSimulated2DOriented.run true false @@ -1716,6 +1717,7 @@ make + testSimulated2D.run true false @@ -1723,6 +1725,7 @@ make + testSimulated3D.run true false @@ -1922,6 +1925,7 @@ make + tests/testGaussianISAM2 true false @@ -1943,6 +1947,102 @@ true true + + make + -j2 + testRot3.run + true + true + true + + + make + -j2 + testRot2.run + true + true + true + + + make + -j2 + testPose3.run + true + true + true + + + make + -j2 + timeRot3.run + true + true + true + + + make + -j2 + testPose2.run + true + true + true + + + make + -j2 + testCal3_S2.run + true + true + true + + + make + -j2 + testSimpleCamera.run + true + true + true + + + make + -j2 + testHomography2.run + true + true + true + + + make + -j2 + testCalibratedCamera.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPoint2.run + true + true + true + make -j3 @@ -2144,7 +2244,6 @@ cpack - -G DEB true false @@ -2152,7 +2251,6 @@ cpack - -G RPM true false @@ -2160,7 +2258,6 @@ cpack - -G TGZ true false @@ -2168,7 +2265,6 @@ cpack - --config CPackSourceConfig.cmake true false @@ -2310,98 +2406,34 @@ true true - + make - -j2 - testRot3.run + -j5 + testSpirit.run true true true - + make - -j2 - testRot2.run + -j5 + testWrap.run true true true - + make - -j2 - testPose3.run + -j5 + check.wrap true true true - + make - -j2 - timeRot3.run - true - true - true - - - make - -j2 - testPose2.run - true - true - true - - - make - -j2 - testCal3_S2.run - true - true - true - - - make - -j2 - testSimpleCamera.run - true - true - true - - - make - -j2 - testHomography2.run - true - true - true - - - make - -j2 - testCalibratedCamera.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testPoint2.run + -j5 + wrap true true true @@ -2445,38 +2477,6 @@ false true - - make - -j5 - testSpirit.run - true - true - true - - - make - -j5 - testWrap.run - true - true - true - - - make - -j5 - check.wrap - true - true - true - - - make - -j5 - wrap - true - true - true - diff --git a/gtsam/nonlinear/WhiteNoiseFactor.h b/gtsam/nonlinear/WhiteNoiseFactor.h index abe0598df..26e20ac08 100644 --- a/gtsam/nonlinear/WhiteNoiseFactor.h +++ b/gtsam/nonlinear/WhiteNoiseFactor.h @@ -32,22 +32,21 @@ namespace gtsam { * This factor uses the mean-precision parameterization. * * Takes three template arguments: - * MKEY: key type to use for mean - * PKEY: key type to use for precision - * VALUES: Values type for optimization + * Key: key type to use for mean + * Key: key type to use for precision + * Values: Values type for optimization * \nosubgrouping */ - template - class WhiteNoiseFactor: public NonlinearFactor { + class WhiteNoiseFactor: public NonlinearFactor { private: double z_; ///< Measurement - MKEY meanKey_; ///< key by which to access mean variable - PKEY precisionKey_; ///< key by which to access precision variable + Key meanKey_; ///< key by which to access mean variable + Key precisionKey_; ///< key by which to access precision variable - typedef NonlinearFactor Base; + typedef NonlinearFactor Base; public: @@ -93,7 +92,7 @@ namespace gtsam { * @param meanKey Key for mean variable * @param precisionKey Key for precision variable */ - WhiteNoiseFactor(double z, const MKEY& meanKey, const PKEY& precisionKey) : + WhiteNoiseFactor(double z, Key meanKey, Key precisionKey) : Base(), z_(z), meanKey_(meanKey), precisionKey_(precisionKey) { } @@ -110,8 +109,9 @@ namespace gtsam { /// @{ /// Print - void print(const std::string& p = "WhiteNoiseFactor") const { - Base::print(p); + void print(const std::string& p = "WhiteNoiseFactor", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + Base::print(p, keyFormatter); std::cout << p + ".z: " << z_ << std::endl; } @@ -125,8 +125,8 @@ namespace gtsam { } /// Calculate the error of the factor, typically equal to log-likelihood - inline double error(const VALUES& x) const { - return f(z_, x[meanKey_].value(), x[precisionKey_].value()); + inline double error(const Values& x) const { + return f(z_, x.at(meanKey_), x.at(precisionKey_)); } /** @@ -136,7 +136,7 @@ namespace gtsam { * Here we shoehorn sqrt(2*error(p)) * TODO: Where is this used? should disappear. */ - virtual Vector unwhitenedError(const VALUES& x) const { + virtual Vector unwhitenedError(const Values& x) const { return Vector_(1, sqrt(2 * error(x))); } @@ -154,19 +154,20 @@ namespace gtsam { /// @{ /// linearize returns a Hessianfactor that is an approximation of error(p) - virtual boost::shared_ptr linearize(const VALUES& x, + virtual boost::shared_ptr linearize(const Values& x, const Ordering& ordering) const { - double u = x[meanKey_].value(); - double p = x[precisionKey_].value(); + double u = x.at(meanKey_); + double p = x.at(precisionKey_); Index j1 = ordering[meanKey_]; Index j2 = ordering[precisionKey_]; return linearize(z_, u, p, j1, j2); } - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + // TODO: Frank commented this out for now, can it go? + // /// @return a deep copy of this factor + // virtual gtsam::NonlinearFactor::shared_ptr clone() const { + // return boost::static_pointer_cast( + // gtsam::NonlinearFactor::shared_ptr(new This(*this))); } /// @} diff --git a/gtsam/nonlinear/tests/testWhiteNoiseFactor.cpp b/gtsam/nonlinear/tests/testWhiteNoiseFactor.cpp new file mode 100644 index 000000000..a141641e3 --- /dev/null +++ b/gtsam/nonlinear/tests/testWhiteNoiseFactor.cpp @@ -0,0 +1,38 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testWhiteNoiseFactor.cpp + * @author Frank Dellaert + */ + +#include +#include + +#include +#include // for operator += +using namespace boost::assign; + +using namespace gtsam; +using namespace std; + +/* ************************************************************************* */ +TEST( WhiteNoiseFactor, constructor ) +{ + double z = 0.1; + Key meanKey=1, precisionKey=2; + WhiteNoiseFactor factor(z,meanKey, precisionKey); + LONGS_EQUAL(2,factor.dim()); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ From 5a7ee5f146e1fa439a24c1c615e360049056fd69 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Tue, 18 Jun 2013 20:04:00 +0000 Subject: [PATCH 073/256] Disabled serialization syntactic sugar functions --- gtsam.h | 82 +++++++++++++++++++-------------------- gtsam/CMakeLists.txt | 10 ++++- gtsam/slam/CMakeLists.txt | 9 ++++- 3 files changed, 57 insertions(+), 44 deletions(-) diff --git a/gtsam.h b/gtsam.h index 45c701ee1..cc78038b6 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2110,47 +2110,47 @@ pair load2D_robust(string filename //************************************************************************* // Serialization //************************************************************************* -#include - -// Serialize/Deserialize a NonlinearFactorGraph -string serializeGraph(const gtsam::NonlinearFactorGraph& graph); - -gtsam::NonlinearFactorGraph* deserializeGraph(string serialized_graph); - -string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph); -string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph, string name); - -gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph); -gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph, string name); - -// Serialize/Deserialize a Values -string serializeValues(const gtsam::Values& values); - -gtsam::Values* deserializeValues(string serialized_values); - -string serializeValuesXML(const gtsam::Values& values); -string serializeValuesXML(const gtsam::Values& values, string name); - -gtsam::Values* deserializeValuesXML(string serialized_values); -gtsam::Values* deserializeValuesXML(string serialized_values, string name); - -// Serialize -bool serializeGraphToFile(const gtsam::NonlinearFactorGraph& graph, string fname); -bool serializeGraphToXMLFile(const gtsam::NonlinearFactorGraph& graph, string fname); -bool serializeGraphToXMLFile(const gtsam::NonlinearFactorGraph& graph, string fname, string name); - -bool serializeValuesToFile(const gtsam::Values& values, string fname); -bool serializeValuesToXMLFile(const gtsam::Values& values, string fname); -bool serializeValuesToXMLFile(const gtsam::Values& values, string fname, string name); - -// Deserialize -gtsam::NonlinearFactorGraph* deserializeGraphFromFile(string fname); -gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname); -gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname, string name); - -gtsam::Values* deserializeValuesFromFile(string fname); -gtsam::Values* deserializeValuesFromXMLFile(string fname); -gtsam::Values* deserializeValuesFromXMLFile(string fname, string name); +//#include +// +//// Serialize/Deserialize a NonlinearFactorGraph +//string serializeGraph(const gtsam::NonlinearFactorGraph& graph); +// +//gtsam::NonlinearFactorGraph* deserializeGraph(string serialized_graph); +// +//string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph); +//string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph, string name); +// +//gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph); +//gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph, string name); +// +//// Serialize/Deserialize a Values +//string serializeValues(const gtsam::Values& values); +// +//gtsam::Values* deserializeValues(string serialized_values); +// +//string serializeValuesXML(const gtsam::Values& values); +//string serializeValuesXML(const gtsam::Values& values, string name); +// +//gtsam::Values* deserializeValuesXML(string serialized_values); +//gtsam::Values* deserializeValuesXML(string serialized_values, string name); +// +//// Serialize +//bool serializeGraphToFile(const gtsam::NonlinearFactorGraph& graph, string fname); +//bool serializeGraphToXMLFile(const gtsam::NonlinearFactorGraph& graph, string fname); +//bool serializeGraphToXMLFile(const gtsam::NonlinearFactorGraph& graph, string fname, string name); +// +//bool serializeValuesToFile(const gtsam::Values& values, string fname); +//bool serializeValuesToXMLFile(const gtsam::Values& values, string fname); +//bool serializeValuesToXMLFile(const gtsam::Values& values, string fname, string name); +// +//// Deserialize +//gtsam::NonlinearFactorGraph* deserializeGraphFromFile(string fname); +//gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname); +//gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname, string name); +// +//gtsam::Values* deserializeValuesFromFile(string fname); +//gtsam::Values* deserializeValuesFromXMLFile(string fname); +//gtsam::Values* deserializeValuesFromXMLFile(string fname, string name); //************************************************************************* // Utilities diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index d5a2fee90..45acd92e3 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -32,11 +32,18 @@ endif() # To exclude a source from the library build (in any subfolder) # Add the full name to this list, as in the following example # Sources to remove from builds -set (excluded_sources "") +set (excluded_sources #"") + "${CMAKE_CURRENT_SOURCE_DIR}/slam/serialization.cpp" # "${CMAKE_CURRENT_SOURCE_DIR}/discrete/TypedDiscreteFactor.cpp" # "${CMAKE_CURRENT_SOURCE_DIR}/discrete/TypedDiscreteFactorGraph.cpp" # "${CMAKE_CURRENT_SOURCE_DIR}/discrete/parseUAI.cpp" # "${CMAKE_CURRENT_SOURCE_DIR}/discrete/PotentialTable.cpp") +) + +set (excluded_headers #"") + "${CMAKE_CURRENT_SOURCE_DIR}/slam/serialization.h" +# "${CMAKE_CURRENT_SOURCE_DIR}/discrete/TypedDiscreteFactor.h +) if(GTSAM_USE_QUATERNIONS) set(excluded_sources ${excluded_sources} "${CMAKE_CURRENT_SOURCE_DIR}/geometry/Rot3M.cpp") @@ -56,6 +63,7 @@ foreach(subdir ${gtsam_subdirs}) set(subdir_srcs ${subdir_cpp_srcs} ${subdir_headers}) # Include header files so they show up in Visual Studio gtsam_assign_source_folders("${subdir_srcs}") # Create MSVC structure list(REMOVE_ITEM subdir_srcs ${excluded_sources}) + list(REMOVE_ITEM subdir_srcs ${excluded_headers}) set(${subdir}_srcs ${subdir_srcs}) if (GTSAM_BUILD_CONVENIENCE_LIBRARIES AND (subdir_cpp_srcs)) # Only build convenience library if sources exist message(STATUS "Building Convenience Library: ${subdir}") diff --git a/gtsam/slam/CMakeLists.txt b/gtsam/slam/CMakeLists.txt index ba5ad5d24..c9497f167 100644 --- a/gtsam/slam/CMakeLists.txt +++ b/gtsam/slam/CMakeLists.txt @@ -1,5 +1,10 @@ # Install headers +set (slam_excluded_headers #"") + "${CMAKE_CURRENT_SOURCE_DIR}/serialization.h" +) + file(GLOB slam_headers "*.h") +list(REMOVE_ITEM slam_headers ${slam_excluded_headers}) install(FILES ${slam_headers} DESTINATION include/gtsam/slam) # Components to link tests in this subfolder against @@ -15,8 +20,8 @@ set(slam_local_libs # Files to exclude from compilation of tests and timing scripts set(slam_excluded_files -# "${CMAKE_CURRENT_SOURCE_DIR}/tests/testTypedDiscreteFactor.cpp" # Example of excluding a test - "" # Add to this list, with full path, to exclude + "${CMAKE_CURRENT_SOURCE_DIR}/tests/testSerialization.cpp" +# "" # Add to this list, with full path, to exclude ) # Build tests From c7576deb1557b2050998f5f881224984b1f5e20b Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:49:55 +0000 Subject: [PATCH 074/256] Added flag for serializable to parser, no codegen yet --- wrap/Class.h | 3 ++- wrap/Module.cpp | 12 ++++++++++-- wrap/tests/geometry.h | 3 +++ wrap/tests/testWrap.cpp | 3 +++ 4 files changed, 18 insertions(+), 3 deletions(-) diff --git a/wrap/Class.h b/wrap/Class.h index 54db8970b..5c04bd609 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -37,13 +37,14 @@ struct Class { typedef std::map StaticMethods; /// Constructor creates an empty class - Class(bool verbose=true) : isVirtual(false), verbose_(verbose) {} + Class(bool verbose=true) : isVirtual(false), isSerializable(false), verbose_(verbose) {} // Then the instance variables are set directly by the Module constructor std::string name; ///< Class name std::vector templateArgs; ///< Template arguments std::string typedefName; ///< The name to typedef *from*, if this class is actually a typedef, i.e. typedef [typedefName] [name] bool isVirtual; ///< Whether the class is part of a virtual inheritance chain + bool isSerializable; ///< Whether we can use boost.serialization to serialize the class std::vector qualifiedParent; ///< The *single* parent - the last string is the parent class name, preceededing elements are a namespace stack Methods methods; ///< Class methods StaticMethods static_methods; ///< Static methods diff --git a/wrap/Module.cpp b/wrap/Module.cpp index d5bbd881e..02c1787b7 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -378,13 +378,21 @@ void Module::parseMarkup(const std::string& data) { throw ParseFailed((int)info.length); } - //Explicitly add methods to the classes from parents so it shows in documentation + // Post-process classes for serialization markers + BOOST_FOREACH(Class& cls, classes) { + Class::Methods::iterator serialize_it = cls.methods.find("serialize"); + if (serialize_it != cls.methods.end()) { + cls.isSerializable = true; + cls.methods.erase(serialize_it); + } + } + + // Explicitly add methods to the classes from parents so it shows in documentation BOOST_FOREACH(Class& cls, classes) { map inhereted = appendInheretedMethods(cls, classes); cls.methods.insert(inhereted.begin(), inhereted.end()); } - } /* ************************************************************************* */ diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index 13553e986..6c6ed28ad 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -22,6 +22,9 @@ class Point3 { // static functions - use static keyword and uppercase static double staticFunction(); static Point3 StaticFunctionRet(double z); + + // enabling serialization functionality + void serialize() const; // Just triggers a flag internally and removes actual function }; // another comment diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index 648058c6d..f993867e5 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -251,6 +251,9 @@ TEST( wrap, parse_geometry ) { LONGS_EQUAL(1, m1.argLists.size()); EXPECT_LONGS_EQUAL(0, m1.argLists.front().size()); EXPECT(m1.is_const_); + + // check serialization flag + EXPECT(cls.isSerializable); } // Test class is the third one From 8e736199895fa1165a94cf120447db657a015caf Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:49:57 +0000 Subject: [PATCH 075/256] Adding codegen components for serialization - in progress --- gtsam.h | 3 ++ wrap/Class.cpp | 37 ++++++++++++++++++++++++ wrap/Class.h | 3 ++ wrap/Module.cpp | 28 +++++++++++------- wrap/tests/expected/Point3.m | 24 ++++++++++++++- wrap/tests/expected/geometry_wrapper.cpp | 26 +++++++++++++++++ 6 files changed, 109 insertions(+), 12 deletions(-) diff --git a/gtsam.h b/gtsam.h index cc78038b6..35def3b76 100644 --- a/gtsam.h +++ b/gtsam.h @@ -470,6 +470,9 @@ virtual class Pose2 : gtsam::Value { gtsam::Point2 translation() const; gtsam::Rot2 rotation() const; Matrix matrix() const; + + // enabling serialization functionality + void serialize() const; }; virtual class Pose3 : gtsam::Value { diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 6586fb061..bed5de9bb 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -124,6 +124,10 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, wrapperFile.oss << "\n"; } + // Add serialization if necessary + if (isSerializable) + serialization_fragments(proxyFile, wrapperFile, functionNames); + proxyFile.oss << " end\n"; proxyFile.oss << "end\n"; @@ -278,6 +282,7 @@ Class expandClassTemplate(const Class& cls, const string& templateArg, const vec inst.templateArgs = cls.templateArgs; inst.typedefName = cls.typedefName; inst.isVirtual = cls.isVirtual; + inst.isSerializable = cls.isSerializable; inst.qualifiedParent = cls.qualifiedParent; inst.methods = expandMethodTemplate(cls.methods, templateArg, instName, expandedClassNamespace, expandedClassName); inst.static_methods = expandMethodTemplate(cls.static_methods, templateArg, instName, expandedClassNamespace, expandedClassName); @@ -388,6 +393,38 @@ void Class::comment_fragment(FileWriter& proxyFile) const { } } + if (isSerializable) { + proxyFile.oss << "%\n%-------Serialization Interface-------\n"; + proxyFile.oss << "%string_serialize() : returns string\n"; + proxyFile.oss << "%string_deserialize(string serialized) : returns " << this->name << "\n"; + } + proxyFile.oss << "%\n"; } /* ************************************************************************* */ + +void Class::serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, std::vector& functionNames) const { +//void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +//{ +// typedef boost::shared_ptr Shared; +// checkArguments("string_serialize",nargout,nargin-1,0); +// Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); +// std::ostringstream out_archive_stream; +// boost::archive::text_oarchive out_archive(out_archive_stream); +// out_archive << *obj; +// out[0] = wrap< string >(out_archive_stream.str()); +//} +// +//void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +//{ +// typedef boost::shared_ptr Shared; +// checkArguments("Point3.string_deserialize",nargout,nargin,1); +// string serialized = unwrap< string >(in[0]); +// std::istringstream in_archive_stream(serialized); +// boost::archive::text_iarchive in_archive(in_archive_stream); +// Shared output(new Point3()); +// in_archive >> output; +// out[0] = wrap_shared_ptr(output,"Point3", false); +//} + +} diff --git a/wrap/Class.h b/wrap/Class.h index 5c04bd609..d66d805b9 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -56,14 +56,17 @@ struct Class { // And finally MATLAB code is emitted, methods below called by Module::matlab_code void matlab_proxy(const std::string& toolboxPath, const std::string& wrapperName, const TypeAttributesTable& typeAttributes, FileWriter& wrapperFile, std::vector& functionNames) const; ///< emit proxy class + std::string qualifiedName(const std::string& delim = "") const; ///< creates a namespace-qualified name, optional delimiter std::vector expandTemplate(const std::string& templateArg, const std::vector >& instantiations) const; + Class expandTemplate(const std::string& templateArg, const std::vector& instantiation, const std::vector& expandedClassNamespace, const std::string& expandedClassName) const; // The typedef line for this class, if this class is a typedef, otherwise returns an empty string. std::string getTypedef() const; + void serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, std::vector& functionNames) const; private: void pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& wrapperName, std::vector& functionNames) const; diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 02c1787b7..ec346a7a0 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -448,16 +448,6 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co fs::create_directories(toolboxPath); - // create the unified .cpp switch file - const string wrapperName = name + "_wrapper"; - string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp"; - FileWriter wrapperFile(wrapperFileName, verbose, "//"); - vector functionNames; // Function names stored by index for switch - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "#include \n"; - wrapperFile.oss << "\n"; - // Expand templates - This is done first so that template instantiations are // counted in the list of valid types, have their attributes and dependencies // checked, etc. @@ -470,7 +460,9 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co verifyArguments(validTypes, global_functions); verifyReturnTypes(validTypes, global_functions); + bool hasSerialiable = false; BOOST_FOREACH(const Class& cls, expandedClasses) { + hasSerialiable |= cls.isSerializable; // verify all of the function arguments //TODO:verifyArguments(validTypes, cls.constructor.args_list); verifyArguments(validTypes, cls.static_methods); @@ -483,7 +475,6 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co // verify parents if(!cls.qualifiedParent.empty() && std::find(validTypes.begin(), validTypes.end(), wrap::qualifiedName("::", cls.qualifiedParent)) == validTypes.end()) throw DependencyMissing(wrap::qualifiedName("::", cls.qualifiedParent), cls.qualifiedName("::")); - } // Create type attributes table and check validity @@ -492,7 +483,20 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co typeAttributes.addForwardDeclarations(forward_declarations); typeAttributes.checkValidity(expandedClasses); + // create the unified .cpp switch file + const string wrapperName = name + "_wrapper"; + string wrapperFileName = toolboxPath + "/" + wrapperName + ".cpp"; + FileWriter wrapperFile(wrapperFileName, verbose, "//"); + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "\n"; + // Generate includes while avoiding redundant includes + if (hasSerialiable) { + wrapperFile.oss << "#include \n"; + wrapperFile.oss << "#include \n\n"; + } generateIncludes(wrapperFile); // create typedef classes - we put this at the top of the wrap file so that collectors and method arguments can use these typedefs @@ -508,6 +512,8 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co // generate RTTI registry (for returning derived-most types) WriteRTTIRegistry(wrapperFile, name, expandedClasses); + vector functionNames; // Function names stored by index for switch + // create proxy class and wrapper code BOOST_FOREACH(const Class& cls, expandedClasses) { cls.matlab_proxy(toolboxPath, wrapperName, typeAttributes, wrapperFile, functionNames); diff --git a/wrap/tests/expected/Point3.m b/wrap/tests/expected/Point3.m index 3a90f1982..836482a7d 100644 --- a/wrap/tests/expected/Point3.m +++ b/wrap/tests/expected/Point3.m @@ -11,6 +11,9 @@ %StaticFunctionRet(double z) : returns Point3 %staticFunction() : returns double % +%-------Serialization Interface------- +%string_serialize() : returns string +%string_deserialize(string serialized) : returns Point3 classdef Point3 < handle properties ptr_Point3 = 0 @@ -48,7 +51,16 @@ classdef Point3 < handle error('Arguments do not match any overload of function Point3.norm'); end end - + + function varargout string_serialize(this, varargin) + % string_serialize usage: string_serialize() : returns string + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 0 + varargout{1} = geometry_wrapper(14, this, varargin{:}); + else + error('Arguments do not match any overload of function Point3.string_serialize'); + end + end end methods(Static = true) @@ -77,6 +89,16 @@ classdef Point3 < handle error('Arguments do not match any overload of function Point3.StaticFunction'); end end + + function varargout = string_deserialize(varargin) + % STATICFUNCTION usage: string_deserialize() : returns Point3 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + if length(varargin) == 0 + varargout{1} = geometry_wrapper(16, varargin{:}); + else + error('Arguments do not match any overload of function Point3.StaticFunction'); + end + end end end diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index ad1df801c..c18c2224b 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -2,6 +2,9 @@ #include #include +#include +#include + #include @@ -236,6 +239,29 @@ void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxA out[0] = wrap< double >(Point3::staticFunction()); } +void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("string_serialize",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); + std::ostringstream out_archive_stream; + boost::archive::text_oarchive out_archive(out_archive_stream); + out_archive << *obj; + out[0] = wrap< string >(out_archive_stream.str()); +} + +void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("Point3.string_deserialize",nargout,nargin,1); + string serialized = unwrap< string >(in[0]); + std::istringstream in_archive_stream(serialized); + boost::archive::text_iarchive in_archive(in_archive_stream); + Shared output(new Point3()); + in_archive >> output; + out[0] = wrap_shared_ptr(output,"Point3", false); +} + void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); From 5789c7de8316be64b978405d3af0323bee812f3f Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:49:58 +0000 Subject: [PATCH 076/256] Added codegen for cpp wrapper --- wrap/Class.cpp | 57 ++++++++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 55 insertions(+), 2 deletions(-) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index bed5de9bb..a817fcf82 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -403,7 +403,9 @@ void Class::comment_fragment(FileWriter& proxyFile) const { } /* ************************************************************************* */ -void Class::serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, std::vector& functionNames) const { +void Class::serialization_fragments(FileWriter& proxyFile, + FileWriter& file, std::vector& functionNames) const { + //void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) //{ // typedef boost::shared_ptr Shared; @@ -414,7 +416,39 @@ void Class::serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFi // out_archive << *obj; // out[0] = wrap< string >(out_archive_stream.str()); //} -// + + int serialize_id = functionNames.size(); + const string matlabQualName = + qualifiedName("."), + matlabUniqueName = qualifiedName(), + cppClassName = qualifiedName("::"); + const string wrapFunctionNameSerialize = matlabUniqueName + "_string_serialize_" + boost::lexical_cast(serialize_id); + functionNames.push_back(wrapFunctionNameSerialize); + + // call + //void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) + file.oss << "void " << wrapFunctionNameSerialize << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + file.oss << "{\n"; + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; + + // check arguments - for serialize, no arguments + // example: checkArguments("string_serialize",nargout,nargin-1,0); + file.oss << " checkArguments(\"string_serialize\",nargout,nargin-1,0);\n"; + + // get class pointer + // example: Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); + file.oss << " Shared obj = unwrap_shared_ptr<" << cppClassName << ">(in[0], \"ptr_" << matlabUniqueName << "\");" << endl; + + // Serialization boilerplate + file.oss << " std::ostringstream out_archive_stream;\n"; + file.oss << " boost::archive::text_oarchive out_archive(out_archive_stream);\n"; + file.oss << " out_archive << *obj;\n"; + file.oss << " out[0] = wrap< string >(out_archive_stream.str());\n"; + + // finish + file.oss << "}\n"; + + //void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) //{ // typedef boost::shared_ptr Shared; @@ -426,5 +460,24 @@ void Class::serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFi // in_archive >> output; // out[0] = wrap_shared_ptr(output,"Point3", false); //} + int deserialize_id = functionNames.size(); + const string wrapFunctionNameDeserialize = matlabUniqueName + "_string_deserialize_" + boost::lexical_cast(deserialize_id); + functionNames.push_back(wrapFunctionNameDeserialize); + // call + file.oss << "void " << wrapFunctionNameDeserialize << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + file.oss << "{\n"; + file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; + + // check arguments - for deserialize, 1 string argument + file.oss << " checkArguments(\"" << matlabUniqueName << ".string_deserialize\",nargout,nargin,1);\n"; + + // string argument with deserialization boilerplate + file.oss << " string serialized = unwrap< string >(in[0]);\n"; + file.oss << " std::istringstream in_archive_stream(serialized);\n"; + file.oss << " boost::archive::text_iarchive in_archive(in_archive_stream);\n"; + file.oss << " Shared output(new " << cppClassName << "());\n"; + file.oss << " in_archive >> output;\n"; + file.oss << " out[0] = wrap_shared_ptr(output,\"" << matlabQualName << "\", false);\n"; + file.oss << "}\n"; } From 07407ff76370024773fd4f94ebefa32938114065 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:49:59 +0000 Subject: [PATCH 077/256] Completed codegen for serialize/deserialize functions --- wrap/Class.cpp | 147 +++++++++++++++-------- wrap/Class.h | 4 + wrap/tests/expected/Point3.m | 20 +-- wrap/tests/expected/geometry_wrapper.cpp | 36 +++--- 4 files changed, 129 insertions(+), 78 deletions(-) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index a817fcf82..38aef00a1 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -107,10 +107,12 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, // Methods BOOST_FOREACH(const Methods::value_type& name_m, methods) { const Method& m = name_m.second; - m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames); + m.proxy_wrapper_fragments(proxyFile, wrapperFile, cppName, matlabQualName, matlabUniqueName, wrapperName, typeAttributes, functionNames); proxyFile.oss << "\n"; wrapperFile.oss << "\n"; } + if (isSerializable) + serialization_fragments(proxyFile, wrapperFile, functionNames); proxyFile.oss << " end\n"; proxyFile.oss << "\n"; @@ -123,10 +125,8 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, proxyFile.oss << "\n"; wrapperFile.oss << "\n"; } - - // Add serialization if necessary if (isSerializable) - serialization_fragments(proxyFile, wrapperFile, functionNames); + deserialization_fragments(proxyFile, wrapperFile, functionNames); proxyFile.oss << " end\n"; proxyFile.oss << "end\n"; @@ -404,7 +404,7 @@ void Class::comment_fragment(FileWriter& proxyFile) const { /* ************************************************************************* */ void Class::serialization_fragments(FileWriter& proxyFile, - FileWriter& file, std::vector& functionNames) const { + FileWriter& wrapperFile, std::vector& functionNames) const { //void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) //{ @@ -418,66 +418,113 @@ void Class::serialization_fragments(FileWriter& proxyFile, //} int serialize_id = functionNames.size(); - const string matlabQualName = - qualifiedName("."), - matlabUniqueName = qualifiedName(), - cppClassName = qualifiedName("::"); + const string + matlabQualName = qualifiedName("."), + matlabUniqueName = qualifiedName(), + cppClassName = qualifiedName("::"); const string wrapFunctionNameSerialize = matlabUniqueName + "_string_serialize_" + boost::lexical_cast(serialize_id); functionNames.push_back(wrapFunctionNameSerialize); // call //void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) - file.oss << "void " << wrapFunctionNameSerialize << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - file.oss << "{\n"; - file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; + wrapperFile.oss << "void " << wrapFunctionNameSerialize << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + wrapperFile.oss << "{\n"; + wrapperFile.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; // check arguments - for serialize, no arguments // example: checkArguments("string_serialize",nargout,nargin-1,0); - file.oss << " checkArguments(\"string_serialize\",nargout,nargin-1,0);\n"; + wrapperFile.oss << " checkArguments(\"string_serialize\",nargout,nargin-1,0);\n"; // get class pointer // example: Shared obj = unwrap_shared_ptr(in[0], "ptr_Point3"); - file.oss << " Shared obj = unwrap_shared_ptr<" << cppClassName << ">(in[0], \"ptr_" << matlabUniqueName << "\");" << endl; + wrapperFile.oss << " Shared obj = unwrap_shared_ptr<" << cppClassName << ">(in[0], \"ptr_" << matlabUniqueName << "\");" << endl; // Serialization boilerplate - file.oss << " std::ostringstream out_archive_stream;\n"; - file.oss << " boost::archive::text_oarchive out_archive(out_archive_stream);\n"; - file.oss << " out_archive << *obj;\n"; - file.oss << " out[0] = wrap< string >(out_archive_stream.str());\n"; + wrapperFile.oss << " std::ostringstream out_archive_stream;\n"; + wrapperFile.oss << " boost::archive::text_oarchive out_archive(out_archive_stream);\n"; + wrapperFile.oss << " out_archive << *obj;\n"; + wrapperFile.oss << " out[0] = wrap< string >(out_archive_stream.str());\n"; // finish - file.oss << "}\n"; + wrapperFile.oss << "}\n"; + // Generate code for matlab function +// function varargout string_serialize(this, varargin) +// % STRING_SERIALIZE usage: string_serialize() : returns string +// % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +// if length(varargin) == 0 +// varargout{1} = geometry_wrapper(15, this, varargin{:}); +// else +// error('Arguments do not match any overload of function Point3.string_serialize'); +// end +// end -//void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -//{ -// typedef boost::shared_ptr Shared; -// checkArguments("Point3.string_deserialize",nargout,nargin,1); -// string serialized = unwrap< string >(in[0]); -// std::istringstream in_archive_stream(serialized); -// boost::archive::text_iarchive in_archive(in_archive_stream); -// Shared output(new Point3()); -// in_archive >> output; -// out[0] = wrap_shared_ptr(output,"Point3", false); -//} - int deserialize_id = functionNames.size(); - const string wrapFunctionNameDeserialize = matlabUniqueName + "_string_deserialize_" + boost::lexical_cast(deserialize_id); - functionNames.push_back(wrapFunctionNameDeserialize); - - // call - file.oss << "void " << wrapFunctionNameDeserialize << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; - file.oss << "{\n"; - file.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; - - // check arguments - for deserialize, 1 string argument - file.oss << " checkArguments(\"" << matlabUniqueName << ".string_deserialize\",nargout,nargin,1);\n"; - - // string argument with deserialization boilerplate - file.oss << " string serialized = unwrap< string >(in[0]);\n"; - file.oss << " std::istringstream in_archive_stream(serialized);\n"; - file.oss << " boost::archive::text_iarchive in_archive(in_archive_stream);\n"; - file.oss << " Shared output(new " << cppClassName << "());\n"; - file.oss << " in_archive >> output;\n"; - file.oss << " out[0] = wrap_shared_ptr(output,\"" << matlabQualName << "\", false);\n"; - file.oss << "}\n"; + proxyFile.oss << " function varargout = string_serialize(this, varargin)\n"; + proxyFile.oss << " % STRING_SERIALIZE usage: string_serialize() : returns string\n"; + proxyFile.oss << " % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n"; + proxyFile.oss << " if length(varargin) == 0\n"; + proxyFile.oss << " varargout{1} = geometry_wrapper(" << boost::lexical_cast(serialize_id) << ", this, varargin{:});\n"; + proxyFile.oss << " else\n"; + proxyFile.oss << " error('Arguments do not match any overload of function " << matlabQualName << ".string_serialize');\n"; + proxyFile.oss << " end\n"; + proxyFile.oss << " end\n"; +} + +void Class::deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, std::vector& functionNames) const { + //void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) + //{ + // typedef boost::shared_ptr Shared; + // checkArguments("Point3.string_deserialize",nargout,nargin,1); + // string serialized = unwrap< string >(in[0]); + // std::istringstream in_archive_stream(serialized); + // boost::archive::text_iarchive in_archive(in_archive_stream); + // Shared output(new Point3()); + // in_archive >> *output; + // out[0] = wrap_shared_ptr(output,"Point3", false); + //} + int deserialize_id = functionNames.size(); + const string + matlabQualName = qualifiedName("."), + matlabUniqueName = qualifiedName(), + cppClassName = qualifiedName("::"); + const string wrapFunctionNameDeserialize = matlabUniqueName + "_string_deserialize_" + boost::lexical_cast(deserialize_id); + functionNames.push_back(wrapFunctionNameDeserialize); + + // call + wrapperFile.oss << "void " << wrapFunctionNameDeserialize << "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n"; + wrapperFile.oss << "{\n"; + wrapperFile.oss << " typedef boost::shared_ptr<" << cppClassName << "> Shared;" << endl; + + // check arguments - for deserialize, 1 string argument + wrapperFile.oss << " checkArguments(\"" << matlabUniqueName << ".string_deserialize\",nargout,nargin,1);\n"; + + // string argument with deserialization boilerplate + wrapperFile.oss << " string serialized = unwrap< string >(in[0]);\n"; + wrapperFile.oss << " std::istringstream in_archive_stream(serialized);\n"; + wrapperFile.oss << " boost::archive::text_iarchive in_archive(in_archive_stream);\n"; + wrapperFile.oss << " Shared output(new " << cppClassName << "());\n"; + wrapperFile.oss << " in_archive >> *output;\n"; + wrapperFile.oss << " out[0] = wrap_shared_ptr(output,\"" << matlabQualName << "\", false);\n"; + wrapperFile.oss << "}\n"; + + // Generate matlab function +// function varargout = string_deserialize(varargin) +// % STRING_DESERIALIZE usage: string_deserialize() : returns Point3 +// % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html +// if length(varargin) == 0 +// varargout{1} = geometry_wrapper(18, varargin{:}); +// else +// error('Arguments do not match any overload of function Point3.string_deserialize'); +// end +// end + + proxyFile.oss << " function varargout = string_deserialize(varargin)\n"; + proxyFile.oss << " % STRING_DESERIALIZE usage: string_deserialize() : returns " << matlabQualName << "\n"; + proxyFile.oss << " % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n"; + proxyFile.oss << " if length(varargin) == 0\n"; + proxyFile.oss << " varargout{1} = geometry_wrapper(" << boost::lexical_cast(deserialize_id) << ", varargin{:});\n"; + proxyFile.oss << " else\n"; + proxyFile.oss << " error('Arguments do not match any overload of function " << matlabQualName << ".string_deserialize');\n"; + proxyFile.oss << " end\n"; + proxyFile.oss << " end\n\n"; } diff --git a/wrap/Class.h b/wrap/Class.h index d66d805b9..7e3dfd221 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -66,8 +66,12 @@ struct Class { // The typedef line for this class, if this class is a typedef, otherwise returns an empty string. std::string getTypedef() const; + // Creates a member function that performs serialization void serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, std::vector& functionNames) const; + // Creates a static member function that performs deserialization + void deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, std::vector& functionNames) const; + private: void pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& wrapperName, std::vector& functionNames) const; void comment_fragment(FileWriter& proxyFile) const; diff --git a/wrap/tests/expected/Point3.m b/wrap/tests/expected/Point3.m index 836482a7d..385bfeabb 100644 --- a/wrap/tests/expected/Point3.m +++ b/wrap/tests/expected/Point3.m @@ -52,11 +52,11 @@ classdef Point3 < handle end end - function varargout string_serialize(this, varargin) - % string_serialize usage: string_serialize() : returns string - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + function varargout = string_serialize(this, varargin) + % STRING_SERIALIZE usage: string_serialize() : returns string + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 0 - varargout{1} = geometry_wrapper(14, this, varargin{:}); + varargout{1} = geometry_wrapper(15, this, varargin{:}); else error('Arguments do not match any overload of function Point3.string_serialize'); end @@ -71,7 +71,7 @@ classdef Point3 < handle % Usage % STATICFUNCTIONRET(double z) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(15, varargin{:}); + varargout{1} = geometry_wrapper(16, varargin{:}); else error('Arguments do not match any overload of function Point3.StaticFunctionRet'); end @@ -84,19 +84,19 @@ classdef Point3 < handle % Usage % STATICFUNCTION() if length(varargin) == 0 - varargout{1} = geometry_wrapper(16, varargin{:}); + varargout{1} = geometry_wrapper(17, varargin{:}); else error('Arguments do not match any overload of function Point3.StaticFunction'); end end function varargout = string_deserialize(varargin) - % STATICFUNCTION usage: string_deserialize() : returns Point3 - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html + % STRING_DESERIALIZE usage: string_deserialize() : returns Point3 + % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html if length(varargin) == 0 - varargout{1} = geometry_wrapper(16, varargin{:}); + varargout{1} = geometry_wrapper(18, varargin{:}); else - error('Arguments do not match any overload of function Point3.StaticFunction'); + error('Arguments do not match any overload of function Point3.string_deserialize'); end end diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index c18c2224b..b50428f23 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -223,23 +223,7 @@ void Point3_norm_14(int nargout, mxArray *out[], int nargin, const mxArray *in[] out[0] = wrap< double >(obj->norm()); } -void Point3_StaticFunctionRet_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr SharedPoint3; - typedef boost::shared_ptr Shared; - checkArguments("Point3.StaticFunctionRet",nargout,nargin,1); - double z = unwrap< double >(in[0]); - out[0] = wrap_shared_ptr(SharedPoint3(new Point3(Point3::StaticFunctionRet(z))),"Point3", false); -} - -void Point3_staticFunction_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr Shared; - checkArguments("Point3.staticFunction",nargout,nargin,0); - out[0] = wrap< double >(Point3::staticFunction()); -} - -void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Point3_string_serialize_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("string_serialize",nargout,nargin-1,0); @@ -250,6 +234,22 @@ void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const m out[0] = wrap< string >(out_archive_stream.str()); } +void Point3_StaticFunctionRet_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr SharedPoint3; + typedef boost::shared_ptr Shared; + checkArguments("Point3.StaticFunctionRet",nargout,nargin,1); + double z = unwrap< double >(in[0]); + out[0] = wrap_shared_ptr(SharedPoint3(new Point3(Point3::StaticFunctionRet(z))),"Point3", false); +} + +void Point3_staticFunction_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("Point3.staticFunction",nargout,nargin,0); + out[0] = wrap< double >(Point3::staticFunction()); +} + void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; @@ -258,7 +258,7 @@ void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const std::istringstream in_archive_stream(serialized); boost::archive::text_iarchive in_archive(in_archive_stream); Shared output(new Point3()); - in_archive >> output; + in_archive >> *output; out[0] = wrap_shared_ptr(output,"Point3", false); } From 14c5f205dd20db12164f5588b356ac407b15e33d Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:50:00 +0000 Subject: [PATCH 078/256] basic serialization works --- wrap/Class.cpp | 23 +++++++++++++---------- wrap/Class.h | 6 ++++-- wrap/tests/expected/Point3.m | 2 +- 3 files changed, 18 insertions(+), 13 deletions(-) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 38aef00a1..8bc6ac38d 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -112,7 +112,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, wrapperFile.oss << "\n"; } if (isSerializable) - serialization_fragments(proxyFile, wrapperFile, functionNames); + serialization_fragments(proxyFile, wrapperFile, wrapperName, functionNames); proxyFile.oss << " end\n"; proxyFile.oss << "\n"; @@ -126,7 +126,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, wrapperFile.oss << "\n"; } if (isSerializable) - deserialization_fragments(proxyFile, wrapperFile, functionNames); + deserialization_fragments(proxyFile, wrapperFile, wrapperName, functionNames); proxyFile.oss << " end\n"; proxyFile.oss << "end\n"; @@ -401,10 +401,10 @@ void Class::comment_fragment(FileWriter& proxyFile) const { proxyFile.oss << "%\n"; } -/* ************************************************************************* */ -void Class::serialization_fragments(FileWriter& proxyFile, - FileWriter& wrapperFile, std::vector& functionNames) const { +/* ************************************************************************* */ +void Class::serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const std::string& wrapperName, std::vector& functionNames) const { //void Point3_string_serialize_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) //{ @@ -463,14 +463,16 @@ void Class::serialization_fragments(FileWriter& proxyFile, proxyFile.oss << " % STRING_SERIALIZE usage: string_serialize() : returns string\n"; proxyFile.oss << " % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n"; proxyFile.oss << " if length(varargin) == 0\n"; - proxyFile.oss << " varargout{1} = geometry_wrapper(" << boost::lexical_cast(serialize_id) << ", this, varargin{:});\n"; + proxyFile.oss << " varargout{1} = " << wrapperName << "(" << boost::lexical_cast(serialize_id) << ", this, varargin{:});\n"; proxyFile.oss << " else\n"; proxyFile.oss << " error('Arguments do not match any overload of function " << matlabQualName << ".string_serialize');\n"; proxyFile.oss << " end\n"; proxyFile.oss << " end\n"; } -void Class::deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, std::vector& functionNames) const { +/* ************************************************************************* */ +void Class::deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const std::string& wrapperName, std::vector& functionNames) const { //void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) //{ // typedef boost::shared_ptr Shared; @@ -511,7 +513,7 @@ void Class::deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapper // function varargout = string_deserialize(varargin) // % STRING_DESERIALIZE usage: string_deserialize() : returns Point3 // % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html -// if length(varargin) == 0 +// if length(varargin) == 1 // varargout{1} = geometry_wrapper(18, varargin{:}); // else // error('Arguments do not match any overload of function Point3.string_deserialize'); @@ -521,10 +523,11 @@ void Class::deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapper proxyFile.oss << " function varargout = string_deserialize(varargin)\n"; proxyFile.oss << " % STRING_DESERIALIZE usage: string_deserialize() : returns " << matlabQualName << "\n"; proxyFile.oss << " % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html\n"; - proxyFile.oss << " if length(varargin) == 0\n"; - proxyFile.oss << " varargout{1} = geometry_wrapper(" << boost::lexical_cast(deserialize_id) << ", varargin{:});\n"; + proxyFile.oss << " if length(varargin) == 1\n"; + proxyFile.oss << " varargout{1} = " << wrapperName << "(" << boost::lexical_cast(deserialize_id) << ", varargin{:});\n"; proxyFile.oss << " else\n"; proxyFile.oss << " error('Arguments do not match any overload of function " << matlabQualName << ".string_deserialize');\n"; proxyFile.oss << " end\n"; proxyFile.oss << " end\n\n"; } +/* ************************************************************************* */ diff --git a/wrap/Class.h b/wrap/Class.h index 7e3dfd221..d33124e50 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -67,10 +67,12 @@ struct Class { std::string getTypedef() const; // Creates a member function that performs serialization - void serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, std::vector& functionNames) const; + void serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const std::string& wrapperName, std::vector& functionNames) const; // Creates a static member function that performs deserialization - void deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, std::vector& functionNames) const; + void deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, + const std::string& wrapperName, std::vector& functionNames) const; private: void pointer_constructor_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& wrapperName, std::vector& functionNames) const; diff --git a/wrap/tests/expected/Point3.m b/wrap/tests/expected/Point3.m index 385bfeabb..e0681ab41 100644 --- a/wrap/tests/expected/Point3.m +++ b/wrap/tests/expected/Point3.m @@ -93,7 +93,7 @@ classdef Point3 < handle function varargout = string_deserialize(varargin) % STRING_DESERIALIZE usage: string_deserialize() : returns Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 0 + if length(varargin) == 1 varargout{1} = geometry_wrapper(18, varargin{:}); else error('Arguments do not match any overload of function Point3.string_deserialize'); From b5b1eac597d181ab1993442432897b3687c21151 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:50:01 +0000 Subject: [PATCH 079/256] Rearranged serialization test to use new interface, added serialize() flags to Point2 and Values. Serialzing values fails - now to add export commands --- gtsam.h | 30 ++++--- .../testGraphValuesSerialization.m | 81 ++++++++++++------- 2 files changed, 69 insertions(+), 42 deletions(-) diff --git a/gtsam.h b/gtsam.h index 35def3b76..081eccb53 100644 --- a/gtsam.h +++ b/gtsam.h @@ -267,6 +267,9 @@ virtual class Point2 : gtsam::Value { Vector vector() const; double dist(const gtsam::Point2& p2) const; double norm() const; + + // enabling serialization functionality + void serialize() const; }; virtual class StereoPoint2 : gtsam::Value { @@ -1555,29 +1558,32 @@ class Values { size_t size() const; bool empty() const; - void clear(); - size_t dim() const; + void clear(); + size_t dim() const; void print(string s) const; bool equals(const gtsam::Values& other, double tol) const; void insert(size_t j, const gtsam::Value& value); - void insert(const gtsam::Values& values); - void update(size_t j, const gtsam::Value& val); - void update(const gtsam::Values& values); - void erase(size_t j); - void swap(gtsam::Values& values); + void insert(const gtsam::Values& values); + void update(size_t j, const gtsam::Value& val); + void update(const gtsam::Values& values); + void erase(size_t j); + void swap(gtsam::Values& values); bool exists(size_t j) const; gtsam::Value at(size_t j) const; gtsam::KeyList keys() const; - gtsam::VectorValues zeroVectors(const gtsam::Ordering& ordering) const; - gtsam::Ordering* orderingArbitrary(size_t firstVar) const; + gtsam::VectorValues zeroVectors(const gtsam::Ordering& ordering) const; + gtsam::Ordering* orderingArbitrary(size_t firstVar) const; - gtsam::Values retract(const gtsam::VectorValues& delta, const gtsam::Ordering& ordering) const; - gtsam::VectorValues localCoordinates(const gtsam::Values& cp, const gtsam::Ordering& ordering) const; - void localCoordinates(const gtsam::Values& cp, const gtsam::Ordering& ordering, gtsam::VectorValues& delta) const; + gtsam::Values retract(const gtsam::VectorValues& delta, const gtsam::Ordering& ordering) const; + gtsam::VectorValues localCoordinates(const gtsam::Values& cp, const gtsam::Ordering& ordering) const; + void localCoordinates(const gtsam::Values& cp, const gtsam::Ordering& ordering, gtsam::VectorValues& delta) const; + + // enabling serialization functionality + void serialize() const; }; // Actually a FastList diff --git a/matlab/gtsam_tests/testGraphValuesSerialization.m b/matlab/gtsam_tests/testGraphValuesSerialization.m index 5583dde76..23401f370 100644 --- a/matlab/gtsam_tests/testGraphValuesSerialization.m +++ b/matlab/gtsam_tests/testGraphValuesSerialization.m @@ -6,7 +6,7 @@ % % See LICENSE for the license information % -% @brief Simple robotics example using the pre-built planar SLAM domain +% @brief Checks for serialization using basic string interface % @author Alex Cunningham % @author Frank Dellaert %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% @@ -17,7 +17,34 @@ import gtsam.* i1 = symbol('x',1); i2 = symbol('x',2); i3 = symbol('x',3); j1 = symbol('l',1); j2 = symbol('l',2); -%% Create graph and factors +%% Create values and verify string serialization +pose1=Pose2(0.5, 0.0, 0.2); +pose2=Pose2(2.3, 0.1,-0.2); +pose3=Pose2(4.1, 0.1, 0.1); +landmark1=Point2(1.8, 2.1); +landmark2=Point2(4.1, 1.8); + +serialized_pose1 = pose1.string_serialize(); +pose1ds = Pose2.string_deserialize(serialized_pose1); +CHECK('pose1ds.equals(pose1, 1e-9)', pose1ds.equals(pose1, 1e-9)); + +serialized_landmark1 = landmark1.string_serialize(); +landmark1ds = Point2.string_deserialize(serialized_landmark1); +CHECK('landmark1ds.equals(landmark1, 1e-9)', landmark1ds.equals(landmark1, 1e-9)); + +%% Create and serialize Values +values = Values; +values.insert(i1, pose1); +values.insert(i2, pose2); +values.insert(i3, pose3); +values.insert(j1, landmark1); +values.insert(j2, landmark2); + +serialized_values = values.string_serialize(); +valuesds = Values.string_deserialize(serialized_values); +CHECK('valuesds.equals(values, 1e-9)', valuesds.equals(values, 1e-9)); + +%% Create graph and factors and serialize graph = NonlinearFactorGraph; % Prior factor - FAIL: unregistered class @@ -25,36 +52,30 @@ priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph -% Between Factors - FAIL: unregistered class -odometry = Pose2(2.0, 0.0, 0.0); -odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); -graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); -graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); +% % Between Factors - FAIL: unregistered class +% odometry = Pose2(2.0, 0.0, 0.0); +% odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +% graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); +% graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); +% +% % BearingRange Factors - FAIL: unregistered class +% degrees = pi/180; +% brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); +% graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(4+4), brNoise)); +% graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise)); +% graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise)); -% BearingRange Factors - FAIL: unregistered class -degrees = pi/180; -brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); -graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(4+4), brNoise)); -graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise)); -graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise)); - -%% Create Values -values = Values; -values.insert(i1, Pose2(0.5, 0.0, 0.2)); -values.insert(i2, Pose2(2.3, 0.1,-0.2)); -values.insert(i3, Pose2(4.1, 0.1, 0.1)); -values.insert(j1, Point2(1.8, 2.1)); -values.insert(j2, Point2(4.1, 1.8)); - -%% Check that serialization works properly -serialized_values = serializeValues(values); % returns a string -deserializedValues = deserializeValues(serialized_values); % returns a new values -CHECK('values.equals(deserializedValues)',values.equals(deserializedValues,1e-9)); - -CHECK('serializeValuesToFile(values, values.dat)', serializeValuesToFile(values, 'values.dat')); -deserializedValuesFile = deserializeValuesFromFile('values.dat'); % returns a new values -CHECK('values.equals(deserializedValuesFile)',values.equals(deserializedValuesFile,1e-9)); +%% Old interface +% %% Check that serialization works properly +% serialized_values = serializeValues(values); % returns a string +% deserializedValues = deserializeValues(serialized_values); % returns a new values +% CHECK('values.equals(deserializedValues)',values.equals(deserializedValues,1e-9)); +% +% CHECK('serializeValuesToFile(values, values.dat)', serializeValuesToFile(values, 'values.dat')); +% deserializedValuesFile = deserializeValuesFromFile('values.dat'); % returns a new values +% CHECK('values.equals(deserializedValuesFile)',values.equals(deserializedValuesFile,1e-9)); +% % % FAIL: unregistered class - derived class not registered or exported % serialized_graph = serializeGraph(graph); % returns a string % deserializedGraph = deserializeGraph(serialized_graph); % returns a new graph From 4d76386aa76485af196159662f10d048683acdac Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:50:02 +0000 Subject: [PATCH 080/256] Updated expected values to match newer codegen --- wrap/tests/expected/Point3.m | 5 +- wrap/tests/expected/Test.m | 46 +++++----- wrap/tests/expected/aGlobalFunction.m | 2 +- wrap/tests/expected/geometry_wrapper.cpp | 108 ++++++++++++----------- 4 files changed, 83 insertions(+), 78 deletions(-) diff --git a/wrap/tests/expected/Point3.m b/wrap/tests/expected/Point3.m index e0681ab41..27b7f46fe 100644 --- a/wrap/tests/expected/Point3.m +++ b/wrap/tests/expected/Point3.m @@ -14,6 +14,7 @@ %-------Serialization Interface------- %string_serialize() : returns string %string_deserialize(string serialized) : returns Point3 +% classdef Point3 < handle properties ptr_Point3 = 0 @@ -51,7 +52,7 @@ classdef Point3 < handle error('Arguments do not match any overload of function Point3.norm'); end end - + function varargout = string_serialize(this, varargin) % STRING_SERIALIZE usage: string_serialize() : returns string % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html @@ -89,7 +90,7 @@ classdef Point3 < handle error('Arguments do not match any overload of function Point3.StaticFunction'); end end - + function varargout = string_deserialize(varargin) % STRING_DESERIALIZE usage: string_deserialize() : returns Point3 % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html diff --git a/wrap/tests/expected/Test.m b/wrap/tests/expected/Test.m index e493b9a04..8e56df6fc 100644 --- a/wrap/tests/expected/Test.m +++ b/wrap/tests/expected/Test.m @@ -34,11 +34,11 @@ classdef Test < handle function obj = Test(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(17, my_ptr); + geometry_wrapper(19, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(18); + my_ptr = geometry_wrapper(20); elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - my_ptr = geometry_wrapper(19, varargin{1}, varargin{2}); + my_ptr = geometry_wrapper(21, varargin{1}, varargin{2}); else error('Arguments do not match any overload of Test constructor'); end @@ -46,7 +46,7 @@ classdef Test < handle end function delete(obj) - geometry_wrapper(20, obj.ptr_Test); + geometry_wrapper(22, obj.ptr_Test); end function display(obj), obj.print(''); end @@ -60,7 +60,7 @@ classdef Test < handle % Method Overloads % arg_EigenConstRef(Matrix value) if length(varargin) == 1 && isa(varargin{1},'double') - geometry_wrapper(21, this, varargin{:}); + geometry_wrapper(23, this, varargin{:}); else error('Arguments do not match any overload of function Test.arg_EigenConstRef'); end @@ -73,7 +73,7 @@ classdef Test < handle % Method Overloads % create_MixedPtrs() if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(22, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(24, this, varargin{:}); else error('Arguments do not match any overload of function Test.create_MixedPtrs'); end @@ -86,7 +86,7 @@ classdef Test < handle % Method Overloads % create_ptrs() if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(23, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(25, this, varargin{:}); else error('Arguments do not match any overload of function Test.create_ptrs'); end @@ -99,7 +99,7 @@ classdef Test < handle % Method Overloads % print() if length(varargin) == 0 - geometry_wrapper(24, this, varargin{:}); + geometry_wrapper(26, this, varargin{:}); else error('Arguments do not match any overload of function Test.print'); end @@ -112,7 +112,7 @@ classdef Test < handle % Method Overloads % return_Point2Ptr(bool value) if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = geometry_wrapper(25, this, varargin{:}); + varargout{1} = geometry_wrapper(27, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_Point2Ptr'); end @@ -125,7 +125,7 @@ classdef Test < handle % Method Overloads % return_Test(Test value) if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(26, this, varargin{:}); + varargout{1} = geometry_wrapper(28, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_Test'); end @@ -138,7 +138,7 @@ classdef Test < handle % Method Overloads % return_TestPtr(Test value) if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(27, this, varargin{:}); + varargout{1} = geometry_wrapper(29, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_TestPtr'); end @@ -151,7 +151,7 @@ classdef Test < handle % Method Overloads % return_bool(bool value) if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = geometry_wrapper(28, this, varargin{:}); + varargout{1} = geometry_wrapper(30, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_bool'); end @@ -164,7 +164,7 @@ classdef Test < handle % Method Overloads % return_double(double value) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(29, this, varargin{:}); + varargout{1} = geometry_wrapper(31, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_double'); end @@ -177,7 +177,7 @@ classdef Test < handle % Method Overloads % return_field(Test t) if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(30, this, varargin{:}); + varargout{1} = geometry_wrapper(32, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_field'); end @@ -190,7 +190,7 @@ classdef Test < handle % Method Overloads % return_int(int value) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(31, this, varargin{:}); + varargout{1} = geometry_wrapper(33, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_int'); end @@ -203,7 +203,7 @@ classdef Test < handle % Method Overloads % return_matrix1(Matrix value) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(32, this, varargin{:}); + varargout{1} = geometry_wrapper(34, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_matrix1'); end @@ -216,7 +216,7 @@ classdef Test < handle % Method Overloads % return_matrix2(Matrix value) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(33, this, varargin{:}); + varargout{1} = geometry_wrapper(35, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_matrix2'); end @@ -229,7 +229,7 @@ classdef Test < handle % Method Overloads % return_pair(Vector v, Matrix A) if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - [ varargout{1} varargout{2} ] = geometry_wrapper(34, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(36, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_pair'); end @@ -242,7 +242,7 @@ classdef Test < handle % Method Overloads % return_ptrs(Test p1, Test p2) if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') - [ varargout{1} varargout{2} ] = geometry_wrapper(35, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(37, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_ptrs'); end @@ -255,7 +255,7 @@ classdef Test < handle % Method Overloads % return_size_t(size_t value) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(36, this, varargin{:}); + varargout{1} = geometry_wrapper(38, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_size_t'); end @@ -268,7 +268,7 @@ classdef Test < handle % Method Overloads % return_string(string value) if length(varargin) == 1 && isa(varargin{1},'char') - varargout{1} = geometry_wrapper(37, this, varargin{:}); + varargout{1} = geometry_wrapper(39, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_string'); end @@ -281,7 +281,7 @@ classdef Test < handle % Method Overloads % return_vector1(Vector value) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(38, this, varargin{:}); + varargout{1} = geometry_wrapper(40, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_vector1'); end @@ -294,7 +294,7 @@ classdef Test < handle % Method Overloads % return_vector2(Vector value) if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(39, this, varargin{:}); + varargout{1} = geometry_wrapper(41, this, varargin{:}); else error('Arguments do not match any overload of function Test.return_vector2'); end diff --git a/wrap/tests/expected/aGlobalFunction.m b/wrap/tests/expected/aGlobalFunction.m index cee69491c..09ece0b83 100644 --- a/wrap/tests/expected/aGlobalFunction.m +++ b/wrap/tests/expected/aGlobalFunction.m @@ -1,6 +1,6 @@ function varargout = aGlobalFunction(varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(40, varargin{:}); + varargout{1} = geometry_wrapper(42, varargin{:}); else error('Arguments do not match any overload of function aGlobalFunction'); end diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index b50428f23..35c2a2aec 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -233,7 +233,6 @@ void Point3_string_serialize_15(int nargout, mxArray *out[], int nargin, const m out_archive << *obj; out[0] = wrap< string >(out_archive_stream.str()); } - void Point3_StaticFunctionRet_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint3; @@ -261,8 +260,7 @@ void Point3_string_deserialize_18(int nargout, mxArray *out[], int nargin, const in_archive >> *output; out[0] = wrap_shared_ptr(output,"Point3", false); } - -void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_collectorInsertAndMakeBase_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -271,7 +269,7 @@ void Test_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, collector_Test.insert(self); } -void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -282,7 +280,7 @@ void Test_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -295,7 +293,7 @@ void Test_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_deconstructor_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_Test",nargout,nargin,1); @@ -308,7 +306,7 @@ void Test_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArra } } -void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_arg_EigenConstRef_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("arg_EigenConstRef",nargout,nargin-1,1); @@ -317,7 +315,7 @@ void Test_arg_EigenConstRef_21(int nargout, mxArray *out[], int nargin, const mx obj->arg_EigenConstRef(value); } -void Test_create_MixedPtrs_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_MixedPtrs_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr SharedTest; @@ -329,7 +327,7 @@ void Test_create_MixedPtrs_22(int nargout, mxArray *out[], int nargin, const mxA out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_create_ptrs_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_ptrs_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr SharedTest; @@ -341,7 +339,7 @@ void Test_create_ptrs_23(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_print_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("print",nargout,nargin-1,0); @@ -349,7 +347,7 @@ void Test_print_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) obj->print(); } -void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Point2Ptr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedPoint2; typedef boost::shared_ptr Shared; @@ -359,7 +357,7 @@ void Test_return_Point2Ptr_25(int nargout, mxArray *out[], int nargin, const mxA out[0] = wrap_shared_ptr(obj->return_Point2Ptr(value),"Point2", false); } -void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Test_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; @@ -369,7 +367,7 @@ void Test_return_Test_26(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap_shared_ptr(SharedTest(new Test(obj->return_Test(value))),"Test", false); } -void Test_return_TestPtr_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_TestPtr_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr Shared; @@ -379,7 +377,7 @@ void Test_return_TestPtr_27(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap_shared_ptr(obj->return_TestPtr(value),"Test", false); } -void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_bool_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_bool",nargout,nargin-1,1); @@ -388,7 +386,7 @@ void Test_return_bool_28(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_bool(value)); } -void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_double_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_double",nargout,nargin-1,1); @@ -397,7 +395,7 @@ void Test_return_double_29(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< double >(obj->return_double(value)); } -void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_field_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_field",nargout,nargin-1,1); @@ -406,7 +404,7 @@ void Test_return_field_30(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_field(t)); } -void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_int_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_int",nargout,nargin-1,1); @@ -415,7 +413,7 @@ void Test_return_int_31(int nargout, mxArray *out[], int nargin, const mxArray * out[0] = wrap< int >(obj->return_int(value)); } -void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix1_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_matrix1",nargout,nargin-1,1); @@ -424,7 +422,7 @@ void Test_return_matrix1_32(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix1(value)); } -void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix2_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_matrix2",nargout,nargin-1,1); @@ -433,7 +431,7 @@ void Test_return_matrix2_33(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix2(value)); } -void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_pair_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_pair",nargout,nargin-1,2); @@ -445,7 +443,7 @@ void Test_return_pair_34(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap< Matrix >(pairResult.second); } -void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_ptrs_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr SharedTest; typedef boost::shared_ptr SharedTest; @@ -459,7 +457,7 @@ void Test_return_ptrs_35(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_size_t_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_size_t",nargout,nargin-1,1); @@ -468,7 +466,7 @@ void Test_return_size_t_36(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< size_t >(obj->return_size_t(value)); } -void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_string_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_string",nargout,nargin-1,1); @@ -477,7 +475,7 @@ void Test_return_string_37(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< string >(obj->return_string(value)); } -void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector1_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_vector1",nargout,nargin-1,1); @@ -486,7 +484,7 @@ void Test_return_vector1_38(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector1(value)); } -void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector2_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("return_vector2",nargout,nargin-1,1); @@ -495,7 +493,7 @@ void Test_return_vector2_39(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector2(value)); } -void aGlobalFunction_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void aGlobalFunction_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("aGlobalFunction",nargout,nargin,0); out[0] = wrap< Vector >(aGlobalFunction()); @@ -558,82 +556,88 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) Point3_norm_14(nargout, out, nargin-1, in+1); break; case 15: - Point3_StaticFunctionRet_15(nargout, out, nargin-1, in+1); + Point3_string_serialize_15(nargout, out, nargin-1, in+1); break; case 16: - Point3_staticFunction_16(nargout, out, nargin-1, in+1); + Point3_StaticFunctionRet_16(nargout, out, nargin-1, in+1); break; case 17: - Test_collectorInsertAndMakeBase_17(nargout, out, nargin-1, in+1); + Point3_staticFunction_17(nargout, out, nargin-1, in+1); break; case 18: - Test_constructor_18(nargout, out, nargin-1, in+1); + Point3_string_deserialize_18(nargout, out, nargin-1, in+1); break; case 19: - Test_constructor_19(nargout, out, nargin-1, in+1); + Test_collectorInsertAndMakeBase_19(nargout, out, nargin-1, in+1); break; case 20: - Test_deconstructor_20(nargout, out, nargin-1, in+1); + Test_constructor_20(nargout, out, nargin-1, in+1); break; case 21: - Test_arg_EigenConstRef_21(nargout, out, nargin-1, in+1); + Test_constructor_21(nargout, out, nargin-1, in+1); break; case 22: - Test_create_MixedPtrs_22(nargout, out, nargin-1, in+1); + Test_deconstructor_22(nargout, out, nargin-1, in+1); break; case 23: - Test_create_ptrs_23(nargout, out, nargin-1, in+1); + Test_arg_EigenConstRef_23(nargout, out, nargin-1, in+1); break; case 24: - Test_print_24(nargout, out, nargin-1, in+1); + Test_create_MixedPtrs_24(nargout, out, nargin-1, in+1); break; case 25: - Test_return_Point2Ptr_25(nargout, out, nargin-1, in+1); + Test_create_ptrs_25(nargout, out, nargin-1, in+1); break; case 26: - Test_return_Test_26(nargout, out, nargin-1, in+1); + Test_print_26(nargout, out, nargin-1, in+1); break; case 27: - Test_return_TestPtr_27(nargout, out, nargin-1, in+1); + Test_return_Point2Ptr_27(nargout, out, nargin-1, in+1); break; case 28: - Test_return_bool_28(nargout, out, nargin-1, in+1); + Test_return_Test_28(nargout, out, nargin-1, in+1); break; case 29: - Test_return_double_29(nargout, out, nargin-1, in+1); + Test_return_TestPtr_29(nargout, out, nargin-1, in+1); break; case 30: - Test_return_field_30(nargout, out, nargin-1, in+1); + Test_return_bool_30(nargout, out, nargin-1, in+1); break; case 31: - Test_return_int_31(nargout, out, nargin-1, in+1); + Test_return_double_31(nargout, out, nargin-1, in+1); break; case 32: - Test_return_matrix1_32(nargout, out, nargin-1, in+1); + Test_return_field_32(nargout, out, nargin-1, in+1); break; case 33: - Test_return_matrix2_33(nargout, out, nargin-1, in+1); + Test_return_int_33(nargout, out, nargin-1, in+1); break; case 34: - Test_return_pair_34(nargout, out, nargin-1, in+1); + Test_return_matrix1_34(nargout, out, nargin-1, in+1); break; case 35: - Test_return_ptrs_35(nargout, out, nargin-1, in+1); + Test_return_matrix2_35(nargout, out, nargin-1, in+1); break; case 36: - Test_return_size_t_36(nargout, out, nargin-1, in+1); + Test_return_pair_36(nargout, out, nargin-1, in+1); break; case 37: - Test_return_string_37(nargout, out, nargin-1, in+1); + Test_return_ptrs_37(nargout, out, nargin-1, in+1); break; case 38: - Test_return_vector1_38(nargout, out, nargin-1, in+1); + Test_return_size_t_38(nargout, out, nargin-1, in+1); break; case 39: - Test_return_vector2_39(nargout, out, nargin-1, in+1); + Test_return_string_39(nargout, out, nargin-1, in+1); break; case 40: - aGlobalFunction_40(nargout, out, nargin-1, in+1); + Test_return_vector1_40(nargout, out, nargin-1, in+1); + break; + case 41: + Test_return_vector2_41(nargout, out, nargin-1, in+1); + break; + case 42: + aGlobalFunction_42(nargout, out, nargin-1, in+1); break; } } catch(const std::exception& e) { From f1b1a2f7d2b6f9233299b81bf6c632119b68a88f Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:50:03 +0000 Subject: [PATCH 081/256] Added export flags, Values now serializes --- wrap/Class.cpp | 6 ++++++ wrap/Class.h | 3 +++ wrap/Module.cpp | 14 +++++++++++++- wrap/tests/expected/geometry_wrapper.cpp | 2 ++ 4 files changed, 24 insertions(+), 1 deletion(-) diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 8bc6ac38d..c384a5377 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -530,4 +530,10 @@ void Class::deserialization_fragments(FileWriter& proxyFile, FileWriter& wrapper proxyFile.oss << " end\n"; proxyFile.oss << " end\n\n"; } + +/* ************************************************************************* */ +std::string Class::getSerializationExport() const { + //BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsamSharedDiagonal"); + return "BOOST_CLASS_EXPORT_GUID(" + qualifiedName("::") + ", \"" + qualifiedName() + "\");"; +} /* ************************************************************************* */ diff --git a/wrap/Class.h b/wrap/Class.h index d33124e50..efbcce26c 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -66,6 +66,9 @@ struct Class { // The typedef line for this class, if this class is a typedef, otherwise returns an empty string. std::string getTypedef() const; + // Returns the string for an export flag + std::string getSerializationExport() const; + // Creates a member function that performs serialization void serialization_fragments(FileWriter& proxyFile, FileWriter& wrapperFile, const std::string& wrapperName, std::vector& functionNames) const; diff --git a/wrap/Module.cpp b/wrap/Module.cpp index ec346a7a0..3f16fbf1b 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -492,11 +492,14 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co wrapperFile.oss << "#include \n"; wrapperFile.oss << "\n"; - // Generate includes while avoiding redundant includes + // Include boost.serialization archive headers before other class headers if (hasSerialiable) { + wrapperFile.oss << "#include \n"; wrapperFile.oss << "#include \n"; wrapperFile.oss << "#include \n\n"; } + + // Generate includes while avoiding redundant includes generateIncludes(wrapperFile); // create typedef classes - we put this at the top of the wrap file so that collectors and method arguments can use these typedefs @@ -506,6 +509,15 @@ void Module::matlab_code(const string& toolboxPath, const string& headerPath) co } wrapperFile.oss << "\n"; + // Generate boost.serialization export flags (needs typedefs from above) + if (hasSerialiable) { + BOOST_FOREACH(const Class& cls, expandedClasses) { + if(cls.isSerializable) + wrapperFile.oss << cls.getSerializationExport() << "\n"; + } + wrapperFile.oss << "\n"; + } + // Generate collectors and cleanup function to be called from mexAtExit WriteCollectorsAndCleanupFcn(wrapperFile, name, expandedClasses); diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index 35c2a2aec..c56545847 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -2,11 +2,13 @@ #include #include +#include #include #include #include +BOOST_CLASS_EXPORT_GUID(Point3, "Point3"); typedef std::set*> Collector_Point2; static Collector_Point2 collector_Point2; From ed3ab55538822d2029c725897e7dc53bc0061125 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:50:04 +0000 Subject: [PATCH 082/256] Fixed wrap test, now passes --- wrap/tests/expected/geometry_wrapper.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index c56545847..1dfea33d4 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -8,6 +8,7 @@ #include + BOOST_CLASS_EXPORT_GUID(Point3, "Point3"); typedef std::set*> Collector_Point2; From 23de91d44dc88f563dd1c713cdba5d238381ca7e Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:50:05 +0000 Subject: [PATCH 083/256] serialization works for graph and PriorFactor. Added second flag for serialization: can add "void serializable()" or "void serialize()" to allow for either just exporting (necessary if no default constructor), or implementing the full serialization functions --- gtsam.h | 90 +++++++++++++++++++ .../testGraphValuesSerialization.m | 6 +- wrap/Class.cpp | 6 +- wrap/Class.h | 5 +- wrap/Module.cpp | 7 ++ wrap/tests/expected/geometry_wrapper.cpp | 1 + wrap/tests/geometry.h | 2 + wrap/tests/testWrap.cpp | 5 ++ 8 files changed, 116 insertions(+), 6 deletions(-) diff --git a/gtsam.h b/gtsam.h index 081eccb53..33149c344 100644 --- a/gtsam.h +++ b/gtsam.h @@ -200,6 +200,9 @@ virtual class LieVector : gtsam::Value { // Lie group static gtsam::LieVector Expmap(Vector v); static Vector Logmap(const gtsam::LieVector& p); + + // enabling serialization functionality + void serialize() const; }; #include @@ -229,6 +232,9 @@ virtual class LieMatrix : gtsam::Value { // Lie group static gtsam::LieMatrix Expmap(Vector v); static Vector Logmap(const gtsam::LieMatrix& p); + + // enabling serialization functionality + void serialize() const; }; //************************************************************************* @@ -299,6 +305,9 @@ virtual class StereoPoint2 : gtsam::Value { // Standard Interface Vector vector() const; + + // enabling serialization functionality + void serialize() const; }; virtual class Point3 : gtsam::Value { @@ -332,6 +341,9 @@ virtual class Point3 : gtsam::Value { double x() const; double y() const; double z() const; + + // enabling serialization functionality + void serialize() const; }; virtual class Rot2 : gtsam::Value { @@ -374,6 +386,9 @@ virtual class Rot2 : gtsam::Value { double c() const; double s() const; Matrix matrix() const; + + // enabling serialization functionality + void serialize() const; }; virtual class Rot3 : gtsam::Value { @@ -427,6 +442,9 @@ virtual class Rot3 : gtsam::Value { double yaw() const; // Vector toQuaternion() const; // FIXME: Can't cast to Vector properly Vector quaternion() const; + + // enabling serialization functionality + void serialize() const; }; virtual class Pose2 : gtsam::Value { @@ -524,6 +542,9 @@ virtual class Pose3 : gtsam::Value { gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to() double range(const gtsam::Point3& point); double range(const gtsam::Pose3& pose); + + // enabling serialization functionality + void serialize() const; }; virtual class Cal3_S2 : gtsam::Value { @@ -557,6 +578,9 @@ virtual class Cal3_S2 : gtsam::Value { Vector vector() const; Matrix matrix() const; Matrix matrix_inverse() const; + + // enabling serialization functionality + void serialize() const; }; #include @@ -591,6 +615,9 @@ virtual class Cal3DS2 : gtsam::Value { Vector vector() const; Vector k() const; //Matrix K() const; //FIXME: Uppercase + + // enabling serialization functionality + void serialize() const; }; class Cal3_S2Stereo { @@ -640,6 +667,9 @@ virtual class CalibratedCamera : gtsam::Value { // Standard Interface gtsam::Pose3 pose() const; double range(const gtsam::Point3& p) const; // TODO: Other overloaded range methods + + // enabling serialization functionality + void serialize() const; }; virtual class SimpleCamera : gtsam::Value { @@ -675,6 +705,9 @@ virtual class SimpleCamera : gtsam::Value { gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; double range(const gtsam::Point3& point); double range(const gtsam::Pose3& point); + + // enabling serialization functionality + void serialize() const; }; template @@ -711,6 +744,9 @@ virtual class PinholeCamera : gtsam::Value { gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; double range(const gtsam::Point3& point); double range(const gtsam::Pose3& point); + + // enabling serialization functionality + void serialize() const; }; //************************************************************************* @@ -994,6 +1030,9 @@ virtual class Gaussian : gtsam::noiseModel::Base { Matrix R() const; bool equals(gtsam::noiseModel::Base& expected, double tol); void print(string s) const; + + // enabling serialization functionality + void serializable() const; }; virtual class Diagonal : gtsam::noiseModel::Gaussian { @@ -1002,6 +1041,9 @@ virtual class Diagonal : gtsam::noiseModel::Gaussian { static gtsam::noiseModel::Diagonal* Precisions(Vector precisions); Matrix R() const; void print(string s) const; + + // enabling serialization functionality + void serializable() const; }; virtual class Constrained : gtsam::noiseModel::Diagonal { @@ -1016,6 +1058,9 @@ virtual class Constrained : gtsam::noiseModel::Diagonal { static gtsam::noiseModel::Constrained* All(size_t dim, double mu); gtsam::noiseModel::Constrained* unit() const; + + // enabling serialization functionality + void serializable() const; }; virtual class Isotropic : gtsam::noiseModel::Diagonal { @@ -1023,11 +1068,17 @@ virtual class Isotropic : gtsam::noiseModel::Diagonal { static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace); static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision); void print(string s) const; + + // enabling serialization functionality + void serializable() const; }; virtual class Unit : gtsam::noiseModel::Isotropic { static gtsam::noiseModel::Unit* Create(size_t dim); void print(string s) const; + + // enabling serialization functionality + void serializable() const; }; namespace mEstimator { @@ -1038,24 +1089,36 @@ virtual class Null: gtsam::noiseModel::mEstimator::Base { Null(); void print(string s) const; static gtsam::noiseModel::mEstimator::Null* Create(); + + // enabling serialization functionality + void serializable() const; }; virtual class Fair: gtsam::noiseModel::mEstimator::Base { Fair(double c); void print(string s) const; static gtsam::noiseModel::mEstimator::Fair* Create(double c); + + // enabling serialization functionality + void serializable() const; }; virtual class Huber: gtsam::noiseModel::mEstimator::Base { Huber(double k); void print(string s) const; static gtsam::noiseModel::mEstimator::Huber* Create(double k); + + // enabling serialization functionality + void serializable() const; }; virtual class Tukey: gtsam::noiseModel::mEstimator::Base { Tukey(double k); void print(string s) const; static gtsam::noiseModel::mEstimator::Tukey* Create(double k); + + // enabling serialization functionality + void serializable() const; }; }///\namespace mEstimator @@ -1064,6 +1127,9 @@ virtual class Robust : gtsam::noiseModel::Base { Robust(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise); static gtsam::noiseModel::Robust* Create(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise); void print(string s) const; + + // enabling serialization functionality + void serializable() const; }; }///\namespace noiseModel @@ -1118,6 +1184,9 @@ class VectorValues { bool hasSameStructure(const gtsam::VectorValues& other) const; double dot(const gtsam::VectorValues& V) const; double norm() const; + + // enabling serialization functionality + void serialize() const; }; class GaussianConditional { @@ -1140,6 +1209,9 @@ class GaussianConditional { void solveInPlace(gtsam::VectorValues& x) const; void solveTransposeInPlace(gtsam::VectorValues& gy) const; void scaleFrontalsBySigma(gtsam::VectorValues& gy) const; + + // enabling serialization functionality + void serialize() const; }; class GaussianDensity { @@ -1250,6 +1322,9 @@ virtual class JacobianFactor : gtsam::GaussianFactor { void assertInvariants() const; //gtsam::SharedDiagonal& get_model(); + + // enabling serialization functionality + void serialize() const; }; virtual class HessianFactor : gtsam::GaussianFactor { @@ -1283,6 +1358,9 @@ virtual class HessianFactor : gtsam::GaussianFactor { void partialCholesky(size_t nrFrontals); gtsam::GaussianConditional* splitEliminatedFactor(size_t nrFrontals); void assertInvariants() const; + + // enabling serialization functionality + void serialize() const; }; class GaussianFactorGraph { @@ -1329,6 +1407,9 @@ class GaussianFactorGraph { pair jacobian() const; Matrix augmentedHessian() const; pair hessian() const; + + // enabling serialization functionality + void serialize() const; }; //Non-Class functions in GaussianFactorGraph.h @@ -1508,6 +1589,9 @@ class Ordering { void push_back(size_t key); void permuteInPlace(const gtsam::Permutation& permutation); void permuteInPlace(const gtsam::Permutation& selector, const gtsam::Permutation& permutation); + + // enabling serialization functionality + void serialize() const; }; class NonlinearFactorGraph { @@ -1535,6 +1619,9 @@ class NonlinearFactorGraph { const gtsam::Ordering& ordering) const; gtsam::SymbolicFactorGraph* symbolic(const gtsam::Ordering& ordering) const; gtsam::NonlinearFactorGraph clone() const; + + // enabling serialization functionality + void serialize() const; }; virtual class NonlinearFactor { @@ -1974,6 +2061,9 @@ virtual class PriorFactor : gtsam::NonlinearFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; gtsam::noiseModel::Base* get_noiseModel() const; + + // enabling serialization functionality + void serialize() const; }; diff --git a/matlab/gtsam_tests/testGraphValuesSerialization.m b/matlab/gtsam_tests/testGraphValuesSerialization.m index 23401f370..999335bcd 100644 --- a/matlab/gtsam_tests/testGraphValuesSerialization.m +++ b/matlab/gtsam_tests/testGraphValuesSerialization.m @@ -57,7 +57,7 @@ graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph % odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); % graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); % graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); -% + % % BearingRange Factors - FAIL: unregistered class % degrees = pi/180; % brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); @@ -65,6 +65,10 @@ graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph % graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise)); % graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise)); +serialized_graph = graph.string_serialize(); +graphds = NonlinearFactorGraph.string_deserialize(serialized_graph); +CHECK('graphds.equals(graph, 1e-9)', graphds.equals(graph, 1e-9)); + %% Old interface % %% Check that serialization works properly diff --git a/wrap/Class.cpp b/wrap/Class.cpp index c384a5377..15c4a742c 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -111,7 +111,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, proxyFile.oss << "\n"; wrapperFile.oss << "\n"; } - if (isSerializable) + if (hasSerialization) serialization_fragments(proxyFile, wrapperFile, wrapperName, functionNames); proxyFile.oss << " end\n"; @@ -125,7 +125,7 @@ void Class::matlab_proxy(const string& toolboxPath, const string& wrapperName, proxyFile.oss << "\n"; wrapperFile.oss << "\n"; } - if (isSerializable) + if (hasSerialization) deserialization_fragments(proxyFile, wrapperFile, wrapperName, functionNames); proxyFile.oss << " end\n"; @@ -393,7 +393,7 @@ void Class::comment_fragment(FileWriter& proxyFile) const { } } - if (isSerializable) { + if (hasSerialization) { proxyFile.oss << "%\n%-------Serialization Interface-------\n"; proxyFile.oss << "%string_serialize() : returns string\n"; proxyFile.oss << "%string_deserialize(string serialized) : returns " << this->name << "\n"; diff --git a/wrap/Class.h b/wrap/Class.h index efbcce26c..f5267cee2 100644 --- a/wrap/Class.h +++ b/wrap/Class.h @@ -37,14 +37,15 @@ struct Class { typedef std::map StaticMethods; /// Constructor creates an empty class - Class(bool verbose=true) : isVirtual(false), isSerializable(false), verbose_(verbose) {} + Class(bool verbose=true) : isVirtual(false), isSerializable(false), hasSerialization(false), verbose_(verbose) {} // Then the instance variables are set directly by the Module constructor std::string name; ///< Class name std::vector templateArgs; ///< Template arguments std::string typedefName; ///< The name to typedef *from*, if this class is actually a typedef, i.e. typedef [typedefName] [name] bool isVirtual; ///< Whether the class is part of a virtual inheritance chain - bool isSerializable; ///< Whether we can use boost.serialization to serialize the class + bool isSerializable; ///< Whether we can use boost.serialization to serialize the class - creates exports + bool hasSerialization; ///< Whether we should create the serialization functions std::vector qualifiedParent; ///< The *single* parent - the last string is the parent class name, preceededing elements are a namespace stack Methods methods; ///< Class methods StaticMethods static_methods; ///< Static methods diff --git a/wrap/Module.cpp b/wrap/Module.cpp index 3f16fbf1b..a31f57e79 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -380,9 +380,16 @@ void Module::parseMarkup(const std::string& data) { // Post-process classes for serialization markers BOOST_FOREACH(Class& cls, classes) { + Class::Methods::iterator serializable_it = cls.methods.find("serializable"); + if (serializable_it != cls.methods.end()) { + cls.isSerializable = true; + cls.methods.erase(serializable_it); + } + Class::Methods::iterator serialize_it = cls.methods.find("serialize"); if (serialize_it != cls.methods.end()) { cls.isSerializable = true; + cls.hasSerialization= true; cls.methods.erase(serialize_it); } } diff --git a/wrap/tests/expected/geometry_wrapper.cpp b/wrap/tests/expected/geometry_wrapper.cpp index 1dfea33d4..e00004d57 100644 --- a/wrap/tests/expected/geometry_wrapper.cpp +++ b/wrap/tests/expected/geometry_wrapper.cpp @@ -9,6 +9,7 @@ #include +BOOST_CLASS_EXPORT_GUID(Point2, "Point2"); BOOST_CLASS_EXPORT_GUID(Point3, "Point3"); typedef std::set*> Collector_Point2; diff --git a/wrap/tests/geometry.h b/wrap/tests/geometry.h index 6c6ed28ad..bdced45ed 100644 --- a/wrap/tests/geometry.h +++ b/wrap/tests/geometry.h @@ -13,6 +13,8 @@ class Point2 { void argChar(char a) const; void argUChar(unsigned char a) const; VectorNotEigen vectorConfusion(); + + void serializable() const; // Sets flag and creates export, but does not make serialization functions }; class Point3 { diff --git a/wrap/tests/testWrap.cpp b/wrap/tests/testWrap.cpp index f993867e5..461f00405 100644 --- a/wrap/tests/testWrap.cpp +++ b/wrap/tests/testWrap.cpp @@ -219,6 +219,10 @@ TEST( wrap, parse_geometry ) { EXPECT_LONGS_EQUAL(0, cls.static_methods.size()); EXPECT_LONGS_EQUAL(0, cls.namespaces.size()); + + // check serialization flag + EXPECT(cls.isSerializable); + EXPECT(!cls.hasSerialization); } // check second class, Point3 @@ -254,6 +258,7 @@ TEST( wrap, parse_geometry ) { // check serialization flag EXPECT(cls.isSerializable); + EXPECT(cls.hasSerialization); } // Test class is the third one From 45b5389f8a65453a724d8d5ec1518b1b85b185ad Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:50:07 +0000 Subject: [PATCH 084/256] Serialized more classes in gtsam and gtsam_unstable --- gtsam.h | 23 ++++++++++ gtsam/nonlinear/LinearContainerFactor.h | 15 ++++++ gtsam_unstable/gtsam_unstable.h | 14 ++++++ .../testGraphValuesSerialization.m | 46 ++++++------------- 4 files changed, 65 insertions(+), 33 deletions(-) diff --git a/gtsam.h b/gtsam.h index 33149c344..dcef6e23d 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1787,6 +1787,8 @@ virtual class LinearContainerFactor : gtsam::NonlinearFactor { static gtsam::NonlinearFactorGraph convertLinearGraph(const gtsam::GaussianFactorGraph& linear_graph, const gtsam::Ordering& ordering); + // enabling serialization functionality + void serializable() const; }; // \class LinearContainerFactor // Summarization functionality @@ -2073,6 +2075,9 @@ virtual class BetweenFactor : gtsam::NonlinearFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); T measured() const; gtsam::noiseModel::Base* get_noiseModel() const; + + // enabling serialization functionality + void serialize() const; }; @@ -2083,6 +2088,9 @@ virtual class NonlinearEquality : gtsam::NonlinearFactor { NonlinearEquality(size_t j, const T& feasible); // Constructor - allows inexact evaluation NonlinearEquality(size_t j, const T& feasible, double error_gain); + + // enabling serialization functionality + void serialize() const; }; @@ -2108,6 +2116,9 @@ template virtual class BearingFactor : gtsam::NonlinearFactor { BearingFactor(size_t key1, size_t key2, const ROTATION& measured, const gtsam::noiseModel::Base* noiseModel); gtsam::noiseModel::Base* get_noiseModel() const; + + // enabling serialization functionality + void serialize() const; }; typedef gtsam::BearingFactor BearingFactor2D; @@ -2118,6 +2129,9 @@ template virtual class BearingRangeFactor : gtsam::NonlinearFactor { BearingRangeFactor(size_t poseKey, size_t pointKey, const ROTATION& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); gtsam::noiseModel::Base* get_noiseModel() const; + + // enabling serialization functionality + void serialize() const; }; typedef gtsam::BearingRangeFactor BearingRangeFactor2D; @@ -2142,6 +2156,9 @@ virtual class GenericProjectionFactor : gtsam::NonlinearFactor { bool verboseCheirality() const; bool throwCheirality() const; gtsam::noiseModel::Base* get_noiseModel() const; + + // enabling serialization functionality + void serialize() const; }; typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3_S2; typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3DS2; @@ -2160,6 +2177,9 @@ template virtual class GeneralSFMFactor2 : gtsam::NonlinearFactor { GeneralSFMFactor2(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t poseKey, size_t landmarkKey, size_t calibKey); gtsam::Point2 measured() const; + + // enabling serialization functionality + void serialize() const; }; @@ -2171,6 +2191,9 @@ virtual class GenericStereoFactor : gtsam::NonlinearFactor { gtsam::StereoPoint2 measured() const; gtsam::Cal3_S2Stereo* calibration() const; gtsam::noiseModel::Base* get_noiseModel() const; + + // enabling serialization functionality + void serialize() const; }; typedef gtsam::GenericStereoFactor GenericStereoFactor3D; diff --git a/gtsam/nonlinear/LinearContainerFactor.h b/gtsam/nonlinear/LinearContainerFactor.h index b5b9729d1..cc87e278a 100644 --- a/gtsam/nonlinear/LinearContainerFactor.h +++ b/gtsam/nonlinear/LinearContainerFactor.h @@ -26,6 +26,9 @@ protected: GaussianFactor::shared_ptr factor_; boost::optional linearizationPoint_; + /** Default constructor - necessary for serialization */ + LinearContainerFactor() {} + /** direct copy constructor */ LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional& linearizationPoint); @@ -148,6 +151,18 @@ protected: void rekeyFactor(const Ordering& ordering); void initializeLinearizationPoint(const Values& linearizationPoint); +private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & boost::serialization::make_nvp("NonlinearFactor", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(factor_); + ar & BOOST_SERIALIZATION_NVP(linearizationPoint_); + } + }; // \class LinearContainerFactor } // \namespace gtsam diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index 27dd8ba1c..c4feeccef 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -86,6 +86,8 @@ virtual class PoseRTV : gtsam::Value { Vector imuPrediction(const gtsam::PoseRTV& x2, double dt) const; gtsam::Point3 translationIntegration(const gtsam::PoseRTV& x2, double dt) const; Vector translationIntegrationVec(const gtsam::PoseRTV& x2, double dt) const; + + void serializable() const; // enabling serialization functionality }; #include @@ -122,6 +124,8 @@ virtual class Pose3Upright : gtsam::Value { static gtsam::Pose3Upright Expmap(Vector xi); static Vector Logmap(const gtsam::Pose3Upright& p); + + void serializable() const; // enabling serialization functionality }; // \class Pose3Upright #include @@ -142,6 +146,8 @@ virtual class BearingS2 : gtsam::Value { size_t dim() const; gtsam::BearingS2 retract(Vector v) const; Vector localCoordinates(const gtsam::BearingS2& p2) const; + + void serializable() const; // enabling serialization functionality }; // std::vector @@ -288,6 +294,8 @@ class SimPolygon2D { template virtual class PriorFactor : gtsam::NonlinearFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); + + void serializable() const; // enabling serialization functionality }; @@ -295,6 +303,8 @@ virtual class PriorFactor : gtsam::NonlinearFactor { template virtual class BetweenFactor : gtsam::NonlinearFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); + + void serializable() const; // enabling serialization functionality }; @@ -302,6 +312,8 @@ virtual class BetweenFactor : gtsam::NonlinearFactor { template virtual class RangeFactor : gtsam::NonlinearFactor { RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); + + void serializable() const; // enabling serialization functionality }; typedef gtsam::RangeFactor RangeFactorRTV; @@ -314,6 +326,8 @@ virtual class NonlinearEquality : gtsam::NonlinearFactor { NonlinearEquality(size_t j, const T& feasible); // Constructor - allows inexact evaluation NonlinearEquality(size_t j, const T& feasible, double error_gain); + + void serializable() const; // enabling serialization functionality }; #include diff --git a/matlab/gtsam_tests/testGraphValuesSerialization.m b/matlab/gtsam_tests/testGraphValuesSerialization.m index 999335bcd..9f49328cd 100644 --- a/matlab/gtsam_tests/testGraphValuesSerialization.m +++ b/matlab/gtsam_tests/testGraphValuesSerialization.m @@ -47,44 +47,24 @@ CHECK('valuesds.equals(values, 1e-9)', valuesds.equals(values, 1e-9)); %% Create graph and factors and serialize graph = NonlinearFactorGraph; -% Prior factor - FAIL: unregistered class +% Prior factor priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph -% % Between Factors - FAIL: unregistered class -% odometry = Pose2(2.0, 0.0, 0.0); -% odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); -% graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); -% graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); +% Between Factors - FAIL: unregistered class +odometry = Pose2(2.0, 0.0, 0.0); +odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); +graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); -% % BearingRange Factors - FAIL: unregistered class -% degrees = pi/180; -% brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); -% graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(4+4), brNoise)); -% graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise)); -% graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise)); +% BearingRange Factors - FAIL: unregistered class +degrees = pi/180; +brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); +graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(4+4), brNoise)); +graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise)); +graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise)); serialized_graph = graph.string_serialize(); graphds = NonlinearFactorGraph.string_deserialize(serialized_graph); -CHECK('graphds.equals(graph, 1e-9)', graphds.equals(graph, 1e-9)); - -%% Old interface - -% %% Check that serialization works properly -% serialized_values = serializeValues(values); % returns a string -% deserializedValues = deserializeValues(serialized_values); % returns a new values -% CHECK('values.equals(deserializedValues)',values.equals(deserializedValues,1e-9)); -% -% CHECK('serializeValuesToFile(values, values.dat)', serializeValuesToFile(values, 'values.dat')); -% deserializedValuesFile = deserializeValuesFromFile('values.dat'); % returns a new values -% CHECK('values.equals(deserializedValuesFile)',values.equals(deserializedValuesFile,1e-9)); -% -% % FAIL: unregistered class - derived class not registered or exported -% serialized_graph = serializeGraph(graph); % returns a string -% deserializedGraph = deserializeGraph(serialized_graph); % returns a new graph -% CHECK('graph.equals(deserializedGraph)',graph.equals(deserializedGraph,1e-9)); -% -% CHECK('serializeGraphToFile(graph, graph.dat)', serializeGraphToFile(graph, 'graph.dat')); -% deserializedGraphFile = deserializeGraphFromFile('graph.dat'); % returns a new graph -% CHECK('graph.equals(deserializedGraphFile)',graph.equals(deserializedGraphFile,1e-9)); \ No newline at end of file +CHECK('graphds.equals(graph, 1e-9)', graphds.equals(graph, 1e-9)); \ No newline at end of file From 456d1b5cf76b33ceb8b15ebdcbfffae9c977f44a Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:50:09 +0000 Subject: [PATCH 085/256] Cleanup: moving old serialization function to gtsam_unstable, renaming matlab serializaion test --- gtsam.h | 45 ------------------- gtsam/CMakeLists.txt | 9 +--- gtsam_unstable/CMakeLists.txt | 13 ++++++ gtsam_unstable/slam/CMakeLists.txt | 11 ++++- .../slam/serialization.cpp | 0 .../slam/serialization.h | 0 .../slam/tests/testSerialization.cpp | 0 ...uesSerialization.m => testSerialization.m} | 0 matlab/gtsam_tests/test_gtsam.m | 4 +- 9 files changed, 26 insertions(+), 56 deletions(-) rename {gtsam => gtsam_unstable}/slam/serialization.cpp (100%) rename {gtsam => gtsam_unstable}/slam/serialization.h (100%) rename {gtsam => gtsam_unstable}/slam/tests/testSerialization.cpp (100%) rename matlab/gtsam_tests/{testGraphValuesSerialization.m => testSerialization.m} (100%) diff --git a/gtsam.h b/gtsam.h index dcef6e23d..4e91e407f 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2229,51 +2229,6 @@ pair load2D(string filename, pair load2D_robust(string filename, gtsam::noiseModel::Base* model); -//************************************************************************* -// Serialization -//************************************************************************* -//#include -// -//// Serialize/Deserialize a NonlinearFactorGraph -//string serializeGraph(const gtsam::NonlinearFactorGraph& graph); -// -//gtsam::NonlinearFactorGraph* deserializeGraph(string serialized_graph); -// -//string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph); -//string serializeGraphXML(const gtsam::NonlinearFactorGraph& graph, string name); -// -//gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph); -//gtsam::NonlinearFactorGraph* deserializeGraphXML(string serialized_graph, string name); -// -//// Serialize/Deserialize a Values -//string serializeValues(const gtsam::Values& values); -// -//gtsam::Values* deserializeValues(string serialized_values); -// -//string serializeValuesXML(const gtsam::Values& values); -//string serializeValuesXML(const gtsam::Values& values, string name); -// -//gtsam::Values* deserializeValuesXML(string serialized_values); -//gtsam::Values* deserializeValuesXML(string serialized_values, string name); -// -//// Serialize -//bool serializeGraphToFile(const gtsam::NonlinearFactorGraph& graph, string fname); -//bool serializeGraphToXMLFile(const gtsam::NonlinearFactorGraph& graph, string fname); -//bool serializeGraphToXMLFile(const gtsam::NonlinearFactorGraph& graph, string fname, string name); -// -//bool serializeValuesToFile(const gtsam::Values& values, string fname); -//bool serializeValuesToXMLFile(const gtsam::Values& values, string fname); -//bool serializeValuesToXMLFile(const gtsam::Values& values, string fname, string name); -// -//// Deserialize -//gtsam::NonlinearFactorGraph* deserializeGraphFromFile(string fname); -//gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname); -//gtsam::NonlinearFactorGraph* deserializeGraphFromXMLFile(string fname, string name); -// -//gtsam::Values* deserializeValuesFromFile(string fname); -//gtsam::Values* deserializeValuesFromXMLFile(string fname); -//gtsam::Values* deserializeValuesFromXMLFile(string fname, string name); - //************************************************************************* // Utilities //************************************************************************* diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 45acd92e3..5b69a25b6 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -34,15 +34,10 @@ endif() # Sources to remove from builds set (excluded_sources #"") "${CMAKE_CURRENT_SOURCE_DIR}/slam/serialization.cpp" -# "${CMAKE_CURRENT_SOURCE_DIR}/discrete/TypedDiscreteFactor.cpp" -# "${CMAKE_CURRENT_SOURCE_DIR}/discrete/TypedDiscreteFactorGraph.cpp" -# "${CMAKE_CURRENT_SOURCE_DIR}/discrete/parseUAI.cpp" -# "${CMAKE_CURRENT_SOURCE_DIR}/discrete/PotentialTable.cpp") ) set (excluded_headers #"") "${CMAKE_CURRENT_SOURCE_DIR}/slam/serialization.h" -# "${CMAKE_CURRENT_SOURCE_DIR}/discrete/TypedDiscreteFactor.h ) if(GTSAM_USE_QUATERNIONS) @@ -60,10 +55,10 @@ foreach(subdir ${gtsam_subdirs}) # Build convenience libraries file(GLOB subdir_cpp_srcs "${subdir}/*.cpp") file(GLOB subdir_headers "${subdir}/*.h") + list(REMOVE_ITEM subdir_cpp_srcs ${excluded_sources}) + list(REMOVE_ITEM subdir_headers ${excluded_headers}) set(subdir_srcs ${subdir_cpp_srcs} ${subdir_headers}) # Include header files so they show up in Visual Studio gtsam_assign_source_folders("${subdir_srcs}") # Create MSVC structure - list(REMOVE_ITEM subdir_srcs ${excluded_sources}) - list(REMOVE_ITEM subdir_srcs ${excluded_headers}) set(${subdir}_srcs ${subdir_srcs}) if (GTSAM_BUILD_CONVENIENCE_LIBRARIES AND (subdir_cpp_srcs)) # Only build convenience library if sources exist message(STATUS "Building Convenience Library: ${subdir}") diff --git a/gtsam_unstable/CMakeLists.txt b/gtsam_unstable/CMakeLists.txt index 74fae5bb9..39fcaccc1 100644 --- a/gtsam_unstable/CMakeLists.txt +++ b/gtsam_unstable/CMakeLists.txt @@ -14,11 +14,24 @@ set(GTSAM_UNSTABLE_BOOST_LIBRARIES ${GTSAM_BOOST_LIBRARIES} ${Boost_THREAD_LIBRA add_custom_target(check.unstable COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure) +# To exclude a source from the library build (in any subfolder) +# Add the full name to this list, as in the following example +# Sources to remove from builds +set (excluded_sources # "") + "${CMAKE_CURRENT_SOURCE_DIR}/slam/serialization.cpp" +) + +set (excluded_headers # "") + "${CMAKE_CURRENT_SOURCE_DIR}/slam/serialization.h" +) + # assemble core libaries foreach(subdir ${gtsam_unstable_subdirs}) # Build convenience libraries file(GLOB subdir_srcs "${subdir}/*.cpp") file(GLOB subdir_headers "${subdir}/*.h") + list(REMOVE_ITEM subdir_srcs ${excluded_sources}) + list(REMOVE_ITEM subdir_headers ${excluded_headers}) set(${subdir}_srcs ${subdir_srcs} ${subdir_headers}) gtsam_assign_source_folders("${${subdir}_srcs}") # Create MSVC structure if (subdir_srcs AND GTSAM_BUILD_CONVENIENCE_LIBRARIES) diff --git a/gtsam_unstable/slam/CMakeLists.txt b/gtsam_unstable/slam/CMakeLists.txt index 1a92167ac..27ade7a5e 100644 --- a/gtsam_unstable/slam/CMakeLists.txt +++ b/gtsam_unstable/slam/CMakeLists.txt @@ -1,5 +1,10 @@ # Install headers +set (slam_excluded_headers #"") + "${CMAKE_CURRENT_SOURCE_DIR}/serialization.h" +) + file(GLOB slam_headers "*.h") +list(REMOVE_ITEM slam_headers ${slam_excluded_headers}) install(FILES ${slam_headers} DESTINATION include/gtsam_unstable/slam) # Components to link tests in this subfolder against @@ -19,8 +24,10 @@ set (slam_full_libs ${gtsam_unstable-default}) # Exclude tests that don't work -set (slam_excluded_tests "") - +set (slam_excluded_tests + "${CMAKE_CURRENT_SOURCE_DIR}/tests/testSerialization.cpp" +# "" # Add to this list, with full path, to exclude +) # Add all tests gtsam_add_subdir_tests(slam_unstable "${slam_local_libs}" "${slam_full_libs}" "${slam_excluded_tests}") add_dependencies(check.unstable check.slam_unstable) diff --git a/gtsam/slam/serialization.cpp b/gtsam_unstable/slam/serialization.cpp similarity index 100% rename from gtsam/slam/serialization.cpp rename to gtsam_unstable/slam/serialization.cpp diff --git a/gtsam/slam/serialization.h b/gtsam_unstable/slam/serialization.h similarity index 100% rename from gtsam/slam/serialization.h rename to gtsam_unstable/slam/serialization.h diff --git a/gtsam/slam/tests/testSerialization.cpp b/gtsam_unstable/slam/tests/testSerialization.cpp similarity index 100% rename from gtsam/slam/tests/testSerialization.cpp rename to gtsam_unstable/slam/tests/testSerialization.cpp diff --git a/matlab/gtsam_tests/testGraphValuesSerialization.m b/matlab/gtsam_tests/testSerialization.m similarity index 100% rename from matlab/gtsam_tests/testGraphValuesSerialization.m rename to matlab/gtsam_tests/testSerialization.m diff --git a/matlab/gtsam_tests/test_gtsam.m b/matlab/gtsam_tests/test_gtsam.m index 1f8125b81..2cad40df8 100644 --- a/matlab/gtsam_tests/test_gtsam.m +++ b/matlab/gtsam_tests/test_gtsam.m @@ -30,8 +30,8 @@ testStereoVOExample display 'Starting: testVisualISAMExample' testVisualISAMExample -display 'Starting: testGraphValuesSerialization' -testVisualISAMExample +display 'Starting: testSerialization' +testSerialization % end of tests display 'Tests complete!' From c7e79fb546c642a55cdbf3ea4c875cec28f9966e Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Wed, 19 Jun 2013 17:50:10 +0000 Subject: [PATCH 086/256] Added instructions to gtsam.h --- gtsam.h | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/gtsam.h b/gtsam.h index 4e91e407f..109deb952 100644 --- a/gtsam.h +++ b/gtsam.h @@ -76,6 +76,18 @@ * - When forward-declaring template instantiations, use the generated/typedefed name, e.g. * class gtsam::Class1Pose2; * class gtsam::MyInstantiatedClass; + * Boost.serialization within Matlab: + * - you need to mark classes as being serializable in the markup file (see this file for an example). + * - There are two options currently, depending on the class. To "mark" a class as serializable, + * add a function with a particular signature so that wrap will catch it. + * - Add "void serialize()" to a class to create serialization functions for a class. + * Adding this flag subsumes the serializable() flag below. Requirements: + * - A default constructor must be publicly accessible + * - Must not be an abstract base class + * - The class must have an actual boost.serialization serialize() function. + * - Add "void serializable()" to a class if you only want the class to be serialized as a + * part of a container (such as noisemodel). This version does not require a publicly + * accessible default constructor. */ /** From 278c1167854eaf1dcceb75d28ecc9e7a9c2f51aa Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 20 Jun 2013 06:49:56 +0000 Subject: [PATCH 087/256] Cleaned up spurious import statements --- matlab/+gtsam/VisualISAMGenerateData.m | 4 ++-- matlab/+gtsam/VisualISAMInitialize.m | 10 +++------- matlab/+gtsam/VisualISAMPlot.m | 2 +- matlab/+gtsam/VisualISAMStep.m | 6 ++---- 4 files changed, 8 insertions(+), 14 deletions(-) diff --git a/matlab/+gtsam/VisualISAMGenerateData.m b/matlab/+gtsam/VisualISAMGenerateData.m index b3b602afe..ab47e92db 100644 --- a/matlab/+gtsam/VisualISAMGenerateData.m +++ b/matlab/+gtsam/VisualISAMGenerateData.m @@ -2,8 +2,9 @@ function [data,truth] = VisualISAMGenerateData(options) % VisualISAMGenerateData creates data for viusalSLAM::iSAM examples % Authors: Duy Nguyen Ta and Frank Dellaert -%% Generate simulated data import gtsam.* + +%% Generate simulated data if options.triangle % Create a triangle target, just 3 points on a plane nrPoints = 3; r = 10; @@ -24,7 +25,6 @@ else % 3D landmarks as vertices of a cube end %% Create camera cameras on a circle around the triangle -import gtsam.* height = 10; r = 40; truth.K = Cal3_S2(500,500,0,640/2,480/2); data.K = truth.K; diff --git a/matlab/+gtsam/VisualISAMInitialize.m b/matlab/+gtsam/VisualISAMInitialize.m index 8da23a1ec..29f8b3b46 100644 --- a/matlab/+gtsam/VisualISAMInitialize.m +++ b/matlab/+gtsam/VisualISAMInitialize.m @@ -2,16 +2,16 @@ function [noiseModels,isam,result,nextPoseIndex] = VisualISAMInitialize(data,tru % VisualISAMInitialize initializes visualSLAM::iSAM object and noise parameters % Authors: Duy Nguyen Ta, Frank Dellaert and Alex Cunningham -%% Initialize iSAM import gtsam.* + +%% Initialize iSAM params = gtsam.ISAM2Params; if options.alwaysRelinearize params.setRelinearizeSkip(1); end -isam = ISAM2; +isam = ISAM2(params); %% Set Noise parameters -import gtsam.* noiseModels.pose = noiseModel.Diagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); %noiseModels.odometry = noiseModel.Diagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); noiseModels.odometry = noiseModel.Diagonal.Sigmas([0.05 0.05 0.05 0.2 0.2 0.2]'); @@ -20,7 +20,6 @@ noiseModels.measurement = noiseModel.Isotropic.Sigma(2, 1.0); %% Add constraints/priors % TODO: should not be from ground truth! -import gtsam.* newFactors = NonlinearFactorGraph; initialEstimates = Values; for i=1:2 @@ -38,7 +37,6 @@ end nextPoseIndex = 3; %% Add visual measurement factors from two first poses and initialize observed landmarks -import gtsam.* for i=1:2 ii = symbol('x',i); for k=1:length(data.Z{i}) @@ -56,11 +54,9 @@ for i=1:2 end %% Add odometry between frames 1 and 2 -import gtsam.* newFactors.add(BetweenFactorPose3(symbol('x',1), symbol('x',2), data.odometry{1}, noiseModels.odometry)); %% Update ISAM -import gtsam.* if options.batchInitialization % Do a full optimize for first two poses batchOptimizer = LevenbergMarquardtOptimizer(newFactors, initialEstimates); fullyOptimized = batchOptimizer.optimize(); diff --git a/matlab/+gtsam/VisualISAMPlot.m b/matlab/+gtsam/VisualISAMPlot.m index a6a677723..874dbf523 100644 --- a/matlab/+gtsam/VisualISAMPlot.m +++ b/matlab/+gtsam/VisualISAMPlot.m @@ -2,6 +2,7 @@ function VisualISAMPlot(truth, data, isam, result, options) % VisualISAMPlot plots current state of ISAM2 object % Authors: Duy Nguyen Ta and Frank Dellaert +import gtsam.* h=gca; cla(h); hold on; @@ -12,7 +13,6 @@ marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate()); % TODO gtsam.plot3DPoints(result, [], marginals); %% Plot cameras -import gtsam.* M = 1; while result.exists(symbol('x',M)) ii = symbol('x',M); diff --git a/matlab/+gtsam/VisualISAMStep.m b/matlab/+gtsam/VisualISAMStep.m index 25b4c1027..82b3754ef 100644 --- a/matlab/+gtsam/VisualISAMStep.m +++ b/matlab/+gtsam/VisualISAMStep.m @@ -2,19 +2,18 @@ function [isam,result,nextPoseIndex] = VisualISAMStep(data,noiseModels,isam,resu % VisualISAMStep executes one update step of visualSLAM::iSAM object % Authors: Duy Nguyen Ta and Frank Dellaert +import gtsam.* + % iSAM expects us to give it a new set of factors % along with initial estimates for any new variables introduced. -import gtsam.* newFactors = NonlinearFactorGraph; initialEstimates = Values; %% Add odometry -import gtsam.* odometry = data.odometry{nextPoseIndex-1}; newFactors.add(BetweenFactorPose3(symbol('x',nextPoseIndex-1), symbol('x',nextPoseIndex), odometry, noiseModels.odometry)); %% Add visual measurement factors and initializations as necessary -import gtsam.* for k=1:length(data.Z{nextPoseIndex}) zij = data.Z{nextPoseIndex}{k}; j = data.J{nextPoseIndex}{k}; @@ -28,7 +27,6 @@ for k=1:length(data.Z{nextPoseIndex}) end %% Initial estimates for the new pose. -import gtsam.* prevPose = result.at(symbol('x',nextPoseIndex-1)); initialEstimates.insert(symbol('x',nextPoseIndex), prevPose.compose(odometry)); From 6f2cbbb7096dd4784c3c51054e3ede0318689f37 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 20 Jun 2013 06:50:50 +0000 Subject: [PATCH 088/256] Added two new datafiles --- examples/Data/Plaza1_.mat | Bin 0 -> 677168 bytes examples/Data/Plaza2_.mat | Bin 0 -> 296733 bytes matlab/CMakeLists.txt | 3 ++- 3 files changed, 2 insertions(+), 1 deletion(-) create mode 100644 examples/Data/Plaza1_.mat create mode 100644 examples/Data/Plaza2_.mat diff --git a/examples/Data/Plaza1_.mat b/examples/Data/Plaza1_.mat new file mode 100644 index 0000000000000000000000000000000000000000..806069a8c7ad755e5aa6a72bf983de2630440948 GIT binary patch literal 677168 zcmb4}Ra6vSw8sC4fRfS;D$?Bz($b7lk^>`M0z;>CBOxFi64FC=!$>nyLynR|jL@8c7Z(tEuB&9oZ|~%4$M@X8)dp^0hr7&kLr0(IT0ZX2MTDLUiO2|v$_R`6tA$0M|9{VaIGVa-|NZx0 z)F$qK{`q|KM5Y;bj00zqmLjrrMWO60=;ulWRW4oNs2u+{fb?gtXcl1+S-@FMx?JLL~aXg7Q z&3S`7Pu&W8xVypzT_Uc|9wMHjp&C&$Ls72^=B|qRL8-Sz@TK6h^-rcsaf}<4Mb^I! z1@LcNRYP2rJFG3Oq$R9Qn17pyNYcvRp^Co?mGmQy^LFXPt7iY(%G|fbWF#Y*(u6)= zcufi)D|^HvK4)|yk5=L)kWosZZrYOo?=HV@)}C(#4*d{HE1#nVLzz)uKyj5f&&~^S z6UQw5gd{j^xNbWq0L%TUnLUc*Y8Y$3#;wk%{c(>_=~exkEOG~Bfn2TAV*ijKp)D&e zjrVVgejgV(y~b>EP@QM&ULHBKcMT0&{c%xnef@sF2x65h7a@~vY&&`|mzFO%9nN2_ zOP8NlTdYXS3xo0UO?YgO;BltV0kI-bu~siv}BvTvn|6mvH`WltLilV z5&b$e<*4{iYZ-GnkLn8)* zo|>often$8QVb6)le&86t~QuhdNUy%BWhKdf^;U9exYf%!Nz*hY%bgl8q-0W8YI6s z#c8e*lw%c7F(%%W-X=Mxw@glnBzKZiY^D*vFascK^QYy-4a-itpHSZvn{ zu@yY%-aU$3R-Jm$P~GbN=%$R?QgPNl1D$15wr8e_AL7r$%5H83GZ6v_JTx#2XQ@?5 zW9Q7keG3WkHx5%}eQJx2T~sA68Z<6o%@FEg<5~a2i*A#$gQe&EXNBT6Z5Y2y*8=gP zoAh@%9j!8Z;D_#>0!0#u zOMXLJoV66VLi~!i5;Q-Bluq8On}A)Q|n8mD7+tnHr-b)ySy!jhfsDsxN2Cx zLyMrFohl>b4!q9gETa10zG4VX>%rcz&FK1!pG;c>Zps?ovK*m#ed&GJkNDHx<$>t7 z_9r0FD$G+}KD$f3;}Of3&;j`XgQ&ryRhUU$U&5W&Z{pR>&-E38Z7-7;S5sDK=M`U} z6a>W9%JI+dTA!#awSlfzF2#4=hu{xym8;M23MkLoyhy$A6?YEx1gX^r^Is@9D6P3D zD+Jt^tIz(us5+Zi7S2}419X~m6??cji$U`>lFc8;_Z6GzM~j{u#V^;6CD6_i)TZSj zwg1?=a+6DZwk}~9weE&he4+JHoZ#n5qL%PtWmu?6kV|dj2}nbX3FHZTmNmu))B?&T zj?~}f-h=j9p%K?<%EF!=RRD@mmIBhwuhMdj#iII+bNkfJ;6mRrx2|B(J69URjiUj0 z;vxU#_vL`hlXQ>rdSfDI+bD{?<~PiLL?zJ_JI3ffSi}{=xA;)|N}@05T&}C_huh_? z29Z|G)AF72w`H9}$tk9{zB9A!#kYY3T@#B%24S&`pyYG?@$FnZUGgE)Lf%EB%%S?( zlUuzdZT_l$*e7aB1@b%8$7}XV+xpB%rjq&(h!>JFij1N8H)ce+gt7+B7M7!^ ziv&jVu1S3%>l(am2H81jH4J@-)ropZpuhOtW^=LsI|6jm0%yGUP{=u=PwH0QwGoJ^ zBNZcg8#Z&}(G9ybU7%esaU}WMi=?{Q{(8$5Fq~M(oFEu4`;$RP!%)T2dmprJBRIjr zr6&qaHWss{Dfk^S7o7Pj0MM-a`(^z?!i=Aq^)1O)dDaku9@FJ&DeZM?<0P;6nX_*H zVzt>XMpE;7?B~^-*hS;w86@!eN^~%&Os!0YaHK zAvL~d;i{QNp3no>tK}Kr6;Vf*$J3?50=WQWqts^Y)c6BFn8Mmjz|p97CxGCU?I_`> z(Rt7UgAf3m+}GkHe2wb?3;_T%dfpqma#LIG`&~e2M#(piJ_S{D40iQCJ`qfG|G8Y$ ziu`e1YEafO+WV%dbe<2L8@%Ks+}%!VE<%Mcu-1M$p&sA2>-Q&_#$2QqDOFmv->qp( zr9cs)p-8+Mj=i!q&D{#xLxY~md?;l_I@HmKd-ot$%N&6$WwllJufei^Wamotchu%< z5?H^Z?4R-w#GO9dkDw`VvYOib?)X7|Jt29ewEI%_U6AC*RC#1hZHGqaCPm8?HAdB1 z&l&Lbms+zCY$W)Vanb|@Mu(Y!KR4_Q2-i-y%Ma>$9DQ19e=e|G>fJ+YbVS9!bK&!} zt%uv0owb}s-cR22re}+G#?m+<7pm$u70^H<59;BX=MCNMNn|&@=|W0w>Mz=k@{`4= z@`P6ESw1Bslff!kt+gN-_C}BG2wAX5{W65U?kh9Sm88ZIf)Fccqnp}8DDNKR4 zt*qC3S>s;I_e06^{)9mnTbbMBb5{);_2rpRO1Jk_tbx?#ULe&_-WgX7#6o>)6H9h9 zV3QX~lzOlw88qlid=Vch<)BR?^WaA<4jN0qta|yD?4P+?VsdW;)ioA$iQh|J3(wpf z4;@Q($)8FJcnYt&Z$9B-zI%KtcB(QfD_{8SApliYc47`r$%9WfG<{?}47&19=;1|Z zTuffUJ8W!)?)p|@eRWf@f4@uzvx+ApN)L2`{R&wXnS?6+$j;YuBCF@txC&XZ)`y*M zWBT}C=-<_O{7|x9a%(XfRa99A#X{UaA_^~s1uGqj`|u4bps|0G<=@6!Z+*5J>HiW5 z!1X9Q{21)9hxVh_dKq-{yL+8UY{UIE!sRR^z(Y_4Q~%i^;B;Kc4zX6X!i-hyyK5y@ zIagN39A@nl@4v-e>Zf2GlW)o@akKv6JvG=%cp`aPCM;RbdLeHR-L??-anIO8HMNCa z*WumEs{V_o#G1*-S#%cpNxHr3y@=g^H)Umn$rEv(rna-luP}K4FA=q&2gRCK*i*)l z+w3H+qqU^2ZSJ%YY%8JeJU(#+*?to8cq6Hgja#Kd(ap$lA)0LW)`{(~$X$I6M#UY{ zVG_MJPCna=a8lJxwFe(-rU5imsI@rA=*BL1*a+owVa>dDQXy3h%9^fG`L{)4wwBBG zhVS25{mMsGHwv@cKK5Z2DJ|3X2D)j|kN0>Omw0adhj%Jj`rKXpou?MnMXzZz#0XRfZmorV#rS;0Q3!$K|E-mCfE+|k)L#AhFV~%X zpk1OR4B?WT92mT<@7d@B=^3h95+8uoxlI#bZl-CZez06XshH*F-yB#Y^w0;E26pe z8M|KyS8btu0b+1pyvm$gw}5` z&r}B@n8IxA-a9AyOFIh^v;=X{q;z)z>|s*nQg_NA1M#)lu}eIdC4`5c)F1nTVOvCO z$K0Dnx68&u7<)>yAg-W#Rz=K@8eTU&gE!vhn^+{JqgYE_Ka8!7)X5~K_uGA)a#9gq zvJQ(YETJcox|w@l8^$%cl^`lv_u8E-i@td$brOl`4x>; z1vU90Cx6)*S{=5~v3rzEg_2LFkfYKoKk%YA4=z~(^5=^m<`a=C;bNB{ICM%?$tdwfrEOLkRHNLnkEJDFDjg5WQ=_&qo)lpWCoTOab~}uH%YkGRtlUUv3xdXl?d4{^*->3Bw<{}3mNF*pxoYa z0R+Far@pi1Q=7gmUd+F^d?c2=P+EOoPWFAfi-a;8pFYRIh+~3dsq~=|Dc-|sme6$g zob9Ih=n?UnY2wu=EMOsMFs6xG$;DHj)A?`q7BN z&Y7|{z()wlhQ2W2;Ha-3MK8jRR!}V^_JN_+KOhw#kyEDbgGaln3 zpUYdLKRt}Ne(NifSkNWp*;*(0T18k#VoKW^AIvH^+Obuf`gO8E=aRox&C&@hJbME- zpr-!7QTT!~MBW+D@yzW-p+Um6k5bwZHHXE`aFGWyB z$S`*X-NEE5HWSNd2eCYV_{@|^B@P5_??hg#qSxya!?LmO8P2Hq>uD?=cKL(GLf9Dzc($UqcjO&6lh`xtzia`E<(m()n78X5@HFH*bc`L#%6ykSr5T@^dHKdpb99U= zihEB&MQxOm=Pgf@ASn?u1>~zK_+?q?w;_p8cnRJZ@FhDn4G;VEbJsUr2QAYjX)D{( zceVYS4Jb@+n8mV>wV$bJ)SjU>=&h;gO4h2PC%ENROiX=f> z2Tq8`)6DA$pymyDlNjci&v%!xF6#;(0-qa?(X6lTd^Nh*tbj1FGW#!=vRg-p1PI1K zsEGp;w1sY_zexNhKQ+0QFoY*~-Dbx^x(Y6)7MJ7=1!CIXy55c_YF-rnP3suBgZL-c zW@Fd1AQLB}uiW;?&t05Ge|%g4Y{^?C=nC%xs%GWJ(BpRyNtGpy-asvt8HLod)~||? zhe%^^N;XEPh>1t-eG%1%Fu zMS;du-d8NgOo{PjrvtIjtZ@Rhb)c~9i;GwL9xkJC-lF*9L2BH_x>Bjs+oG{?F50}; z96$0ehqud-&4GaItb-fqV>YyNpe2xY`ZGi7s;>vzjVaX|T9o#E#N_T^WPtBo|mNzCV5P4yF0xyy|;`6K% zD*;}W@#*`ebP>0geU_V?e7NFp9q)-7RXmsx4K*h?^quN@-E+WE+kFg8XzfD8?SJu2 zI?lR7IwU>?VM3=0t1dEb#(Zm?vaNR%6oqY$t60sA4kO9zKUT z3j*3_d|eareZHQJa!^@afEH1!h_2sZ!gHGvbCFQ7IR;6bt%1VUBQo>3L#oI~g7x z&`ZN)Kw^W1TYQ+z^s8m_Nc_G>r+ZfqSWQsWY?+baLY!1gz058V$2WBp!=z747u}VvEcGlZsMRPm3MeupX>6_X z@Qy}QxOz>%qCQ{ChF}ek`Mk{yj#)=~MqiTq1n9+gT0b#unT?>vL?WpYOXD=^M*gX$Ff&ZYU1(wNP>6Cf>HH%Xj&9nu5RQZn-H?kMpT_jY-?PNq}fA! zSHEGwVY@MHygq*}(@&%O)U3xU9u)L=VZp3%LNrcySwroj_um~LXoY^e5VaMss>X61 z8gDw~GGtufxyk|u9ih+ALu&1wr*iC8mM?*ec{H`MVsT%#)!vPRS}8*E@TTsjBgE?> zO+`#zkuVf~W)PVOXG2K>FK}o%HlKf0FSITPP7>mBl9_+u z^3I_BXZX)v60SV)Bz~e&d(Tie!We3Lq3aBMKH0q?8I#P2zPlHAcM^0$Cw1zzE2yEY zTR?OC(J)p1H*w(V9Z60HG*z|3G@jq%&Auj(_RyI8Ye(4o)i&zb)@uQS2R$ zW3FCn`twj3Dm89#*dmJOVkJ>5^kFo@n6^Ug&4UuFpvmt=KN31=;HYMu0M(w>9=Tr( z;o=HDldR3?grEf-f7VFGzBW(Nj0EtnC$GTT{t(1^)GrN@$g^-jlC$P8n$AVLq?^4y zeHW?|J!6PF#@uSVBq<y%`ydC#zsCIrUtSPjYaPlWf$MJ3;(^sLSl;$nGg$owy!@iXy zX>&%Q_LXQ{hmrW5POE5KRyv`E4jfACa`ayFR?zngBAz5utGL?+vEnN-lOI&$A+>px z$_HD@I-5Vkjr)m))kkg!bbnS0?UySv9XSsOjSKA+QV4$7w4mmwA_8!^4s5Orn~HIT zhTm!%b@0_ZV`DgiAg7*<=~FAdDG)Uzdk7I&l2`!!#pBdsB^TUMFyaA+8OD(-E|y(I zP-@V|XTUi%qsu0VAiuWJa~;d^Mr3iUr5=h#Wev;W@!olJU5<1G)akL(Hz0B2V2{@; z`5ZdIzI1mw=^9d~Du#v>1|jpGaU1$%W%GQR_EvQaHGRUstZp3WDYH6)Fg_jAyI2}(m^}Z3J;mi2egmU17viPSVt%4r^tNpoY#EX=ll>_+J{*8`6my^?U1-hUbb)tUc8T0aj2 z=aM%ptqKK=M6#isw2`Q8v8t61BUvO8I>�E#e%!J(SRkjF^anp;m>wenb+nRoGEr znMh=;g|?b>C0t$3i$Mlm#0~SnjbZiLAFVd7Wdyt%KcSHlmg58YYU;CPka*pyG zmU@`b*#RU$l4(9@I6aiCZ9__TQZ~0{Fg=W3c-?ilnnU05{+ppjAFXJk^CxnRX4jmB zL!~q7?}Z9Q)q`s1NO?|hptW`N0eDrQo}Xzqyd}?ae6DRm4y|KY zkat%NC?R1smy>ep2a8|HXMY-UWh0fdCkpX62fm9H%k%pvf=gh}D0~lKRCm7wu4n%g zU*P@x>Ah$&SI}lm?gk5!yr88vOB%yefz1dkm{C0xIT+Vn*}%5RD1P*C>W~z&5TiC5 zAk?6is}fc;F)(4COlJuk&Lt$v%Ku!?SwGH@DJX1fw4Y7ay%ee0T!BsWfr>VABI34I ztZmm^SX>oegro;CRSw?ECYg3G$4plE1Nyww1&*e*VVF_hsZ-ZMg=X4r3J1B-y8v5m zQrESVp-vhL|7P0qBYQbrma%fWX*AN8IPaH6v)KcmPk+_$&V<)-KZKc=6Tk8H{Vo1hphhC~wHK4T4K!ad z1m60lPq<1(BM~o1C+AvIc5mtu^jGx!z8ECi!sWuNq1(W$A$Y5dWzABA%GWNHf@7cV zhOG$ec#$_RO%!qVOSa~$o2E!__#T@bKv&6j1RFyOSfZP}ruyxn-()ddAzD@gvMUv8 z9&Pjm1SgIPM=A%8ZWGsoDrjo1^9-b1pc7n*V@JDr@X9yc2dDtY)5d@6ft3UM?&0lR zR=Jr4m+>QPuT2OqKtgwSN|8s3dQZnt1;>S8L#IziW^6iL_F z5KJxp88n=je`?EK)>-ebG8UU4JV!8Y23E9AF{(VF6P`)!Bn%)&`IOOYBY2@(__DdF zw;z9*P0?(bm5e6f?wVo}nL|v1k#QOQQ(YGPTK!zmhhASk>Eq$98sUaHf*U8{Rl}5N zjbpBY-_Xsq-O=?s8U91pUDLN7&_j>{)tznI`6i8{=eK?)PUbey7Hepx`eb|BjTS$L z!iS+hGO}4dw~eEepq;{fCkX0`7uc_Ldw@B#Ws^g&Bz4IV0{x)u)5^SYqL5jbvND4~ zl&Ec-drjTWrHI2q`Ep(f+F5<4sgvfol=pzHVicI@69T>jj=Df(rlQ7CE0B{+vW%BI zcD2^EqxGj=U^y3!hK*SE{*fN_9*CJMuK=`Kh(O{yt`s`GRIaMlDz$6d{`l*`K!wAj z7m9ClI+lyB{C$Q(Rg^G)yV`0&29X}wp8HX>>1QHo|btrr-D4Jq* z{MyO(zh*R5gSR5|8G6>yo#S48Qp@jSV$Xy}*f2Y`Ons$$hW-CC>x{ zX%8eFdNWI9JsXhgwWSTgq_7b6iGxO`Np+@3fq?ielEXi}EE%(3J&%J4me$E%L$yZp z7Jl=~3&;Z1FLX(#W{828H3?dq0o^P$oTmeE@0j6YqT!=5qvrYDN~}%GNz;_fIn8q6 zP16b35(HwY>?Vnx&61g`i2Suv?v~rq{sH8dx9C{1H?WB(+zDTe`mVo3<3LmNn)PJh z2Q|(@IqzmkDD=wogZTE3FQf}{6a$SU2^%91dZouD=2)Q`k$ad z2m9mh^-p$W_y#wbrMZDU70@;-QQxrTPi&01bZ5m|z5N$z)B5(cq~NGAO5B`&z?nkG z`%>tRl_*XA@xUtMBY4}JGo0;}z+(hx%x;sE$((NB@Jj*%y3{mPUf!M$dHnk73MW(W zZSb2AZ<8(MX+1u@laa1vL7Ves2rJ;mx@h2j&98J}F8(kwTL=X{X4!Lux% zj+~xr!@ZujWp!BU1N*_8DLX!;cgfmSveb9NC>IMFnJ=;c(}j4?CgEd~(U75z0P3Za zjp%snsq#iE!t<5WOy%X`p%Gn(Ep5s@EIQyT2qzyovSi|-r)(g@X4nA#|-2|ZGt36aaYH)kpB6S*~m&$p|QK-#lo*o>5kfPciVlq zz%9Vl%FS3fD&uhykHE;13^P7MQR$H>%B-gA&*LQd_i=}JGMAq1K(Ce?o0{~N#|t~O zwxhz#gnMRmQ-gwY*3neGRu}cn zxy)(d@oPkY`sI@O=1Nmx=v|f3JLg9{S=6Or<)pmz3ToR=P@rR3ew>gtYTIEoX00NH z(L(x7=xu1gqg6p3Ri{qUni<8>^)AR&2k2?;f-K-8iqnuZEdHnE1E;@$<`5EMZR4me zs?~=kDCj%Co2hOFQ7rZG4Wdb=C9<)R@|5@bZyRc~h4~tYz0J&BXHjcTb!HX#K)rM( zU5yE$lK>(fGzRe)>&Bs(lC;2?uSx9I-+*IlyH!*NfX_#NC~r5!>BYIfbD^wLATN8T>0&uH zv+-?UU#ar!#U=EXK%bU=JDh)(q&M%^9UOZI0^H}aoY;|08(*B_*<1*6(_I-P=l&;u z*d}A~{DD^qZjl|48{|CIR{@Pt8=|@PDM&g)lmqKElUt82>7<5!zYN%^6TUVXg13hUPQGQUJT@A(FW zV#W9ZI%!3R>P!0@wguNYB_2=9&I>!-DO@@U!pBz8JA-8aE;fQ{UcG6Ds!PI zXX09TY!(M@TQVz{(l563w~`ExJdfMac9@#l+5qC~a)Loit&T>t274|V6EmaC$#w(N zQ5ziwAM35gcD=;qux5qNU>=^1t^NWNA5|;Q|2V2*mi?P$RCzQnbn_M;ol-m0XtXTs zFv;64js1Ja6`KEPCAEK$r~L?dJ;=*^X>(&Z^-n{J=!$DCN`4H@zF;;FQwORgKPpEU zmUSKA6K=$;v+J{J6o>RaioS6+DC_z}uf88NwGk-<#-HZwCfpZ*n>Uh;!ht_v`vy9mtGA{pi*DXbwhqRQkj1PL(a@TD;Z!4Z-|D8Kz!W9`Esm~P#`&X)63jyI*Q zU_SOkzo!jXQDMA7dku`rV`QLAz;frn^zpUDq;l8+4ppsqsYkxHzhNqV;0~4 z3P4GYo2c_RZ-vx>+uir3`(FPoq8K4Qk(1U~S=y`Yrp9k7kxsZtT-ICXIq1{mk-trR z3)0N5i=MOj1|Qh&DG;zV-o^4wT}y?hE2$F~Y@bJ6G_whT9B2p$mJ0O+)5%K`uF?)h-QGL~>0qzaV~|na!cw z$QVTs!gC%nk>eJmCm*#{YEFkxIF|NY)zv7FVzgtAojbbZU&tm68w@C%hd7SN9KR2J z(tLwZSHd*19NI`S%PLH&&%@1HxMUjZL2&K8HXoU4zXqskk%yc8`ruCLdf>RqG@qEP z`|D-%Sb*p+QVD&}JE-$1rzm8|57(DeF@gohuQBLr-mk{1!fyN0+b<+sy+L&HF$g8d zdL7x(S5d(G7M6kvrol1Bo5sP*+ybM?oE5t3Q}s3POJQQnZ>=sE<~WWn4j z0$G;aHX;JJ5jMY?W2-`Ueh-8g30FB8m&&Lnve0j|?Vr3XSv<|6=u&H-+9v)mNGc9 zk2P{khTXpZ-&fI;K$rTMs|CtVHm}R^~q3@ zP+E=AK6a!SP}3rRlRuJvVTt_0!Jz)&3=-N-pjf2Ux4r%@Af``E(td?`Bxb||DEzLr zohcwz`z-nS!>?%gQnl(va|RN%9{sZ(;BH(dIZ}M_4;@=}6b^k$%aftnkdB}yf&|PM zFXYR{PizTf>QVKMp>ye45alCPiu$(EVYJnhY7LaLn{=*A+yD{%#4Ai!QjZ~a@r}JPxS^_N< zY`ki~KbE#pSIXaatf}|g67u{>i}Y^7@eyPN-3u0aP@+nuF0mr4N2`o;K1K93H2#6< z4VO~Haz&|4lq5)r)uhuGR#qde9HfhD{R3^oB&KKQ!h3-MDZk}VYNjphthf#0z?NA0 z;VyZEP3Vl^(E9K#*9Ib7I!s=@yuDKL>Pfsx<@9Y;_jj77c=}LmMMXKcCKl}f$u`t@hQ)utbwC+tULegTv+<7)G2j# zT)L>NP{W0sv2_2y-)MzC2_Y1|Fp|58a##dqLyrpxN2#4w zb*K@iH-|SwFkH%Hvhh|+n5M^3xjam80(z%kY{f3Z_qUm@d_Qjv1Qv{mPA+` zY^7TZ%r*GEnRv#%jVq1q7XerEj5StpObPdoxMR;U{X8I!$7Ekim^!mIBqpa zh2E}b&FT8+x&`$^+y5s1QfihneJhscqOGRi=sj5VPk+oo27Tg%>J zAmx=3*G0fjGVe=GQ=wL>?s-9=kzvvIshT3i8B{azv_LtW#vg||KEi2-eJCuKAFG)o zS`N;2+Z2Eo5rWMKQ;Dxp5U$yU1>h=wvd%Qu~jHH+^J)taT#ManBr;{5<^n=~ymz%s9c~Q=itqH;w|C7PeFWJI@9{u#kwBk?gB0l8J z`hv`N?D$MqJve+6DB{u+d4%K|~Qdrtx~Kh_(i-UFw&bVg%P6R>vk)Ih)A{Zbyv&nBwh0=#OO zw9(dsk63@pom+4Z4xD_?3F%`>!SIJnVkc1t=j9yv1vHTff(EEZ~HYKxc4OgB=;|XZR z!|$1Iy}nw5#xDFimc@=OinVbz=lRt8yo9cz3E{Iomezn2Pvf!_-9Za)h6Hn70~#<% z9`>Z;hx7TwGjM2HjLZ$8j(IT2RUY$p{5$5Pf-JF1^tMapzxXDIb^q@ROn(63UhdDi z@zzHm$_AV5KN=$=%{gYq_VJ87sK$_v4)B&V@#-=RN7Uk zld0DUWu`w$X|xsSCQ)dM|K3}QuH@pv05J5z&^ zPik}O2CB{(z+HZnvazI=?u(o+naY}|9O0&s6X|*XM8*#2RQ?rH-hTaP3^{?Yr?Kpk zLw7x}UM#IDr;$dMgK1>$ukYHOcK!IycIBH(|0Wt)CQ@79H?rz>WZEUzg*2q1J3mdb zVw@HC374RsuAS9Y8eHC&pGJyF^)}a+SliojJmB!nW$zt#S2oK?A=3BK$x|0(we^jQ zshNfZLslASC>zr&;!1sHsA@ZUq7T>&cs6a*4*NbLUeGB=9$!ziT+-4;6MZ3LARj#9 z{E#Pu%Wu9^5@gJ8T;%~WM3B=jSWDqfi(^8Q0Vmf(NAdxp{7z?p8g?L!=4Cb174eb*;0MO76w%a{c5puKjdA2AUx zOKi#Tc8?QNO@q>1H)o>4N0ixfKWQmw8)$yjGmp~Je5ybM&@_NO^LV^=(>;qm!pQ8e z@2@ZW6db*Il@-p9VoFMT^9cGL*4fDXZmLXl zFY((e1Zhil7ico|n{7k1WcL=5B>rrqCN_>a5CxJ!Y}dc}F7(L;mYE-Is#WzCL<)=6 zI$Eu!6mUM;th6Fw5PM7~zg^2C*3g~YDwvG1ZYQA?%aIs}v;4Pac}%Hvu8a5c(5f`@a}O4tWho9zxzj${pG^M3N$ zaT|DpqQ!k$ZL*IN{;MNa_tUnQX;If>*~`wHhqb2*eu#@CYlimd4r2kOiwBF#HSb3* zGl*eiS1}n9_l^%kaPS*SW(apwqr9P*}Ti?PbeUb%AXRTf`Y>h&%m8^-REq7I^>dT9FfAk*vjP+{7YCB@zrfyy}sk`LIZg=a`95z>tkN|!TOaE|srGFf%xB8=MV>gZD-^BL(M`}Jn ze7hbx_NRS$Bg)9d$`MBNbwzd!c^#D&@U77pc!Ev8;u050lf5&t`ym zEwsaecpjW7XYo}<9%EF)^n96@wnwGUK6$^S6b_!%6YKTE-~DNoY58<>Fo;k~^~%Lw zECh_d-5(Ig4tZhUo^lkQL*X)(?l%j}yLw^v?S`@QFZV&A9~Zz4g$Vbkf@NIyZuVE z7C3a?i3;U~t>(qDzhg43^|o0r{xd7JZ!4mHyI&U2iYuEW;7SF(pQXMoa?Gl#yS~_4uYpm)h zfKGP&(-{M;7QXs1$L8D@__eA6gE(nz$ZYici{XU$i$IZt{{51BJOX=Yr<@hx+IHKX zqevTi2Xt9OI<@iZe2RCtzgV$g9O)-dW<<$^%t0x~hrzSmyGhy0>|QHOY%y_Jqm(0M zYNP(vzbfmLCYxu)gjcT!xITHZrd>e#3Y09ysvFBJ^`VaF$msW-X@6D{y>0+}2aRK1 zW=VJH01rJ3lA@otyRFKUH7Gh9nxM|mj(4#Zp$Xar9ncXNb9M^ZdBRN=wwFH~``7>H zjk*s%r?qrMvKo(tO{5D~@{&!5k{;{$m7rJR8st%&c&&LvLU%xB^^J5he-jKFphj0I zqwBvi(IdGF#W!T1Z$_T*734=$6cGwJ`Y}7BwE73R)8K8d@EEgcfXgv5V$9iD8T(UD z#1vW?ni1TuU2K>q8nk$k{Wj!C)=q|yJ!;@|y^LYI78!;0hgUR$ZwB#=aE$9~hT)Vy zRTgGtDW)&p%?Wq^H)`Z#YAPVFv!3!K=}cd#-v_U1yk_{4!-@TdGcN-6i96@|EzT0h zVo9$$nt$Jl5QGu{xt$O@?4&YMXV|D;8Wk zXq>hzp7wG@>7hM&TVN6N(&Phl17AVy;ru4j&L1h#_wHm&}AQZ8hY@HJ(lpo9uW9SwX_X z+FSW;7d0dXBtHTDp$AdmB9zUlv;~`!XLTI{MAVHZCi1JI2wbTMD}u{taRd<$5X=f)jXSI!R7}UN ze|2QNqRFj9jSftygM+0yQu@9ZeQG6J0_m(;8Rjwqyug3-FL(35(p{~aBWc@c*+a7d zl=8KOH)*m&^E@JrE#8U@tD(bvO2adh?V%D3OZ~~>L|U*@Z~Ell!vY_zS!a|d3yE8- z)>7Gv#LFJO-Kd?@*DDLlQJxS@%;j$;RnPV^#@(zkT{7mxhoG`b=GT*A-fb#gq{LRs z=}nAOt=J(gR+7vH?`Y563nSB^BEoE~#Jy9~ImWvo@qf`Za~>8PV>A52ncF6Fe;|Hr zcVS;6->2(L6`I6Ivx=AbFWi}+HLI0FUUSIYPYSX1(VMsXWB1y+`U%b39cG zjC$KEq+!0F1OgYE4Y%~%HC@|?P_IFev}@LzW+D*b*V&W8_U1%;M(8%cexE5HliTab zIIk%!$H8^}zOW7w{>0IVZbk#~Zl?LRHsF*JB5%h}m?l!4zVYw6k`5!7WZEY5Cs@OTy)&%r}00ry4A9(Eo$ zYG924qQ*tC5enydQXf{U1lrxkou}Gd$0~-{99?g5wOLtxie&TwWqcq}-$mBJiV{hf zqL<+f;;h63W*UJZhR4$3wXVGr@- ztq9|iT9icF0|i{8FVza_xM-X-&kFsE@dIGJf3dZTlUYN*ahtn7!)Uh!9zUpA zY#q_jbyC;3I2%aR5)D`O{_-;KcjRt6MbqJ?E*4uXMTh*Rd=4N%Uyn*g6)Im9x*vBa^c9)wV(oGmU55UMR|+*YGHR2ipk~pd{z*ZL zQOPcP0aK{4THbBDTJ3C`^vS3I7d;yvD@k7q7Hp0=c4cx-4iQyXqgN8*AgLZE8X9h{ zF)q?VENX+ueTM{{s=tr&DmLF1VK&nv$^p2jVEDnW- zMwZzgW$BSRZoOED2A)nj9CrSJ%wDdNX#y?B%+N-N^q!A7{3P!fZ$w%~Mspx^QqElU zy^ZAJGA$0>Il)ruzl8pS9zE|&3UYwH4)E4mr zk7*c}LiugyiU_5zSn7w{B=Pt*?Nl1xl9w@1;nb$WK)-Zwyh-7W4OXhUMYeobjMdN_ zvd6VjuEWPNPL8dmUb$W66AHu zRD_$O)=!a?T*Y$pF~XfMIhc*PHpb-N4EzK3<9-dzE z$bKY$tOBLF5L*9azW^(VlN|Xt6S~&;hnYNT01MsN^-<(ykoF4r`dvUi~WtQ;rkzn!8buKtBW?{1Bgyc5%5Ij zP0F%^yZLx7A~-$9FSu&@@Sgzte6WDgc_|ZnI^tT+tlMQ(8%!q>8QPy7=L}1d_CCpZ zsG`NN#!P|pyyVGUVo!#CR(YF3?#O+ObrW8=d*Vr`?Uab$Gc8ppD(`1!IKWc-8*+97 zP~CGbtI{pCAyMK4L-v%}Vo%j}1(M9XNZF5AO3r_Llio4v-NIrN{||l7*nNO{4t%Hl zJ#bJPMM=&cxRjR3sv=DORQN|0(DMl{3G;kOT;4$ZqbOHy-#4&l70(~(M&w3CC?#mU znMhTdSB(==l2)~CCCp4{Mfo)p^cSWcZT8-wEl{)jO_0t9L)gUppo9co0~lyg`gD>3 zqs$+epJ9VkOb}9N!j)&#&1twWw}ai~6CdqU+q_jHNO*7?`X2z8Kxe<4&wQV=X!uNq z;ZGLfWK;(lRez%A(>`GqmEX!x|9BA&$~(|)qX`|Fe8Vj!d?LfvKMPUd*Ma$YCRCUE zK2Kdb848SrD01nrt~Z-d`l-)qi^IRmFmiJdCWUmMsL_N2w|!pVdsQ+_y<3Q_P8}#* zX2PjEK2nRLH)L2lT8JXY4)hE#p>&$xixx|sO2GQR7Gaxx2Zs8au&mT~jm7jX87l7- zqD0k!`5R3b)8G?9K4mg=aVoMZ?7*@`CiJZIi=^MxGR*z95HkfGm~S*;jLv7R#i$|~ zhSnZNgG~qa{nLa2$9-QShr=@T)E&kG{|?l|nykN{@O_!S<;!sD%fs0EM?2=uGvU4W z7e!G|vkV=s9!AOU?bsJ(LYq?Wf6=#hWfeODkXK%*v4M(tcX(#H7%~pT$k0aL> z1$tjBMmJ*@roL>qo*d6g(0ELNqS0b(Z0kb3r`-mN&L{mb{g47h!^Nn(+l8KM>|Uc^ zE&dq3UxBT6i*fK=7uLRL7teloB$&Ep3r^iEM&)o920m}Mk$g}2qsOO;jn?~KjDZ)r zFn+$>CgyUj1lvw4a8g%{qk~;|{qJ@%>S~r?aM~73y-|!_qg~h-YL`I&Z~0?c=oZYW zD#rNuZWM>u$;s!W1XH(f!KSOlm~gVo`aIBXGvB!sfWuvh7{0y~9hMm|@0ef_^+c3-m7>nyfS#>_M2m{%0Cdo8!}_O6u_?}gksGFM zWiD<;o-!?mCW*{nt=4Yle#RJa`5tS0`b5ayd5Yu3_f2={u>% z7>FLJN$CA_1tzWR!RBOPip7Aj6=;~b19MH~s0i)B#w1}Xd36V3K+Fz||DzlQ$vrr( z5vK9pKoEvsO-8r*71+3=2la=9|K>a|2cd^48Ji}`Q6JcY>W#wJsq54-9BfaHV|FflTqzjfr_dgtbbMbCVknp4AU_5G~9kr^;m*@PZ0;!6z`TsTUQ3*;&l( zw?XKpRAHoCi{5#?nC?4!7x!&O5SAHLSe2yR^}qLaS@XBgW`FZ?lx$O>$3`uB9qh${ zZu=bicRLt!K2V{{Yg!yo_hO*I{w?};e>nzhRbl?CS`_Z?#i-D|p`Lq4oeDAR!6fRR?)!SM$p6bQ=-|f}R)uTZuh)`i`t`;ZL`q0H^_B+&Xw*mu~ zs4zEMi&a;9vGynXJr+gZ2cg1!1htk$AoM=uIm?Dvt+%@vpzt-_daEjn-S#e{nMcj@EM3KU3GC|RY&sI*?p zIdA_T=HR>KSUX*XQA#a_7WHDluzemm&J4ofg(`Fo(V|OAFUH@ue~)|U7ldv$DpV}j zqV!NN3Myvrr(c6X=xkPEW~dhHxAtOuwfzB$skfG6t*r_JmuayiqZiw>_W2f@uPw*? z-;@{`qQ%T@y{P}d{vh+b?pYkjOu@KcD=|;hkDfBeL)3jJ7+ZBIhpgwT#5UJ{3|#N{ zKKbkk#<&wHXmhs`Q+M`bU%X=hxr{uEx{4G`GFGDgaz75lIv%!o@9ki8C`+;WQzbS# z^yBr7j)nB$p%ANODLDCKB`Rn3W9xdyBL1HhjGE#UwE3YD71R6Cu*OkC{aL{%El z+_|r#aCJ2{t{*_fUZ)a^;XNTZY)nJxl4{h-2QX%@(=pB~S&1<}q@g~b8VBMBFy}p| zQue(Xf(c`3rPg~=jfPhSP~GixoV*PonDl)brutN4)w%&p$Z{$p4}Azu{+fpOp02i< zJ%FumI+b((+e1)VmW}~GeT<>PTbQ%(p$g_@*D6dunvT*tA7lQETR6Djp%2J2YZZEx zq~m1VNgV!Q2&K10TITys7$#iHK*5R{%sn=Q(i@@^%>Q5*=K5t|p1cMXM}{z6FREnz zZ-rrrZw7j9uE7B9kaevWeaQbF3dfw#3~WuP!MNi?X!G>LRebNyFl>4z0|P#&!Ls8+ zIM^wwwpd^a!#JM|^uAkz!$m__|IH&GS#&dnVQo|frpjv2p=b!b+eIIfr)@Z@y)&>m zsRrvm8^WZ1k&gb%499|H8R#LaLFGq7sB06Qqz|287_%?~Gt+BOaCitsZK4|9yAp;D z0U6k~wFaY(4B_Nu(IN#WZsM^KsR+Q@u0Nl|$_8wW&nSh8jW4R5%9M*q)B zF>f#%y=K(my%$C>F30sO>(8a=Fp`a#)9SGH`4Q_n&Gnqc(X&#Vx|wZV+ty)0x_z6C%6WCD zSB+q!joU@~H!lJen|5PW(;4iW97VT9Zq4*PGy*mIc4OO~GuU{26!Y&t`Z@2rMxaQ( z8~e_jLGc%Naquy>7VCUQVA9^*C@ngJsa>NO{@~F|oco~&3~tCcVf)K2$y`lwlpaW~Z1 zH`Rc-tH-R*)7?8P1|C?8nO~`~{F@4chSdp)?!|#8pnTWz<@bp*5A{f=qA?}qR{K$UaV?3i=i+7 zh?Dc5_>%e~qEK{TFE)RA76mW;hy^iE7a_D1xxk2CyXJmHzb;0j&5U<(%KyCed7KdgPR+ee zo(H2b@a8^L{Mm#;u@Tj8%!`e^Iqk66p zC%4Y+W!_FiW2#{vCY-&9!+pPCz=HXG7E4yHL(e$}(B`i#Shi#Wm09Ai`QMdT^uCaf zUQR7v|L;AkS>k@`tBl2xd;8Jj;TFvIn?S*C@i!KuF2`czo&6|Y--3-k6BwE;9w5)t zu{e2aKTf%};P9de6ud6J$@xoSF?H4f99-0bUh5_>@0j>o-n$%&#`y#PVL5tT9$D;1SesrGEf=15?Om7wsasLWp(c#v9O#kh3 z)I2ePHVW}=>%E9Y-P!%x~I<-K=n5*opThhI?@{W0Rfb}9Ax?hYj`hYVRPOcpp4?uMq4%CbG+u1S zsh_4$5#@c?VqBCAuV)ux-lcYQxjlu!$$n$JUn@uDO%3M0tw;4rGX|?9_js<8qwXsW zDmUq|KFo}*iIN|fL!BH;dNo!b(PLBe z*`dLDXFa+sHDg|ipONzlH)Giq4L1Enk2XupICw?!Gp208$jch54th*qY{se!e!p;E zOXXO0Nn>@E9&>!mI4G0+NY*mp>dWepmfnyI(Cz>Epeeh-+pLvr*wr$LXYPV^R= zF*ng~lKqP0Xmdt`;q&w;eA0~SXusd+UxOU`T92S8Qjd}aX7t?d`#X8=lVji~8jKq6 z#7Ivw##H$I!Ff;0v7}yuarZm1%-xIuF@94P3--#fq*{Z+_dBuH-Hc@lUla45Bggm; zHCBJ_L>rMA#}j=2BoY;-m&)V8k?~WyyG*5x|LW;33xf?xB+Rny3{uu7A zK<5?3*e2^nh0fN2yf!UH(IW~}1{ULBVmCH_XzOTEcgY`HMGACTT8!E)-6*KC{R=q` zO3?Us1?m`}ux9@6Y>(heuFWji6ED z;Ze7_69w;$o8;18GanU$TTvceg9Dp8arEf8$u8|#^D(o3D_TQqFjU%!n)k;&?y_Oq zd=&h+6@_6n=uGLv;&;dSxokbR0F!>&io&OBur9R|VJF4-(|XdAqu0m zV~pxO6nx!WD9yIy`~d) zXA~-1^04-QwC?p}3tHp6gm`cf#vAj{=av?SW#8gJoY#{s#T`+YdpZw=3yz^Q(1MaU zuNf}KiWXtg={!`&97AoE1$Aj&f#l^%6nbCC!{PtdV)bJdG%oWBq7FsT=s)LWRQG7H z=P?VGNxg!JzcmWQJ$aaLQ;Y3F3o4~vGr8{@i?H=V9@gH}V!}iVD&o9mk;iL`P_N5F z$yE;XyLmX;uf^Pn7M!=%`!AfoHyVpS$-|0nE&Bh(f?A2!YVz37Ga?y7el+Xm^96TJ!`z4;l3Y7J@cRs@VZrt8XpTvmUzvfjs?*e-}y4?tXd56 zv0%Q$E7YaR9EGWua?xo&ir$Y}uq^N4FzPaYF=n33bFcffsPVI4?qaWS{=0P%wtkiC zHtQJL9NlOhphZ>`WKEdQx+xa>z9~SBy$<6STQN6t!UE2_Bw65|_X12E zuET_9t?033!b0M>9E(Bi1(@r10(~N^Xx%s=(xu;G3Hn?uz=JTx{2Bv-+21vO9@tt zS778b^*HuQH(F|Zm(w>_B^b0!f%e_?XxPz>AxC^yxU9RnbcK6f6=?L*;qdlu6ps3? zq_0{f=ybk{_L=o)Io^$hmA(nY)gr;jRt5S5*JI&J-Kaj~yNdYgmZ5N*0!L@mV^DTC zroQQ$$UL20ip3rZ6btJy@Vu?)TAxHT)+x4z0Q!*kL(^3F2Frzfh1uzT|PJ zsM~=S^C^^0yoKrW1*ycjEe>_s9XKk|W9`mf>^eMoEq!)rIocoDg}T{#3{C1q@57VR zc>n2g^m}v{#>@5SxvCcxm6M-yDK{?1j^7J0XQ>|JSM;L&?a5N=*R&kvzZaq)P>&sP zz38WzypB4)w*p1K7Gl0okIJRJsH>d(Joj!`j@3`^Lgh3)W=eWdRrL6J?saZCs*JnQ z-}Vt!Jah+h*F2HVT<=K03d3&H-~I?2Jny)lCqA)({Z|uF^5`BEN1a7Op$)GepSqF0 z{UQ;akL*F=g0mQ(VMD!*C2gR9ZQ9AxEiq-{eq8@)wM)`RaN^doy(dRCzQUf;AKf98#u33fR z#zyz^8~x}P6p%@r&1+C!s=}O)8u9u!{iqfN$cS%SGTJ^?Vd0HN)Q!K3Au9v2$U}58 zcBoWnt#5SuT|Y{L1G4!(G8rvpD%5v1V$c8fqb@E$&iUENSgcl|>bpi1{?U)saRFPn zXHGJDm#9#FqY-t#^rJF1;3fL(#bop^QMt7=qG+ritD^(9x}2Aty!FAkIBagj%%Og? zN&<4|uMNqlxmJWhpEsg@upgDn0=Bs<+mwtQN)_f`X~b50Kk8xvw)4NXWQ=@Gg~gW} z(a_(I#^`{*(SODiv{{QVW=1nwlLygwLYPY&=TlJruOhT2G`pYI4&uPvC-YpUewu>f zZ;MbB(2N7C2C=nL_%eC)AZr>5ULOygUIIpt^tDkH}$>Kq@mkRUU zbCQCRYem>Ky&07Y2T}Bfu)w9q2Pv3qE<(k`W{g}ih=TpXzmunsJtLEtWYE)9oYDZ#>416JG|!l3biuW|pAX*iHuf?Y-fI&Tl5WPIRm z_x+zk%eE4XY%pNbcSG3p#|$O=lhQE#r4lrrF<|?DhOpw{z}Gonl7@Bi5^Oqczy zIs;Z4enw|&@IIHJKT0uvsv2uowV-hK2ujWb7g4`nDOS%_qxYT`>?<6>jMKsUnXjLv z7&A$Y#tki4v2z65zYH!W|Do&9=XEtUt#3h5`G|XM4ld!GeyLlr8r6v{Xg@rH!q0-= zpwIp-#j#mx)URs6vhooud}QVUmkoEM=s87w;K6+{=D-Mw&jzbqrrM=gJ4KC=t6I={ za0EkqW*uZc?np5=SdEtFS};L5f*Q%p(g)|Fe5x8V(p#|o#0XYg3VxIQx211B_#axn zZNc_8M&5MSFSv|6+>@gBlWGiF*@D{rBd9qOe2BWzja+rIMUys71QnV;8Vos|a z^|o0W?j=}{xvNUCc;`h_U$^7fomof7$L#gkx1tnV^Dd&T(T=%}Sye8Te?E`;6{R?u zcME5=*gR+eJ(`V@JQ9S=Hp<@jO~3rRew4MJ)c%jxpcOdWZ97 ztw+C(GR(hn8Iva7!w&K6cd7p?8?dRS45e+CvB&!!<}R3BL!WQlfCF!rq59HgRE)oe z!&~OmGS`PTVBfVetZTXK*7qJN=gxkQ^VV&^;=^TVJbxKA zx)PO!c1-X44XY#Od`Q2p+JtrGmFQ_`$5!1KYC`9nCeD?cu=<~sn0vV$6MBBbnBX~j z;$FWAy)~66IoFP5*55EBaLyUxS+)s{m6e#Z$ApR|hkHF7_7UgLl%Y|oL62sWd;O^c z(-Xr#=6Qe&?Z0ZUZl4K_jSjTf!W!r^p$v=5HK^HV!md9Z7<4!6tjk)B3^iLcD0tn3 z3FjQ>TpfOnJ`R*&Qndz^9VV1sabU)(@J8k$Q08`p20JQDIC{~69(Ti<=r5rR1?3uy zw3twJ-hqa@VV}6P2FNgTjRxaYCak{Vz`CUHX7V{(hQ?G4I*U!1an6AqtHVF#+$}Qn zNz-8A0TYfjINa+yVFu!ymW7%`joa5vm}zie^``Li{Aa2RN7rjmb*R2_+2%I(7Hy0qeUjSzdJB;Mfhdr!B2+91PzYuGPynD zK))ZtT2U`UXTlNmIb=fZCl0(G7ycRjI$ehHWDSNKFkz71;Wj?JjXK}RMB{P|rtUML zq{-nnDg27dff+LFSgXOFLKEhkcA%suteyUzB*U_J4fZsf+8^vgkGSxwxLJltaT>Jk zF`+8{_p9#t4*#5dKPf}ccn!`|n?8Rqzn?$&pNTpI$WWK8!PHMpm~_^G9{&#O;2u+D z*t$=HwMV}|+s956{SjfNe&TEtt*FALH_ez}aJt{y#a~e0XR|RssS2G(%qTzSMD0k# zHTo?!8@-oRVdh>ligZr24n|xjPGL5NEUCh>*Ui@-?8D*zdiG21H+>8G%&)@GVlxU( zI&o}N+{u2wY>b&(g(0t*aqP4cl_TP>nE$7;Q9Z8;jjx$eaomaCzlgi|UXYEcVO8j( zFr%pLKj<%f_G{h;XJc1H6-I6}qvtzLtmu#UhQ9I5#zIjQ_U$rb!x1Ou-;el~`3lZP zQA8D1B%0k;II-*}v4!}YS=bO>g~pX;^n1&R^1+B3E)7B17#UcF*5ziDA9iBX{fK{2 z=keJXlU#+lE6vz-(1`;!@ptT7osHU=RoJz}jKc?+gF%ztk{Xd zLGkzW`7c>mJgo}#F=kX2IngpG?&iCZEVNFp!q8YVs!uuHjz-)h&Y!YSFs%xk7MM}2 zbfWxrL=SNdW?{_KDy&^%MvvW299Sg2<@_s+B_1E+9KKtyP^Zs!}BE9b?mk!HCBJJc;7+5fb?VXb@3)WxB zz@f)KLD{5JnD);hY`r_FL(pn?3q_|Y(Q)kz2JUw06!guBLhFcZY@et@PelusY;)-n zv`eRA*`F#bct(eLb6T8nh08Dee`FNerY*yU03CM6w%~x)<%*zr{8Y5Hs?c|w4pU~e zV7JDlTd=q*3bTJwp=6v6D_?5CGOf#1!GLch*kn_o!B2E?73v?;p?PKt_N;ZeL4Nn5(0)>d#U470oZNza>s)RM#<@*J znOTK5M(I#LsRi9jTz;ibu2Zq~j0($qbie-f9op8p+!9O}F%=yrR5;|O!{Evm9LRU+ z;rwa|YD_9rc<4~A{}GidTyFD!uc_E@RE6H7beQ&R3yN2|^zy&dY3Q4ugZ|&`L7B;h zt-<0u{Qr^ZsGpUCJ=^y<<2oB!2S)Vqomh&#g*m8f+=KO9HtZQ1@tdIK(P(Un$-%4z zpQ6-g!_p}6UCw`8iXvGK=C#~j2s}ph-fUC zzuc);6&6RGL($@qzw>?dbd;aW#qd#8SUUe4CM_CyPq2JNG$u9WVwqbNwo1;SeC^2l z^mpHMY}~X0vrq5CwEpv$;y=p4?{CCl?#30EX4!|Kx6fn2lcWA%-j>MFbHfVEy0#Dd zd@nfl8})#9C7+4K>sO%niG7&XcmV^R7&XZG3uI_4T7lM~eb|2OJm$XbF+_b|dl9Wa z=VQs3YK)7vV`!SkFzeIgXg!mUxxUpXjaqCb~G>a5Y-EL?vKHE@k&(wtr|Ti*`4c)JzNBBM`JMMWInc!tj6we zJNhPjxUxRsMeIABkCvI$XnoF(%5;wr>|Y&&=I`^-c*THVsWM#hqN`=;C9jJ120cOdr~YmWT`Q4a}9-kw&(xyg5Q4M-Fv|;xp zFF*F59E-KdYAjz~`t;>*uRccIp6j`(MJqXzwT4=grwz?y?58KODf|Cof^2%zG@~WzNR- z%tCB>*NB=69az%uGmd$9d@fp&3Q@e(h*{rtV96by0M7H7i&bwFqI9DX<)=F^{*KSz zIp>MFs7Wcryh0;(9_zq_dp_g;`VQ-p3sGKdMC;KGjJxSGfxbUF7elKGQNPNF#m72O zeAOqAdppNY)b&>YmyF2sgxBWgeHK>0PFVD=rHgO&0^3}0%*)`|{n?DBb<``(*_ znwf<-kYU8Qk2|oq(_Xo-zh{`UG=LlJ6zJcvz>F0{<_dyaEfDKK!x^NIZd%Dn(=J!1FxlVy~pA=zF z%)hbyS{D{b{319%OM!7ai!k)tgBX9c3$rHsP2$`)6lngX2y?$Z=(MW~I~Vyy(!Vtd zG;Aosx^E9+Lr0f0KI%7FFy-ZWs4OeOfZRivpzWUQ?9-Sj%>B8SQ6BX!c4izx%eHRp zk&b*k~Mvl6WT z;V>p#xrWv|0aMB6;%nGCauZrs9>HwSTd2PhFio)3{u=fSZ^WdRkD#^UCWf~KNXb{6 zfO(Od(EZ9c=&icxjEw=)1^rzUug$-jb~9!jYe4(eTXcVz`SIYp0no;iF#X`pzJQV2OJow$IZ# zV~Gjv6}{N^N6M16GKP1RV&2sz=lcA9 zET{@eX5PD#F=^$8*q+ja1uyqw?aGivlcl%W`)?Y0}Pq!u%=k{axry;4F+nS8I zUwwq)`^V9k-H*YQA#c(jYckf_O0oR+;}{&>kF9ATY4pvOjExUUF>c^Es;Bj1!_ts+ z>h)PNMxH9g?z_iP7S)f6B_SESuQSQ0xLb`)Jrw`um?$?7X@i z14Q3D<2VQU=7y>0>(Nv+cW+18uo+9`4$R95%jP_DD#}LeK<_~_s$(2Duqtesa~@K$ z{oHmecbJ#`^&N_{!gAPuXDWuaY)AKTC(&Q#Kut#2+k)D|sn{2=0~_y}v1FP9YS&xPw_p(4%OmpW>-Xu{bH5yGBP>|IdJuhoi^yj`OFHT$73e$D zf^};KvFEplmDKBGIwm;EQ6FW&(A|Sr`(eZ?LC4q(G`d!xtk8neRfBlr*9bLpaUvb_ zhRQME1q&KJ{R6|dM*NfW|4hf?d*zrNWkL0#K`b4LSk1d_NyqHS3LFTvVEy7jjC(&~ z4Ru|Zfr>vW&^_FOohgG@zBQtNeP(2!?QS_{Wm&Lf@gNpxBMPavTLzX5mt)p*7Bnv& zMD6W}wX8R#W8CjMushg-LyHEn^?F1Rb+o2q;N2aVQg1=gqCrf%9#KquE*%4&{1`10 zE$IICAj)@7UdR6b%*24NDo}Cx6xtsdcE-b#-(^1cW}^L21=c@u8apG0(NZ>Py7rBYNb28DtumUX)PGMc}Flx#sX#^$dnHcBTiN%Yp z=(+hJ+H0q5rcXU@p<-|+%9E|wqj~6z4^4iLx{q0kqJf<#-Dt(!0}oMuW6Boh=f+zY zIb|1S`Jchup;QGE`@H`2c_1P%ht;63 zb^Vb49f-n|ifrs|&|&B4W|W1venkKFOR!3*!r%{dPIonvT@PZpO-9mvZ*I8HJIrsIam`hglyrW9UTJ3g?_e zVe3T|$_sU<_@){AeslSRdwwHD{Wul+?$e=7+l-=4(N4jFBhygntwQTw9VTsVMsc;M zlJAaAL(vQsI`le}R5xR-O|*-5Bb|!YsVYp`twYQDW(>B7b_)h}O3^G+p}kUvLkF5s zvQMNV?@TEMM5?gyjom2KH>2Y#k)Apno`#JPDy&M}jmBqfm~}+Fhy5+nv3uJx3~kV( zMr=dv#1WrTuT#^|@xd}|Jfuher)}7iJYp|-kDiW6?=Qm}NA*~&vZ3VF5mnUX&*@n9 z)iN|**Q5ORA5k)4#AnR^v1qJ%F&C|wpJ8C#SyXno?PCrei$=?oTr5xe40~$NqU4<0 z=YsLk(Wpt!#gxpwXjpp|<;&a+Z&`fz%av4MfBby8rm6CLPuQl{8yD>H@B?T4R zi%BjDU2(+1x)v;?V_>0+D;gp<86!gnb5ty1-|lbx>-#zPoH^$?&-0wo>3WNI?XEZJ zbpF#_7#S2=quF?67J62!L%nMk4wRq4x@&jUYR2@>!o1vd*tU5Wnm+Er`m1++q?vqi z7WU6vhl+C-rtay&$jf)hnmzrqu;Q6@Xn$oF76zTcENj>v&8YuPK~ujSZE6j=Zaa&W zSz&dWgHj3(%-(<=wFcvEJ&XFM!uDzwFMS-_&e}2lbPXm?Ig533!`$S_o`OStcI@e@ z!IlwcF?ep+KJK$N1qaUA@wc>L@r`awn;%xMS!7GWpp$kSI#Gk6zjkAv7`9)tbZrV| z?6PCg)f)8N=*IHdVIMPInS#0wJNBQb!J*6DSY-GzF6ZR=_ZAroW85=P9Uo|)w zeinskVV{v#-Q!q)$c|};YH;H~H(Ij86xO*?ux-5^O^0hRtG^rVGs6yYPiqPm71*)x za19D-H+IE`eXiM%nu7NC?dWQ%!PM`&u`4d@3(fWgDQGITV?;v@*7bH{(uA-^&4Sbv zEVA2ia9<7fm7hgjOjwg<;`|g;R@!mMU4x#J-B>j)>|gYgIR#sm+cC&pgC!l^=szzs z^L>;B3m%oQ|Fn!DJ5{WU4sYSSKUi=uQNoDzGM4O6QTL1RC3QMw#{5JH{p)3{e_zGY zGr}Rwj$15PI#WX3i!!$CR&l6TILv-0%qXTx7`Z~mh7VO7I4O9D`q5 zQ?dLP;fQAKf6Zu_Dq-R(8H0DI736qz|I8d&l=cw>C>z=Y;;z$Xr z*2oxDrDF9_;TztU&Vq@5m2haajCtiMHb#ZF^G-7?7&%))SH6se{VLji5suy550fTI zn6^yD`Z5)JZyR--??D#KnLWr2zZ+q} zhS?JK2kpVg{VJM{2q(zzA1zpKlCW)`j6F+KOzRN-Lx28i#@vY#wl~QbT%%%nuW*w2 zQ5KAuC}Hu-G8SxCvG!Y`lm7hKj6oA6v{%UJ-=?C)Bb?IA=rCi_0}={L<-qu#Dtf*Y zPV@bk86&+C>gr@{-=m`Iu<$MGzcyq1ObL4(GDd!=q8Jh0MSi|EW7cC5_AHmt_NI!S z)bKN!71zx;FhjziB{I6IR2=$J=;oc=V!`4+OWim3L*We-JKMw0YIcpZVEoGxW~`C} zR;gG!BD_bl@|qcc``dp6o9b46a$A$06_w5!;N|vx_ zwT#uCI|dj#r#9U_w?DI8S^GcIIutt_%{`kgz!G(WMAJ#%s+ej+3y`Dr0-G>btpaKr>{u8ACTnSdlJclvBlogTiI@ z``(N#_elZMWQ=%C#kO|gC-T#8Mq#Xku0=BT|6RqzL*ZBG8?PA?#!A>|m2u!z6)p9G zpSr1L47pFjhWRqaUstj1fN+(1oi}65pCr_m$*4Hht2gs}O|$Nj8H2`3m{lfY^1O3s zs~UA(Q`h(ewgkP5iA(pQY0fzue9bUOyh+7u+~B;yjjS7;ey4`68y?aG>Y3 z8*R6rN6UP}&-~slV&h&17M*ls<&YPL(hR>a?-a3Nj{`f-y3zKt7Zd(s7@`i(i`c&3 zf&Itb*!8>fn2>7tmHu2NV%u&9_MLR&;B{|czH9U_<7Y%Hb~~`^KW_94dvW6&!+-H< z5uUaz^kVQd z!wAjLMIs9CJ21J~jjqdH%rF^7YDO*+vEl;GopPM8j?De||28zTm*} zW;gbAd9iAOAy~6MUBv2D4ouqb#@;htjC{=Sd*)L_w7>2^lj26@J1@q>8Ez-O*&^y! zIxu;U8w)zTSQ}^f198m~QOR|n?h7{-eCx%*@rDr2eMH3m=Nzc)b7Nnp7pq!E-$7kQ ziI_aifx!+pn)Z5e=(_$+>N8!$v}YXX`llO1I=onakKr!Ox&CcaUhLHy zLN(*3iWr&cKykMl^WHm;m4e}q-^YoV`hl?Z!~Wi!ndx!!hB@%_lp?yqyu}K+!(*#i`7kfJ?pN{!Tft2 zSn|3X`}TUVp-*pMU9^b)WCv!r+*ozRi*={L@-|w; z7K^z~rm;2l;V(^q^4WND5vvj$SpU2m^FQ#SrA2?grr;1UZ-N8so^oU1 z4)6Up>l;N}&(6c@O|N3do_e&u^8+?Sj2XxKTsjY3&R4Pjqk0Va^?Pg_J!U-bap^ql z+Wac|_taxh%>`_`aBnnuH9m#9M~X21z(Fi&^9sk&X$Ao!Gce35<{W zF!+iwjy`{4A=WK$Vn~sKE{`u@ukiuuGBX{AQk~dfR|0!yW79F@2`4tbs9?|)A4Yy>oWwXf9S7$+ z(Uz}ZM7C@lIE6Tj>6kOi85plnFzX{9_8c=NFmFu9 z+*h2~vRuKKy*>>6#`q9*y)PXtk2*2$Sp|c3`p|XMIF@24b8^syeq#Id!{+DBwfLn4}Cc3 zG0xB|{>h5<6P?(;SV5(20EfOX&ZIvtTd_RWiG%YLw7l)Zq=UvJ&i~PhMH8LaE-F}D z<_nCQj1Lpu^>d%ai(jPxsvHw0N z=FL~ozSW1JpBYV@*Js7Z@lLeORj|+LL-By|G3q`(9XCcevFb@BFn-e)nBQ-l#l45D z7&_XCgO4j1v&M(H`;4y^T8KG!J27&Wg1rycqHczQZO{0y zyxM3XeltQgu^ zjQMd2#-#bM;2q;U;%Tv>Fv5w+6BLY`=R;SSalU4-Ap`YewqRFc6K1XOV`o)#D*bpo z6Wi97VCVEE)aCdC?udShK0cg@@po>)m?=$|x7d%B+oKoIuVIU^_wFrdiEqM$96zSL z6#WOiVtz z8QUY9Fy~1>id&)=k-vSJ*n4U-mW*v$6nLM0EH8`Bq#v3xF?rQiY#Gypxha0^dOdnE z@o&k*UiW5fjA}yLEI-;`i_X$i?q7_J{>>Qo_vXO(gKOyV#b$HP*lbLkRDz`&nzL`N z!-(G4CG>e%_L9K6D8bN|n$fiV8itIY@HFw=m5oVpB`B_K#)5xbL*3cf9L<3{vQd~& zg0>CK*pfLIuq*Z%_6fotS>23LrPr{kD|V@7#Vy%rd7uP?S2kn&wriNs82hYd zM^H8@#uAKN-i*Opui@aqSQ~NuoQ1Z65=>jwjGmMmfpK2kbDBK|pT;2dO-wQ#LS6C= z%#D6<8Q;e*#p>j@u;FzN3jM#JZDRcM|yMAc*=6lJ#NGLkaBcQZ$;D7!? zHuPU8!-}b`Sf4SB8O4+H`0lZx&Rd32A+4A@Wf(iBO<6_$x7o1ji!!YIrWHfdhOy+K zDXZD%fDJ2p%CL7_EA}iJMo;YIHT?b)8+yi+<6u-P2G1SF{#PdDQ~&)ow4Eu#;(}K6 zj~T{+=*cgzzR89ayUWlrwiR{eVH{jM`9<>AV8f^rW!N^R6)RJQv3Tp0wVL``8#YdT z7bB&kn6OhcEbv!gfTw7t_u|yHN71xw~Sn;nf$k@ zIMlWrbHA^^go*9gnK^Pj^-Z0I8O_Uo^Zx+=0RR6i)_qvh<^I5N2*O1us1w0)k^ql{ zXm~=IGLRG-&=O1{Oh_yW$i>4ID)DeYS_FkUk5m*>ajk;1HE9^t?BH=3o{*NXAf3fx z>hw@74+d4t z+)#k}3o2Ay{~m*-9+mvQS&X(X3S6F3VZfd5Fnp~?73W*TD4Zon*@}axko3u7 z*8f9-<3oig7(awLv&~qUD5z$CV=Q)mREYAaLzo+4#^`)O4d2@ri^c^-n0V_D7SA_h z<1WEYrdq8m)Ajc-EYOUm&4O2)HgAbVMOz`Z zR;w|{&5U6y1Pb!~B@PV_l%P+F237fkSgQAa)u~t!kLgJz81|9|EpHFHyy9Jl{c-3B zEWxR@8uTd~M2+72HR>=k9+TFTpsi4Yrrm>RKkr@7ddDhEnp1-LaT=^I7(}Dw-UjO6 z6^}U!OR!n4!LogWs2TKr-D%g0t1x$>7{$vp=-5AmjUC=^@cW%O9GzE!p3iDf@#-Kd z2fQ1}>r5OrUM~GWuf}7de+dq4)L?k^Ad0QtyPXbv9f!7Gi*YoKf4-(9NVyRRXggRvta#4zHia5v#T-ew{2*Vv}5lM z3pTa+zD?c#T#bf+?U?j@JLcC~aJ=8Qnf#_FqHO+l?45fUOKU7>8t{DpP(ZK0hkHJ` z8q;QNN59N=Y<|sxIeOoB**Cr#N0r-A@N_#`Ua?@~QQsEwI+%$0MP;tF{xH^D{t1gc zW~qp0!&-D~EyJmf!zi}>geuQj`-%6Zwb*;0499;yjBV~eWAV~i2bj;IwP^6Hz#}PI ztSPo)>o>xK%uQetikDPi;x;Yj>#SJ$jj)w-&q*=gtpZgoTFg0M#mskvhsfU}39}xk zKvSjGc39815|V&yYdY}zAypY<*2`>uXhVB+&y?0VgbiethL`2DgJ9ij^C5^GVJZN;fh z;fLJAkCRdNdIc8eXtBP|ijkiR+sNyb6qA-zpnjYa2QjaTA%=N24`D`sl@3NxqtgwT= z4oNZSPB}&`(BeRW72W<6e#*X1DY~62$NXR|7ROuBrV{Fz`~M_i`pt4oyHAVC=d9S} zF{hJwjZ)MNl;h}3EoQB=V%jm`F`l21qUU%y4vVyCD7Rw58R2Kl%Lh_CVlKx3ffl3I zT3zcxVVBdPPo!8pR_(J6Mg6T1HKPSHRDH#4@6-JimFzwS3wA9c2g7xAQoZ4E2 zS#RplGCYF8xBb85p1P%=Exrofa&_3&F@j}%{sztoPr=sbs<5e1hqApkR89IHXZ}~F z;Q#&xV*L&swthU~^0fa~+_Rt*3@E6=?!7uRnMN?|y8l1PZ#)^(mRDg^whl87jG*1< z-_84?6dXQVh2eENZ0s4qf&ciQa4Hd{;OM3*JaSZr`fo-seBA$E)cC8l7_6ID1|u0xw~1d|;8MyEc*$=DN7g|&AHkrb{{N=`cc-B8LKOzQpu^m;iztr? z{1*4h&|#{^$!i@r9B>Jfo)7FLk3BMs>Z``G>m8`@zl6fVz%$&tH`ig0sv0AEIl@fB|8rPSM&@0xw#H=FYiRj!cLT}v19mKq7l~fQnAdv7JHIAF;{MP z{oWb+mtFz~BpGSS$|x4|T4}z#(-5+U*8R@N;0R zSLmqIXlVwHcQjy<&VZFeV`y6%`YUmjWuWq414dpnV6Kk?^>>B-#=M&{Q1)U2dVXv` z+xao9k%W#pJz~s6#aj*NH*CPNX%6hV9pYe))?}cvpaBOyG+^=I80LnD{!YJ&GSG8x z1NNRbp!hBamfj4x#+=7zp!k^vOgn7AgtKE978?3rzW;m%D)%&?so#L%x5h9yEOeat z&CkHzT@5H4FksNlG3@$1U~XLlO8N|FkU6k% zG-QIgjmkjd#s(Z{HDIN24DEA5Cpm9Z1_tbGz_4}$ipR#VZA<7)@?4UEw#OT=^`rqC zPmE!+U+68TQ%`1KZp<5~f6su$SI1Cb3;BaOglAy)x(4hiHDJ`2W0<&g!4&U(nu(L= z-oUgQUtw_KHLPh_aGN*-h|y(m8iel zhyh0@Fjp0Em(w6ywoAcYEL&kj!Hx-Rd@;gY5 z=2Uk$8`DinjJ$CYC6Wm=ZHW-@9p9&M@{AIv#!sSr#RM96N8Cf+=dv;XuDz&OXhgT? zCeU##!kfChl8rTIm1z6zBqqjBVDqaH_d2cDXQTX@5{tu(=vFX+KA90d#9fn(U0*BF z&2bWKOD9~EOi$#r#F}3`2IW`^=!f7X?>WV=pMwrtXY4Pk8}*8}{Rn z)`V?lk6_};h`~(Z3+TCNKiX?dIDX#ae&)eLjFy=%VAr$zG5qf)O#ILzgnJSagN^&; zSbXUqX8HG{Z{>r>Zuf!wWa;*1lMMX?MWFNQ@ z3GoW2P6t+Cl0lC7_qL+rul?xxl-C2q9k&t{Z_Cj!bkODGSc#t_wi^KfnBJ?X%qwq^J7Fz{T z^kZ!t4y`Lj%~mz0A2nmr&w{1I^?NL4&MiXuBWf(JF{A#l;BQV<{t{Fs6yZRQ8cm1I z82N+XA-o!k12c-yCtZz-3NzY26hw1x3gWRVw#c=9T8)z*m@#ZXu#E4E;?U?_gl&(i zaq1;ATGWE&_?X1y@*-^9sCIeEj9K3aVmSYoSPb$iLeE8NbQGG=v|k|RJ#PsfSyF_V z2h~{9V#c1Y1uN*+5(%c=Da3&FYK(fO6uV*!LWrz=$ER-`dwzUe<6q^zJ(Ih z{ZWYH^VQh)tQn{F2_)R_o3W@86`^>w8cp?Pl;zC^}bqq{Y*sMUk;JZInu-QoZAN{qy~t`#bKr_uP9&M1*s- zihkKbM5IKd3oX!+U`*PyVhyTwH4K%@sG5rJKSc|yCDu-=;j{*=V}+rIEl;5_hn`P; zucNG+)S}vA%8|Wj!Mal@GwC@h(nPVDwCbD%DmuIuRid9lOA?-=%qtYzNp;Rypod@W zMLnfXp&Xaz=v`SUyGdU^vp~1)-G{oApFu_WJt$X7#va${WsT~W??Zd;oIwL-zd#EL zsZ7itVW5sn*{Hrd7Y!fhqs$hn!=y*9FiOB}dp@D4uORY!H2wC@4~9UEbxr{{3dDr-I}lS_4;RPqr69iGQV4gcn%zPtFS z(s`;2)~jNmk|Qj1h{8o34f*I{wK8PN z78f1k^UOjEtpr#*z*7Wp^m@Kp}}f= z^hhw(bJCpa4D{}7Haf1!MMc*0QT23j+N zjRt=`ht@6Nquem6H-6_aP?0XyRQ%~2x{bz1weqRkuuo@9e&J5Yr?4kc)u$dXxd#CdP8sy4X5zYzO~ey zxbN9E=neg7^vKC-G~i}GI@&E4i0fWygO<2QqeFSsQ}K;{v`TDl(4@(tHt2+QG%C5h z8a2D#kE(RY1*0o%P%W3}so1+3eVx~j%5}@_!uR=S9qP6?8coZpMkkv3QO--b5S(X= zO~};!jYgY1s?olz{;Bwq+-}U*utCS|qtRgZYSb*NAMI(D3&r>JeH|L39F3|tSEKZd zezdPfE)2(Cu0!>eqS1-iYSg8!A60lRw`Wr3;5t;}UM%X;Q!_RGa0oS9Cck&mtmAfQ zPiZWgEPWC66&*r}i+uQ`;^B6v&5>9%pzb1S_}37sq9q@J=UHKgHWkLA;eTC3ho%jo zBHHr%u-;)iw684|?Rrpyz7`om_0#1e@g1MDLk)9d(edFLw9jz}4PP(M!t+YALwiUp z%Dr2I)_ojAE$rplSU=ew)ftLK1HRUvDyxRj;Vk*6NymKcP*zjyRQ#m|wNV~I1MVtB zqds+Jk+d0fZph!#bcjlIiTZu98@l-4m}boK%3^$IM{bF2lVhV z4tiu656#*oKzqt*36tiCI-ug|9MnadhgJm%P_5gvMC=oviL!piqmKH#squUPYSBVV z!u?HiKou5oP!%U08lEdaw^h)Rah>;>sLi){^pP_Ub=)pM8=7b-_}(U%sHZ9iEm_Y) z$F~d6`&qP9toNOX1}Jk-89N@@mn}fIHPZHD-WMinsLVla7V=QJ5do@EM@z$fe`2EI zG!822z(Xb71gK0ZEgkzj%0#*IIB0-756#*nK=sEJGSFcrYO;WXCeP)eb#VfeSxd{r z{x>txaTW(1mgJ#18wIFaEG-M`9A%<)1M%qiEZ)?3vH<0rq#eLMpJAdU5*)N)1rKev z7oZ##?ck&nx0t9>Z#=3c!9&|^1gH*&mOUxC!$gN>a8M?bhvq~I&_}BCbMRb_GEq?} z4(h1GLw%hEC^L+fJ1M=HiB3F@N0WcmqT}5H)MYm<56|Tw6KxRZpvn3?)WuAIjt0{5 zai5t?v~C&)olxhYIlcn4XC|!xy~IQ4|Sq^$yiHDX%2++F+XvNs?dL~LAjYpY^Jk(-~0M##|m0;Y)L{+ZG zqjm3U(FPp>O82IfV%>{OROU@QdRmS*1@9ZE>y2TKioIY=>iAme}jTn8&K77uQ#U{?3lFXy-M+w@poV477r# z=~59#1{rWx&bwapn=Q=Ren2OF4HJTVj^+36*#JtBe+*{Nbpnr;?8x>`l}1my!RoD_DwVh%VEBEDtXG34h+Xjw^t!ec!nwaClo;DU^v_X4@3?rW zv2q`J3}wxZi^ zs4Td{bdd;!(x<_4&Jm$dl6jG3DjNp-Bk!xYW`@DlE04v^H|&9>7fu|_`fm@Y%f2<5 z?YI|)PlbND^Y31`Wumb6jD0wGF0dbk>)}9scI9-Cb_4`Ou3xL%5CK&)=TJ||?}N3v zC0$`h_knhOxAkSQNT|5JWX0({ks$vr*66~INZ?d`)2`jhg1hrqS^2zTfvcL4>T6dv zuxp>Y+6=K_Af(N$W@i-m#U{Dw3`T*)E4|m>qM~8H+wigD^I|}}ZNAp+q8Qk2mGar| zcMK%jbM=f;V!?gR#j$E?97KG3>h>`u4x)kvD+k5m!BEq%_DgO&SkKMy9G%61lFLqU zOj{1jUq0@mp2&fI*B=@8n>i5nNbU8}&m3^->HiBf5}<#Jq0e`h1hAg7(3@7702)q< zKCFD10A3fiUQwEp2oOeX&azB|-{I^hJK}`#0DY6(?L^4guUp?XkqE7`Ok8a2l3>Z> z>EWh1NpQY+T>EKn5-j@QOwpA|hW&4n?!|0LhLc}{R;yMfgP!B=fEllo;Wq20;QfLW z`0P57YU!B*MFw)$4xC8=NvEe9+lNx1QIp47wlEd^RGj+Xc%?#C#nSp;hf?8ZyJ_#N zp;Q=ozc4Rk?taiY+ZQ3Tc|UjvR;9$A*$!e1@9w;!b9PhXClkp?EUsoT7nY4CoJ zhV6!kG&rIXSLI)u1_QOj{q0}UfbTb7OwBMIrq|hd|M5+SzgB5w%b$GXvU>h|PX`Cj<8Ozcfpg%LMHv3TyL*OxQTmdcGtn z6S{dR4=?_k3H{MlnJd3$!ZhyIot(M?tj>l9%NO<2c4Whxr@K`xDzf3`Z}(qvFS5ZhOv0Hio&%RZ-If%n=0K79wFO5l zbKqQp?CGeW99SRa@kIJy4m|e$Cw#@l9JsESk|*(B4xBDt5up7l2i7dorzy|Qg@p-5 zUDFrkf@A9L?M{}taBtQYy*{s8*v+`2Ihv3Qt9OMMHI(N9Jg1@n4&PP#yrjMW22$SWR6Htx1v{E&2Y)Sqy7b<{1=K>=bW80}ia{Z4 zrAmz0I~KyNR(Xk*h(c&(&huYeSqSk5nqC915E|nzg!*(9f{TcSMc3CtP`eS}_*$k2 z7z;z(^>m9M;N4#%Cmf5QZPy9kCA*7Ye@{n9MrIL+d(!uxJzWHqKStm3pa@hx^i5Cd zEfW5onSJ1i7Xu|STypcmVsQACUij6Z80MepuI%1i42n`~kC=oPgLu+Nr{CdXc=*dZ z+xA*97}u#^nf*lQkesp4r(zf$Tdy)9TLS-91lCiHOJJY#z&!Q!B|x*V%Uc&x0;zST z#WPAv!2e6SeOFTnY-#UK4eTv}w+AJn62F$f)|d%xZN*ZEsnDFTUsVc{*OGepn@eHW zfuwouA*FC9LU~(idMU7H{GE_}suauy=gvwWEQOhO+mBxmD+8M7_N$>`gt(plaGF?vBhdU}=5($Lw4gbT>N5wRV)jfj4iH!akJ2j8LXinbaY8RX)&n z&-f73>jn?VJ0AjL!(s1`J%_+l{qjhIL^+gCOV)SZbqwO<)Skv~JPwPNcUEMF9fzi$ zNqx$xry*oC@WJ0N>tIIW43UTz4UlmnhZDqW1XqbYid1NXqZ`?y)%P3WMSj@vF_9}U z+atN}l+RU2t-53IE%X}1Db*O2%eTP&zE+1U~6cWrBE*ag=z_eq=H)Yix5Ya7}Nn6|tnIlhMy2r<@ z&nG_h!3`OiKdsyNpsJqou*<#&+MNsJIvu(|Guu*d@p>nOE$~s7s{0St6#2hgRC^P8 z`AzL{buExsmpnq(xD3JWaCPUBLNIu&H?r);Y4bK$!KhnKgZY7dUo&0LHk&{3o%cl7 zAI#~S$7e0R59V!(27kZ%an1aN#n@olc$2y4R-2OxwXT@IXn&AZAh=|{@mRA$t6Giu zspf45Wmw0|U*{g&rQ_~n{&F^Bw^`pwFudbc9Q3>a^!p!F(A93ho`~t;aRD7rUG7ay z_|yq$-+!!3J^l>#E-2w!Ch}q3W?g^A+W~0NmAM4V1R%Y4bJzaTH!$GY^0r|92>d)f z?4G(~6pT_-8qeTw$N7-2;InmTYvIFjaN((V^u_!Hua6x~`b&R< zgtBs%>P``o5^K(_YM4gmulDJ2o|sOqG{*-0(Gw-}3PvnGIL#nNhodIygJ+V!N`K>R z`^89_(}l#n3F72er_6Hgh*{*0ve>~kaig#>XqG~B#srzCme z&{`M!K$6r4at=L}r4Y%{z!L%b6!K#Czo(5XDCE=JgY)isQV46B?DJbYDCB_XML%u; zh3vX4CuY4p}G#<1CfCgQteE;|3j$y)rIlLY2^kC)s^-LWFq*jf+nS9r#+(#21>Pq-n0bn?ek1mfb24 z`b*iA@l|MgYdwDdg`GV=IX zgXmrgxqH26Y^%^qFM8Xb3ANKvmo^BekgHp!z2yom@A?vI5<43*F>$^@B|$h1@vmRd+$CM(&Wc7K=hwyY9M`CDibXk(wf#Lgx2z zP8<>X)-(2+P85ZN%QPzO5jyrwp}$WkJz;@yaH!?;EFgdU1> z8@5fRkhE8A4$p+D__oHGr%*`#(XRuqgq{OuFTYd@`7G7za9^n6kMRER{S*@Cy{+TD z(4`_L?`%mE=Jkdy?GY-akT}yeUAS)D?~aW^B_{$6Ju)Z+Le}rNEmZUK>N0~&3fcTn z+3}sw9TB(Uqp~REu-Nvac=T$=ZJ!w&me`ozVbypK1_<-efNFLc(pX~ zYs{GNQj;Nq&oet!>SV~QDEkRbds!mdT6yeDmn>oY*S+{Dn@V2Pe}t>*bI8r!n%c&D zb4c76x$2Q2N2*$9KjhiXB`>d$zcx?`fO$o@GjEenmWOYcnMp zZ&Rq^GONh>&d-%`?yE@95kC*_0l{7zB+Kjx~kH6(A|POF5YtRV2lNkt$BP@zS4rMd$DiH zaEk>gWAS!-y|f^il4C8Q;+Dk1Z}a95ZA2Z%HoHCoB9FYDtowU0ky(S2(^Q zQhf=}lKejLjGp(%lGKl>x;TBYB*EG?I#1?V5$lzYe!H4jk(omQSriW|@+H1~CqLSX z6!@&qs6T8)3^p0H=r&uCrBCztLp@d`v#mLB>rX2p`2E875Y3vn(`2HF38rHeC3}nk@Uf zVV|QMoxu4;b9OADlO=iwuC=G4J`SRj#10SF9!J^00030{}k4DKuzx( z0PyxWx4o~5wvx0%>zwYriH4SzkQ9*yA+%_ss3fE`HKbkNi0C|ph)ODzB9)>gO-=c| zzrQ|zocF%ZxzF>Q=Y4Yv!b>U-n1b!@4T}Y?reGJInbhiH3ifJ2M_8Rq;p~69{BHK9 z(4Qc3erc~M_>Mf^m$}CjPI4U``9(JcjUN*is*Fs*MsUzQS;iV17) zWI$Lf`^vZ140y+{wN~_)0h6xy#f5wZTs*+l%W;PR1FvovAB$#y(!1xU6V5Uq`{)y1 zEe{4vSvC5ewqbyy%<}6_BL+13ZJ+Vo!hm>-PZwfE8DM*l#O0Y7pjCf&*VA!2Y-zj@ zZuyB0arw8D3Q0PY*~;-fDWrpU&Qqs`WI9Cfy=bfqqeHV-cdx*4I(Uxo-kY|ggJj)& z*#{#!c-+wU6j7mrz)=1~t_U3-cAY-Borw;4A16JQ$7$f7)1vb66Acthqx$=S2F6D` zOLi2~AmZlg_1Y8~JoJ?QY!Xca`+)2++tV~~l4O0|d4L9H!XC_aW;C!!>E$ldq(Op~ zobPQ(8eHm(lh@*)K~EmnL+Ke4xTDl9+0kbLKlXBlc{G~9g{N^6+7%|yr22xPao+@n z8_Mn#TrolQpltho#sqpa5*5PTOyIk_-fdP36HwF^`kAC_0>Km}jz^nJ;6vPdLkEfp zB)E?r@%cl5Wyh_@!b1dz#L4{hX(8aelRit}Qv&9nH_B$^62PvXl%}6RKs)=Ii$D+o zipRKr7kLs8sid8Bz?uMOj+X&7`UD8F=D*TZB0%>q(UmSp06jNbzkC^on*&VQN^Lj< z*X+o0E5PA-;)%49OE|3Gj%K~};RCU&9#0Zw14vgzMlMiBIn;Bw(J0)Br|^whK=u$}#tw5!7q=J%WTaMc(B%iDj1e}*9(CsHa~ zFB*aw&+gPlOGCh=?hBsSh}IVhx~xnYK*>Tx4V^TAAI594Q#TCY-^ih?-!29qsz-Ou zR4@SE@9Jl^PUypdm!gVERrBFP4Lg595J~T#V32esnA*Zmk(6)IeMAW@M3J3v>qyhm5f9N-wuI&`gE=?>1HDSM7unPZI4Z!#B9!|NV0Xdh2 zM}F?rfFD~k-~Y#<0gH3u2`2;9fp2k)h#cDn>4i}t`<=GIy==ayzL#py{LZ)ds=gX% zgoG;Wui6T{d(4F*)wja^!6~_ed8!bS<$UeDgeoN8>VJ1Cehc7_^LRaSyKa%?_3 zaulJ>?n6zkv?B1Sgvqa@Du9oR#(cVn0yrj|wtJi?4-WK{gbRZ5ASl^%>E>-YsBc?M z-zgynGtW+#>`9dcyEh+cCepHyTQ$Uyl`R7XO$NrcTV!BgNXKHV%O=Q@w@#cmxDhsq z&4}GRD-AmTsslG%l>(vTdJD%gB%yrtZ+2_(1~?II<+1vR3RiaD=@@t+0ZTuHX4N~z zfxEh3i@5+$%6o>gaK|PuI?p z7ge`@&WV^I{d-v*`ff~<*RRyH#;N}%^RCW5vcK_*F|^Ecz$N(4)ZAaLg7ft`G=$AM~a)W zx8)e==lR4(QE;5}iPn2{YjK?XrY^{L_4fpsa4tBpZ*YoA%wq(aTONw~Aea{b^CAsu@B}O}E$v^U2Z9j6&k)>>{y+8^_x6!c+;cmb5o?P)#1GY z9h0Pu^u(dksd3VyE+Z*oev~XpRW+aa`h(;robNT<9VX8{Su!427$jwm56;qy`^lF6 z>=`WNGkH-zW|r5YlT_3;-Spq%7IMG0?19{b29n_1EMM$cNbZc3wXC}S2tP)yjC3l# z!cDX6)7w6_;kQhKT}6Gm@!bz?s3#5j@nJqbfxhEI_{qM*bit?*{GcEHefOPFyvSf| zc;E90ypMPKjqmytezV=|qs)dG+=-oyC$oGOe{>=K_6DnYeEOc=5;nDfveU*u*`P$R# z@s^pG`&|F|a2yMPOSi?+_PpIa5JSU7U+}(sc8k;yX?v(_6BL z<2)y^mBVYoQ<#&O;&yToDB~br2fu9bGUFhG90p=Pcd-)z{_)q29%3iv69y8cC)m&x zkxM4+A{&vxUnQ0JkCg~Ykb3D8#Y)_`dnNAe5({zF(f3-%Ar?Y3>qwGY9W(LV(#U-R zVAxd?rs6z$O2!;1q^OU@T+aRh(Wl;Rqf}<(6S%or63GGor&aB3&wzX=gFN< zkS!vy3nn2LWPNDj%s{pVU7TQqVlWw>8r_Xl52?hQ!%&>q{s2%cW~wY#QerSDD~*j6x`F|%ePkpaxz9$9Z{t-A=1!YAlgMux`p>Rk z!@!a4+p^6$KZET|90q50$JnnTo%Iw9A6&=awqcKu`VHjaypby8v%)>1 zd*U%D6?B*GLXI(~o{dVtz{w`ih$Rt&p=SBn9Au|A^QzlT3=BOFlv9#0II!P|r5O2p zSh+#>76$wUAwq-5Lrr{_&n9Cqpc8IkdK-hQQdHf)$XEMw1)c9;K<1{dd`Dg#U2TuO zi{Af8vzuiK2BWhLxiv`qX@3y?9tNq8S~v2iV&JgGcBBCLbL-ug+tM)Li#k&=h&*Me z{`ks$4Cap<)=){uKqtVzt_>;4U~=4$fx+RxSIl+DR4IE)k4y}v7uvNIvoLVuH;ZgU z()@x~qO&ph_`WF8DhI`7+}ZL9DNo-Z>-_+Ouc}oBE67brl~>4Iy~21G}Ghfo;? zVY{jqLy%IZY|cxRW02=`kJeB;6y9{d!oH|bc|^$dfH?uTopkym-NPWjiOe$UDGQ+tj-zYgWUO>lsdM0vWZ;uwUqKDxRzf;6Fyxm*AYKJ<<4Vy#E{Wfs-B zh?M6(>&e!DfuP^##CBv=wugAkOAMlWM#PC%81U9=b-zX?^t>H2e2sz9v#mEDA^l@A zbdNP+ke8geQT+`D5&kK2ImlLHw(F*EG03S(EfZ?Oz*FGJa2fIy&(#*4cc>rkg}-S< z?wQ=IU;ZA0kREM2pJoh}d}7n;kzcZv_WnbfJNldNZNb2OX^5VT46Bc+qqJgRQP87z z8rdx+mH82w+k326>jMU|YUeHmBk$yKdQBkf?yNTJwP6s@-OhRi8Tm_Y=q1unUHyaT zM+{;=g|F{MZlL9Qr66m{3g~mlll1Q&-P=*W4X4dKL0XA-rO0-mddYc;+9Ef*j$aY& zMBne;t9DDsGXdl!&rcYrs12)$bYb9X`18#PWOiZNOf^z9^Mur2WYvxOL8opEW;bsC zTZc^j>&hb6gX*+H?Dlaas7yW?$OPRx9UanP=kyw zMvf+q@A-{4@UhTS$X}^;KiiNI6NjZmf1vpvbF!}r zId9m_^#>VOt8-N6CpuS3253>p3(WqiT}VAUwi;p-J!cB4$wjX9_bJMZVIYBdR(T;u z8rE0~khjO$yQId^`M`XYB^WvEKWo&7tT}7B)o22P>wZ+)J*33WLW=w(1};iTTCS7- z&o9>9hdf!ueNXcjs;74S0e@u9n5VbE6pF8}7g0BIR@L`A;EjL@rO$XVCd!mKhj}91S_r*MMB^ zvsKzKi@xXWYUY=b;Y@w}(?|=Z&8KK{sNXt52l7e~gFOlv&#^zG16eim&2Q5p25KUA zTK6MW4=i75N9vSZU^ZSt^K4S$LIN^uE1%*gB=$OPi~ceOneTY2`;ZM)t@j#PT)mfDY#oDhXH3E)kj#VO6lMx!6uTsZAerQ5y5^A<_Y*H0vQVJz;=!31q|!Cv zUoFT*?D+5VH9w$F%jN}w5)3qs6cLJnE`eR1tQuj z*Hif@@Ra!(U;0M$UfBy4Ynl{zH#TnPZ%l#jAzS8Xdnlk`Ps2sbDez)IL#7KEI_p#$ zVnKn1148R_$Sk>oGS@6AaC2h4kkyI;E@>_FQ^>LHXQ~#E60(b@O!lHYC46%TMLG{e z`@BM46)ZomV2$#1xVriP^6w^EQz~+12h?y;GTf00AK{}OG6!yybF?^Z@nTL=T~22Zd_vM@L@)ZgaJ3xkA8yi%)| z2++SKPm^sTFjOS9G$}6%&@?xbeo_>+(Qf7@JP?IV>(gPeEuvrv&O^z+MPYS8*UVl* z4757INzOtH4pms28HbBOW<4*fc9j_Tx|3wbfEc(uC}gB^iNlnZ|2J(_aaeWF@M1F; zhlBo|qrJz(;lI5B+3xY;kTPPu>Fx`0c(GrsbyJRL>s5^xA-kUx)s7-{j+^laTT!9$=~g)%q_N3?n+`}*&2LXHA${d_{huJa z=H|>>klN+v?0zHZ*PWkj+>7Ftol+#Msc@t$r?1t93I)sI>~uRSguME)C}mHDgGad4 zpCc1?5d-gApo+SxMlFn49b8&sV3+d(_{{AFVaRb9E0jZ=Q zI9Y-m6-bu)fef3S?eINBh1syQv5gs2SliN&`fJMuP>|i;F3l$ix38bD^_7%@0jBsB zD}8A=?%S1d&~_u}T-uh`Pu(fxF#S6@mM937<&yBDZJa0RW@Q+q3TKAia4`D!a1uS^fRWv2$A7t+d452}H<@>`W{ zXSM<73+LL~%<52g+gLR%K^+?1oO9y%G$6OX>cV?F4Io6!f8?cT0Cr1AJMJ5Dc*^6h zq9z!A44k}jQWJ9De|WK}N)xO%sf*05Xo5~;`9p%H1y#y@aS^dvaM{8zlI+leSn=BQ zJSlC+^y*#@@zjQr)tsKEMcTkO+!t*%uMJ06i&Se2bwJJZY}R134#?4a!*W}7AmIs1 zY`ugod=$`m+TgAWbyJjvmp)Gu6z2>sABSN z|95@3FQBTLq-p@d#%#;wXAPjSul*4(X#jU`2@i@;3?aKXJfOb}1W;eBq4w(<@mko)#^_t{7za5`w3{Hw(XT;yMmoscjF{nCJ+m2Sr1@yRoG`GGMU z_~n#1Ib;ms{&dre8*q62tX68!5(mLAZO>T4aNwhLEU%X0AbXVM1NA!&*MG{cH1ZG- z`!ptGMu~tM|1D1l(g?61k`C`XNWibQl_NS-}4t=|Z+i!o48TO@!y5c%AS&jk3IzcZI907yW$znMU*aHF@5kqLxKkBn07On~iA zTc^}<69_Qy{5%b%Y)nq(SIhsH?{k4W{^BC*y*2$c*`8-l$9mZS6|75}Xc26Fd`t_R(Qv zd_MN&F*@A(lYB!dkPhKOT*^67bm;aGuvSWQeFlf9=oKSU4BFdEBF7{9BSxL z-jEdS*GPvr<>#hqopcZuT6%9YNQcE7kvNelI!MZ8{}x!GLx^yVcor)I%A@^t^m!Q2 zd+_b<&B6@uUa{HvO`HKS=FEqRH!xs#BagI_Bm;&Ik*bAM21sl=lI$kN0I2dzX9zN& z=0PpTMGUQblpzw%!hl$NUj@l!I_z{*Ok2u5<~!4q^y4xS!4fbzn9 z>21&pBRVj9A3YVJL*|gaas1LY?SwRG5g*)RMH^d zLr|$Ol?GLhH%zZb&>&LJ&i$V^4Z3SQ17>V#&`{WAKeLkt9N$^RQ)Ou&JS6nO2}8gC zyD*SHZvvhdGFz^HGlBmB0096043~F2)qNDlWf#d7k-hi2#vQ*qXebGlgrtn3WLBh9 znxqgaX;3K@Dj~%E6s2Jk;W0DH3?))L_pkFh5 z6iXF%(4pa`c4OBkI*f`Y-Z_`j;rGmK$-`_q#Cwe;ic>lDZh`h!V(2(Lq~Mf#fDWlM zL8t6p=qOK%w=1R7vHo<+k6tZ00z*Cz^NG=MDx3CV-4p@i$Ll8o*aVL3`P}jS0)ZV` ziP*4(0Ha{{ac)Hd134lYr$=a*bD%YMm(q}4{z9iZiH1!*i#~0^G{ovAWbD{VLrUz5 z6E`hsXszF0vqhGM@pZ=Xr888}nuI3yHd0Zu&SBfqTq?-9=wifCvCaAGgRs3+d{`YD zaL$&BlDnCUA62Nx_>p^6h>MB=JA)unCk6fEpGs0oDER!Q`R47b6ui*hUhfx9!R}uN z=H<3fuzJh0_;wQtUWI7eEEA=`bVVeyW|WM2yWLmSKawFi;qC06MMi)&|D^UwGHlY) z0z2HuD7Y~tDq=y#qdlAIE{l^<$*lOxny^Nd;k)~K)z;Yb_yK9~fiRrueCzezSFVVkE}qlo=^FD&I+lj z(_VePR(M-_d8?MK6(YBWMDnXz;mG;KE7M$7AkXVJa&=n5kgRjFrO*=XU-E(y6D%R` zv@KtBza^EiJH2q`9c~F9{)C*{UujBn)M~iOV}g!X5AP}k33C+1j|xYj(^*BpXO$AofabC`eE>U`dAhVKSuT&h>hkP{wQM7J}8OV06>-bGXB zJFU9?q0kgr7DT8UY1djx)7_BMvV>jklMvc?#=<9OMn)(EUYzVDAt8zHXNaQj7y5iABP1nUP4 zq4sYs@y2FDglhAW#qtf{`jl=-Q!zl5R#VTGM13rrad!<}(8KyY`ubi6^>CZIwC+Wx zE-3sLGs4#BV(P*z-tuf6>>QW8Cn~0cdDX_%HBs95Fwne4cSH+&dE!5ex@y5;h-szq zRuhL-J{l-7*2EaeLSp+Z4Ggc05H01_z**yIIj2B%sL-b#?QT^=S=O44Q%p5f9&&RC z%2kEO80?`S9Sm^lI1%7jw%!R=|{_qwlF*3UH9ETcxb1fDRf%dD2qG3doFffmW7mgc0IqUEK;-*0((kU;uHU`mt8I^A^kg1bLX@SMr&IeQxj#d zze}}Mm?Q&(CeI5kZPGA27G3!5m^7wiRs9btN#j*>KK{IuLT_~W`NR+@cwF8vW1}bq zj5U9_SR;v{Hg`(zVM)&aNZzEbmW0QRo5k4`5~z1^6youffX!E$pMZ!2#C|756ulIO zt@9EsF@JHKdUIOlnwmHa{0i6p=n;d;Nt$Hkbuma#?+Ld$h{3|E$ag817)%B_xOZlW zLQukF^w&C3IP$WGdf%_Wc$$sYt8o#?U+u#15)r^5c}bVVau7{FSEw2YLq3^HLBsk3+;n9}D2ay{k?7SNLK6Zz^<0C?98zdVigv z^Wyh-jQ@859&F&6OL47Uft-KxcB6J7b2-JNcCsW|-)TlV14 z^p>bu_WK_}%9jt%u*=Io`Rw%n$$lH0k#Rp@iamPjjYMeJ54Jh~fvI1*W9&#C$Fs-I ze`og{yJ{cNH^80`w>(lXhzAp%O*_?Uz9aq?PD<{-> zX3E%sY^&fn?`n3nN9fW=k)PR5u4(I~33ReA9*taCZr8^)kO}@6M;~Nw6xm~tHZsh% zvFWVp|1-h%Un*g)+BC(U=l!Ml54T48jUesIb16@iY2aCtYkC=5H^-B)iCMYoS;RLMOtFdcp-ha40KrR`gn zp1A}Pu9i)WOiCbrwDwVdz9iVv!j|rbrH~>JQC(mqjkl`t4###;!$JJ0 z@Xu@oxQS-Yc>At~^`yb(Tn$C!*X>RrarDGhaU}i&p@jPAHZ$raCG6UOIkz4q1fN(w zrfaSYAJ!>k%G;+Js3OC8pg_eJl1REGqq{NNTd4d_Z8FJNbCpv%eQ zVc1Gd>=k(KK9j78vis-zW2Cg8_-K*Xo}vZMCxRmPq_i>pTj|-kRBfcp9Xc4Tr~{)w zv*@uL9jMAVjZaf`aUs;L*1tv<34MQMDm?Vi^(Spz+o&FDOe;?Z9n*)1^$iW`asyye zA7k*tXEsYvgyg%-(HsJ&+IXNao-YKR^KrV z|89xA{FQ-k^{w#icZ%k8kQL{S;L3AhT9pe06ZfkAxn@$Zv2lCu z&hHfDSnuYl)u%%KyzT1ZU@F#|9rty}r-FNb?#azlRJ0r$F}$fy192nz?{gm-B18ij zZ_;R3F<*Y3R7=D0g}Y)JTm(|muASX%P9Ww%U{mux0wu1I>Wygxj9QbM-+dy$a;zEe z|3e`A@`(J51RY}gV*dWnq2rvU>XM}_I;yYFysF$mN98%zY5Nd5w%%MQITuSumP%;= zcLp81N2|*NUed9BRq(64209i!H|jKS?(etQ`~4#?1Kvi$%kmW%*#BQPqk+T#NkfmW zxtW2Q$qQng`xvnM6u&*FQ-`e#Wi{9PCN@4YU{oFQ(4ek z@oZ|tZ5DWQh`aw~u`nQTw)12T3;G#3Z2`|&h|uHt{kDJwyRpm1&KI#zv9m-YmSfYz z1e33E;_drB{cC>4Li5eKexD~Sn3|pb8hDR|s#Twb?b2BIsxagza+!raHoUdQ`K-!=x6wz#$IVKGqL-*d6vh=C2&-J27Y7}&Dd zb$6K<1A4m4hK-gmaATyk{M!_V-*_muV+ZJHuF3HeZKGr9f1AH_RMYWd?5>3@=$Kh~ zdT=nG4#Pv){;Ch@Fg6nUX?lZ>((Edp=y*DIzO8spji!V2jLNJ&NQY*|t<}!EIDIcF zc|yaH!;h8wj5aapNNm6J-PMGSvbcpa<%)EiklfH?BTNVP)(5efBLvRoO}iW@Cm??D z>?3+IfpNbt`A)tB?m0%V(@hB|3yfaQQ=vcqG)&Zuip^Vh-7+?$!XdJq zskTUg{HAYZsHWg}`n5wRu2V1;nb9HQLxFooj#H`;1$Ox+S%LE$o=X#+CBGwsMve+I zNg^YVq`hXygN&+)@c=OmGLFd1=BysK#+T)46R`!>5Ntl@6?fDc&wrP`K25O(>F34| zk$(z#|qobTr&DLB|5zH=jE2_K;waT5@|hnS|r#%oxd=NXXyR zo1n~3g6rHuQuYgTxLQ1`S-;mDW9OU06;_%f^Lej;MwJ;3_ualcdB_ZH&%ecpTAAV0 z=gXVk^O+&axkV_Z!xT44r>CciO%eO%KdvRWO;JBGYrpKIDK7l})Y0Q*iny@u%QJLS zqz2`?{8KVTw}rs>r(CAk_fX&BT8{~~m2KG^0~2`t;NAP~jtPWrcYkg=VFFckPs-z6 zCXoNAGSEsl!5Za<5`Ic1keCnrAjD;YXSbC8z3Vc@gZYFt@5_u4IO=v{>rG=w6fQRX zi84mI;))h&4`Xy4n)qfyHAcA1=EPXT= z&Tf8&SUfryy-dRp63yM0R`nY|@X7wH#S8<8aW@Jc*=c~6PaY5DOB=u^^u3o)gFYnB zN*?l#(?>8hO2vGQK3+4n*aUOwqoJsD{f$yR$Qs^xKt8O8^u@rJb!K|7n*G#%a8eha z>*p65a&*B{6CAa~R~LTwgvPy;baAMwx>CJE2e(?&IG(t^oel{Kf1Xkn>h(O{&B z7Ooe+R60GO2|bIosdpY}!p%9vah10wh9cISh+Uo5trh&I2F=}P!k2}p;hV)|En`R(M>|Z{-*#8U_`=)qpA9OAdYW_g zsjUhGx29A&6e)vUXc*P6r3}|Ehj#MaQo=9ZOUs-kl%QxM!F^Ru5#L+BtUsu}8b_e< z)Pk23toRx!z(mOekG+9(k>gx!-SqbAvztG|d8T^uM ztKF(AgMmveLWMh}QAtYtWN}prAHU4G`wvJ$!2aXghc=R!*_NERxAX6O?-a#{ zfSX4Meo;_5e@U&iUx5_Wl6_jKA{hMm+19viIWEc9Z;4pB9JAA5*JGT7@!n;wPXDwJ zxPIm|4?kQ6A+3XpR_vu14Od$8wLuWI+Xku(`ULQ<&EDxo4L=kkD%SaD^5L`J<8xfD zycm|@{wXHNgWK~ym1RXs(4qGBmf0>Yq>wB|6eSnf4@;Y3o`ue{+vf&`-+q{72ZuL2 z4-lSV`%LCuOje#|dmpLNc5(f|W;Yb;3G0rqzYP8huedb8e(X*OtX1h@cT>WPJD0Yw zU#=ebx=HIj+oR5BZ)@CLcF^QVgRdc*XiWC8J9M&<(6aJjg~@dh3CfN^x#9!F(5dY; z!^y+M-m;&%+e;^iWxQOkR{2d4pTid_jf;O06ML?dclOQ@O>Zc3@h!825ziW(6X*UA zPJX8vHV)1c^jmzynZ>`v&kMslM{EBP$BX-Ch>!)MP`7$kcyxhCys$B5#%7U73tYYQ z+nGh8h-md3%2*`Svc;GQsf$Dg{pbpVU5kV$C1;Z#&mu8aFiuH~Ss;4*-93sw{Ud5> z)7Z{ae~IYCx?eG4^Muf|KcUet{t(x*`JZWQm?LU8uWn{!{U(-chuqDo|3w_8hq_dK zoF?e9CwM|iCy5}JUilmJ31at3u?>k;!^DM7zu$Ki28o08#be)`dWi$vHhGGyHlpL; zcF)c`HAMT}6<=QaJtow{HXSICdd(I)H>UmF>oa>&u<$PT(q4AiM;~@);1K(SU+gcL zo-wxO>rd9cx>Ibsp#BYa(|)mcE%lDH6`5mOy4~ws>i(DgJ>Z|{Z0;ia%=x8{Tw<4? z@mk`0UMdfCO`_c1%=5xvS+IP@6MocQ{abMNuprv{`=`uImZ56-?y%QgLNGc=(soN( zjwzuYr*XX%I8xJpbirQ~lHoV4{K#Tx+(O#4V?hkuJJbqnK8Zta)nNI#1PPSimoDz! zEQ#gZrq9JzO2I?oRD4yf6eM#sB5s|K2A8N?(V(#m?g|~q3mB3CX>EIg!L^lWvwiVl zIU$Q<&u@*sZF-~;BL}RaB5NpIYC9`rG*NO^os;^W@~XI(+h^^0O%RF) zzc;QaYFKcp|8KXHI-HM}GA>+Ihmu&{%Gc5w(7G7zwl-Y@?awylChBM+{joo{M+rwa zcj}Yqo3ubFk?t4i)WZ3$ZAr9XZOp7la}nm|=riwc(uXTLuxYoAlu^~i#4T>m@O)j& ziDpamvGgFeai}A;K@TR+%Em^wbM^%>^oFlnAEe;%<^n$hWc@o;c;$xy%(Y^ST#p(; z;8yw8GHxS`7Dy(#uQ9?{kIJ-uoDu4N-%X#YF~ZdT{7bT8#yDuIG^@PD7!}*y79_73 zqk8j|kgpxac(-k={)vJK9^IYY;I-QXjadrcxUx-9wyaz9*Q5zz853HYtxVA#?;4lN z+4Egb^YrsRnqt#v@78K@Gti#D|L|#t8P<1A%w=Yp!OyxvVa*RS*kyGb7PK~p)~ui} zcZ@ki?Kkjhelmx+y}F%;6bVul8r3g7Nif$8V+uVWq5hKXwgV$1?94v+AVSvyPOa-^ zDt#@$ztT6W|BeNYZ;&ll_|F323u>Y%a+YX+GF$V+!xA^68@TS>wS=0Q#8TB^OJqmS zz4tb@g21QEJv)zBL19!Vau`;e`m~|vg4Pgz-8UHL$hp6))L+hBw?@)NpS4H(tntBf z*tt%J41eRF?K&Z3{1)}{t1Ko%+Pv;c`VtC~`?#m<)=@AMD&h0=G6nN85`N2DDd?<7 zXRc77B8u*?>f>$>SB_uZ`{+IuRXHDL-hHLw-R8wduUFFG*K@T)R&7bZ#V40p#NkV`q%@J%n*?S>YV@_*2$b>- zXwC`JVVBvm$wq???>#rvtLSt%9=X|n-kpxiD+)x7BIro|DpB|?m5!&1e2%Wq>2OmH zHc|Yd3?NW|RY}}gPw{0I2q$l4jdQLJ?$dZbkyT(NM?-P%M^Elijy!FeT3MLr& z>%PRcFj4XPr|$P}OeAjDJj6H41YM2sXbV3J0y0dVA`W+T6*t}LSWmp8n18Ua9_>M zuaY(_%&^)r3S+|d>E)S<>x)Z;p?hf zY~~lvyIcq^AyqO_aDINgH7N4U3C(bs)+^cmgC zG4iD2((iqe>zwJ(9XGueWJ?F3aH>6-#PR`oK^vqj-pFnHk&Q!HH0;jgW-6a!7p!z@$SB4vbt@S-urWpiu($0A= zY7oF9h0;7B0&7c-hMyXzLH~7J`%TU~2Bw|iw|zl_bAZ$K#Z(&R2EVGy9-(1uM}kM! zb{cqD5*g8C8dht&);?9F!G6}7?#V;L2~)?n>%LKOfj@?OX*Csnjp}8)bExo$Tay_W z$I%6IU%Px?DkQ>|8lGfOv6v*jZ>>CsPwlVs`Oi^cBey-9KF1IZMt;>$A8$E~^cLTN+TcKv|xNd(k z$CeQ5LpzpusaxSrq?&&F5-X52GK`A5Eit6FO3bR<5{dz1`^(ZT zL606;D}C4!Qcn#$%GOwd`QyV+2A#cxz0a5x7DRBGk(W{^B-2&d3;HPPdk+lxB!Rn*x#_pCKGJ-JYlj zGJtlq{Ae3z|NjpF0RR6Cmv=nYUlhmfJs&%J@4e^u`#ef0l{CEvk$Jw-b-H+b@?4m7z78yO z7Szo+bkJxpP*b>98{?AE_o!uBu)jK3$tJ0Vi_KumJ8iYw7?&VvmINE#cRjQ~eZm8WHw@g$) z$FqW1)=6cQ7xX0;1uEmya&=eqh!XyZX8UuvD`A}h-E<(?Rh45aCld=drMS>rR2 zLZTS_LEWTpBZB<}@AiM#Pr;F=JF|7~3uCVCl%L0MA%y2n%MR0o&|6xe6|r3q&wnT0 ztJ4?2DnDE1OXB>Ps#d!_E5iqxlb2qZ0WUWEvmD&Lg$LH(a^1Y6xv_Y4%Lap7E=VfA zb=cX%iIwcP4$PvQ$hRG_kQ1Pm*ziBuQNS$K~r#wUX#MResugd-B(4+Jbu>?`l9LX zVTog3=)2etcqYI6NdG18p6fIAjy^2ID{`^^0o{aX=Lye$MX-G?3k~|vLHuzm@jG^S zfY_Kc=X=X>gy>SZq{V0ci{N}aV)BtPNrX)mT=^wAO*F)@Wb1Oy5#nJRDr{T-62ke5 z?!G7f5zBkyF7r`V2y2}m``&ajk*@qXhZmGsNbk77JB!;`$z(S1lTk<6NO{X#yY4V{ zGBw%v)Ss;!WNlzmX1Ova`Kyp~WMzPpWM^LS9lyXu3gl)U->%P1<_NJx_m^{%v%mH| z+GfT>syg>hE?wp!*Sd=A%WLN$xicTht)1Z^=R-%+oL6|r(r2^ul^;ALj$IYJ`hth- zy{>UVE0l-4en^MTBF;lz4G@q0`jDG+>bSQyLx-ExOA2~2bCHWY!9{hqXZ+vsudYL> z94GmJJw0)w0|z;_bXg$Ojh$=>r<6H*vyo|(g$*nLtYo8Fp5x73EM!>By||NWnaQAz z^pigfnaESh`xD26mWc(8?|i>bE)t|#{5tNTd16PI&J7>=Swh;CTS?3P55XE|R?eR= zL2PM{7^wemlsLFLIz^HGmH0|7_C69CAhfIP4{UAhAXZlAYVMw`CJwiLiCNo_PH!E2 zZay(lPdAuNuaq_Hp^tuRjHzlJqSsIFtQF+{LBBlB7nc<}PUmKQu(O}-54~*%ZSh|C zEIp5MFC}W?FTG+->=;kl5`F%$le=6d6GGh-sLg>a7_2C?%++KAw{zN|+;MiS5$Nx9 zxx|S@Vf|%xeQqc=_l}k|@Zhdfljg_Ge7J2t#r5|+KQs>?5;ry##1w1J>M6ZyHRB8JxFXW12qwv&Rm%juWh4zkC=}2N+qAr6(!t?iZiK-SB78qQlO8Z3MNB^H|S=nz`VBjwX(V@F2;79;VV|fVDtH(Qub=t zc`8DasZ9-On+&i0*r^Un!M-V}X>}-=i=S>hse!_VloXPpiSWRYo}oLMcrG=xw$Vrn z3aehd)`S*>qm{Dj+_dp?aC6nKVQu^#E)M&0PzPBC)GMribl_%RxjyuOE{dYQo{jvX zi_{LC{KoBinB1*;?Pj|k-cyXGDen3ZcJjOwKctUY@jngMEDey5Z6^IS&H(oQGEQ<0 z2AKNlA0bFFgq?9(=-duN^h6bToqS*jH22e0CJph^N91*vg%Msm+st2yF~aG}iQ4uz zM&NiiG`qxaj6@&v>u=?RvKpC)*)6xwg2Zwig782`dhQyd!8|6B9I6jf6(yLp#PvGxu6f~aONpe!8z znqY?XB3hzey%|ERyWUsvn&Y+Vy3&M==3tij_UUMEYLYvZhT z>2?cj$&k-!zh(h8>-Xv%y%y+nuPGN*w1hox!Yc<~OBncCk3Pt?L}+tM|G`m9SS5)b ze5G%Nq&?2bhr_MlbLMhRX_*x~qkE?}uUMgurqSuS+8X=!tCVpkS>w?+3&+KG)~LTS zt-4;+21e_`@^@~xfl&A*bBh}`aJ;K`O>W2rDc-6buT*WZZZ(rfk*_TxSNXIs-?D{g zwakd}2U~>eKIfa~w*ylGWwpDr9n>D))VDlkhafHEUjr3(cp+ui6!F&%e7i0=^%xMy zAvV0#@g<;;@X@<4g~0N}RuPU;0>%61DQ7+s$p3lg%E~gsUZTqJQb?RVG5hVB3JKb_ zG?fkJB+BT~_l?$*Fzil#<++!{&ro#}j-w=6XX0wZ(n!2Mv~lB_A`(jO7dJU{l6cE{ z_Q2;k5&@Z&DPorXdru}!$V=9iY zoH)Osjtctb6d{!%DmI38yx+V?1^bN;>mfqJe&yQcC2blG_NLt&r_x|AvD@e7RvO;h z?p?I@r{UDE@9lHpG&I-m@G?3{gI-P^$KCTZ*q!EgF3O~#M*rs7nOqu{u2ww!S4@M| zQA@FA(4flf)_A9phD)(5LiA2Xe|z+8-hLXEQ{=|7Mras!2z_EcM#I30n3w7l4Whj2 zg1R#_WQgAN(we0q`0(@+h0$)Tzq3i5@x9n!PhlBjyuVZ5nk(OENbV>I^%|g|I&tXO z-48S@{!DH!d`H9eS0}<6s%c=7623lNLc_NUp?z%(|3>DUGwc}tp3;fkpMREyf?dj- zwvjXh-Wr(m^fC}vX3{X;Y{eNz*u?4xlHyd@47zYn+PImg5Z_ z9~kHVI98^BPQ~r1<+`O@D)L@{HR&=HM>`Il(}<&DQtO!_OAr+|Gh|P`V8rK)k-Nri z2PzsVHe>w;RLEDYqQ*#5u@XLrCJri;9`il#_(Ni%WtU+8011(^xzyZ75>9%*HHZ=t z33vOh`el!;VqE3sg?2_>O*-}@@!OH` zPHoqn)F)A_A7dD+M54)2rvJGZ35~#kCKqlJFNFUE9a%qtTPUZS?nWV_H||E?Ir?o^FIZW%n1}W>0Wb`A<%Mg zIAjkKfh%GotcM5fP%rsPSRQsbBN&M%`#0|FakuD&Y7@enzQX-h14r)ug|SVFRhHv1sn5(5S1_oCNXBEKlZ`Kf>Ub290u+2>;R|_OQU=7F-WZaKV_f~r}n`2#u!|w7VbCl%0e|gK^9Qi8m?92a} z!BbeF&9vAIwZbiGKEY0zL&FSoGYLzhucnY08ol)KrYS~+HkXQfn&SD|Upelg zrf>+jsF~Ahf~8Ha{I%yz(0P#O&@D$3+z_-le1OFSZ$}>%2~`?nSN!>q6OqQ)R<%9w zmYFeDMhSL@KSpqE&aE*hFamAVxmfIg5j?mI+QKx95bNTqhGB+Ym0Xn;&o)HtB_79b z9)>8)a?$=IU(9cKs&tX2Y}R?iQWw^Dj;~rM)WPP{8I(pX9sH_#KOB~&4QgYa zj2uN9Yi8{3=$_HS4PEctb#t0HGTs!G6Re3>{XSBEzG+}2_oeLe9u1s+*i`34*zlJ9-4{`W&mYwE5*9_wo1&z@?jqQHUOBtx z0R_jDZasYeMi@)Q#newi!my0zaNgu9gt(@IGKu1X*l2Qa>Qgd5cD%QDIl{#UA89H^7^c~~Bat?$~&=Xsp zn=8|P)7hd5Rm(j`=@*MFD7FUQ>7RRlXU%>Yrn`9;b66=3(zj&XFf6(Kk-pw|NTK`u zdwSuB*hhywujzKn9W5!^>2&!g*YAF8e?>^tt6dx1(oQ&~7O{zDeI|z9-8bIHG)%n7 z9jwt@`-7N2=ikJe{+q}v;STO>n6~P?AUz^P*0N6YG;S0o?Mzc9?i31>3ohD}qbtIs!qxF6LxMuigv=Xc zhET|<=gHx{S1IJlv(a)s`4p0V_v?*)g%tAD-_5;M4=JSh#wn|uYZUUH-T+H^4267J zlr@p)Ng zh}?SN+}ZJ3L9#0%NHwWXfXw%6ozm;(Ct3EC+)KXAN3Pw&Z`87#mn?GU<~h#7L%K9K zC52URky}1z^hj>!BBim$_kHr_UkVgAE-9t2(Nt>=z_BU!P zL|bRz#=7N2Ld~X?jBT1HvhV%!*mY`#Xjgj_CK5G8)OLLNO8oszw8jPh8xZ?Jr2QL= zAbq|N$ug=MPe1k&%)6YYbS||JW)tZiZ)Wp}k)Q*&(=WcF>v69&xe?q+r23|B}oV{Qk-q{YJ{hdxun~=$j~7_4{wl(4~#%qK+y4r6ru{qlk1iur z8SwV)3OzdZ0Kax5Gt#4#Gp2s9!2NmSg;XjV2p7xtGZ)z*bo+GLbT0>5^j43JnR20A zo3={m1~*;?Z0RLudEj5I^}^ep51#_}EN_nCN0@ng@yb&HNY&M(x%LU-h;xeK^%NoG z4@H=E+Xy4{vPx8UM?5kKQOjzifP6hMh9L>ix@cD_4f6W_eDT ztqKl$)>X4rs^G5O&0s!LRb&wC_HVLP(Us3X@P}OurYj{^MSK{1=he6N$8$B9`KG;| zXHv(3AM3u(u2n}b$6&k9X?3vn`BleNsv|l%Bx>E1I$S$=pTucufa!tuSeTCnd}Cwn z*|Ib+783ovw@m~2ZBqGtoSNuP4H`GI(}e32XL>=XCIoJTFGW7k#Ic0hcDK)(xcmB( zT^2H=+#5Y) z>+l2<%X)BIDGZOY&_`#>O-K46efSniIu7OPqowWR`iOo;|L@$_Ym?9L)`$Z zb~B=ls~LJ7m_KdfV}MN7o^^E$UY&b1okC_Cz(uRTpbQ4!Fp$-GF=&7m@yA9x*bI?a z-jz$}8e-Qq=D;U=3}M*cAi|z$2yIsVUgeL5xG>pw$wtNqgj%BSj-5uJZ`^Xa{hARv zdIqU=-A2&toRyDZvmjO%$>K~YjB*qX*2IqP8p zp+}}Cdaj#5yXTwk zgZkb#+bko^P~+ut&9Bl7XSX$9&S5oYaLBU+31@Qzt#7jZd(j*YSH76ncA7&lJ96cp zoCOGl;$ZjxEO1lR^;^{w3sgPd+|4;{fe(!x6W=W@VeD2P_%zlMe@d?@Y^$}ztG&8Q zmi$(DZfD11#RjJ&Ag>*3gN$4|W&US2D7H%WSpCHY2_368 zGl|h+Rff&m?%5{tgTZlptwRbURG4mnl86M zwr(oC_g1X^-9|<6NoAGzMg}il9Xlvj!|;p5o^1?2IQI3uI9EW0b;SLEuXh>zu9E5A za+L~;O#zZ^4F8Sa{i#12ONF=~Gk0bf6-6)Yds6%v`{(u{I#Thjb#n-5 zK}EYpmi<+2hPCnwI44WR4w;yuB7Vj`Whr9|B%fo$)!GYJWcl+^7+Ce?d|9x(w9WK_48@y)Z z*YKkl?pvqraMSf^%Ts>_A0GK0HL=zXJ3TUYYUtTPrJyPAyEtRK8TTNS*$&C-9!_V* zY++NJ6ye!pi?Zdw_`bKc$V#m*aernD>(V4X?i;osm;RnOlx&Me>Yj`9M{N`|@9C6kPLV)-q*x7`NinFS`C zjJk?_wDMay#RhAaXZ8sN*kDugy}t(u8{97MQI-<3ft$u_C;1=NI6A5A7G7?R*fIre z)$`VPIU2OFY^ODz?mWNRT-O>DjU_T~#R>y6vcmg2tq||BXM1(N6@vdW5uZJ21>ck% zd;GRqp)Tn;>B->AQ;*`x-6kzj686xjl);t7ZWOlj$1HK#JynKcV~MrfzCK@AvVdbk z)p9m0u%lLJ&i=FoKJ$0f-FLUZW~blcYStE*Zw>IQSFk`vMwaabE(^pL$=#QpGzXFM zK|HJ599+Sg)%-Ara-y`0-a~T?OTTuwpK1;h-WaF;W9Il4EZgzY*Bl!kog6ssVvevK zykQxp<_K*+>NzOOnCD>`D92%rrynQ0hkl!(&OdO2g7D17O`o*-xjoo1KP)sv>Et9`;wGLrieNU*ylpO(tkNwR4ZNfeG@o0-0Tf zOu%*L_*!DZ7)DkWQs-KY5vVcb;{DVZwSr8dOBalx&y+JF5o8RWoW-LC8;v0o*pQZM zXpDDEb>A&TjN#E49@#i;grIsW9o-Hiq&!qU>QH_+)@uk>ud=5v zD-5x{Hq&JECd20V4>ZRaGU6thU-6$Iq<)mA6|FPGMP|KTV?#rj@Z_pliWwp>+2XkO zoB>oPM(8}92JoIf6{lKg088aP%D2xMK*IL?ccTD?K38u|zqiH!CDB$q&r}RxM`;Of zU^RevdRPAM8hvP8%#)Wnr4Np#`j>))K7!ZnkgS^3gP~W;T=7#qJZ->tnFD%=s9n+* z*U-bjtF)1CUvx1hWv&^Lt&0P)TuiY$b#d>R+)#t0E^66~MAX`Kz!hqEKk=Ln%CgeV zRIJfKv%G$j_+>V(|=#6Bk*06oI#8_ z?iF~)7pzf-ZO^U;kNMTHX!oS-NtYT9dxY^8-c*DC&QX~bKQ%-Lk@lXtYT)1s*g7$( ziqVGHzu6_KkbjkQpXZn=&VN=LSSD35n<4gc7l$hRpXjx{eWwEU<~IVrFRS26ox`*I z?J7|G6t%!1seV%D7;ac~aoIG9m|5V|cxk5w*(v#k7(#6iBsm;Uh{I3_p-` zIadj%5`JE24p4%#afouamJ)Phr2OZ8DWW!P##iBqB0}zTN+|~`;!s}8?H)r#yuNbY zYR!xS&hrRPCBIO>_mqT@tYZp@e`PerWUhdWBVDbFrSe!w>WTG#FUQcQ`47?`WTCiU zAZ(#S2G)&ckF~m_@z6BpuEpn75ZMtVF7rVOtCrF}KkJsn=;4IgUmqo)5?+49zDFE^ z%DoFG+r+RWB#{>UMic>Qear`nMIcVR-9B@Vf~0o!l^2(UVes5&Mf<1_8ZM+J7}p8l z(4FL8gXw%=jvDEc@!~;6)y-sPT`q_mT3vBXkOQWD(hbEUtO$4>VSfqC5G<9jTA{Ac z<4TBg=hYYKXL(%>7q-pOoA!E+*Pi)9ck~u<9=9vE=j)Qn}2&dJoi z`B-NMz3*_pkO=WRzrQ}uIrl#2p68tNp8LLTRt{p$ebWSgQ>j(#^WTJQ*bS*u z`~DCQX+O*azt0iBuS!2)a{MLMPfXmKdH0tnD=pY(;kQ7%@$3!$*uFrVTNIsDS6?Jb z!sjOoTo;Lhva*(IP>jx9${}Da6vu9Yx{}H_$ zsZNiF{{TinxxW#j2Pk|C{>#LpHyje@rhUSC;6$RFdD1t56D7~&E8p3|h2#bub*Zyl$l{2bh|FznbnoBCcOp(aDA#MT*o21{ z)$jVll562b(Sccl>+ARsWqHSy%4&Wz_$j4@Q7wR!U6!d6WvkHbuC|Z8If96?|K(?e z>q5vw$cf|731Rf@Mt-OC4iWVBfTmK*#?@$_r|^uJ!y2^h?uXxDx}xZLbCZ~6xhP_F z$gODEh#|7st<+uhV(7`)A?GuMIFf8Vlce-S94WoN^(2KPffAdXVr!Blkb=eAPghn; zA_=pli&rm8qP-7e?_C#>LL<%DbcmHgHWFenn*^oNj6lo-o^#TO)I9cmVL=)-UGF=! zCtL>U9~r1WH6?>$!b>h543b5PM}5vGcFCejPn+r@mK?fLI)Cg`h8*&{zk9)FMh+Qs z+PotX^5~+u=&kE<@<_Fg8MwV$9^Li$VP8d6K)ZQYRRmm8KsSmX<$dW?KuU&x7f9-g zD3T<0S~o}$IX+zqr#(_clTqb*AEp!$>B>S>uc;DxH*;T7_kTt3!-C3aeOK_ULQp~x*5*5n4=JJhAv=Ao#gx#l`CiZN#EE=?Jv1(l< zix><+$!)eW=yZ76)^kzPNT*QvIHO4lmF15!7VtiZ$MCQB@{vU19{%;4?nxlex!XUV z_ll#3@{?nGrNq&ukJm*kH;SQ4A5IXglcMPRHJ1%yj%(0~9pblg?~9=5t(NjTIE2xy zE4O!i4W0x|Hyu(*qRo@kAu9sejgOJvAuidC?ti5)(J6;1s=iAx@0 z1us#OVvGH_khI6C zi7nV*7xSgGo!t`Fr83U$V~^O*Z~5*$$QI^k57;a_#*U6Nyk56?lKp(0k@J&+Y4$JY z^@o)TXW0kxZ26u)n`dV&99cS*w#b$d%n31xTxL@7?jH7 zhI`iY2NMN&fm3%fQy_>Bj%s%_oPWa)4l#WR4(nFIC6jrv#34Z-$)nF3p9{k^&6=YL zIjiBrqm}4bS5Z)eu-a!^#lYvUXUXC=acI~T|Li{x2?*>P72dT=65f;vFGGM7EU$0< zml!GyL;FLoLZl3|*5;5yF35u7G~--TsvLwIF*G*2EsvkuPo`%pKvkcX&68|JaJ$zi zn(;&l{F2<8b8400kM^SX#9I}hs4~3tgH=KB(4R(&8CB>F**iLSf&_`>r1?b-GWfAd z>F1-!aAwwFa+XI8{*`4e`NpZih~h*#d9^y6S+#-h+ZA=N)M+j;5!V3n+OWKb*EJw3 z>S4lKIZe2>>*Do0>6*a5eAClLK?^v%D|1wCYC%_8$#lG|HbhP3)5flA!|}jcA9D#E z7?4hhnYy9_?*qE_pA^=GHCLU!QsQ)BedN`3@UgP7zBbW8SbuxOB)*5{{(q?^K zD@7j`w zpRhf!{TF$<_F)qrT4kQlF$4Q${*gGW;z3>QbnH9xCe4S~EsBJACDsZ>8`NXhq_lFq z$HqAHU+KiQyrRGOhJC9m5I2h5>bX-scQy0wH0B)*p7jIF9~e; z!$379?6walyfm>FPv2EAz#fc_sGwudI&~yjW09}!E{FfO*FDH^!TwfzwbdOvDZ^IV zgB=hlJQs*1dpbP{#kTs54M+U{eg46R=de9tn)lFe zCkYo|^Y19R7GvEFP;~{iYllN9V7H)=`Ub4#^zThA*aHIfsb8`5XHvd{SkVL;_c*rx zM1Sxv?22;(=`Z%5@29PTdS-CPTjQ`47EbmoDPi+m&hJsjHYQ8;>tY|&oE@;la*&Fq zt+5K53kn^uistisH)FrENIV|c+W%y=_F@B{@7#08`KxYOuD!zv3FPk#-!SAF)II^!6_7 zC8d>316Z9z;^Pl&sc@FkAM8WBxHn5!RQ^bXN8b#jHSc?fU~jcwS&+e&+dZa`vHb?Q zV1PYepwdOf9*Tb>vkn^)r6%Wt^%nkh<_K0|N}(zmD@5tOcojRJRF{*EHF_d&vlv?& zls5ew8}6HMv;k{8-rf2hd#sQ3pcAVcD06-U+f(^zW)e%ibbszI_Mg155VwIDRPO!S zBf1vP=f?a^MXbQOi5YdQ>I=U~eXOIGJf9i1c2*&ufn`_>k?pWU*PQeDPZI+gSJH`Q3$B&Cp}$ z36_;5nOlY3e8MF96*h-qo!^Yz*%Y&;8`~%@x6+4=cJ7cG#wJCb`ZI}rv)gaOAMB{D zz|R$|UtF)CfFU0D6DvX-%X6hcKn446vnxd#tD#<*XpH?a|1sVSd-}t=vrMeNfAN$( z*6F00h%>g`E9voe?7E+^ZM(5qld<>rW8=O>{s_gQT_fWW*fYgJ7h|xxH)8oOVLu7n zD7l6;3QByOj-5IZHkyU)QCi#e0PAf2d}A4Qpl@ez4OUbrcmFGF!mLS zGQI?U!wwcIm5*UVSvK2dv99U+2j;O`ZamZEG%|w%6iF4pj)xSPNMOrrCiN7tU%2-l zAz?qy*^Oyp6{Qa5uEidk6nwK4`z>$$bTIZHB7cv>ik%g$NWun)RYw+MJ=bs1eTki| zb0|wPF#~OW2kUF5_*_WWY^%UpH{4PAfUPhu)SJTErR^-_rDd*sq=)v>n)x{Q_|zSlR;P^M6>L6r<5ISk|Ze60z8T5uvIC zteyRkd=@sgN;Z&bhR+GBvvG)O28$Jy=joRCzAW|Y=kF-S_e1@w2DNWyaDDuN@+(<$D5-Ro5%)BQLn%$kM(O4- zR?#K+v&S5)L@q2Qlc-?Ru2)syONCEj2d3WKrGkR3aptKWDonCuKbwis!23d4~U)*bZ?gNy?BfXMF}4S zn;$UYX4&oF)!&)0mG|GQn+yx8-xQWIH?Tl?G3dflBnzz8HZ09OV8Ldi7zg7X7X04% zOUX)*0I`eiI6o&~u;8;>`yK*Ht*S1MUM8Try8Zr|Y67k%?F=g&Cm=TJYZrSJg6TV6 zQEl=Fj0UKRPqh%7;NRQ*(F8&K#d+4WC4#E=UWznZ1lh^izh#^dQ2r&(8o44!OzLly z@<4F9c`SRM4+65&6aPQE5h&z9f}S4&9*b9;v;GLUjz0OhaUTL%a`rcF+}4Xyk80b4 zfUh#aHE0Kdy#G|0@pv5aWPhpWW(2dG>9$4daevSA$1E0tOZy$wYw&!g?a70F8VDry zn8Df72n?ewglG8>6ssNJHTXfmL~rfF;|2meKV4S$&LCh+K>v|>7y(Y%`@SqX;dQwx z`S+(L0R~m09KV)X@bb~&0_Qds++x>v?9XMvJ-6}b`u|wad35NRtOEb~Y0)8I+$Tjd^2yB*w*3=W&aLFcpP zpKZ(`(k3S}UdkL)1m~iT4dVY=S%y398O|Hs+BZtZ;d?DNx-WS<{*SO0OzUypw7!&wZ%&MO5kvIzY7BTN-ZlXZj?zOgDt0{1^WOd_*_okruEZy!{qA8r@ zzP3esvnkju`%@SqrqJ|4Kl1l$6Nu+d?D!dD0$&@VU44-WoU}Dkcl~D!XDdc8s8tw4 zw?Nc&$uMJ(jFJk^Fg6BNlmE``n=}He64~uq_l;n_I>pi{5Vx9vJ)vJ`(PsdU!z(wO_BDWS@p_jx4(o&3O!Q`I zkUm6@GvXdi=)uQo@tL7uJM{%2%1gY%R!rb&5-#&;mt@)!y1lP2j5Nzw5}-1ihte;dkmZKr6Rz zqSHpN9o@^+f?DYf!6r1Y85ccRlQtRuM8=(rlgh{CHNo_ zPdZzr2n-pg;OVCdpzZL0{IWnEMEl#0Cf}8VPi{$h57K0zx}@`@NP-L`&`;-8MoELf z@h5v89hCy@D+UNi=UXt;v==>;w(vJT2 zygx}Ke=`-&j-Mt%_q#p2C^<{S-lJTATXV$vORp>&G#7|3%Ma;e@0JMVWnsyPBP)br z4cnAUh!bh+$3p~_3*Gt_^5`Cg8-+=bCT?o*popdf(d88$bUF}_>Pudf@aw|1vEzJ5 z!tvO}Rhs;0tAf93={tUuaDClq&MpBosVF|;JuH91 zfpzTFC^XF=dE=Qi=rqw_r>!H3sCR;CA-6@5>w|3xC#A&Dr={+?hzv0_aQu^SH%lCe z);?-`KPZki%c-5+6vzPLhbWM)P`$kQA!9JQqInN(!A*X%3e^Esa#Z_BE?B zWROtEA=%(585DA8jUlB}7A38GJXjwrhxUxvtvzBWk6im#o=tt1N3z3TRekR$pu^6* zj;%Wt5og-TQp43ssO4t&hBb9c=vqLvyF{om>JJY-r!S|1%3c**wRoh0HU<3Y9we!v z>{Weg1_xEq(O&0o!{w@|__toU--0S?a2qiGLL(vf%tQ&P8O5jF?eC|MkwCk62cJ6`l`OcZB?XhwM&~oVL8r(lp{y-r_7WMHs*RM} zCFAF-KL6!OAtU|0Zb!Iy(J;}H_8ncGf3#|pZ41110;KM^jfk;Z;hJ@avUn`tiPj-))xF)njBI> zIr%LLThx@0ig>NtJm=&N3W;WbE|kzg&x?*b#kF;)${?Wa!y3I^nQQs z8V3^MlKi1Nv`kdnEgW-yvP9hG>@N+>Tp%W-{Eju=oF^XJxK@co{UKiKMtPMP|0cd1 zJ=3gkWr`4bdV8M4oFM#{>K@lg4-<{!t?F0*^bzGdR?~O%eIkrwQ_9;N>xnyg`)}@; z%wSg?DQ1)xzhNH_v=(#D>SPP;v&`XT46v`RK93M8yXjyfJbaH>Ofdlk_%Guc)Zl3(U+qoe`uHwLxVW@y0Z(k=&k z8BO?6DC*rArwM(&YC-x-n$S=2nmQ7s1vaNgJE>h-IDg~5)a9fNwK_c-CbilyOFi)F z21^GV&y3nVW9tBI-|JJy30*)IdAy1>y5Mi8`rmGr9w;0Bbhlyafuh0XBvGUfW?W^; zwblB-eJ9Orjimt`Wlg21R2e}1V9E3rv=(yqi*B^8T?-1$#?eByhLFG^DyP_J2&MXI z0X-Tl3YxI z(OR#y7;g$L23>>y8ccy#B>q$i7X|(%m`tg$C~!@*&7M1w0)-hYS+`0GR0zB-Y5z+B zhl1D14{*I{6}kQC*Dy0kl{=$l|HKTM3OknHPMAT>fY)<7HFIzqbM3RHwX0Qed_xOa}fWb;`UXM3YX|t6&dTPu;A|+$QMe5RLc*CcHgAJol1w% zrI%EQdGn%wWs(XVd*oK<%F{r^zl68Ifd&bJP6ta*(jas;@QJj5qM)4H4aFAFINaiL^}7YwdUvPOrRmV8R8H61K!<&1 z=Rbx~Yhg5|wp;jFRY+IVXROiEh>|1=T-Z3z$c4fgL&umpb#k-whhmLM)s7TMct38T-OH!txr z!NXXHdrq4PLZyZTrvnqF%f?l}j|mbnO~c(MnXvBD_sJVqnUG~EW8s>^gtj=!;etgi__qtzlJ6aFu!~{;G%x=Qwz4w9@fB zr+OZ~k7dFMnaUK6Be>o@yq(+2iwRyaSLC=66NC?>t9p@`@F&93Kx5ewe(u@TxW3a8 zJc{7WM6o60?c`Xq^O7algdP{z<7)|TKM+l8EiB=w$1A5_xDMC27yP3BI|Ecse{QR( zU;urt|K-a>2AsQ}IvecAfYysplyAX+mK!nx4k8RV&{`pOua^#Xboi@{>;G3}vwJ$v z(P8ACPlU`iI^>V}F^}uhK|Aw%%kdQpaJjPE+`H8RLXcD_r48k+fW zkxMif4i~mq8%~3J`CHRxcG94b?@#j9jWpoSNhKH1X>h~l@tPDJ8a&#`ysD=_gT)6H z(O*{6AVz9(#((xUz&p+&$h_cOmn#*|iXbltQH_DtpZxUMgh`AxnhFE<1VW z)Ac*g@BBZU``pj-+}FXN>YdlJ$v__Hz8H0l4CfPVK0Nm$!}pZ4N?VR(aP}E~7H38V zH))JQxF#7AH12LMh>_v?aH!VSCJ9b>*In)%Cc*ePz0;|I1U7dZJ0BI2poC3vqacL@ z7xKOyH9Nw0vfH|7DQO*Xzk8dAwoiQ1`=c?!ddFnuD&`QIIliqUUo$X zVzPQ}R8w@I+@{r}drTYjI?CnFrD?;{G*a(gV{OQc$G@5Qt_4yOHFZlKT44SJGhjZY z3H?^hPFew)AosNB)%yhvuwA)zpddg4>fNGcj{YS8_jY{b#UKJGKJ35S@K+sH#~poC z1Jq%S@AcxHKWd;-j|sTop$4rdv#Yy$RKe-G?X`vd3>MfG9;?H{hmX3wZDx3&If(dP zZoq;0>!P6yTO5=`pmOL@fp9@C|1=jBz^5emat~ucB{1U@_6!!}ZXc0K8B>O-#kj0V zcV)1khPX>kDgnjnN@1YC5_C-b6Wq6m0T1KhGrK}CuyQSMa%x=>Mz2RjmI*1snHtr9 z8;S~$ww^dpN05h)7?CfQT5?d#_a}dVC<_J4e4EpHGK~C^XKJAogq^r{qU@CJN%2s9ot_Z4Us29Ke~ zJm$ZIprD6oGiyc=G=Be@I>IXezFW7wZ1wrTpH1y*<{=))@VAjU>c<6w3WUSEh1r2m z=UzpCA}biqpWpk=kQuOh63uGM|Iw2YlOOtGH|V}(lcC0|EA#^#CV2sai}ZNWrC1-I zIeL9oa#~HrB%Rw*)p2LmDE*X=m8szCA^OnU?Oypy-|3{)+8m4F7J9;V{DbPm8oC0P z|Cw_`S+vkwrLOr_b+qQTpg>o%Hd>sr4@JHHJ56hC(93&vkOrT$&d6ODp~-UC$6TEn zqtS=5C%sQj(ss9xyb`IKrkShTHk)jX`364)6ySSX#=|siMK|s(_prsF!SUljoEL2eS-9lhU-qcpuo<| zXJSVuRK7S$^Kqb&r~?l_b8w>T1WT~z z;X-)d>vjY3+(`GX=7}N=9;B4!enY{S7j-drUr^BJLsBiG+~2hLQOLQaFeiBdq*lVB zeuGsIXN4*dW ze+)7oQavQnhCw@sinc$AN~nC8Tfr|?3B|JX+$&yGLg9kj|HWG?qmyme##05#NTK*V z>FlO55^+2*7jJ__yI%>XwB5&|2oA2jOT$r0#%TFlf{qO5*6e- zZ`>O-qk={+U+C1uHrHe{<7w^L( zUflaXpJ{mH8V>$xT6kn>`8X;@438r6()e#J;Ske*l$~9zI7GS>t}6Hxhjxf6`Y2t* zAv-0iWwI#_rD_IgA7{ZKo%Hllv3DxyCdMjPCqM=Lo1QT>P*Op59&T0H?O4PoVI4gZ zfkltK3aM>)EF%|wtFuWN={UU*lJ`?a_$!EVkzW}x@oC0=E>uE(w{qha&6QAmQFOJ$ z2&3*hp8UrAP1RB#|QLS|mN4JJ7H*`wGQ0v*0DpyW1bgpb%s@+8tiCm0uYM_gt zgTJ`cPRNTO*&61Gj&NagHB7uKZcqsA$kEuoyHg0YDcS|Q>=H!3-^k8#vkRc?mlLyL zU--~L+fUnl4|tKi&qr)Y1P@ZdMS8q;;YN1Z(J%FkxX{@-AB##(PNbCHB4YWT9TgCb zNIFN@P-P28fbS3sO4p#;UGru}_O)8SIeNBf3Rn?k7}=!h@D5L8j;_((Kgy-=Xakr!ks&ji$N7(;?cEhL+TbsZLrwOP=J7 zlzQ6ksC(>~+WYhb(<>)gt-jEok^FU}ntSQ*exJVKzw;Me)V!)Qy5JApM|fglAbFnN zWfR-98MH)yv2et1)P9XFXTBScZf`y@OJ;*hY{5)B zZgRkTu45Vev0PyI@^$)P7!SCmd@eQ)=Y!6!2Yq5!1z_)yt2fV?34!p_KYf_JjQ`I! zjI`1|5fEM9ylHYk6nvid?aQ_ogF%+J=8?|g!1d#v>`x~N=rbdhj+#pXe(i#$psp17 za(tDGRFsC%LnhX#JTh?daUIv%ybOG)cS~LFm4*LCzB#;UkORju>x(sS*~SdA0I10zJ^nsEJhi!T*gA{ zGL%8P#xm1g3=2nD*JCx)uz;xaDi$#n$PcKKynIsybfcWUp5n#9LxF2rN3Y@FdtaeZ z_a+W{jm$}>gYjTd=qJ8w8V`e!x8Jp#R)rjW4n>CnRah9XU@bkO2Dzl=Q#S2tAY1K4 zuC`K#k_FsrO>XThljpLv-dehb%v1J>dDPS0zBQF-pQTi)8B^qwuKXj~h19{oE+bJGEr zUFLnedvsuYhk9qDIuUF}MnCkNB7#`IRTR@BB78aaNX4X|2>0B#>vLpCa3I@5$oZ=& zuc%*&lsq%z9`mi#t5s`9PAKEz*B``($z+Rk;AL!AC)_tX% z5u64+p4z7jj&~2ronY`R zKgY%AjD2MS#|pFJQp{D$IRaySOttAE}d;SkIe{zVFtQbP7 zGE@7FaYMk&3B6nBFof?JzR54&GwS6oAshMB5U$o)ToJ!%2$KETW`BYWVRBbC?Ul13 zY+o9e{%c_fYo(IU3$+Y^wP{y)m9Qb4q&C*(FBm{$d~S?nxdE_71Y5nxGyr>ho58=~ z2H>l}H{IuE0Ou-a0;J3h;QsrEs`jb|Kxn5~&a)dp!OxQQmJxjrrA8gfA+Bh`y!J*S{Y?)6Vx_MqWtWHwl=D}pM z{5mQm6sqpKkVb_q6V@^6X)0t!9~-%EM1`{SXyMlaRB+&YF>~OT9 z$H=dfu{OHYaj%vFHu9Vyc`qpt`njU#&3y_`gc9NllPQo%4LK7LL4huoiff_gDByM> z_1kU_3LHyMbaQo}faU%jR~IcA@7K-cxEuot*eS5>uvDYK+Z!j3nMqK<>yuE53JV2@ zHI64Tr*xq>C8y!vH(i*in^U=1qYHd5TNCvj>q4G;UDax=E*z^oRdLr-7XxVJ>%`o&y89$JuPOgWJ(2{dVZY}4lOzD^rTs3u z7=HWL{#BA93EBfQ3KExzKu?}W_WAB8>=_hFKL2sq^zSYuO`g3h%eUM(*WT|(WQMj4H)X{Z!j(;KtNcu zalbwRsGi=#*lKl@|76{^wo zj-Vzy=zYb^zd3-1u1mrGHf=b#{PwGOn+*P0Jj9J3ET#(h&U|BxZcu{7Xw{y(;kwF zD9p0x@e(vdV8bUmW11oi>e?3Gl{6uke%60p?|}epe_6X@{FM)`&hiJFit~b{XQu4# zGu&Xn&3UEjIVY$#&`*y3WQT`Q{*&A+Y!I2prMb<^0=!MfS)Q>m0aiZO*mz-s&OCfq zbpMwXdRMi-^n(YB^h(F%qY~d|=qBsucKv-ZMvrGCs z50Ns6bHlUQr$+`o+dcl5t|^NGJ2q*q;j*ZV`GKcVy)0@Ca6NX1TMoUpW#`B3@Un6=?BT9X_b@S*iv~U`DkLhZBZU! zHk$uAn+8+Qx(vEmzjjuW)x7M$1!F0{fg*mhhUdnnIdW{*l;>6hCwdtyDhU0 zV-PLzYU<=&3~JtD-@khZg9>$0n$N2$A;-yQZW;kf=yXik(SmnMsI=*6{jh*C;>gET z<)2YTFWD?qDjJlL*AuVZ$(mSH88P#kcms=E*Vw23tYFdpmG;O9r{v?&`4Im6P_qZl)sjp=Phxl)c~Bs zUrqTp;~Z51$u2o+Xd*{A|B{^=66>*e{*6Tq-5+8z4JuYe3$6iTy!MPbEE709m+&a- z@k9OGJ9re{L(5oV`0>%fAo7(C9O|Q(P>jNG=q$TmYz-EN41Iqt&o!!`*sJ$*Dm+w> z?uz4O#H4~EcXPBzWn&TT@F!Zl9u^fBX3i9URz}7TEiSRTC?iQ8KEFpxO6Z){Ki!0Q zC6pFa(K{!vgpRi69(`7hK~MAUx-5>e(8$WqMKSa$SDMG|41vlNTz2SWeYC<913}cPAcD#RjUlb$1?a*(YZ=AqT$7iF}wAc~}=)j(=FD z0H-%?2yBlPVd3N9z{?gGn7k4hv0j6LJMuU6xD1t`=tB|4;f)f^VMzla6lGw#GOKu@ zR2h=CUI)Jm2jzDkMPB_qgeHB@Kvu&GFtYo8hm6BKs3WHQ~?~ zUe@=?nlKsd`L2&e3v`d{QI(I<0`tf-)|r2`AT(GYJL9-E%<&(8xT8uNk_c5M9|U!P zqVkE`!cPb6B0nu$YSMwIk;}6^;zTHkiHRFWM0n~s>OSX71bL?48n$$GddB48*Rb6<&En;r-QWu1bK0{}}E<8_ZCf5m5VE#<0yQUQd25&y$ea-OM!<>f) zGAk%xbmj1Q(@6>l|K4#rT2>E&l&`+FveJW+iKZl;5Ix3x)zH!KSP!g{-nyu@=)sli zQF7L+dQiNVe=by!3Y^Zj!jgAU!F4w7JH?#}=ZIef3K)Ld@KJXt`yLev_4&lQim5O* z+|*(ZRA`zX$aDQlg~M%Ag2LTYkQw(4INVQ##&K89^+75azw8m>V(^ti%g|^q6_mu% zBxF0NAgr!E$?}m39wzlmlqxDz)(WcMDx`wTka6|V3@W7lEhLp)rNZOtqiN^8sZbKR zk@wn$3M%u-@h5euz{Q#*R$u!dlk{{iu3fAoxdxoy^t+e9-jyC&7%hCAV1QeqC5- zD4jKw*9BQ7tER)#WU$ZMyR!10458nOFnV_w_kE!wZ^D}lY5RNk7Mqcw5_|s36-J+Q z>2a`eE|H*PA!+VrD+yN1!>sCxNFbK8yEEkm2{Pl}g>hdXK^>(gy4jHgekEm~MXndOpgKb1O__`%;zK#fC zUrdj4mNELisewn}DG@#zoG!a}j|hUauB`k7BE*iSjO$+{Lf$%gx5XJEyt?P}2yah> zW5300y-bPFA-IoET$2bUnHHH3#fXrxx2U<}uMRxrshaVr(Ses%51z9|>cEfKSIURX zbl@9$Pchik20JI$4Z$*P&?{23EAiEaXPvt=E~se3z^q4gD)!YOpn5 z8cDjM2A>=q%GR~ipus#dLVQFOE^ve<&E8f8!Om3oTV|>-t+gN|Gl_>i)TDxl1UxW5 zULE_3#Y1ZZm&~tH95i^54zn8Kz%1xK%O6ky?_GUmZKf(f7~)8oZNP$p{UsqsYbQ!Dak>>XJB=Y4Z4rvWtV!&%Qkp5@H~A%Tx6sUK9#Ce~!88 zia_WMM4^*}p?!3VOIu$EW)#nrn_UxtgP)3jh^O;Gt$2C zslI#OuG60P`q@-R{i8ij>Som@Fr!y7*X<{SSkVF&Gj)244RK>jnI=a$kk3!*2IogE zl(-g{`0y5LO(@+y!>M(jp|RUg(}TSqgN%)9R^u4Xajwo!yS-Cci!!4*w~Uqnb!MKTc67z zOPv{Ifj#nwu+y%!Vn7}_xn8Xh3s69v(}%xnGkoTM00030{|uLRI2CRb$L%e9ue-0i z-78wZx<@KyMJm}!q>xl36553%QVEp?DwJfD+#^wvh^#b`mQ<2#KYxAxdEe(b=e*(^@v zrq`z+b_D~7Uel}_MGTlYCLQ)vjS1nKE?!U%V8W1sK=Mo(6YhQYid{a*1nqqang)wm zz~paOXc)x;ZAmfrQ}Q(`ps<0vzy7$(IyP)PBA2cl&jz_PV74buAyS_M7bcdJI50S1z9UyFSHJm3I7R1Lcc*ur;nFtTD zG&VR6*XvGfW}3%2(koEWNN!JV?TkK*E3V8Q>UU$BS;KfAu! zUH`*`t8VqJbMu)X8)zt2ymq$#%nf1p#hLJMCI2b$1_N#{GmIkJF<@OgZ%OViQ}`0{ zG+ign6m)Go8W{pp_%yQD(4w9Whc@NDz3N4W*MyT%1;aG3U99c(?l=uv)g5T*hBP?! z@_t}yITifaDLc>DQsLaR>)-e;3dmB3uKZvMgq~h{^5!%d_D|MzxMz^z!ZMD5mpK_! zeW=%s+DPy^^@rrWT_kXgc0b~;MuL0Ag--}&MA-E0KGVmG2nw5@1b4_2;lJD3hfMAf zz#y(`{AB2_YP42<_-zbvp+nRC>x>~f@a*W~DkC`5k@I& zHRhPRCRqPyy{S~B0XiPfel?40z~QgUk6m1^4ui!fM@_QT;H1sc^~QawkQyMlcgR2$ zl^O(#elnu_$RPrN;rChTuK8i};J<$8v@I_>2(_ukb@=H{y_h5*jJS@ueA0;Nf{3rT0Kn%}Hoe(_@<^8wL zYDRP;>`jF9MseI$E^l4Mk;GiP&OzM?DV(@qHz`{ygEPQaU7RR~4g=~BDqR#X>z&i1 z1^P-j)nsmA{7xAg2NHJ~o>jp>Y@Zubq>9IbA9Z=0RKq6U-aeyXbv$t6;*@Ze2L5zR z-o>D5;#A!uMaM}^{QNnpX{cTcQ(XxAx17>O-!fIHg&sP%F!Srw8&h5Esk19#$?BnN z#WS|_4?T$YsAWKXa3UWy(RsekXj?)5x8-EcTtaG!^rnE_+*s%DsH z9V2OGWrkTF<>uG!Hp4f;!-`hd%D;0Rg&9c^;XNFh`ELcjawebIe&bOlxA9 zV_!)X*JGhM=4Hr7h}oFq6W8N%=wyx_%#~litvAQi%}={p-ON$?zinZpS+*tCmqxBL z$H=^Re``l`+$K(-T(CCBvOUr|G8VJ@_xx92Pcp|~IiZEDvN@jnO;9@VM}QNbszW3? z1X!LNY1vvP!25k|2{P#d6on2)O79ln{Mv=@XI2YPF1km3njygBc_t3$B?M@ubL~J# zHy_`;o!%04myZ>tjkd>5@bO6PnrugJK023JbRQD%QLgoJueb~!?QGAjGH5qLGtcXf zKjoSsJ(>91d#@R~l&t=~!`2M7%<-_Hp&3rHat`EQdf%)cfdd9#UyjYC6oDz36H{Zqi+(O4F$ zpX#d6^k(5kk~VZKW}(FQ;6qmkEc|oey~HXh7TQG%O0qvQF}h?zzPf>l>MIWD?6||k zV^KLuYtAz9=AF^S7h{G1hC!Sg zGU`e+Jb8D}g!hDsGg81_bCinLG(tN1R#8#K|15j192K>%CrDJWC? z`q~Jcg5~?{sl^>+%+>$X@Z&HUk5n9*S!qc|S?jLJP5mV7nlvCn8VN^Y-e;KzN$6Tt zUTFHAh%4Tc{ld=^aUwA%F?cBvOQQ?7T6`m*m9IoceF6a+C+uHLa0n=C|L3mic@v~A zb2_)}l`%R>N_Gh}jq%e)f_S>C5xO|uA6RhK5HqL7A1JgL;NEZCp0hFr_i2eF%_?S3DE|t@%gKy$3@mj)dh#BqoVm$6(91fM?@=YzwY7( z4~rVb>`X&04Tml{StXE7Y`4g_#v7ryvDt<`I|^)^0c_$-+qzre_;UywY{Q_ zs89N3*FT8JKazVcZR{2ik`8(9h-(vl|8G%!6~9T;RADQBBCJNl{f#=^;)SA&@SF3z zKVKGRUro^XtBJy*XEp!ibe{{It{v>1IQU9vF@1T2Dd-l~h!~gmi+vQn-1*QUXL+B{ zcWl+7uEfv6{1g53D^1^o;pL4E;o^hBuktT?JTrd@x5w3ef46E#xM3)4uBqg(Fq2;W zH>u{YFyT3EioN%rkRvhf62%)6wwqf>%HA-N_IG zQ9iN!ii9{Uy*;utxp0Hz znieHkef6w+Nu4r0X%GwFQ8fp4zBs>v^GF5wsa_zqRTbV^E${UiRfXg20k;zq)!?Rn zj{oDi>L9R?7yg}6hlK3JmW*BvxKwWxalBa*bl1;4Qdp-2(y11i0TtSykn+ki^o9=n zx7hVyQi?8g>MM+7ZPx=?owlqhYkhd4u333h)d1#q$6t8YU;vcH%naGRhS1V->`k?v z5!hRdSXe$b0zUVWBQ??(B%V*}&l8wHjDVgO^34Raq-LxYmlGiCTIlf4WCHZ|*x4+3 zO8^U_0dgFbIO|98zmIGoLd~ybtCFr0f#$7+In_>v?W6VdGdIkHyOB$ZC8mq$zX8*^W&DIWUzZ-NqTyb46j;lItnYuFzI7? zCa8@JeVcgR+JDF(`BUB1P@4j)wg#E>EuuiYZ24x9KLxHRP1;+fQJ`P8YpqHH1zcEb zy~bpyFqfiR_;(o?qtPEZ zkgpx5-c8^_L|SOb6?ZPksOd!JCUc?bc)lndx!{m8GqPlm3nNE{E$a1n&=H*L8?%H5 z{<=QBAs#%C5Bj!sc^D7=X=m>%isgamqhW{rVIG*Wf7TBin5DtkVXr72pymDz729|a z&8_Tsu#N}C`E#|a7x17)gIdos;K45S_}g`(Tv#ViOWxkhg^#(4Nn<%&*fiWfRJ?-= z@l87}*)HJ1jPp6kyE7a(A|d&p_Ynt1Dx%t-#&SUM=0T^axg2=>CcxsvtgjaT3Zt(+ z!3LGc`=yFZHspM{Sg@v+1v&L+f*L$n5Jdk+sve#7ZuZ*J&eKe=OCRXTXEI@B@X|1u zM+`Wj7HrR3$ACMi%?|xE>!F*1y;nwxaQ4XqRhk&Y+XvX7QQI z1z(BKE`Emh;sy~0N}Y?YZzn>>`l$l_`9yd>JbL%BG!ZPA;6O2 z14`D0P_(rs-!RJn@twXoC~c+R22d4R%u7bAGsJ0qb#0WMr}?Fy=km!>iVS4<{5HT?f^{ z+pw=kN>LrW4Blm2(N+VC<9Y4d%~auPO!SkZk#oSxz27$Rs1m$6)86TRP61Bt)VJ5V zC>ssC1~1W>!@NL(%x1Lx11y7uHv3Ae2d@QeLCCj3f$ ze%#n%L>O;d({OG7kkBC~P(}Uc524MyBQ^1XpM@9QKV35J{vbRn`c^Npc_mcMx>jdd zS1CO5&fs#&lQPk#zNt7v>sHaf3qxaB&EJ&pegthCXx z{?*MrG##|uqL{W!Qx`KMiozF6>f+%9o;0Ul4+ZIqBa@%$ zX;-MYaMR6$MhZ0Cd}^?dv73har4-vIZ)w<;7J2fyBOM#}ZFsfzAsvaeP49J0O|c`O zefnIwDGD;$wn<1b@Qc32Z`Uveo{&f|)%(D}FrE2T!S+m~8ifkm?=dm^&Cscp1}wC9 znT#@wW8uFKej>&9Ec{kbwNiZ{8&i|QttwL3Sm7nk~+<)OySi&F|{f;Fi6sz*k zNmoT-HGc-YtRRr$xPPpMYUUD`Rr#id){M{0fGqS%)ft*5ho z^(&%2S2Kl+)28wdtbMsCa;RnK&}QrEKNfwxkAvSc?Cbn8Ip}of4;BDVO+u{o;nC$FRsue}Stf(QC8hZ-1zfLk}p;C}s_H?_7I0dgMyeHp( zPeyCA6CX>f$r!VC2dnft8Sm%p*!k=v8DBe=E-=|c#)8ic_h0&wQPRY6P5DYPs<()* zTFfJ3uco&fS)Gi=q1#qE{~{sTCQmf_oP>dX@hQ>QNvOU&-{gEO33)%1YJt@Z5$Y@YF1NSb|@9>xaZFSirWF0C@Yem()scO~1N88gA; zkxu8iyG_u?A>-qn0b{HVEKYOVG0W3SoOQ>H@c8wh-Z!U=aHn5gvrSy>9W=mFfwS4Dm;r9k-}b>ZULOxS{bY*4uqUn|up zJ(T;+V`NU~Vytv$ss4Ul+`8e2=|X8;4F6Akby$iH@*^(YVe0CjJXhV%C_@`B&n+ow$<#uJyI#9C>uDkF!P19&FKMED+09)ER81WJI`>v+p$0}2WhU;k)WBt5 z8j06X9W6RCthd^$V_JoLgmae~ruufyg!rrB$xmMP?z8_WYu`L$#bj07Wy%QmCaB`} zlv{Gy!751jcEc$zdk+5Y+FBOf-g8~8R0?k$ke{gkEs3db#lr|pNz7IC_WjRS0-yGhGOnEv$E<<-jMK$p_*8m- zY(d40=uZhRz{hA>bi38{?5iV_q8)4VQ8YX*>eIHf^x8Tm3VK0IX#e$3v}o5QTfe{& z(dcU>5xyQ44XSg-_uKywS?sx#f4Ka&=#9s4=;o=PB4X3!kfz81k=-G|v0|mKBHiI$ zsf3zOBER>a`Gz(FlDD_DiNp;1bGuhR6GgT-+kY6kA-cs={;2I& zEv(Zr^mNc`7h11y+^Hex5gN$-tu9FXDjYA)th>GCm#}?X#@}s!{|HkTdwz0A{U`L% zX;^SkdqSvqW~QR8WLl_sIQ|8dAP!2OY73eNBw*mc$TVd?DBU~<+P0tmJt0s9{cGQ(rMPPFB=ppUN`^X!Rd)0( z(9wX1t!saaNoqpa-d$c3KQuw-+;ghrbFEpADU&`@tPPRwFV|el)PajtPgAB6bwSZI zJ=-{353Gq%i!^-oAvY)y6qXsl=}pOlja);Z+r;ors~dr2gkGk_lo5>hKdn;gHipd= zOCIdGV*)>QJEAOs02>=VvN%@>aK>A5Kt-GgeM$y{XIy77_#*m8S|Fsr z9G|U~kqH!V)9&tg{){r)Z`7N2;#9cow=Y7KPlY?zRw(zoQ(;H<>bhHTR8WfRnl8$r z!WtKU;qxjg?4Rs+@ocBU!;!Kd$G%hH<%1C^{TV7qKP-IRsY(L{shH)#L>efse@XHe z(BOSN_L(oGLDct}M+LKa`1|#*2QF=-f&7aXVYkC*5EM+Eu{%VArk0MLD;YG{-n+I@ zw}b|cqZ@ZWYo@_Qoq>#>zi2={HMx$ZNr$1VkWShXI>hdk*oxcfaB*!xrx0h%`DK$wUN?iv0=hM zHOBWC8>IQMPRU=`P{=Rtd1=Fe9L?8yu~#`DTXauujW`#2bs}xWJh{M9k0iO=;X>TS zo4Tu{c%WWm=Tqj!gP6NUHob*B@O7u}jS@G5I|l2O51E=lr+cpM3wtwgb|KAm4mE?@ z3NC#4WHU(R1i2Cl&7d#p$?CJu%%C`Fq4UZvys?<$MJU&Pzekdhc@_}@9{<@$Ae8?O5%GR3Yf!I7|q6HsXL$~+|XV)oQ zYVdkQd4L4>1++mZ}G24$veto+WYqstIl1sm|8I0!6{l}@A zoyVFp{#%21@KbfeqXA_eOtHu=ukyISoZ}X{+J*}Q@(;e*e&T@Bmk^(i`#A8^r|^@O z0SA0~1H`YFvtggTTV=R28yYEpDBF8k&=Tgo%yAzJBt6E~1go(?C1mV(#Wm*ac^3O6 zEMkJxhH{rrFBxF`s*(9OnFVxcw6nek4q<>#46%2D? z-$$iUVZ82-e9;;z+=|Q++owi_sCe63r&=iRd$+Dk)j0}uBy|>7Zl=KT2OYcg1Qd9Z zt-ojK3>hXd#ILxP42vopa!n4CA-mUbvTP9}D{-FqRoqsODBeX^})CLW`)7 zO0tu@mP(0=WT!|avV`VPLe`Y*k!&eR_AT#x`d#Nd=Q+>w;avB*|JIFM`L1si!SL&G zAFPZbJYL0^1)fuYoZGi;4j_5>C*9~6EhrB@UODpG`{dxe>+kIWF|v?zOWoi~r3~cG zrH7XeNrU^dpcmA60_^ZHpW?z1AfTJL+nIrf-d|ha?zY0g1<9P`y7O50arx0CJz5H4 zgG5Mn$r$jDs1lSKt0C3T4UC&7D{gSX1#U?c6B@ zhyLvf*>Xkz{&pEsTq5{j-E>Rde@}V9>42Q$_y89;1l~%zOX7s*_;;CyxHgy;x`7m< z?p0>W_}y=w|1B|pEH^yvw4Y~U4@ajSSes!Ms2JHB9-m^CUTF{b^Jt7&vwNucMC%|k zs=~JR&#Mk*h=W{o73LK)B6ZJV*c@WT%FZ>zczw#fTJeqb@T_MwDxF{@nw$*q zN}Xn1cNghQG@NBw?i8*StzBS!|77FtwP%Gj6;(ZPyLp|}e~OzU{v`*hxpCTODwGRZ zY7E61S@WQg?Mg=r6#0;jb3@CU@BHXwa0k&mPZ05Reprh?DU7I6Og|fGQ51VsNHqJE z7&`6aa>&77ZUGQKH^h>Wb51Y-;;H@KA$Gl4;!^{;gP+>$~nE*Cnx zw_}m9caeI_6c))i_be7iQjJa(hkOn2<(uuP@uZxhaF3uUK7D-z*tdvtD!ELKX1#3YACag;mAi&L#OK#1YG#l zkeul7lS8u<6r6K%et$Owy*_O8%A}Hlau)~1Ebdd#i}HirB|a21q2L`SWllkos}+$0 z(i9|&ymiM$$*5o7?!%quWJKEfGHve_G8#yJT3F2_BNd~+ejS`-6xSz4o2XSq=?2DU z=L1!deC5lSMTRPJu6}GY`CSFAn$ib|2`cDpc+%_5rYflNhlW@9f-*ADIQn$(u`+t@ zXRV=XuZ&FpjD=WmDkELpf1Ab9NysiB^ZGYK5)yfx>8JCNh#vS_8+V;1B3YZv6Ic!+ z(%-XCq;05#B$A}wx13c(2TVR-mU9)*+2qFEr9b2m$>2(Az!rJr=n64wk#gvTK%d)u zhb$VpBOIKsEsHvS-fH}DUk2@-n}4V;FN3o0nvUZNq>(#uUpSL}?)b-Jf-A=esJ~x6 zGAo{d1`N)o#G4b)Yvb6ny{aD zDn)yfaERxT#%uR~SoF;M;Jil{7U8n}DRKo^bYbi2P|HOudeHwmo3;sy3WQUfm1d<- z`QitBezp`km@jM)y;}+$ns~!&--|(hT=G-BhcPIGvaArtl0!yZOBC>kqX&B>U5`$QqLql#p_Xq%&}O&hkH#6oDB{2){K)WZ`$T%+a zeHWi^j2b68cP`QVO~MAN=Tr5S2+TU`mREjLTKo#DVfv0t9e#;L+UEN6-rITBq66i6 zgx4(VppZaswdxFOaHn#d>w_s)v*)ReUC|S){E7pvKODcaCb^wuyG#05irn1i1WE0z zKf*CBP25GSlMYcl-XGsE4-HrC^jq&>PI_&s;r#lQdFR(Jb8&}JW&@vq=EKK7neC@H z$a)+z%p~g*&Wna~Orv{Yd#s}tnf(GfS6v%dn78|P8T=*wV@?tHY`47O0G``cB1KQR zfYIo(_edfSn2Y+j$cFKO`1|V;!a#t;E4A4u#G5`&#p67EgI z;*fMLk;M2W0c*QsWf|>~@a`33;EN*$_DpX%_BjdzbxS)$G50Xw@Sl{_-AoKbz3y+% z$il#x$$NS{k1>FcK6}ESt!#a$at+&_LF;!zY=zef36v)on3OLU>3@m=3+}ew6}HRY z;}S`Q7}!zZ^kpwwhpZ;D4r~<0Duw-s~DkQo(`$ z+s`Q-b~vbXrLGrW!$H0dMmIDU2a2~=a~xPWkh|wruh5Buk&WA{3zIky*Yr~H;=%)C zukSrWB|Q8DA)~)$c#v?k%DEbZhw@(m+UAXT@RIr$5vE3fL>o^$-$McvT1;%G>Po}S zeE(=lg}gHK;Bsfi?UZ4{q%Q%5C_~}pwpWtr>@m^l&gmLu zh|Aqxoim^eM@d_DKA%?xcly`hQb84{+-?>lqo@Ka3r3me7%GsB-5@6=LceB7W!1--cd`1lzCOyw;+V8 z5+{SO)uIx{kqoKiPaoTz$q-e$@$ruf8H{$XkEyzn!HPNj-jXf#Ks3)OwrUl+r_)Z7 zLFVk=m!fCL5Y0LLZ_I-X+Lx7dSJ>8--|Q0hBty(zouPHMo<-fliQZ(;iXN4T@gc+G zUDnTSE|6g?;2j~&j|{qITQ`LUlHo^j7nXdD45yFtHuT1lL42wTUz|V&{{y7dxD+yE zRYhn;W{|;IyG%4aiwrXj+0t)w$S|ispI*!(L-J0I4()t02oe;luRJBg2TQ&h`g1az zRo&DwFE5i+#b*~ZFGu=lTh<&gK24D&CQcYmBA!@$|$gD)4z zaNRkxWN?KHyO(yC3Gh>(_0q9>bYTjd+iu*4F&HyxzF*7s|tnJyG)vNLym6GQ=%huvj+Gbym^dUI4) zGuzS|-NlO(5Kzx5s3fXE(#~VNT^4E(nsrRQ*hdZC`zneI-B*JtrF8LQwQBHvki+Hf zv>GUNetG^yP93H_IzE0dQwO2zI-Ui->Og++(o;O)Y6W;yU$3(K4aGWotE1#wb@tjw2+e|dU30rZc(N+`i z1E2E?&S^sXlFi`D>zbgjc1`m{swNyM?6Z@7r3p_4dF~FFUIhvO?2TwTjj$rcU@4I&NFFD)P?AvIkNT#UAP>0syUaN4t5eE zpUbw>f%Nf_yT(;IWV}0{*I7gdSG(T)ALDdL2tFZIBFljEZ}G-|%ou=Qrrpgy&j5N( zxD|Ii1Bm9r)`Nu%(D3~sXHw6ApMuuw9s>+0*UIRcoMyn0qjx_EaOpv$;OaRNRu4F9 zT6&Erda&!!Ph_-N50)C==kb~AftJ29D0 zYCMHCJxY4;t8_4-msby7gngv`nP9+FLFoaJCI-BHFCZ@am;u3Kq!sljwu-K+ey$8~ zbWqvGGGst1-{LneVFnnM>XEPa(?Kf0RlqZ!4qC-d+mih0kgkqlT`;G^;rhg$cquvz zeP2_u9n=NeHM`-+d|lY~PkH{qWnCzUdT^|Dn=V{exS=2_pbIyT?qe3`>p*_9=aRXF z4(!{a$XPtB4eQ61`>q6P!=9w5XS=1f;UYwpl|I)3{w*uVI`(UUV4Pm)k!c#7qwsY| zKcK_E6xgxXz20FlZbOBxEXU2oR#bQ!zqbstp9+Uu z%SR4aQo(%C!^L736%w1bJvC%|AH3%^*&b~cvc$8EOiM8oV#`G`sa!Fo!p*}50(*B- z;kYAn5C0A-yx`H^wrWHL9UY&n95NN?opxAdL3TZRZ)r##X4kJr8niYEnErBN*WuenL{$Sdh-4;s_3)~JvMH-grHKOHe}2jj z{*MCp*2gS+O(_s5HRXz7-zVND;!mGs-%|na=4Aa2vG3UsmWA<}Doj<(4)>*~LeTul z?QTp}NYO0`Eg4e*sy#)=>$VEWv6{_ltIC6V^@>EGRXMh zjVHG%L;b$89(R6ah-e#qrONI*w&_1LyIo6yp6sT_OBp1%ZW7)+7fb>HlO$eCR}!?+ z_joTJBEg<|`vhb~g7*BfR_^^InDqn&fxRTiwmsRbV@85u>7~+aV|HKTTv%tXNdjTv zm${P!62zK@1TFHAfM$OCcgj_`50Tzh%1xD}SYkZO7w=-gLH=0j94L z*fu_T_WU~A_L$B*f3|(BE8EYqP4}ECjE*A0#h`c&BesQms-CE`-S^~4FoA9KiQxzQ zY_)0&=9jJ$AtHa~-UQoiS8uy_vV9jc^yDquoU8tJFWHuioiI*jyCSWU8_RYk!a3*^ zTZ)#T8J(?GrvmL*tZ8jfH z1i`r?hx{-iG*7gAwhtkK#Fba%v0(OhV##S)Y+2Rv7aiFO$#C9S3L?TSO`g-?0Ypd| zX;&S+Oa$ha>cnmzB5?XI^jCNgLE{*6i;FE01nxgf{HjibyttFS7V}C_9A;4|60Zam zM_a6`G?ifKpvHowA^2QQVpI zMFv(IN0++K%RtL|4rPas3{2d|?0=9h4ee5McSg5J1HK^3b)uaBmdlBB|1$)b?#$U$ zz)b+JBnaIcEdjz`g!p8r62QIhwZP7M;-Gv?YU=YBF*sNgA0sa=28?lS z)oL?QxWA^AANZThg-^YP6 zf6AYVm*GNg3rA}wk8z`c^p0BR5+39-Y57=Bj}QHjb_`s4%a2aZaA#E62%-d=NPoEz zA#^qVzm?G-5u{VxmZ_*9hL{qI#>Tbc=u?GJ*I0=JdUIns$}db386(par`;GtnI`LA z5tTyDYo=DE^-{>psj7+Z5*F>jibpO<;?PKK2&pm`hi-R%{F$eZM?LE22ev=OBZs1h zhG{thf-euxm<1Bh*L=09(RKp*7!~C>svwOn$%HosJ4z#5m(j0hx24f*lf5btRnq9= z`6sn0U!;*#$NA)v@6ssDTW@XTn>2dr>O4#7WY1e9RmxXOBkNp|ps)9&(EzD6`lXvR z(kV()kta$cvA;U|4ciFlOC1?Jya@;m;0LsY3Fs}&CE$J@`~S9hpYbrkBl~;8WyXCt zl)L*GmLqeWfT$Tbj6&wpRo_Zgndy zZ4*Muk)0DYI|Wh0euu(m1^h@oq0xrH%ZJW!P|Iw+c~DhiDj~g#3yC{Ocea>uB5lrB zuC~4#tbygbiIc%=EQ82d@mDXGS#wQh0$B!&tQ*yG4pwjHSf_;!5hPFjW&OK;!E6iv zA6Au7klIG~PZnmPhE=$0f~90KTrkQQWo2g3l264Av&?o}x_E>##5xf8szMsl9H<`}1r&Q(3Uog{qvg)6!B4&yk|Jx|DMkalA;7O-I2eT)1W%Coc zZf1t^ZsWT6ugvP`yxfGwVdf`q_3TF{$Cxcbc_Tb0Cz%g}+EoiZelyF{HWmYjGtA3d z_T*l{%`yv9cf>m@%`=-Ei?jqy7Mc2npUXm-%S^jXMYB)sSDBLIH$rv=t}`{v{5^Z( zHkjE?F~?(naKKn(G;fn47u+@XtioDz10TQ5Mo}0K+|fPs$fST59{6LneIMWhO)u-b zWk~^e==wN^d%qy;P~!@?cuffIwCJu>t z27#YlB|tNB=g>c4NiY-ou|8iV2|HV4FRWh1zz2@p>}8OGB&Rf4Sd#+IhLxB9%CWGT zpPlmW0uFrk2L#pY;h{rh_>Afj9vYV42X&Vdpi!uM2p233X7#(8t3U>VePbQZaLB^` z*wQyWwX(1+;qBLo|Kz|Vx9T0kN*+9(tZ-P!D}Ys+^`Y!R1!y}(Q2m*&2>S(8MItUM z!RLxkiM5JE@E)GxEDa@s{1-R(icuo0BT{=XyRR7$IWX!|LW0%YvWAoL${>`MkZKa4 z48MN+@kUK5!$Hh^>;8i(VAk5$uUn}C?>~Jz*si7uBIEXSi9}V%xM|Ha-%y3T$2gT5 zPcod}^5Ug!7rURkX=!G>odUHoWro2y6bS!bEFvYM1|BoM=C^{>;O&g!dh?VT?9g5} zZal6Ib~~>bJa1Enu}r}q^INI#ApPAF{Cz4s>oY9RpP)kF@doeKts1a++_ipzou3O{ zo5a=jvprULwU@%q0WvZvJ|3FjCFg%tCSMaSVTJMzjcdYlDbZUS$~4eC%h^D1pg|xm zoRW8gJszJ|{98%`BUszl)JubuRsY6^OEj3bZfI_i)B@onI?ZwvE!Z^KakJe(3j(HG zSZ{V{fkVONPB(V0jnp@0SlMYom+?#>-9-z+LbBy=cxXYJS6|=ni|qBKWyJIB+&g@? z>_+M>EvUz3%GN#7f>KS2)9xZIIG)at;M1rD#i8Yij0r8s3pV9o328&!4z$ZqUmJq# z|LwDI(}svW+k48BwIQ@FzB8{|8!ETW`O#!_AbUgWwc$}6$dHM)xR|U1{eo2~1HC%% zHcMAoT2vQm1D82Cv~*#GD=>jEKT*!se6TN=Als zp)+w?MY;$b`tn*fI~mjA(9aXUde6`yjLf%HErkv(HdjpK+URhqgmPqrlK~SAmVae7 zF#xv7{rK#`03qgG!9S@CSby($Rd~F*^q~FHBvo#ionxWpGf74tE`(Kd_ife(MZIJ@)kFF)zWSV} z=&U|?;mk0k2z@xryQw+(u0Eu^f1c--tq-dwqDBZW_2EvOJmX}wKJ1>l5&htuKFs`m zb*ZvmAJjX@ct5tEMt{FIWzT=(aP!o9qYr043;d%)G_>l?bs`Vcgn zsooyN{(d7(^Zf;VNIh)bRC!b%@L{y1B+!TM-PTQlWPK3Zxw-r_zdnQ{-~9DuTn|3H z1T*J%dcgA()tf!i17lD~9Js6psUgQ|Z|v6t8;-bv42m8wm*vOAR~axX*O{Et%z%Cy z>olb_2530YZd~(a0Pop**|TO0IG2*p?1N)KU*$W>>@Xetw>PAXzMun7ZA83$FdfjJ z;?_eJbf}?4A5sygL#7RV-?1)TxbT>NLL*%lyi#0x6g+idZ}g^~k}bO6dbRGlq@XTb z49Hqve5nKfK8L))+vxyEeK~q;LmQ6xYP_j=t_{Nu!ps17ZLt1xY_?EM8$Q*h?Rd>T zrF|aIh+oG1 z*jAwdSYL|+<~|z0D=>Vqo}vMhuc8wCda2MeFvGF+78Sk+ZB~8A&cov7bB(w)b+}|w zP-R%G4nfRot}*WFV6k|eUN5f>u@k=!-)&>pohj$o{Htp4O7U5#go+wSxqp&=T}Od} z3wyA7?i3)Viw$`QQ^5bpwbk>_$?$V@V8Gjo42G>=XxD$M!r*`Y1ahn@JXi!4nW_p* zg&%b>?^S>#s2#|AN(CZPn$Pm`sz7MM855-(Wmxqw{itZF3_IMn_^%9;;C}!B0RR6C z*LgIQUl<2)lqIr;v5wsgW0^4vV`RS4o*$x=il|7)mK3r@MYdLov`a-=NKzVE(W=7F6wx5S9Qb7Xf-&WaU|*ItHQ27B`Lj4 z1s?H@$<|UTP13mfzM5L+uuvteXwYofoliizh?^LpT@fUTV4t9xBG?1#cMSO{ zAV^&-gwP<5#e0tU-nNv-p2mQ*6)1rj%3XKW zwc=1JU*GakX%W1u5|1zaCJH~lpToU5BB(s`(oK4eFvjjkR2=!V06Uc(N+Q+@q2#W` z{ias}C<)y6{J?*6TwB{Z{h#{N+}l}S-BaZzxR*VAVoS3g_x@+HM`{Er{+>NnEB92O!eVBr zy!$DE3c|ZIXP5s3DoVC5v{dYx=dm1*dpQrx@d$sjbx$VfkEeGg-MOZ5h?mD& z`O3Nd4^Qmb3BSOX13Z_+l6-mgPaZ2TA|lE8EAM&L7w(}eExgf6g;`2YEpMl?v)rZe zOkS1e+V<6L)!gAL;_BZ^K66!0Uoa3__LUnwAC$4>elPc6>_iqt_7AtlE+)42(J*%* zXY@$e_$Zf}kT7ShJjuPXp~rnfXNJ2S*Z*v^o#%#z92@v(Er=mIi=cNOg|JnHWu&=b zA>xGPf=}cNL*lidh3Yc_gL44t0s%^79ONlDRF$bD{^tXRU9kUJ^QS3 zRsvTNbadrti=kk6pZK?OF)j>MBpa-i#OA8b){|9|c$enWSwxmXmy-RP#gS4tm#W0@ zE|T0XMch;d|%Gc zRkEbvMtth?BVQVRD;7C#=ShRJxIKKXO&WKnuV9Uk4CKE`WWLjqLGhB8K zB9mp1qI_b5@CO-0PSlQ9Y0F~OSSj)7Az93JyEB_QWP#pL9%Zc@UdO2aM=zB_*N2{} z12ler)|?7c&tC#RkrxMl8p$Jb_mG5cnLKWAydJ3AE8uNHT&u@l1vn;6m8YdB;)y56 zk)=gI;zp(B-eLk=6xB=)*(f0_V^h(K1|{s(-LPcic4g>yne{v!QO4E$f_SOJDj-Zn z+?o(m1zYILPD+X@?B6=y-Xo?4i`Fv2_oHf%H>L9S38*7~Z12rjP?PaHGE_X8()^#4}1FOx9{*@kyT-E!mndlM5P5|D}l! z;!Wx+ZMC3E&8&EEQ40?J@8{;Gv@qbt3*~OrhTXDrgbz=&@qPH1YXd5g+M!U3_&6hz{AV2S!GiY zxC=+VsU+(o>Br|=U;pYOca5oHiZcl#Eh3b`$0P(!jk3qJ$vEB6MT@Wc-q>O)jw+0t z>8YY3bkpQOW*rrj6L&MuMcAx4@X%H6Ze7KKGgSI(iCucnkrNJG}QrLPN(^4S}f+8a#y3`tJ&wp~t;asbAL&A$3bcIqS@@KC^ND z*?uz^IQ7;hUp9l;lV*l#jTsKV5$OOxK)=7tA2CB3WBmd(Z8}CyDXz?Qq+{3m--lL4 z(;@gkuGF)DjtZBxo2Odoc$FGLdbx;!B-4eKE*1=UC2tTo>dnBW`16KUXBilH@cjLf z7YuAAEVc6c%fM$s(cwiZOk5etzq)D#6Qz$_PDlkZu}oUAwmgH0{fADm|CBSq&E0o` z)WgK9QbW@baTdaFt(y%tWr zVDrZ-XB2X7i_>ip1s{R~XT25+4RM^FfmtSW<@~+( zv@mf#bCCD<9ut3yE=%SmF|nsB$z0HbiCX24;_XZ(qF!Cu$&p~&f1b1P1!HYOT8H!T>8bK|9@mfrfpCGC!v1V7%M0CE_iezYn=RDTj{evDlMtfvy%PrMIQ|_o}?%Cl{Dy&w!ZJoqM=ilvUbY>8thM6uTk4b!)Ueii2^2nop7LC z4}pfcId1*=X)2tgI1XPssaWrslyjWlS66&jxccQ$LArj~Ykw*gGe?QLM)&jkO;-KR z8+R&XX#U|*E2tP%k~x=QKt-{OZfAxB6K;?zBk?O#bq56%3zGYIVic_L7j*k|*AT4- zMy)q*Fa(>b%@Uq4K$j>d*(=ik^WXDcJTo`IllT2|R_d6MA;a^} zuxdpi3D-ll>MQI?us+y$`t2WmsFtu_ygaUt7pi{=hfMX6BPC>gq+Snq8cB(6!Fot} zsPJ-3UJq%TwVWr5b+I~l>ByJ$x^Sw+O#Uw&w6@%x3p=8NO5Vzbc~u>#(YdPi#oDNM ziRAsY(?)(m(ubX2v{2nTx=8n+7WR}MyU--51!7Nd*5=!q_^ooJRmf2j*H`HEc+6_R zX_RwlDtPy9lq2>G66AaDENBd98pRQ z(W8mVZD&=Hq&4MsR9+Q-sb`7p#b_YsH^C6e&P*8;9ZbPaYa%+d>Ird9+I>ENR`n z1id(PQ#VTvv+Cg&>R-#^^0HI)m!@POqqDl!$6N*nTt4iJ_$-BR&xE!i6G_OpdkI>f zlfdTk1HR`LiX)+Vm38`lF)$xTG^Y=W;J~)?C#ALsqj2J=V!rr7_%_{0>G~mry8ilN z`nVt(sKib&Q$Z}f>SY^}B!IW~I&D3E&vQLr$?h`wHOIYLYw@Z`a*j)hkBv)pnB}^R z+HIaJp5eAnyA<^;o#DRn8&=61nC8aj+rMA;begL&otn4t(KNT?^QAxiZPVO-si#-n z4Q9AcJ#_9GX3ucHRO$Y-T0P696wQ{o8P9PuJjd@^ubJmMono6`b`(H3Nq@dvMi5SK zZ}c)d1+j9vnsBa82;pR=@RhCwXmSWYmnJ2Qgi?7ehqWTOOL^_$n=A@L&#bYGuVM%= zbx&_tDvq4>e_e#HOQ2xHp8H5f67<*p$`rl_-6#B%MdqX-UOh~Wt&l-@wB(?3yew$5 znwQV6k%OLq#{2k1OAww?aJBOF68KMgKYO1b5884opA#GfRCaGGUpc6N-9bHn8ZIcJ z$@O+Z%mxCO-t@(_V+3q5aSfuUE5XZM>X(MLGOSD0Glxo*;Y56S>aep4R5I5@Z{X*< z#$!`yM;%nr5i%R6^jHb=NY~Gcb4(<sOC-osS`b^o#FeNr`0?xQamFMkQY**+Ss>PbkmneZ5(?RrgiY9HVXP5el=>)Mz-bn z@AO%1l&R&b1)AzWNU+>H-CGC6S&v%^uk#&Qu`6$Rj}8@jlaMH0Gec8l27lQ0nIMDr6Qismpp;hUeD!x~R z@0~YJfg$|w#FR+;8G@1TTcLH<5IY*buMw#02ch?J!9G8M6 zGC_fiJro>UyZG?!GZfGswVPB{P>}aW_I`Cg1tTP8YNxyrl7h`#(0yuy8H~^!zPp}-{$qkI8nALOfK3O zPInR)#@{rCRL5DD0KShSa=-s{R5ZaAT79&}P7}B**}4WjFu^K%LU9e>$MNl?`HkC5 zAsmy^`s$G>ye`}~^%SFmp}oK+l|@BBXVB^?zK4@$6Kc#(QV}uzdf~sPRNVWlV!5xE z3j1|)yFbd&u=`sro(H4S>Fc2J4KG#IT`WR&flPNAY|E3w_m0~(OYt1matGs*p4>Qb(ndEMo&v5gLEtCdGG_Rw*#++#p%KOL`Mt(c5{I z%i!13V3o5617DV%-sW|ff%Uf6^kQ!?Fr4{pxachdV#{wuN{%qF?A&*ezp6|mwVpTM zY0KoF2S4vw_%jhV-*KAEcXF%tyHC3-m@u)hu+SJ_Vk{vd$x)GoJ58z4S$uD%&0a1` z-OGaG(QHdnHVgmmU%z4Uh6Tg#ZaHJqe7A15S~hNMj(^`KhT^xIV`^*GzQ-rb!F#kL zuAgTP)-TDPv0vsWT3tm|RJOo~Ue=~mTMPbuJYLuDZ-L#!1%DbdEMO3lNH|z#0g_1M zPG-9W?0z)1^v_w~^phr+R1G$=e@5 z%!9zjf;7R`O*0k{TQRrnP?rT-HW6<2^DN+Sddq_Imn`t^2g~nNlm(hu<{B?HTcEem z^@$JF0;SdGt&@Z-a3{~{q}@kzer_|2ZM|*|!CMkhM?%f)kno`|r)6GP$(NYJSLMB%0 zZ8$y}#l*@R$YlP_U{zri1?P zhr#P8I{w>cJTbR}pZhf5@@m)8v3-|K(7YKPJtg;pPN~pA$lSc%Tace0M7JFX=J)T# z&t5l=@^j;qL0i%QzrROk6}1c!&9K_L?|z)O87^BaJpFyS8HytWH?7h!!=mE7GoJG_ zgdgh{ZfobCE1{20c9hZJP!qG<h?_;g6h0(ygeW5eeiH2_1q@yWDG`uTH^V-JG z%f5Rb9v9ic|1I8u5x!11#Q_U?Wwg*X$4xl&gZkWHYozD=+6lQHUx?SyZ| z8pEa=!UqkFajYSI%KMWMm>-t?XBB4zf8~E6D~*gGJ!K;$*h0bM=L$9t4pUHCKuQfV zp}?~sZ@+7+A@YZK=JX?m;2Je(ETtMk{Fs8xY?}exgf{+}PB6g3y!AWV4Gb`A%G-2_ zpBG+*g`ArVBjb12bcv@r8TzIHk3FkNa46ZDWA01B`ZKjv*-EF7jNrUQ79`1B!uw)9OSWj3sCBE$GS^IbqRP*{X!0@vo7aPAXyepBravqY{qa zQPA8=R>EsWg~vKkCFmV6nmYKK0KA(%vl+@*8Z=pvqN0MK zujQ`M*(xCQE@DlnsUlvqFWLL5D)t@rJCm)ehMy}^?r*!S2CL{#ZbV&mSkgo@gp1UX zcrHsVeH9UwSvNwf`R*J^RJ`7GOatwMTl(BoH1XQKgeNRqC|Gf(O{Yv3j$8hmcqgd`g-Bwgif7$-rjOaX(hg6q>O<=6wm4FUKDN~wKc_F|*XK~sjJg>KzgSvFt~ruG2~@o2 z$gkIlJhSTO(Ikvp=grKfld$1bUAr*fb&@y73NGFt;eyqjnv{GJ>;%-FMi!9ZbCSsJ zy-C98yH}eFE|XwvmoMmZmW20YojX*aC@@l7zwg({yob{ znIa+ewRzn$BAH)b<|bcPkg>!tY;KO9+pnG7R~mAOjLA;LvZ*>U0?yT`%Lp1Eqw|4X zG{XP_D|JiH`5T~J=sH*Ax&dU|q{mA5{Vf=O>r^n`m3Q)K`##zkqO;a;>O#CB|Nq$^ z%6e)D>)FBjhhv6Vv(j&dWk!L6>@&fOK@==fn7UJ2OhM-CD$}qj3VtLjM+Pi2LMD0X zis#8jQ2bCI&uuh9ieUIzs2HRCRKKsLhcS#|lz1QWjFAx4H1KxF7|9#fyt!g!0;9)Q z7R?g|Kg0A)|^4dU8u-!ypx6T=l+>N;HUeY}EU{oCXhz z05OSuGzj#?96xoLhC#COaKJknM*dy)ADyDXzK-h5A)CRWm!@vxVusT3(dG~FW(bln z*rWEq48k3HuKC?&Xv(?zlQBVGv%Xx<`3Z7O1*PRgO<%@+pxmxp@!OEPh4 z&GAFk3?@z+ymL9Vf$uEkTbpMC`S+~lb(@U|ObAyemLJY!qK}@;DPO z_SfF~HO<7%Myz4ZGcod3{@Yan7Mi7;MWy*;Y@1*}{wxzAnW?1XQ%r2ndE(m7e{bED z*TRDQQM-RKkTAi-13#yu>-pb#%yG7RAjra*_vgMvi}O9Paz%;_frW@X^~rrCzB7`o z4yJQhxa}wNbz(gWxfL1b-tA#w@qPcd#_=pDt~~H2CWnPfl`&~kSP|4UzI@rs>Z|Q)ar6U}y_#)+aXqJN?MWLea7Fc23 zYJu*bi>%Nrx%cm8Nh_#b_44jmY=zt%9bcY`S>fpxbCt`2RuF%hw)6Ek2Svr>r;GYH z$og5Sc%YSo8NyB;z>(&J|8CH}s7Zf?nm9MpbHQL+i(;D$=@j(P_U zmbZKun>OYk;pm)pq6h~{{johy+AOguW{kMA#1dI;_kVe&Swg2I+n~(L5={YBPmi!I z;ku<+-B#QZ&0bWk>NYk?zpnP(Sir`7f|JU^2sV`O{MePdj19N+_Odo{HXeMxDpJ>E zf$L(gTBfdBz-wDUfL5Rd41NEJs99Pd)5tDqg(%;}AE}46TFgRV@4u00960 zELV9rmCyUO6eX0DB1QK7IQxFwQkKw4N%Bb|Su0COi!G6TO~?|mrBu?Q-qIpe+9aY7 zNhK+zP5s{Qb^Xpi_cb%m%slU$dG7n3@$)+LhLbFqzp$+wjA7xJq+eW^Ckxw5`W^OI zvk6#_SLJx)WLT-WyrvaM&_8ulyOvI`@y~D&b`*$;HYMB^I7St+a zG2yx4%NtH86G45```0-!AxrD9HDNJv$+lTed>#|~Of$Tzc@GoY`mx5}}G z0jZPseH0QHNG(+?pXS9tdGS=!NlOOQs}_GY(Pkig?Z)Vn5)2&Vg~%trqND%ndzRM~ zI_g}rh976raaCiQL`eW0y|UH2f~@FR{{6zQ`$5BWar4(5k7%G@J*eG$ ziUvvI@e8SgG;~#1ciA}5aDewv`i}t(R*FIOQDQXQm+76=+d;*TatV%GH5JW2tb#vB zQPF>P^Mi~{R0NzIJrHI}h18W@U&W=Un33Z1)vMPOaz}4co?I}+(Mq@B_yki_*mr5y zZZ(C-%TJ+~X^Q9@EvdX&rub7myDacF1*eo+eP8%cFu6!i^3xm&o{taJOkOsDOX1?S zRh}l8H~vYMu4;m5PfMOCb{NAyDXD&GrZEh<-Uc1qY>Wr1-f3HC8e_3hZS>@b5&SGV z>oTj2uyS^9xWBg%R5k1tc<2~``saQ?Pro5pANs^q3k;z-_hRRFM?-wHS1DRJ+YtTi z$}gUG4d8wIyvNFL0~ocB()a5dAh@T=yy1~PSOqhW@%{9%X=mV#u<80JyCL7-Q>cgD zc!}U)t{!?UwGU70)`h|5Yx9*3=;A|puFGCcT|BS*^FrpH4m9;d5qW+(IATsuR8r8v zIh|Bxdc8JeQs=LE;;jvhA(^#QEp4p7nl^f9Pz&RXT4(1PE$H&cbH44X=#{$`mZJyx*1KWnPxUTNaE%WFx-Gfm|8*-?+Q zYa(pf^7gHdG_ljC>t1k&CLEj8{#uf8FDe^`X=;pL@#kF9*HbxYqs)dh73P#_X zX~AVn;J1Z7T8Mq)qP4kL3x6zwzF+Uwf)p#gseXYr3d0-aY_@3QTO3a>;iNV$gkJT} z7}EyBw38T@kt4Pf zHv{xAL-Ct`Ylj}b&$RB7e`kc;_b)zN;TS{M z6s9l{Z49Hu8ygGn8Dm`|@kVck2_Ak)dA)X-32xL4IX@3Ff#hXP>C_Svgx818aeQb3 zd(9cc5nssrxFdDh*SQo#Sw*;RqEaBUT4sKf4FwTxt{IPAC=LQ{*b#%}hRT3TI_}oO)=A_|2|whu)duft}7|!#`7O3epvp&!=Mh%f_D;hE$lD zhSZ(~6|dZ`x)wW7Azd>+C~gN8XH8ePg@#ixyRUm$LlPB>qZM}@DWYQFe3#$p^HfBB zxcOG0nTn=UUmsY!q#}1lL|MrvDx9)+^4le7Xk55V<=X-p9$L5`bTg)5+J3_a;-Eol z$ZNg!S{f$9CJ$t}({L^_Fjy&+hNXh>;Ic#-Do#IXy;4HMYGQAo`(+xm8xDx7+G(I# zSgt7^qJh26S50q)>yR`Pdd)l zrO)I<&>{309j{NL>Dxa$F&?9;HzWJAhLl5a_(<^w=F-XTpDHX!+CmjY- z(^5?28IUW#KF?E=fi;U$nci#$!eX7PwCxxOn4`hrZ(|_n-Ba#BC3^c`C zluMK`z@0g_DDMgbR$rsGU3o<6f$X7&itiY>Dy9>^PmGCM&+hy%QDNd-TuZVYmkGgt z>sQA7#{_oHYR`@*b?8oQhWJG$3{)y@`})c8Xi9V|sb|8lLwD7W- zC&pc6W9cGB*Y*K6wn=Dv#))%qxnMAOqcR6}+uUnvj5z4=Kd>)az`+~)8cU6p9QX({ zVy7HAIOo$56S0*8_Lf)7{+%40e>HSlZ4U?SCpO;l3FW}N`N-Z``#H$B_~vJLh=Z5^ zX%}sd;y~SoS@J1{gDsvJ-$Ua#FkvmBt~kPhOYRx9*<`!)+T}Sf$?) z%!RmR+|+X#7nxCQhve+JIJ4$tUW*qO?n~#r_;{F$Q!DoEFDU2YUDMTiyJjwe3UjEc z!(6nP)EIx7&clk`?$V!id5|J9Tm$TQs1rfd9Kgeab6djpXYjDCLg%B!MILH8PJj04 zCR_LrO*+TK@8_f6PO<1hJ|8W)a$@}J zd<6WhoEg{0N2a|{BTPbo3AdP>9hw4o`5)AGv=HD_Rvqiyb^(OvzdpZvSb$(V<9PFO z0d@|zw%xxaz}-U$Up)E*h6yPqZbRIJeIP=mm|a;|HpC=om%H9>iY-U_;Opg${{TD7ve-*;$mPAUr zv_@OU}EIwHb0>w{?lM@4w0uG*B5C_?6x?uvJ0TSzPgvQVs?R;e4-iX0t$uw2=>|=12?C z&%Ng@|4e}U#!3rsoD`t`0oAr4M1az;M@Iu~1(;EOQ|Xt60G4L97pcGakTM;V{{4uL ztIw=`Mk@HwirBQ>@*p3U{21(GxJY!;p6GT(>=sR!PO&+c5mgP zXRF8DwB=mb1mwrgHRPhxZ+}C$A{WYz={hP?9F$%EcGY5tgOH`yqciSvP|{nrJ>nu+ zUpyP*tHm4?5BzmskVMvLpy|@Iy<~mmtx13O9|z$@o<9z);6Qewf9i!E2Vrsx4t$%* zf!kQ-VEubG(otg9)yjtI_MeS@RcunX*}R|eY~)0(OfuccM%?qAmtR}4v1gJMrmju$ z)JA%Sk|Y~_^NQ#08(?Ak$Clc*n=E7-+?nfF$iim~L@$aU`EQ`wQg#E$i~SnY4^vp^ z(uwl2oWa7MWcq`*ByTPXJfL>?DiimHq)OjqFmZjb(q)%76aQWOVbyKUgxvCpiJ2r1 zhZ)a$VEUN>`t9$fKkqT{y`49lS*7Y=uUh1{$%BA6M^O0qn4$xqh-mPcqM#FW{#sYf_ z8g5=w)pXIOVL86!7*405Tg${Q>NORoTIV)MG*B^mBw^p4L@K(~)H|$PsYqO3IYX98 zg_yOodb}7F>_KsX73m8ss*HEL7MQ~FOvjnbou+7-|NBck#}r<7S50xHO)+kDH2TzO z3jUZEt!}WRU`)!a?dh-yuF>b>mDBn>HEuUDpJwn(lAi(P<3!(`TdpNybp$&Z~cC zYmDph@-yRS8>2D^Kb<>_aNly7_e8M~q)I;Q77H?hPhDfPogL}#G@jdP8yg|edqtMT zJR{uomDZUfZiI{HcgWR!HAIbjnoRA8Axh?@PGQgx5f1$E1tc13?mD`P?0=}-voVB> zn=@^;!%+z%JdRSU>Qyqrjt(!kGcoszN~Y*V;LnzFl!7|oFMbs zz1w2*8(Cw#U6ggf-O?C#efd%qF~)eNWl5`VHAeLM_?bqECWxq~w`sbXp!bD~L~x}E z>C5Anod010Z4=jsYpW>G^W7l-teS!%_hmaU!xX{)oVlrdQ&=zRy`b-J3ZtS`=a&?l zLJ)9sp!lgN%7O+gze-Y3cbs#OZ9>Hb(deuFj#MbR`*oTfApb8d)+f12Dz2m)`QzG2 zMcjYa=kA$7L;Q!OiwfB^*l*x|IKPbs$6eP|cf`?Pz3W`}^eP%UtXrPUYop=I#YH!n zA84q5sqgnmhK?<#$`>CdeUeSBSD4XqIx@!Imkn;ABTPH>?UG6j&xFG<{?V?*c->3gl@d$yalQe|v+D z6Tf$^wIz}ArEq%&iDORLjs4{K<#+-2a5Ei^$J_ku$aRy}Z}=C`O^4;9Z#Vmg=}6=M z_A@8_T4Blfyho&8BUWxaa)R`0mR9%PR0$ZkT)eW)--&@Ek93zP1vBu>Y8p!|je&vw z%$CGj2C_Y5X4tebpt5!WacY=>EE&g;dPyc^79})%T*Ab~rPXb9q(AeqpK#jd$i(pR zLP+jnLNrf1Z)qYEw$PLIsbPY7-tObeb|yR@emS{uf{D3VPBYpUun zhGfzoS&W!w=5n#_TY&TI5-x6+=bQgJ#l^sbaZzP87fP+YC6=eTplhuwaVGK1?6XRH zYPh)H{h>6Xikv@Smo-VoC%viCv@PSpS>L2EnOvvk!2df{Qe|{#r1s7+h5qmIalVQ@;r@=y<% zFLSSl(HAcE_r|20ox#KJKBsXrH6GGxjY|#bJZ!xumbuuH2d}CT>oFG|dI(S1dm%jh z^gK4hGn0p+FKX_O&+#xIjEVXBh=i zkd(CTJoC5+A)D_@zrHHM;6lQ0ajyu9v@@3;O^Gnyw980yu^FQ0Y6VSl%^+q~sQY%E z8J^E-Ywq$g!=s^Rwk{E7&`Ejhmy>9Q1#f%Na@-7$D+_AJPnuy~$O+#am1a0%*4y~1 z$_x!Z*1UXQVTRLDz0NYFX874C;}Du}hM_qIvi_-N7=KjeqZDa|zc=e#3IohgyWjh@ zo{Jf>HsvpQYiR~{;ITPe6EjSm=Tx#3%@AcWt~B~Zgu>sSeW%(*(A&@|7hO$$m$9Oa z{9)3!`D`?J{GSNoOD6J`@I^SW%W0n;>Dv}p7yQwWF64a;?R)#~%?&OzZEvd&llQy)_6mw@Iu`+6mkq?jxwy7H z{=yQ{--(5WRCro&ky2*V*{j9H2|*tYOy?ptYUHo;Fb4)Sg&XDfIPl)L*m1m)gXQm^ z7cdh!&=vW?`Q)v}Yqa6EY9>&hwyLY7gE>HhD%{ySIy>v9GZr$wZ=k-Bkq+l7x?yXd&2pKMiKPDjJT zfa`Qp7mKo6H2zu95w|6!)L;>*mqQwj&&Fw(S$Zb0gY<0*hivC-lDeyKcK*%dM`=jc zEjvE8n}%oO>noPI&|qq*Fs@=tgQ4U*LummG0}<7A!^Sl9^xim7yp#s7Cu6f_E}$Wi zlKl1ZY#RI(4vpB)q9HsiazI{&hU8-PUmCJBxLZ!6x+u_a;sWxc)Hz&|=>1FZM%Q70K+=~*`Z;|<( zcWU(;qQR>APQhwfI_}8i-!|gVQSt7Re)V=bl6~}I1V`yu;PP)$?i?MjbAqc@l0Ns~ z#d!gZQ*_uZG+#&6W}szeZj#k%1}F=bQ{G1~@G)*%q&0cY&kJHy=Dc7);mWP0In$Uh z+mhq5h0X+JBt_GGD-+5!zf?CSGhrn2ysw<}=L;{DvO7nZh_q4mKT7Im_*cUpffg*- zv~v>`eOZXwky_PD>Sc1^apDVkUktZ9sFlBDLDtMER`i#Jt07{YzNAh*h~~ftY`B~d zXEc&JNloiMym%iQ5_gyF5KCu6W9^%z^<`{i*yozEFS4;T_^1EGEjCgrX~E|nveD3I z?i=69#wp#*fq`B&9%UtO(C=rXG^#^(C8?_lWy@?{k?mg#By6i*v$47I}>$V|FJPT+}!qOJ_pef!?kOSI4Ih7>0GHf2m2i9gAE%v(BdT4`uTD&k+$~l zVe*Uy&a{rAi-zxQu87wQFXH7oVGXg*wT zb((xP{?~r#n29?VM)B1F{1}p7N{rieNu7>WOqmG0%SG_(^5NKFE|v^E|MZR2)yo0? z%YF2CNHJ)B>}|!vYqPJC+8#VybeS6&6HUHfPw`vd74aZ4`xb!UyUqn`jQVl;7cD#`1$1BQ<-2(T??ODC;Mfd9fb zw|$!u;QRyWih1)%eX#ufDNRL)?;Z(3l6pe??0R4N%ut9$pNHFb8w+8t?&@DfV&v4V zSB?}RKD2O-2a$NJF=fe^sSw)QRTY&~A>KdzsJDPFgu@H{=X9nJN245_)!9NMb-idk z&lRG7?y0k91VRiQoKT51C-r^ZB~Fv25XLDhtkdks{l+_mPuB?%GRvu(wn>Q9Nhh-! zwg}-%Z4T{o6GEzWO8cCL5c8vi3+L?=;u0Z}dha7dkK+bcSAQXV_KkL9mk?3AqiK(K z3(==7=P45?gu3VKMA;xA+{(xFib-7dy3f`jT8Ob~w?NexA(Su5A21_vUdB2}y;vc< zAJ|3fA13p^Z$+n&Xg=33k4d7&bm>`q5(5fTl|&?VRv+=VB2lSp?9e|FS*LGxPLCtk zZ_-PUCGkS9+RwQp9t_C(p+e%Xal^=^B#Qn2&-U)z<}5u!V(On>O0t8Hxb$spU!%hc zV!x~7nOoj=#4XPygVW5{60?^{rDQ}p5Ry0dTj;EFB31?Ed8!6E6a9ydtc?uZLg@0{ zb_hOgCA3=3=}j8A6NNRCKV~lSB*F@x@ej@0L3sPfdENfzMOdB~$#Z(`O*k@|J;$1S z376YODmuITi5F+4O18V~B0>!c(_ie^O>F+4Xw#s+he((%dG6KqJ;bnj{Jf_p1Bvt1 z-ift!K?El^YkJOwV8UnhKko_O5aRhOw=dhNdx_Y+A2);sgc7xkPrtKW!-%-ngyFCy z;Y4?`j2X2jobcXstD(JnA91ZNdf|!X`w7*6Zz|&7_Y+EsjaBWg9w6j@ChNQR9waP! z-j~{JJw$A->U(@hDUxtBU;Fh z=o(G@@MzZbA)*OE(_tIYvKS)ip_7_IUJTJ(Y&~GGD3+LP$#LX`#}cKBl-r7WV~IVt zwT9$e4ijUJR_gyQ9VX_r@fV77;t2lrzY0l3aYW0=%T*H^M~IWIcmBOPafEoeP*tpM zc04iZu2Nc>A5YA!v9r}PP9PqvP}f%}O(5PzTBTvyQ6l|YgPtJ5nhiUr^HmJ5d!wsN4&3Tgw*$f{h#RRM3(gBsIrK3 zLi%d_+Z9#m#PnlZ5(dZ8i6?4PVqPX0#AM}zv&8NU;&cCnrudT?M9J8-o_W0)gxt#D zngFd#LM$ZxpvvY<;>-qzp}(n_M9i#BFZx?Ei9e@a9o3zdMI;z6y`5*7MV$HM7^oYR zMXai?UeI_Zi^%(YEB(ZuEMluFl$w4%Z!hgj3IP;Hi14zV*^S16H{L+l7tFuivphq$&kX3Fee4$&gE@xXiY zW5m5M(*eW4W5g`||8fdW9wS`nX*RO2j}fb*&K+%DnoA6X)%ZWzm`kkkE_UyT%O#%5 zzt=l@JC|5s{b-f)IN2{{H9!#@C)|#TIo;WNoH$nuSNDs@330mvpL6~lCmigihO9Vw z#Iawa*&|7LL~TsAih4&LVe#SB1wuBTIH|ZdyWA|Fcu^|3{QHi4VtlCGsqA7tp;$_L z`22G|@$ycdIa9fSF#PR%=BjN0@$f=N>;{N~u0RR6S z)^|KsUl;&zTgYD7uT^ID9`9qn-cm-$NLDEcp{z0@6%{IqvbPixDe9ie4;3Xs3Mnfo zl&q}Zz5Vt5Jolb+?|sgF&Y(|!Yja907fUIBiun9c5>Chrts3Ht^Z{&p5&-)Y*Gn&)xr zRm9zxiZPW{otDZS#n{8mqgC!^#aNS-nIVT;F?Koh?~}@t#aQ=~_0F~H#h8bnYI{RX zF}8!P{88*Hy!{$l`7>6GWxk(}{jySw$*0u^eBv*`GM{7`Dj1evKMIpRHQ1J5A9hc( zU+^x$Sf>7Vh$NI?uNfJWp5>Ha=f_tKwVsz?=fbK!%#V~{x)Jf=af>BbxP=-l1(kNp`%CPf>hL>mK%CI7V zx%F+g%P_XK*h2g6GK^D^p@e3>3|pI6XTQx=j_oz@l409Xj;V5&t@x44F|1$nFSCC+ z7OP^ivpuOC`>GfCGds(1yq7;1Oz zihc#=%KykT>rN%MyUKNSUwMzr`)+1I~aN#+o z^;?gn;6f|r-!dleW!;7)aY{b=?9hgFdMph;^=ZSB#a@hgrnX_dBO4mlUG11hkl`=; zo3F7R9?tC3EN`)!I;z7j?!3e1M8s~$biKz$b$kxpemR2KvBwp^ZyCiN7Bqn z9e&=JCGj1zDdBGtHu{ONe`{Vop)rREy6>dk<^GKgWKFD%vHZc>RaXu1s}l+nR%H0{ZRCR@6=R~MO)S?ZV`Z4wLedea#Y&4*(TxzUrQQyi3IJm>*?u|nb+4^lZ~wyYJ; zi(*5%O9Hp@Ax2NnmqTfMNHIKPh=z?Hac#+F4!F#Z_HQp5^5z#nzv3S1f6Wy@wr)%Up~4Kdx7$f*q&IHbem@B{Ciq>*NhG0Rk&n%SWhC^C;h}E^A|cmzA&ZnA z5(>#!Ihy>LgiZ;*xp!xrgwl2+~SJ-^u7S*+3HdTJ0c`evE`D4mZ@U`;!nK%f8N7T+hl8gAiPRgj zj*`&x8*BA*xO>;QCZ}-8j7&ZwxSx;L-|WYwc`IP}7Pn3@C$bH9|};(w{EirpooaID@M)D*O5*t{Z#9eSbn<@ogTs3X)E1 z_PEJz8Xu{+hoib0OmOc9t!wGxuE~F}*@@f!_#TZc?yeIi0>Ze=@gG*Xa22(RcQW8= zRK{;C9U-AthwFAt-jc9HW2rtYi*A&?nKW0YG>SAzgKK_ z;V!6d#+u@W%FA-;;THDFjw$0hyzCK>#GOq`9^u2?LYXjP!@WAC!A*lZedZedydR#2 zuX_Cy?%N|q9v^YfODWI3!8H+muks&m+MvYF23)n{?VNXTk3gSz0j`Z!@{tVO0-fr} z6kOk0EB$y}bEXr?A-MX5!n=>)nt4aHd*FWB_2Ziju6M|%ZosYD&TOI$Tt#CyMgR zSC&tH6G4eNbu_Q9iXd7&bB-8&5%f~JhAZ>4FsjYAUG+O7j3^eNff2&OXwNMXWA^(( zh~w98iCQxuq~89Ds`_CY+I3PiS1N29y0v-XWud?}q(X6MnQIh8oL|Cj89NIiu6eE_ ztUX{h4LVdgs;8p9fxV{wj0$2} z!z|~oT~3D;Z1ks>wXV<-cK6j~?t;lb*o*MG7f)XQ#ytGW>0Z^(VR0Kzirh~8#6~V1 z;dtyhh0QTO8Mf6O#}Yqpxji>Fg4w#M1SMyEz?>wdhyHfH!7BfA)DO;U#9IFF1?bBc zlONLGTyH$yN=~n@E}-k{Av;*=H8JlRB=g1g-hLPTmCWiYbe{j?1X*^*y=*{cn*1X` zyr(sCmK^voP*=8H{cIOZSU}n?=T+)nRuH@JvYGoJ8_2|R zv$q9qg|5T=DlcN$fvszjT%X1P-`LLc&=qrn>7^&t@vdBOy#BMB)HoLaKS030fXes( z90R!_yuom;a-AFO+@mqaR37m9PLo6>@j{^gtkd5*URY{%;mk7S1GBhR*Uk<;Ff9>v z7&k;wnrgu&M-)2S&!1U9|bIMWnFAz!)MUE#AR)a30OY|IeD zPvyf7xpv|Zv?jv!lS=~Tb@$cV_DjH2r#cz4CjnExutwWs61aWbuvXbF2`vGM<9eBr zFm+#3Ch6hR7~(@g$&G!`^H+3 zWno6S`M{$=SuhMA5etpj4n_X0$rZdiVE@URI(O=JfU?U&tk6ad_8w|d68|O#W9xdB z;TPqBPSZB(g`NWJcqVPEH=+P_D>K2=vx=ZtdBHD4MhRYY^E=A5DuE*GKBDih47Y6M zpK&nn1iRF^RZ_`LpepxWJxWmlQ+tc-!(UY(&_ZE)#X=PZeI6aZe@zvtKm4Fq98-nY zy^36+Drzt=&G&>UMh*JXE#_Z$se!cpq#vJ*I#7M1_TLUuhnMs<%|Bbzp|C>vsWz_$ zKw^s0D_;#L@6Kvze4qgfZO7@huxWy>)uG8W4^8+}+?DH8tqE!)PwuVLYC#Dfm-~Q| z7CckP|E5{01vVOy((`|{!2GMoS-subkX)&hOPi++L7UuP-p^^nxnzsedq4-CVl9_&Y0#aUD%%BJd@0?2cPSPEO#E!gP1ck z0lypcfZA4~+(f4jT`>baL$>;`!7zU+HcubER6K5S{;3ZxRN5kQLj#C$?R*iDYyhVj z`p56~8^9fV%6T>^Lm0cYk6e1(5TXZtMV9LgA>ha9NE5OOAi2T7RfM+*W%>CF+fD$hKRzTGR!g=owU$ZxXvaEPmSF+| zdbd2w8%)4?V$}aYzX{B+=UwGpG64ketlF+^F`kX1ay~%16;WUF#zEijKmCay>NcmFM zE;GoI@pyXwm>J|;|1t6|#S9!qTWq_k%ph)(FSVxA3@U2rxu$=Z!NhV^!VPwF@OvBd zC_>pBI>LwYZrPZFSoU^_sbl7Fo*~|CG}#=En&s-!Rhom;BvWI0yE$<0^nQm;n#0Ul z)rAEn3s{f}(-D`ofU6gT>*`D`peJ2RE78*eZmihfxf){u^iDkfytggj*0NsItwsx& z;9io@d~X4$Qa6cn)&l&qzgq^dTEdz2q{JXuOZX}p5m#nr37zD@#6~Ymh>~wznv1gp zvOw+c!F)?dHmfb-MV26{d(}txvn9N8uN~h?V+FdVrJn=Dt>9F^H1oQV6$pkV#g@2R z!J@U&$)GqZ$Zk+g&Any?eX|PL_e!mRPe1)@LZcPD3#cW@zqEn_SNm>8jaWhK+xhk{ zt5(nuIdg?hkOBSf_{0Abx^m;B2=B!MA+e^uyNRc9h4TYu*}$ zf>`Zzn5l5H^?{<2Fcp4jNQ59oD&%Z<4rdusK}s~>Qu1ypI39WyHR(bHvcb?W$6+dj z|9+ZtBbW*{jv)~bBB`){GhX+392M^T3gk;aM}<$01|y5-sn8M?-4Ta-ZM2P7HWBY% z8lWN(Lj{a-cKGE4 z7i_RpiV9*h$I5r`;#N2hd(cy%@8p-^bUcq&$7b`ceX#~trN_*}Z>-_mgX70|nyul{ zW&`F|ZVmo#exI7lu!d?!bAv}`@$t}{+jlj{8mu!^1WFHBLwyTpaN90x82(nxk)>}9 z?(cGj`sJ*_g`Z?qFJKLr>|HSnM!f&3($?I03d|;i#F~AjK>6o{BfRe@5dMbQ&HzzB zHEuvAxElX|-)M`wb1BdidF?~kWeT)eKADk;rhsy;%q;U!3Z(W6-V}49fJoG*z4B%h z5Y447W~xx2bD!nBk|+fZFtEx0I}>AZIJ^(whDdZ)OE;a{k#0 zDpo*m)UftT$O<|HQ^%_4tl+kb^vv@gmhf$fhsL(g5;DK}Xcl6YK)Z3l$fw*AB&x^d z($X!#vq_{?I|{#F_dtHTH$JcOzxLZ(Tf#K=i`SbfmOx?Oal3~fe~xy=6Y(_*ICC!H zsnHh;Fv+G->ua@u*SfahLU$}c>U87r%zl=w6uZuaT zEl@l)bj)Ge)n0Kzz#RO0nIxzGn1QLtXQq%IGk9cVSz}OR2Bk*7hJw@0V9QlibSc;j z#&CP0gD+_U4GQ#Hf9R*TTku*%oGH@-1_r#O(9~OoFaI} z6lnFl_)XkRL3Lu8v)aHErg?X!$80mj*CFonZhuU`)iSdp_>BoTeQNyUQDFjG*#FFF@ezZKWB#U{ee2A`14fW<=FtK_5(JINdV$wUk*=%0MLY1y$JLK&^q|i)!7c9O=?H1ktM#rT(>Xd zFv73*E>+EI0&qSP4^mbFFkWh#Zk7PxEtw2%<^cR$_`Ionh78;Cf|%(V$Y7r@$4L`G zhCfArrn@xA@Gxv9^2m%a2%GLz&nz~Etxp2K{^wx~@oN+gdwyf+8Iat~^2!KyhDJ!M zpD}`}-*#2^l#RfxMWsAz*btu1^4@Q_Y6#1Q4-Z#c8iJsu%IU>L1NhNG_ZAWLRI$So->-F|j2imxDWu|TFU=o)3 zE%vP%j3)HB&zw^O*LmJOmkrfmlTZ77|GX-E6h1tYR-y`>-UeD%52%8gXo9>irz$ii z#t&Mjs6gWt>`cu3PWbrlQp);)oe;C9BdMcZ8M00^m#3;JgF{EcQ>EKV(4aG3v6WQ` zgg$%^*?CG49x@^W!%+nwc{eitvR8ni{yh~E&*b4O1v~jdULJB!LJ-##IbfLyOMEfE z1Dead}NjQIXET*{qo6^h2}EwP0osg zzC;@OICPWqn53aXtyMhFPYT%1t_V84l7wR|c`gwul5qLNI@v;fS=Pc?Jy;|E%^*t0ZJeDLRZJHwCfJdj7ra*zSzhU`0MNH!^4FyvMm9NoeSy{Sh(Zhz#5|;u!E#zI)KjU4x zPOkTzahj#9kPq?T;hwNnb`m3Yu9GU#7J5Tq{BzbFY-$BkTL*&A&Ua^b4tz>7R zjGs4*A7jtyzDR8K|A1`_oqe7>JcgwojxD|-JcDumE>CrTF^_5HDq2ZZE@NSogDx+x zuVa=YRqwZvXc0H_a=};(Jt{F+ONB3tNSSkFJVS2_a=DNiY;c7YO}7W__i5OQWJWyn zPxN!3$lbym8RxiAkVfQgn|y9WGP-fQs+kAvYqPuT*2Rl**fvQTKlxCgAW2P{PXKjx z+_fFn5JVTcJ6k=yx1qESkJSzzAtb;#7Z{ar@~xo~&@@Hp2J!q8FHaHX zKX^MrsP3F(c@sCTY40E*)3l^!7VeMMtCtD0A7^o8?Im2!^m;;gi0UtU3-`ae z`b&hqDO+a<dLHH$*rfsV`s!dbSQ$As4-2B!!mURuc%;nG~Z;Yj%A!rLrDrRtns!Vkt_ z^Mu>`he^e_(dX)&2(7}oG6)atPkl&;X0pB#_J>x9mk{{`dr}GM{2hY{b*8NI317Tx zc}0kRjQk>`xabI#;uZ(qlP5G|tKLoc;zvaw;iF{zYlQJue`^Sjs||G%k~2&e2)W0d zS<7&%&kgM$G+Ng&Aw0fe>O*M#`M+>N)ALD5gy&D{77*r@IAMegUeUdT0u4vU2pfF# zmI>u%*BHx*dUzeiNqAjGS&;CS5F!yaZ&b(;et#~fPIx(yLz}QrOV@~S#c#lbuwrkx zC82uYerv-2j23qh7MDxd5+?6taUfK1n%zf8lj`G4cvH#Nh0vzE)Rk~On$eB$kq+Cx zc(MD%zjk?t9G(8XM~?chzwF25y@ZTHXQ_ned%8{k#Z#U7gej_%%7pS`ky8Ki&@&ez zs-OPpzXAwr#FdQW`VG|=0_7?qOC**NI(n8eZ#sR@3!Ub*@|Ip5I|UWkhyCe{g6j_O*%yP@A>2nB;3 zZ3sVJZ;&J0KL2o*SZ^X4?4A+!=#|A24u)8{6S~mS3;&B1Y`zfdl$B#=BVn{W(|$tf zjXPR|{{sL3|Nj)%cRW>Z7yxj4Z|-vKb*;*ZtnQOigo;E)L`jKCB703NTJoXk}$`wGM$ihh+#_T z@blA3K5jlqv5Js4Ao?QVMafhr!he?;%U5vo${L;$@(0%j5#EF@J;FmgP8@{sYsaqT z;a+3-9U$cXaA6&xhI#B*E^cxQUp?WUFN1c3#-i(~guCzFs?Nb>b5c$s%+#&2BHUz< zG@4EPzQo!c!f%N;Z3#&V`K*Md!VlhL;l?2bld!Ren~P9|qx)kfF1B&&dBPO$Ni)K2 za(91Z;1)X%r4gR=_mLx1a`fuEjQgHXzl1O#N5+KEn^$r85-!CyF^w?R`JoQsGY0BT zC(b{T?M(QTbE`68Wg+GMMdH3s**Xyx()P&^rpRf>Ucl|AJ8Baiy=gv{hHKe|r4#Bh z;*1HsFwLPny*IwlhC;@!NC@T0@cFLAi-BUdgHijIBcCe%xMnH-CoNS0P3 z)R+0!b`JOYyUzWD;h$tK#^8p!o#!NUonH4S8rSS$=mEm2WAFY&;lAAd&X2J5ko;sM zk)P?tV#22>TO&lW%YUN#312DN zP6Xoe+^{)EsI%Lem9XaRVE7qa8+ZTK0OEPL(7%;1>g}W1(?s0~CZ8fSL@E>hM85Ri z_z-f>nfaU|>aDiq>q#PC((jxJ_f;PpK0(CmTz!b}>Z^DUKO#>P2|s*^x=TFkL0Hz} z+jtzeUe9VLVOz}D5g(#X?r6L}hMVhrCWx@b^iJzhqK-B%m=f~YCcgK;jh6owvz5q` zmIWq@`$Jc~fd|)Cv~yx%6u%z-9;bQSnC8HVSzNj+^ZpF3%CDTdY25H@2aBh0KL?YZ z{ls<1de=XRd%R`#>jZAb9X>Ncr)jIEaojzLR71j{kb%H4-2L~(*a;u#$;XZ2dYrp7 zG=f{0P(3kBeE#?H$`9PQ%XC@74eF^LL%1E+>yid>zZ@&PIe^<|8`s^B>qxI*5T>PV zI@pJcGFvY6;%@be5$(Y}b@07Y7ZImH@4>IQQWgC=g}B!mCU^W9mO%+0l)oMukU_n# zKP;qu#h>RA!Jn+ncpcMuV|>f;I##>6>DDC~RIx|st<51B)Y;Lj#-b#HcKnf14d{|a z)wiBEXwmc{nXJ6WVrO-%6A_CzV<)lkpI!;nJdYGbDZr|F18{Gw&S zQ#ukj@k}Vzi;mKA^xAf^(b3C&uNQX}Nur5@yOMtUB+>2F^eavhk_gp#MtSwqkov^# zOJdbD^m0wvr?7yAWJe8Ex`Juw&z~gE8fzMQcx=bTAsHH?o=@TKU!GUuP+GVX&V~V?F>qP-M+>;Ae4Eb@56~F#o3#A~f zBKMMU+?f|2vOnWmRV?&0;C3D3;i$xAwHj!+gF7sGnk@%cd&ixJ;kfNHt}Z^fA-D6n zU2%uvUZmRK+74#yG{(ikJk%6%BegloX}AHkHFJEp4|S5fe}zy`alXj2VB999OIMnM zDM-3Re~E!Brl~I8be4h+b{1cc#r37Bp0vl+Nm7m5h|A~xLQny>f`hL^1h>Y!qhc+H zg2Y?2q^5C|BEB=;;2vG>eEk@AvzN}z8@RrfZ`(3(i&w%#199uuCX^52=5#x)v%yua z?Oof1doDjgR2la_ol^`dF4v@;^jshXo!CvP>BSXl{g&H+%Nfc~eTci=%Dwvvv7WbH zOvIHm=)%t8Rvc(ve-zhY+lMdCxJ@5lZ!^P{>c}qcJWW9jEzuGRjuhmXoONi0MnR~7 zL*UtSGIH6PJRWC8M#3^Q`DKiR?2bN|$}=V*_J~guwZ{^uN~V6dwWb8RG4k2M_qI41 zGbk9bmJvrn`)2z?FN-1Cwx)tSHZdf9WbSd@2~p&-+ifoNy9la^=Z!745kYFfmn}4t zgwdFo>;=t3LP$rflkeSjL3DcS-Lhn50Tds5%bT>!hx}XuFTHBvMccFg=oE2(1)oq52xk&e#JzLAMVU7`-Gj(>;5C!Q-ejzSDz_Uzl`nAII=lFrka_=U+-4` z;XU*1t=yeS>>bQ3&l{}2HuN&jlyi#lmJBkPAYbsiW`x=1zeRBQ{RHzQTAkQVn_;F} z(XaQ3&M|v_l%^cwTwsRf{)*6_Uu3Q|P8%L*U1C;Xa&euH|1dYcTYst~^)Ive`0;y2 zhgO*W)*KW125ZcN+?nA*=UL$2^WI@b1S=e^J#O~$BpaAV#pIkm!VbqDx_nl2;Q+GO z=DfsxoKW$iaV={X7v$Ns?3pp+hBB|$*1^U+u&ma>5@f^+2aNwp9@OT8kW;4v(v!3kkxFVI$7V>_V_8}`qDN%EewS@-YW?KBH-cu$vk3O z1bU?3Z;kg61v9P4nBPA{p^EL}zb02PFwEF>ROX`?^k`>WRI zc}g5o8?SUOZIOU$9w|pPG9+L_)>3faumpJK*l9Z(lK@j{uANFI!MDdDoLQYDxLf-$ z=9wB9+)F$DIR=qoU0;P$_$x9no&^z+^d3#L)0*-7pxH2XI=j>H7`g$e6!_4Zh-=G9|FBy?HFGxV_ z_Nc(Wk|eOPJ_#mHB&fJMQ1`Bk1c98U0cB!jcv|u2`0PnCNc=HbGkik^UPkfpPFV^p z+}rC~bCv>+Ka%p=-&4TU92+fHqXN|;WcG9}75WW&W5?+<9^ZOdoWuPk|isX4x z7Wg=}sC7%rfrIMM*E6wlz;>lwC}3C)v`&1FTeOsi*mRa~`!adhf6dSPnWzG!+R`YW zPAkCAL!I719~B_MFQ|O0vLd*pH=Gy>Pz258vA~rYMIasIX(jV0LHc@QvZ9p|47GO! zN2Dpiz#cA9$rdHJLg7FLG;o|3w~%#~qCDGODeRR(h_6OQy^WuR!2Eh^xC zSob`qp$gor+T6pdt^&S67hHFeRlw)dyX}YnD#MR;yt}zOm4PGr-lBe)GDLdVm%D{4 z!%N3jcOg)Q7>mUF&8tdadVhR~S%JrEeaJT4R|#5%jr+BglweDr^8GCxil8`2Q_qT2 z1ckC_dZ)Z1c(iAKYkI2yhS_6DBM}Oq@+{ZfOj`khUsL)N2IXOJ|AAG+{8%T$P!22@%fUuHWMB8_=GeiTz7&w=acHh(HG{GIn+GNi(E z{|oOOtW@Z_dzkdTnF8rLE6ddx6rjz0P4#l6KzULLc}0l=6PGL}0)CQVMe6>Gu?jMj zXMFgj5=jQ9ZJ2<#IT^A87xRA#kRk4VaQVk}60oq9m+rnsf~{uTGxZOXV54P{(@`}N zxV_p^JUA@@dpH6_zCV!w-(zbQCjuqFIo$98n}Gyq)bpj^`Xdg3N;XZaFT~;1K*LJ> zIdLegyH(I+ArA5VWUN|H92)7LtZiDwV0TL2YUmX)*s3cwJm)C}L+6i1?$i*2wOE@X zi+NEPvou|usK)!GYt5I8cv0|(h+>EIaj3S~cE>c@M0ZTL}a9rYc>xPYC|G_`5Bh6@u)A z*5X~FLa>-PG5F}NAiVFm6&Pb82qLlrW1HU!fRpy8S9|se0MC^@b&uZg!%`gGSVfi} zc#<>N#MzY=WPb4_J z4c`A{CPWTs{(JL>X&E9}pI(E%|K2yBD0{NVyj6GZyWjPB<`s$~)jnmGc{a`EoX@u@ z<~h@`Z>FW=%$)*udNN7FOfS3go~rNxX7pg^Az#7oO#YhVEhnYgnF)_{y=63-nJnpE z?;lg1FuRx990yEGuF30cE)=M z8|1s5WbHYM@u-gNu`rp$N=Ah<*H2AjIXe!8eW;zqwk#CwoQRvpXtERIH<*i+mnE#!`&3C+auW631^M$XLcMZwoE8sQin`KH)WRv|GWV3m*EP8Cu2eTDxlv7_uNT zk8Ip&7FHC#ZD)Oc2P@if+f}D9n+^Rg;NwYgW=HkD=^n2|IM8U{Z8xJQ9LQcm{-Z9F z6ZviNzME3bi4LNs{6=*ybWUCtQL?#^?b)(Ndh=Y!vigciram{))m>tD58y@y^d0x6 z9&w|YIVFp=S#A_s(qUY(l?NSFvAwMNga@_PNZs=_CamDEj8tVFE?w{UHLjyKSBKG(k=X=EJ>@{miB&U-faWX;@ z`E5G*CF7PP5*OQ5@UmVK1uZt9pF@)9!!d>7HC8%`5Ij9qOrxW~6D}Jk)agiYUO()x zJ{^t9989h?q9cb6l3x$L9%p&MvqgiBMl|Q$PUFW*T(#Y%sZN^fW2NfA9Tz%%YL_vYqbuG2xDabKd)3=(Ff|4D_NdAFjq-%Xo zkkLj$Dvtlr!WBs9X$Bc|_lIAYu@H67sPrNh9eduHkvWg4*2nALT${y4HS2f(2%f=Q zGtC0H)_!6#GNp0e)f1SK@tT#u+!*FCSS!+2F^X9zc70i%9KqoHztisiBN*53x@--T z5lknF^6rJr2qtjG_lm*g5iDBdH(6tK1hdF>GnUOC#jY)AGgrLEup4axpC|T>V-BV1 z)}-ST7>8fuNO0~X#`k@uy!G=>%(x|-GhSpGYqz^Q$)+@e-BBKl$$L11l^t(>qA53v z8UE*fd?{)c(;P4>ZEKyye$Cz^tqRUz2Ykx{`;_Lei18?^Z^Cn!_F$x&bHgmwQSTn|v)g z^dlF8YUw4)tum%HoifE+Tg!ZK_!%^&e`FT3$+Y{)e_`&+_`ahzs+%cn-}9&ETt723 zF}*7G;SjSus&!X;*9epTo?n_(VuC4UT63a&(-d=y*+GwyhcisQoq}FDFvnDQlO@mn zZJz1=vc<$Qev#>Ls!Eg3W{Ii$D5wjx{xExID>IPlUna{oyObvR6=qDP)0Mk&Ys_@r z+@6KYEMQdjbot3GR@nE)#96+E4cNs-LmGS8A<@#>HuWC|Y)tYoF`#k5s8O*wzaBTJ zP8)jX+VMa|viDK96TING(idi%$Ok*wKmB}G$Pa!W?)4bI6o8_oYzpI>ApDTYt>Rx1 zf2kHtE=j@8zboN+6lw6(5cLr*lm^!!c`-M28A$c4^p>cQfv1;v zukJLGg%`hs&NFIc!I$A|EvzI5Dc5}3_j=1gY0Bc=vAc4RL%S~ddRh+F&fnn~)0c?Wt28Be(3DNha#e!Oy&pxlUsnP_2aONaeM-b z--=U#2O|9#U%3h}L&M1i-&Npl(Z2fAJPhcS%y4DbW`N7?#i%St2Go#ZPFx6M!2GYy zBHKI$?ATuJVEl*y(=of2UtVKTx~@0!?_b0K8nqnl zf6f5DSnE5r_Zc8}I-~OFRR#Zj#k=pJ3{ac2QGlZixV7%oULgktta$DE zx^*i99>pfe9@1if&Bp8vf-(#^{G5Ngg#ZKMMhjY!*Hj>7SUq55Nd;;YxcpicRiL+f zwSN1qcu8gRWJs9di} z13X;?axSmegoSt`MfMy`@JKL9e!Qd!IkKc>7teK&H(U{N^vyb`ylTUphvR2=by8%YW+o(amH-MP5Bdo#{nQRUDEPLjoZCq)~c z`mtBuRMiHtC}aO$8?~W5nQ3nZ+Hmj7w9C#N`1jS0ast-ca7lEH@2!nCd_PX&|7@iV z7r*|yeR#Vz{L8&3A+uQ<;wicLdv&y7v}A9_sG>If2^Q%z6xD{hEpt~Je`~@1JhlQ- zw-%g_+qZ0Ar3E*-JngP$X~Bgs=NiisT0qIN&GWI)f{^@(-~Y*JLHaKFlHX$+AUfu8 zC^KsV94{X(Y=sS=f{7az{agp?QPuP$Y59gND#IULJc2Zj1K z?ztGPgKXWiufKiQgoE2YEnbS%gbKsZTe}#V5YDrQ->O9eirP(wPsM3~TDLZP6H@~Y zd{}RDX;mHk4`v+GexVMVp6;JN9IXz_5Ytn-+tlGsQmO0{L3J?Ra4X)jR}Fr;4k&6q zQiH^~1LRXtYViBhCMg96HBcSxc^#;WkeVQF0*NfqvQ+5bqMW`N&JHD_r911_sVT6``8^1~8r z^t>6+ze6pDp~nDmH;(IQRR!wuF7(`i4z>E_YUhvW;|F8dVYY z?y+${`$YloXZ5Q$GZkR^)bv9cy!7SVQg)hfE5L@qf^K?^JZ$axZ{KaakE*xb+OpYL z9ymu&nea@>0XMzP;Kgk@0I%-z7hL6_#`?@pD+xJpcxc&DSR@PjUmq7mn#sbc4DKY+ zMHzVQk!0_Q_w%!9jZ5TM8JPH4-7oAS1D@|bH!5ww*Q0q1D>fOp_<;M>V5>BUGvfv& zN~EF7>EBxjm4Lr8!a{s5vm8 zbW95Jqo%^XY?6XF^4jt{ZYhvr)zZjpql1R5w)s#Y9fBxwPj~v!p(*B6wvZtmDvTn& zXL8U%_RKlgZ677U?Z~1j_Z3NqaiVCqdrE?=O~yAN4N17luXo|c3=LGa3skv2rNJxN zuAT$IH0b9Dc&1@Y13$A!kF6_IIIcwt2*Rjv$AD4Ld5#L5DUNmA+o;fUHqfGlg9`O( zANP7RP@wstde+HA3ds9&o#3{hfaXNnP$?I#L2ay54H?)@EvK$VkYTbuld5Y(2Klh) zdx}dW{QZ?O9Q%X>$xlN+ll(~#HlA=Ua{~#weh)~h%}4+=iF#I+Nx=6wzr24ZB;ccz zV}Yf*1hmQWA1@mbhy6aIz5>anz*Rt zcO?-sc&NA}LK62{JKI|+lF*(^6;_;H4x8NgaP3FSQ7h;jNr+tzf$EL{I+o+TrV5t= z?{e_p_MWfVD*;bmtv!Q}m%*$2QCC2}I5cDRn9Lb5l*%4b;`=KKwH+f*K23|@5X~)Q z`*&fOGdugNx`jXgCkU@KGC7Nd0wBLEJ+6|>kCXad+esmO5UEw{U^(-`XxrIu z&9*$aeeFZetP?km^ouy%-@}CwmT{T`b%_?3q8GV3WM^6X6|_yi=T5UyX&MsYKPFkFv98jgniDK1^UC?wwPP&q*WF!j za(}XjF*k5E>>Dfjz+ChQ&me1?XC>=h{1=w%aAuy0dOItN&sk<)SUqd3!)kllY&MI_ zqlqHx^rGg}n*3&Gj}JBcne~;U?4FuI!Cbpgo57m2dfJS(=J%S349mMS&qiy4ZiIqX zGf@*!w!UJ`>FFBLL-ArF+yB%^M*Vzlp!%=IEVZ}v=!b=x!-w8ebHK&s4l<4uj^<|H zS0Wwg$>3oZH{4z<$>U|e$?MIer}43KE)=c~+riJC(yAs`D+sXNcDMNF-xgr^ZAvb` zsw>Do(|^iSEnAR18c=ce{IDQo2zV#dT999-&zq=Ll zI_kUt`+eSPpVWDNc0*N9VF{I=J(gZsS!d42UaNR^G1QosJ#zl-_k-d*Y>Ux*_KOW% zY#UAPRr+I#HMQ?5s=jK>*L2WO_A6-pVE2!u(rZ_#_1^-k^=tpJ-3(6ueK+fv^5Vv7|Hp^= zeR#lkYGP}U3oi(0P!Aj~}rEDnxi{*L8Gin8JDdL~Q zF{U6EuDM74IxPs#s#Kx#Zv?@5D*yWC4?zUhbf+baa;`r-WS1W+fi=G=gm0BUqD zx_lYt$KGVp_1_izP&jTFwLFa<)r`5a8zKDozJ{FgbUQyPV)iJ#*~5=(`g`r|L~FPGJKslPS`%P z49WLf*p~_=FnY~N;{#FmC03eayTL}CHgZ_9(D!~CdMQcFx#$S zlz&kH1)XbT!pMp+W5n$au2+Qp&xBPEeF&(uJ(HHOK)}R;^7Q62N(k~awN9ZaBM4{i z(p!{aOpMCe7@`8dZG3|n0;+I6>h4Cnp^D4zgATaZsDV;2WbwXR4dz`UKg#LqxVnxN zwlYQ?U(UR$3$Injvmb6|k3=-!`d>-*8&?gSTV1E`eL(}(z26vD2Q+YczQbz2p(c7h z))z-bX=1|TN%@K=n)p0zznR6W1tal$M|vEz@cVpo>F2XrSb0x2AmfV`%p-aaAJZdZ zV~K}=-vJ_OFRVGcvVn+xX(b6h1roj|J}(j3NrKB%W0mR?60WUUp|B*X4IS0`3Q2Em zteePj?=9BG`wMMds~5Ck+pOfDVs7ifu<6~uw(oi{vh#k{YM_sXg;R1B z5&Ee3^69hhV|{!a@AhaCFhHV`-N!sv11u;kt-W7hfZE^uDqLd*sJAJ%jb|Cc>T;Iv zl?+3iNMcf7el~*Q4=WeUijA;bB=<8x?+ERmr)S(=u`mlH3e@!D`{UJq`)b>+_Yhd0`a!j z6G2K;Ol&z=*KJD0iksG7=QdEWICYMuxQmlpEVgAPQsHDa;46EMiovCj*IY$Z*sdVo z)heaJP_*~dR5=yxZ!2k|oZMDYB*Eks6>(z6-3G2wq1x0$Gs~w!(=gzd*=Z_*Xru1i zGN=&T*>YhanF@_@(@57iDopeCj9VR`qQ&1qT6+%_TsKdre&f7fxNauEFNlgz3(@Nz zcTiCqN+b>XQb9-#q@U$P;!X7vVVt_f`@qoPU@D3?y>8jaS+7*x7ERX%%0eneV74vuUmxJd#zwE z4=XG?wsGQATu4ujFT9t}!&Jahd^5 zY5;FzKLhh7qDXkmkV#CX!^17pG0lUHJ;E}3_v+EH-+AZCkVR9x ziYkvHx0#~tmE5x(w@nd#zg#UP!4xlic}XwaO_56)xympy#cxZgHG8>CA#ySI>U_Hi zR$cOMow#EH_R5euPg706y+PBnZ@UTXos*<5SeRh>grVt5MH75>+4AGXJPn0sbH1tl zM+0|MVz%K28U$;WN~UXQ(BvtW87iUS%B__PFVE3H6K$gYOQE6iEK{Z{iiTrf#w+`L zX(%>0mZ#%PL*teJFK!kM$@xK>w;R#mUNq|bPl*NF=r7wB^Hw_b;e0+12rSgrmzH8`>T`zD$MdzNi5&j_$-qKY!tk zroz2{Fl%uq6_RsJgp;0B9C(?xL3%wEt5af+#4)L0F`5<@NmL{~99GSirsCJ3t*HZC z99`CK4bS>bfv-p6+xgEFcy#cns5Vp3>hb(f+G7gxJ>!$U-lU*1IGBe&mjb)(@25tR zD2N~DGesl?R}`F2Ci+lNM`-96bD)6FL20qtf`a2S4^=kkQm`&&h0Il13Z`~2EnImx z^DOd3vC|i0+%AxMCjQtMcf%@bjm{XO^1$-Ax8cSZcgR^KU}p?*GlPiVn#M5U?l~d6 zKt|G?gAf08k~zNUOga4l8Si`*OkB^BQS{2G`_n!$%(UNJs&OIXx|Z2#GLeklm^f?3 zs1e3#W^bQX8o|y_`NR4sBODEo@!Cc;f~R!)_8-3tkzKIIlYPw)xfgl=WP2C_b{_0V zF+=nhUVmU%V*r}|l_NoW46t`3ocAKp0Q8~-VqvE~)~`DzWs{+gD!rY;>bCkA+)yIZ z{Z|i}X;TuEDm|Rv=a$77oJ@86D2`QX0E@wk%-@$B}76}IRE9n zZ?@f7L4-n_>xr0gEy%c!CVJn{!jEenif1=#fv;@hRj7y-CapDUgLbFNe! zu|5~Z{QT9S`}SwdD=Bp}@|*JA&sM{p<%B=*puKlLi7y?!Zub-&D(Jg!_x@u?4pkApXg(N5DY=HZ3(0Rlnrn6MB7BRi-?ADdD{aWO+!}i}O1* z%0a?yh0`}*In=xq-P<@V3r&Y6zpZJqNIACSUz@5dEP9Ux#NLy^(OZAdTdtSEO}~XF z&7Y(ZxjMmfosTrE>BeF$ZBpnJO5$3%MhdwSZMQewk;I*ka*7hmBym09?7q{!%Tea8 zE_B>U0$EkFu3aC+Vd*Qsl;SA{`8AFj|C&YMMphoZ<|hnIO6+s40YQY=8dw_a6oBpC z=B+mu_;CDFw?=I?FK+&K;!D0P4-D&Ea`xWf!gqnHf|C~)S!;={Tf^k%St6c257v~; zu~JW)bVY>CvK-k4PJ0>CEOq|vSFL>}SsT+1oXD*hXL-Mq@V{j>#=3FaaAyy!()hS1Gh_zCAzG_9>AnQPz_WX$5 zAWQwLk%h~iLDsPAU$4JhLo6Gnx8W|~|5!~8o>vz453@EFmKBuPj<7tH;9JQl&qUD@bj?sQS{&)aKE0M=67U$D zi2k&R!wXe|VjD@4uvzviv3ODvWXYf>Wp|_yG;c3c>m>~vqDQQPhzy)^o{m*k%Ajh# zF(|-Q7Qde!K5g_{7F*tB@clg|hxa*>^V5>@5L(`IOD;#ChPK%$1egw;lnhEH;P~%N>hebjaEVJ@ z%#0+!{+Y?7J!f4~TSsh<0|9xXSm0q0aDq#QbWoW9kwKxk)!YQE-V+!fF{FsP>l=qx zwJ2h^>FMotj}$R}b(!75O+~CB`Ozh=C}O5hLg-h4BFc9s>^WS{+5gOISDkl?pq08u zUg0G`)j`6(hqK=*$}y?@vjlk1xjG(<5@6EuXVAb=37JBX1qtO!Xxf>&F+*M%4XaPK zy@*oA6H{_t+G}Nm{+98#Q&oYnYEk8`C>7M?YCE{ss-UFLzps6{DxR5s)yno!#jv=e z+lTwA2+5(>EGekLr8HUaLZTWD@5}7xom9iYmIONzO&z}X{AGTIs6#O#G(zRNI`~L$ z3Ijf=!!|UpI9y5tH%?j#EUf3uwbuXM(GoSlOx^N%_OS+r-u#^2JEegyx4cS2j5U$J z-0-OEZcVJ<&poPCt_g2>n~3j!HSx|bKtObz7MRPvA6~71K!dFsqJ!zYpyFlEbYQCVTR&1t7YCMjGj0axqQ?8TZ^M0E zG>mCZJIg{J{R1H`+o78yWHKfdMC9|L5`FT4G~&JfqDjyoz|GDK-=eFoRK zA&y5Xbzfa=1Qzo%PxM72SiL{mb$r|ik0OUsT33jc<_`{kWR=s$C26qvc5D5R84aE0mF(BsXn3VFG%J-vgSg>&kDEQ*X#%g?rTYp_nSkmu%JcP}32ter z@6_b*!n%HswI?~&DgF^FIM%=vKMW@XuWU3${c`gj|HG!xmh`5kyJ2qYt>phUdgUsClf&j(ed8tPiN?uTqSje{g96O32OR=ZaOrc zer1;Yr6V|PpI@&E10_1{mJh5M2#znk(!Y(v4LeVW-H2l#!SC37BFCp2ga~^KmNFpw z@1Tkgn}OlkH&t7j8JM+ep1#51i`IL*b(7r;ye4D|`F!R0doIa;MjYQS=(0xr>Hq^0 z_Ix&#oEY5|JimogpSVwG>F3<%;b;7K_!9$)8hK?M?F=+-t$n85%0OGcfT4ap13l@_ z?312xc;{)~U8jc(=q8nBY^Y+O*5p5fk_raow9oPyR5DPl?kHK!;R^0>qx5%=8TdOb zsC4%Q19Kah2L?FYkv|pL-u#(?-CcV#48}R<+FVtAT9}Dj$}tT*Bqp4m#=U*Fk_or# z#BcAnFp(4-F?%_4SH!4(X2`x%BD?F98O$bmw`EtGfhg5D_wctFdb!=DS~bkUf5bbq(9Ika z)q`1$$IS7}LDInEu{r9KzXinpGRKiWcf~)bS|CU-HnHEu0$U%P5j&M&fjj#SXEsz= zAb%xc?P#9`D%3XhaEn_)^T55kL^De$Hj0>x`C4LdW`@ro#S%{MxyHP1TH=S8Kn%|t zOQbt=U(}tl#8UdR)^BoF7&uqL`-N$R3kvQwfo@hH4^TYmyRC5NQEB~Rq7@!Fep-7W z*9u;lBbQT(t+2_gy8X~YD>!bGy!7a~6?VJ%llU8~K%g!cTh(NR%}uZTS~xL%i(luy zMl0Ns3%He2YXy?-q@Cy!EBFLgdeoO$fidhcoORs_haE+^?w+)GEa9HKKI(O+CCn5y9Z4v)gud3AMaEIid9u9! zj=5SQ{}EgFGtm-jk1p+Zow2~kk&i_?8Z7XZ@69Cryajg0m0VE|wSb|3%jVZBEI^QQ zpSvqzflZD20pI)0apsRu!lwu3a2D22{+niw9Vfk_3Et+|8ZX-EL^DT5>UQUL5p#G& z7f9_HFoTYG)N0=vGgNHsnBSOh27+y$%I1S+$X71VedBJ1Bb0&K)ttWQdZOFOCYV9l z$V(VRftwWkjL``>U^N2HXf4{&d(OHgOtXb~h=xga0 z<^6GvjvhR4zK~hMfTLL2%IGWxj>hPZJMUv)pI9a{){}wUC*o0;tvLMMDKS2*#?e1< z!_9m?1|HVzeC_g$4uu;pymvOz@j-Z3^Y$V-gj6pK#HG+V-_7T+djK6S`$J{V+0eoJ z(|plNol`$^CjJD6#|7NZ%IbeMMTN1=la7a`$Ybr?uz1E4f1jm-7-@>7pS$R*9Zj+S zZ)#l+i8I&8UtEJZTz;zJ=&HqT6QnmtOchp|VDFUAmO~jPc<24axj4WCn@>ic6K0v9 zN-pB4fPx9m3iF3%P0%3mj&@zXmBZ!t>vy%^q+!U@U`{)c24X}8k;0kR`8^jVv@K|m z8VN2gl%qk`+j5>bNkw-3xyZmbRMa~h6nJo(%HbSu)uL1?td`v?DBVGYpv>@{X=^HY zw9kR8NX777N?YC-1;N#Q+_8-myq%^RT)av_;;us7`!N(ex9l?exrqXs(feOgC=|T3 zzxk_OgaW$rgq&iNG2VULG$|KnjJR4Qwy>!&4(}jXu)dMu9&185c!3OsWd#Q%9LR_* z+QUs<;&5ur=Z#w{jPUf2%5bZn5mwo96B-nZAo9?UKjn=fP6TQRgr*u|z}47`Y-Nbb z$DKFlXAJQ2KoiBR(g07&CIn)_46yccc=|H30sf38F#r72hmm;6uE5*+P_bL@R~W31 zrv_Wfn~D0UQ+Z&l-lKtPisgB8`46AxFI>R1(#^1>lp9R=y53+b}zC?4M@B^{`Sx8*;JZ(LOc!7EMeS)U4aPn8~7 zp{;`a9HwY-m@;N-yvwfKQNpu;hb!bbzBbWqNaYWm0J#(9yO&ZFQ8J>q&noR?~Q zBA5!ui+d+=@svDTdrl%#9J94UoqZ|%8GqdkKmPK0Tv7RD^EW(VweM_#D0cAVS z$3AZvJeV98bDxoh$=1H=k&DvsvTGsib(6+X*?r`ES!quey45Ge)g=Fl12!&1o3p(PWJOCj%Cwe6ZBDOCF@ zdNsC4;nB(Z`xc8*kl9kbA%3MaN+(TEG-XNSPJdNz_HStfS}q1lxXWNHA@L)Bs|<#X z+j!4A$U-f&rj4gv7TapxFSZ59;o_O1-lshBh%~m*Q7D$j(JRT$^1Bq^yvsJ@y1pWQ zM%<5xo>fGeubpFkH373iObJ4|5_Sg7-TCLO44eCluN~+rsNTN7cVJot%8oA_cU7ul z+l00KrTuEy<8-1bPE{Rwo;l$zN$MandN1q&>&K z^BytW*y*YXd6u*E+A>YdjH|k52x!56RJ6O*Lkpsd78m9@zWwyW{Fw{gTJS5amrPJ5 zqP;v~r-By|KJ$gIe`XP(_D}Qvt{Nh8{%8$%ju7Ei*!zBF83}@0-F*d(Nhnt%h&^3L zLf3(0pH?ptc$&PX2|*FA63nSs)PEcYaEX$Nq)2w=*=`wk=U#V`C>k_SD4C(9L?M(J38jpR z$|z)3ilTm!L{^m9FiS;CyWgk3o{#V6^S;lx?`OR4hH8gWuXU;6xlhFOLs4}c65M!t zotZjnA112_?N!Iu%{3BLx$0Q!CKP&ZKpk}!Ut7M&XyDo(%R*y&4IF)&S=5@Kf%Q?# z-YDV1jqQJ2|6UUZgMKzA>rvnk zmUk@LmjcTbB~DxND6rTk&98k)K?lF{=d`RAeiz0noZO&=hmVg88z&LRnpgMLYhmeW z(Z15}S_lz)LebFH#xbdQ{bna^eBdcDE>40@}uE}Rwn8XdRlBKO+up}1SR7_1d_&zJg*v;vbXuVTGekw! z#lbuEhFE^nCbjRGA^aX5ES8!ugx3^UuDjW=BJx z$me`X|O6*+cum|!;Bo+E270Tc>6U<->jqI%8%D^Tb|O8 z7&-#EaT;=R()P0dkbZXGIdD&s4hR41Bm1=I_?vO6XRZYuCq-XN`nc2a^r2KrLL40n z-<2@A<#eoLyLh?v)8TRKQODRU24>2Y9b@Y=&|y~gbglyf*^vz=_>l|@{74b9E@EK3 z?!~c$ZU$P8M4#9)lZk`5{eM^JGx6q{N0Of-6D2RopMQ&D!ZY{5&c-q(f(H7oNewdb zo4E*I<{9CR`@T8HSVq|Faer#3j}dlx?#$kE)(BFM%UIqGMp$riD9P`O5f(<@nEh16 z7_-jV-#)U=7#3a0-DY9NXiYy{UUAhJd&?3z4||LeCoH9VOT+}@swXYK8kr!J-m4ho zZUXAg7kwL3Ot9qR<*m~9OmIFea4T)f1YORNf)5l;k$zm!+|$++$D}tUMIAPU^zcAV zXMrjFQrdRQb(q2;&V!rz!xRf73w&28u<+yW$bYRI7QQd>wwde1LgEG2{&_(xC~^{9 zYEQF}aY=vOq3bMYM}!9ceab?e`5*&dSjbEt7}>sd1E!kyhkI340KFw91ieUK`BHV4_KU&~r(axkQlZDF{IgXNoY z+z$D1@Zg50=kgQ|;%0l_XH|0`U$v{WYM6ui`8@AbNizh?8b1tLVTMJf2mKLj2KV-u zGoHm}Xwf|5=R9bJj_;hh2yrfSRG3*=d@f>2T^$MoxNuu2*E&Cki^)%-Z}VEXu$VbN zQ0W^N6gvbSUI3^WIWRA)0u38D3JFF)pslvHgf(EGp7Joz5!m`+a>0NvaMXFC?pX-n z*%|mbItl2Q{4L&=1GJ>3g$b3Dc=4f9&V69sHMe`_?WCR1rYqM6fr93Xw%gwUY+WP4 z@t=VH*Wu+v7q&h0#0R@HdB zXe$pXQ6l#xHt=w7p6&d3t9fudy=49m(%$Ah8j@>_czDk=%08&g1J&O~B3hn@K<7Nc z^KfQH(4=i%}Qqk1|l)QC~dRkBB{bc)NXHr`z zusCtk$#hS^do`s{cO8(Bk=*vx7>K`I7V~%+5Tr%9w?h=TSn%Rq_)9MQZuqH1U*|&O zURTk}6I}337psJNb8$s`m3s$ykJhrrBHx#A@h!|xyLZA2%OC$KFQ_#`=}`5;gfuf8 zcw68(w$BXfAB#Ajw=+Y@nm4O#m}VGIIp|4SVg^dTBctI52f+tt>-Y_DVCcwY#N6jV z;rQmrv-un>KDFXqP$CDvt}Dol?&H8Ft5~Anfdfl(EkSi22Zxyl7ny63b^ATN!_=&He>s4(Jrp((-@dWE%< zOd%55P+Gpv6mwI-Q$mh_VpL zd}@Nu3tii?YfRu<71R78*95^UlFV2qOrYgBv~WqF36y7jkIir~LAj_vzzi!B{E?`? zai3;_s)@{~1O*eQp4S?slk+xPc(z9WM{*8_m#?)OFb2oXeYE6}F^pTha<<*s#=ku3@S%j_-N&>vDuKhJ5TMAM7?pRGwF`u`8)hj>`A9HHNU3uH`QlDIXh@ zsnIfqLF56uE*WD4jh3VgiWtNHNZEoV-;B^he;q3`YJ@7$?lJeLMsRj*YWjBH2q)I^ z0<+4E&_BNWT>C|GkMv}htV=P1+9ySmHxWi~Q`yekyvGRiP?u6Iau4Np&HHWjlL=o= z#^)n%n8+SzaXk8*i5Jg~N`^Etv7yxGdd@8-bjq$Zp_qxg-)mQYzsQ6%r6}%71`{8z zP{n7aGSPZCzF#_l2@CHF$u{KPvu3$jR);acKX~)(`XCZls8sc7FB4}lIvwH5go~9S ztKXf8iXVdZMb1ntZm78yy^)Ek7gtyQvSEVr{L6d!C6Q0Gy@}MW1H%~Lbc^?^FHOjyYsY@X?1B$Xn?mp9WY+=8dY4Vy5y_fuI@fJEn$Ld}BZqlL26utKN5*>q) zf)>?DbX=Zwf-!oCjvg!V`X&!Lj^*YbU$>r);pU$9W)2;pr?Q>$NPZ%muxw|tG#v#Y ztB-6KqGQ)9mv*-)lJ8t7e4;o=@)_T;sJLbtnr0*|`*NFx*p<{+iz_q?Y&hic5VMd-Y^Us*rrC za--0Kg*0^MCxk`|(D2#Z?i%+46&dxGocsYQ7AcH*EhqWht{YtAGc{D)&+`@)E~4Vf zZ=V?#GpI=Te)GwKI4b_Uy&He|AQf#DHc<4WBH&nvoZ|*6PF$~b4l}1>i-q1tODYvI zA~v71l&QGjwcU{_K}DghqWMz+Du(JrtB$-Ud8~L+adej(>~8*d+zHY zH`-;yYPTLve_S3EBc}(+Dps9Rqb^1-#&%pis0$Cj_f#2mUASD<7AWe_L1UM^|MPGi zC@FC+dK&8BwXII&q7iNQ%`mbXPuGV0%soM}>$D+sh1aldwl*sNgh)NQtA)Cp13lWI zT6pm0npHSo3kK#Xr`L&Up~Z>z5*-vA;EIH{r&FNr5}9{)GX>91K4LKCDDbWQvD&0v z1F0|V=ifV~0TGA(Z|jXTP_y;n-ScDWn7hW}WZ#b*tfnxd6r!wj|J8%2J z-ZnK{Y!u#}b6gFh4Z=$&R;eNDvR?KD2{jyxJMp>pg(?p3Tbp_4x+)$_?no<5R7GI+ z>vPv!Rq@Ex_(`F*DwKVUw@H3d!K~*yuch5ofy->uinbsX6fYhPaxzuH=lQ`0c70if z3@I(Of|up=t^dv{!7|HP?wGR@3d9&owyP?Et95<-j$TEC(Y#!S_A5d=`P=Qm zMT+qK80meaTmiR##;mGXtpL9;0Uw!3c`R&@@YKwd$AiwDn|G|2$D>cIYiWz*VR$iA z!lhph3B028fFe0;un^u+5-A6{t>-4%w#uRTgVfO$mK@4_S6Q~p%i(7B`}gv*@lobZbqvB98aOJlmL|2;0MRMr@}QQJP%5S58X_pNcOPo_171Tgm%dVu?zy zpxAy|Uath9fk?ZN8Olg5tornJxiaeOd(E`clreu@(v3Yc$$M=%UvcU1G6;>FHT?2( z85!5MV^@Mzpduft`0Kq2mcDH7H1beI?d5m-mp7?m1K(-Z8ipF`dc|G7WvIc-RAiN_ zfI7CXd?@{UhdSD<@{45a)bT80Q=+M?2J$xy{ju`bfPKgDSj}3pzR&RdCB!tbPwmN^ zMmtTkbUkR4P1QuysAGO@nURpS+!mX(|tA(NH_%wrNElg^R)inxfLtyS&o*qvdx|m~| z6QYga{W_cORcj-)eb$zuU!;7EORXzg2Wr8)T@a`g4lMQ7`;^wUT9Qk%*AEBctUix>YsrjLu$@{3HQ3{ci` z*}REmfUXVcg|j>iaB1zi749buaHRJ3e2+Wid_Mg~X8D8xqAuO}y>O`^&c8jFRAy<2 zsToO`rw$l`a&vU!=p{p>MxmWJEf zA=T3pG)V9IwdukVI#k5}&aX44l)5pT5kgB6?dhQ!%Wa-yH4)qRTI=Mms^|M zWrFqVuP8hhFom6`idCkLDIPWL^q<~n3d3%Vr{|OcTHDK@xVIohE$g+&NIF9 zrUh8A|Fg4*sl~$CT$$pFB=4`W&Js2ZWr1_ovVCnn3*GB-pBJ^WFzffg`qrN;)bFxC zmZ;8#WcVDPq19~AOY6c4x3R(b;N!N_lZ{vF%ZCiS$?x~;DqoKfciz5cQ$;N3xVLYd z_~ggYKLS2%G+(SVm`{{rKEEPOjOh%X*-d=#IZUiBYxopSEZcu@OAJxSuq!Z;C}}-qpF&*p@#={)#N%&v zFtUj8S4WpzB=$u3AIc|oCO(`jCZ3cVm#rYS+`8LvlbEU9@v4TnVNFQaePY0k+@@yY zZTG$yZh>x z#Ly>H4>mEp&UzJ}SSIOPu#yN}maQ#OI&V(N24bA|aFQc2#-#AP3-QWA#|=Kj_AN=D z_7Kl^&B{7RGzsYu3niYgVOm8JQ^q`UI+{r~+Baapg57<+DQTrKgL_#yYkf8$^Oz3&NeP{}N?i`Zu{ zw&FQayQyGkfEfJ#C2xc{o+Gv5E%DJ-r;tzo##=r+=G(veyro-z6WfmI4bR-ghWh&! zt|&2J;p80&VxFt?g~dei;ec9MA}chYM2YC!x?bx1i|`H;Q}%WL4kPkUx%5R6&uib?7)x9jVY=Y*zwvqus8#-}AAj~=Ez$Mh z0<;pJh>!m_LbP@%o$>kKJd%aavG$O4TO)F5ikN3Nkw0%Q`M!CTaq>h9j+zynDD_H= zznrMBOIyjFSZ(NbbQ>{2^>e%*v9e>?&i%xyGg+^LiLz&2RD}~?Y%{M(BxcTgJ&{68 zYM{EN6WzxH?w$J=U;UJJi6~;T|3nG#jz^)b(mt{uM`!Mxxu5L&pOkWmgKY4Mcmj_O zvGMq_Zj)#j8%Nyv+wVuRA#s5p8g&%@AI@@?qgkGf2>_y0!Yuux`oMi|>D%;oDk~-jniN$hqymlg8n~X~*a< znXOzXNJP8U1arX&v#$Gfnu`+S;+D`-E?(U!XU8>hA&_n&pEtrqy4bE;$pXL{p##5c z<^i*x2HadN1!SKXEWfS*h|G{LrmF)v?48|A9iV%0>5^W3z~`l;%W^7EJ+NE-84Y;h zEXR$a1LYI;aZ8D5+>o~Cq(0L;)R}DvC{6cP<&nfOjsJ-Rr0+KdnN(|EO z(E2xOG1@?nqL5%XaqhXI9u_J8724u;gT(y`__ANd0BC3|IsSn37inFZ_rVy@TrL|# zrUMPyF(Cyjz~yP@#}yj@woLYyO>QK<_&`*B03Z}=Et(nwtfUqDwPpf0M9-c7Pzr>5 z2(q@+lX{b=eJ0O=KQ8$)WADhk1!rkOfCtvQ;QPG`c<620)H{C}4|Zt>-@7w-5Vn*| zooUSjtv4%nvnvnBRY!w_0(nSJ8Kq4m@}Tk|!!19bhalSgsqQ)+rmQLw*YxqA{dsT5 z?aw?|=KTG0YaSmWJO0~Jxr~pAtoeK7jriy^&I`#|#YazvQhA6AA9tTcGJE&&0ev&M zGtqpg+;zC|;w&ErI*)rvU*%)J-fq_!xB2+Oz1VI0h!1mmDJ8R;566YV^&4ODv0PGS z{rjs1NSUqA5So3@v&Jj{np8ufVAGd@f`j>ok(@$p*a!(sbsJ}ex@os7sl`hq?Q z)t%vE0rUK;`ba+LTYT(J`|`=UO}x}%$4794K>0CKJ~~|c{9{%4$WL-KSD4GkQTtA} z>?t1B{})ns@fi<#rMsg>t9j7c-Wnu;*@YW)_K9%6$Sz-fa3n?QA?{jG7;`dJ5)oJBi@cJk2-$>;mT0&^-WdIkh9fv7d_FQPUk96Foap7mN za=x4d7xjHM-Logna7L(|D%WBLE9u zlanU!Vv3xHZGu7t;gS(1d1Bz|pViKIjuqDZBXL|KxhqV&6eJ)h5c-}l`6x%WNK zIp5{2_n$Z|w*$|h^Gh_t4!;7orJ2jyq3wG?$^9lC1YX|0S8{j|OFsTgj^@F?Nb4fo zg$Mgfe{BNh@Nj+F9;WRe7jkR2mGn1ok=6Wt;6x4=Cr{*TySJT-+|Z@Z9X+}DuOumK zl?4|9d9&h;@?4}p4nKCY)fPJXS4vz9ZINuH?bwrOi^~RoGyeLLT9i~JXJw12Nr&Cm zjwkoY>-Rb|+hDNtbnNqsHlX_t{W!I$>3I zf{n_^KUojM*idcxlH%gThGUY}x>Q3po>V{dcmK=6y?Zj}n&&L2NV96XudwjP^T2!0 zL>5MW|LOeU&%(y2M~N~T3rT%e*?x*Fe5UV<-uIG;v^a{qD31y2Z#Ob1F-(jeSaLGo zm5BguQcR;h6K%Eo{I8jKF+5K1%}i0#@Jq7`UhW_+XUdPPO+WUVcf zD^!>-KPsG&K*jW(9rX=ET&Gv4HB+s=<}@=6EZ2 zHj%#C9QKV{a{tPiqctJJqAiPpPkTAR%>oKaiUc~n?eoxK+c?)Od>+>DWouq(&ch2! z4_8)+8Kx*NtC-+r1|y9Zd8%5k*tBQM&I|(+%)cvWdrZFf+{$Na z?x#(V;P_6{r^^J3W0??Hn8H8bwI?Ck6w*y{+>vTiScf{jIH^Audp|B!UKKePl*z^l zQ<~<&LE-GIY_=ILp9`(HkYa{CF`EN@KAV9v@9MaAhj~!BOQoovp9e!1*4`uy3T%U2 z+*WL%z(eipm9-rdL@{RS(Fk+Io_{}l{(?D7dprU+kD0^a?H-eQZwn}o6p9P3Sm5HM zl2!Vn76=M+?4&zc;?%0J!&B2Nq3nIDLA%uw(|d1Uemc_%2GiDQqjNuna!WD@9QG0C&~{NYd5coQkwF8yi^VP$~wlwa0R6}e}##;kG8X?Ikn z5*5F5BL;fasZif;6z4XJiji&0>}FU{abS4So|}Afy(F)+e-RbkZtEJxLa7*iSTFmr zhYGLp#cPjdll6Gqk9++N6&msXB?PxnQTOcK)5;%Il*Qbg;I2-?`qBC$aLpYWx8PvIdUQP!}fzvhIh zxUn!Nd9f%vj)jrI-Jcd0vygS+>?!dF7G4dOXG(P0Fkk&FH`JMpYig@k?A^{rWc^-~ z;;U?YEz%2L^qLLZ>{9u>i5!%^e^R-Y!9i$WNc!u=98?|E36Lam5MwJ1|6a&}&btFY zuXJ*t(A)asoEq7;ruO`J&$q!&aI8OXw1KPhwmpB&+90(m$X&n52K6l~x+g2yBE0K- zm5GflOeMK=v$eM9^xyw#!Wmnp7UdM6)uR{KEn|{7yD?RBmZsY0!x3l zSzqG9YU|mPn_9RipShH(qsT+|2kDF#R31ceXUCuNC)Mocj|qu9u>Y_hIu-Iz;6Fhc z)6Rod_{{YyCfZ@{>BA?~ZR}9`@taOrh#dwBV=W7h+F`lZtUH`)JKRcqwZdc24xZ!s z&}n9m0)B*Ip07Qkrj38JdcQq9ycKp#yKRs2w6Nz-zS!fSq0?g<13o<2W4;#`@G)(p zW}4kDKIZq&ed>6f4~O>Sp*bJ<;19uW-`ZfV_jCP8?=L_&Y z>-Hz>*8;4tbnZK<1ZtC+arEKx*o%OnzH_(ST|lYiy4IE^Krc~qmqs5TJhJZ7>hVIhRkM6&VBqFS!DNnO=6M?Vn$#C-&VaJYFW*mPJ=2jU`-?3DLUwejIii%PG-MVG4l+f)9x|E)6Ge*vfRdWg>wu1Bbgaj}u6W zt`AMRM4)8u_P2sE0tGwk5*I%q(A&HxYuY>Ve3zQhnV$rfw0#X;s3^f{%@@ipQzcMV zd7~3MM}h$nt*=xi znDysmp2Zje=MybKHvI(de@%_Q)wA?69M+)x0wS}0w=!MmUn3r*t}%ljqE>SywG)*d)Xm| z&t8qzp!;IX&s4Q@BmdvlZGYGHCW)b}bNc+TFfk5<-<$HwTMRc1#e2KRdq6W96e`UV zWAJXcS)`U2Jgc$eng2w1E7cwf?iFFI=d?|6iwL=l8<$HSig2?=@2rHpce;8x4as@r zKCc0Vo0%f)ROe~S4vIkiU6$}Yj*L%~eY#BEYp2jdt7=2Y^A#e)5I^#Muj1|APu888 zuKB~)ViDxGXE|&p>vHx6;n)yEgx@=v*})cMeZ9JD5N9mH_$r@F-EygcL4;Cog^%jPLhL-g0Qqf-Nl`-RwJjLVSHZ9N^G%)Yh(D0MT&opED%_(0cvrBKHe$bmmFo*l43@xV61!`BAOo7JULjBJpfx`e;s8wWybi@7d$I4HXL zmywptfl-R*K)s6k{rD&{KLgAlA}NRMF(nzv%#>@ z(R|^`#?+6s=YGs%!}4_Naj7C3`fhQl&Tm+#P_E(MDq}(N-1}@sCJWk$v21ZX3zu_k zY70YHNc62OCdm11&zxaJB@PP>Un$RZ4Olq8A!MXgi3QJR(WS(9CTPiX21DAJsFkqF ze?DZwC+_0$qa{qVEZ=>%`YaRCo=&O52bplQUFgCi`MV-NWN7vpCO(J0b-(Px#Ic_J z&MRe1>@-_pmCk0Ou%z_v4-+N~-i~v>ti^<@-Ih6Na!lOYV?FZa3jRbdRAk(DKX@MYlR>U7r#5d+C@ zCQ7zZ7(j56R}(o8FONCXJ@%K5tXu9f&O170ydK!deME;zm1gesd^%SCV5ZJJOvml* z3pON1(%~nHO0CY?6C)_|3JmEuFZ<7XXaXHkoooFfKhyAYTYwmOkX}??qrVKsF{Da z=$NCkGq&$oKLypHwV?_P6g)oPU95M70=490Z}N{&a9q>yr`1jhip}nFcSKR}deicP zmQ55muNao8g;O9*@!MKK#s@CmxX~C#L0F*f{aXhqSU24KTq~P`dry@9#NMJHQq}pW zN-G8J>K7*893%NPx{oq2&m2C}`&AXZ%rRs8i^sDP%<-$*U`fXd?I^J~}4Y{dr-C`s(wDrENSQ9~mR7i_^bcTkn zfiGOW>uFH5ndZ4{h=%C<)z-U==p>(1cQahc`<8l2P`H_nBXQKz;pwEd2JAGvM#p^Z zCwJ8z(=nU3nzy=(j=R$vQ}+I(Bd)4XoHw3eJ~vr2P&%QM_M67QW#32TnGCYtX4n`zvls|lI&^LWn*q1d zYp*gn4Cu-^$BJwj(DygJRmo#u#*OJJp9BniO;S;9B^cN|bZo(6CkFOwJc{;T$iR)) zyA(h9Gtd-s;7zSKUkw!wz%2b?cUNxjedZI^0;aeiKmw-0Ra{e(2@)gK#J zW|kQ5rrM&a?%uTr!M0emDkb30Nn0f57Q8+6%oaC)svA64=0b_5Vdg+`>#)ai?X_h8 znk~vwnM`tP{m=emUL9P_I`HhQs}>JI#GIiyjyzLni`d*9}yOcLNo@y)B=5I}eT4=E8Y07orw&HP*e<~US!?(Gm@ zXFv7GIu&5%Q;l1V#w3?^1O<%ofvb^Wnly6GG4kti?ASzd>T6}^m&w4(E$45{%>hhr zw#dfa16YxbMa0 zb?zo1%u?k48=p+hZ~k9jMqVK2$E!sNpY96b;G%!iu0;qR$JDxe--YNr-`wgsNrX#D za(pdvjy2(HHjm?ru)6gF417hPtWZ;ZOU}pfnv>2&l5=z1yk|Q%UJ^lz=hj$RDS}&^ zcu+c7{;h%;WA=V}FYbat!AGhdLh{V`D(qL)mFGf#q*Qw{5#IUZL z-S=~^7@GgCFFJcl3{m`9pWQ`b=or+EK7A<0lusH(2VaXZI(2&OnE^3UyzAnI3aP+1Uh*KPk31o;H!@cU3mnQo^DKak`V~BaL8NeL7;l|1L6851T4LL z@3)7L{P)^lRkD%5{MuXl&7%ptu`JR(yo2PrhCD6xT?D@QCFhUsC9wKg*R1Yj0#0oK z?3XD7+>)z_$%hGuN}|f%rV)6(axpLDD1lU&mQmp`0g3>$tC_Y0nW-Mx9!;kj*b6sha$;Q+>OtAit`A#Y^=*yDJ1jJ?DHnv zBG9j1x-R7bfmtTLbr#PFgg)Q6X5=l&TlR+QEe8m!HSY{f7%#yi6~v#@lt8ch>>{zD z1buo(OU&pbhrUur&b=W;r|HW3->b>>AJ>lbG)bWmlJ>OktrShOo@$kRCG*rt zw&whiLS@z4FutM;`TB2_8`NYd$+OVa(2*g-ax2fO zXGpPR@}O}w`MtB|*fv>hkit^YoiE?W z{gmL@-KYNR+ayqMeX;sUg#;cC91gt5m0)0<^M5HR5+vP@pzMp3fbzs-`{V!#T+Vwr zmr5jHeKBttwv^zF*6Yi>X%aZBkQbaBBXHx*F4rTy1O`pS&KfTXtalfwo~XNd#jiSx1WvZ^aZGAfUbJZOljvfjYW(@6@#f{G9b4dHNGL@cHBTWETQa4`%cj z@d0<2R#VmDG5aW$}g=T)g2n9o;m1{{K z&EDRa(p)3LjJt7%rj&}XsMp}R-USirmyPbNJuHIehFMQ^;zXDjzC-13s0c-Jr}x#6 zK0R<~agXpYF!nzMnAr4IIv&Guy9HZxTDtjfoZ zMN`%K+wDP(buS3KVh_WZ@`7bM?D6hTi)``&dyM6`>CZQ{$In@x4^@oVA@Q`am*ANl zGG81uYs;}iO44oZ$6M?$<4($)lTLQ<$_~3>qHBlW<2!2>kn=~$vC1j0OL#c)Ky8qS z=V7Z`?r5D05A#YyjqN%-sI|`I_;hjcPCwVD`wACM-l^?c(OiUQ%)Pfr#D(<<-wPYn zNRD5ebKK&UEtE=X&(xf=1-;#*$uP_oA?>XtIv_vzi# zn>IM*|7gr+pAG7R4ym5=x52W&%Szfb8}QSA{fbny!O}sU0JT;Qva9RVul>ituZ)!o zyLNL>^6Rl%$r278Y+Aptg5>u90RRC1{}kAHG?d>T2XIT#LS!kCLYo#0X2$IEo_!&0 zlBG~8ONB(Vkc6ULwiZ!TmiQ)1g-S{iDG^d3Z77vOrSN-xf8F!kbMHN8&hy;Q=lz;j z(VmQw$u_V)5o@&ZJr()Awf3A_RQQ!9e0y_*3RQm4$(b97`6gfYA|@5;_v=;;&!pn* zY>%oYWh!D9%a_u7DbTO_F}dX#1#wNLWe$ZDyjhv5{w$sX8_ki{Hh&5_-dXwVwxb|x z(B!>%J_W0P>pql>l2NW7n)#rKjMtGLEe>Rn!8u#z-4;T|t+PhU7fQ(J3wFD~(;_4J zTt1uJZjD8@r+5!Dtf8ZMtCAwG68kl(55_JQ)=iY=_!n=O!UQ=gF zbX`B*b%bh(iQ_&+exGiM1CLiWj~^l7*+Q57n?I1S;Qf$)+fx!$tTmQjFC!uLm1gO& zY!dnn54~$hA>qES)9`343FEG6uJ#Tip~=Ee`XYz~z3J;mjQmM(GI%y}Wh)77>064Y z`H^74CI8XdK|7L$7ij6)LA$!O&UY z{r9OAd}nD~(onXB(m^_Bl8rUoR@eS#x5XL>+m1c0O1H+Tw$aupFRVdgdQR@2Kt}t5 zp!gLWGR|CWJlhmVhLJ|S-ij+^-27Ja%&L`)Irp(DQI&$I4MBI#QYpxHyKLFNk%AM3 zcYXAaQ(!pr0$HVq0*CPAGf_K$2mCy5I=1}3~tT5tWLxs)i z!rll86|$;#D|A*le=3L&eSUGar|SQ&GBv{bge$6<-g}D(1yd@jmNA-mf?+GH&d9Zh3-=lnB>T6^X>X z@L$}idX9?JT?}G_AblDix7MA^ZQ_prS;6qC)2(6$lhUW$zMly%&@@#MfdVEiVfT~*Q`!mWdkK2JG~t{Y%t1y7G;=dgXd3Xy*_i( z2HTF@y%zAw20M)J&Ad2jgE1}2Lm1Q0Dx|La!l$7iSpL0h0}V!pTi)qL(hxNeIHZ|Q zgNk74`G`9-M0)(}<-MWdn)>G9-Vqw^)fQ~ZHKrqpc4+=)F&*ztuMx#>rK2_Q!LGBX z=x9_ni>)lBBj=aX)kj@){C;i}_-G;n^G?pOH@0NpyT5L)nKJ`pnjy)v_cH*_nX?nJ z88}v~U=aR{0j~{%e6mao#!{t|*@3}~xc+}$IB%n0)zTwNc zK+S3MrCl6g*lIw&&M`XAknN-5?{pbx^|f((Tmc+2y=h?o3Ye2K zVOr!Mkl25L`&omB+{Z(d`HOf^KkTRPCg7pYV^4?wIv&;qMt!pi;lcd*nhn%=9?H7@ zdmVd~hxlbxJE9-*@H0DOcVY(*A6yfb6#eF*lGU~-K#LD+`I4A7i}{FlOl#jE;v>Lw z-wkUIK2E8;;@qyEXa8}W>m}4P?`;L)4izGrwHeIM?y9)u@ipb6oA%fSA zUHWlSh-*qs$S%~mq z!RWG0Vi7v-Ib_ATh`?$#Sf#j4ger}3VZ!|)u){Az{7Dc&U!z&oEL(&Fvg^%OWg?Wv zRBs%8B7)7^x1ReuM2OgaJu$6cgwom+$IVJ&R5ewm38sqi*Eu+B)hsc{2TwDc7m6|C zRYK5TOEJRUDB5+?#4xFIuYbT6qcr{R!V-uvjepwd4PT7YEA3Z25{l9FpsIVRSd4YN z;MZ3q#CeHFye7-U$eQ_4wo)!e;0&|p0k&csgDWr3P7Fp$K%|kq7&~okE2l0OS-eN>1j87~I5TkRHuUfQ63{SU) zke)+gC~oYxIGZAdLTZe3Fh`7t_v@Cex+@0V7gG|N#6;cj^Um%O<5Q;*O+!I~Rr~Eu zwdqMgkhH+#@<$0aJqo%iSCB$ysK2&PPl}hXU#+mSl%n=g@7f@V6lpFN?~bjLV$-DT zszZTNEOxP4)E+H`S93GUydgbfm-xXxAZwVVaI9Y~S*;_OFb!1q&soHXmp$t;et^m8aGH7hi z*HK<1!xOuV?xW^1v@|Hszhfyw&3Z?*erp+=c2D}-L6+gZLwL&U{Zh1a-(IlmofI0Oo5nGlq{!XxoW;6N%(F(i^sY-WdwKmivvetHl5`h- zi<3h7z;W5uU@7Dqe?;$flOmvgRWnU2Me_Cy9v)^=T-sGVOI=5bA@$-viGL*c((tn~ zs6zr;dW>1)0|`PihYh*e5?r_Rt)FmIg43VVy{X%Y=djQ*KS$y{hc@Ig=n}YJWybRi zCAbvvhUu#;!IHe(pnJr35i=&A@Lz)%rleCYC1qkp}vTNt9IbuXP#}$3o z7DLVKUu^X_F`B)_F6~1iFs7{jnb{-4`-EBPTCYWzoMzrJo4BW=+|-M^%0-BoM2?-F zBSOK%ip%4ZMd*z@Z5ew>ciKos;}U2-?o*Np}@tJ~gI-DG@PW33PquQW1~ONGee5AO2G z62dM;qCF{*n6IB$o3Kv^e`^~HinkD^b8j_%UoJ!wZ*aucMu^76J5TR76yjsIiqR)! zA-?WhUi_d(fbPZLdN0)ru!P!EEH4ruxBf)n&C>#SdA)z?zfXYBitR6LHwtieu8#2; zTLCiKYRwg`1&B;iC5o2-9|G;m?Gyz_=j$}@>gGeK`Hx${Q$F5bC=E6(;e*`gnEc`# zA9duO=C}L#psAfdEZoe8flOR?LB@ytc37U*5JTpD>?? zYcD<*zMR5Ckez;G^)I6Dt#G&a`xcN*`*MFl9k9M!s&%Xc_`}@x(mfquJT|Y`77Jt@ z5G`9y^vl(go9*I={`u~D!x-eT|PA6N67itQ>n8nA`pEz^57p&QOiFthvI#{zZwMCQ%Hy z7ysU?uz`Wh%ec9O;&Aap|pe@Tt-mgeOiGEP>hi)=1-${*^HIi{*iFv2f zT{5;=#QN;XA>;H+{nByCWc(DT+I2>e!R|=#KjlIce(Vb=EwT_He(^S_4 zuO{Q<-EZUjmyw~_S+Y0Zj*O7~%Zy&wlEF%@x;oRIj4)H%3x`&b@j%^Z{ybt|!9|ye zpM3~#dQ|u(?j~c%KUKEw1aY3SVfNZ=GHjn-p3+=NhPlPCUUWMdq4OG8uYVIxb$j+& zPnUx2f70@~))W}U*IeK_P@t=JFXvbY1r^o1PhLGs!LF#kg)Mg}U|YFRPQ9mK#y8g; z&nHq59ld{JjWrdTpEmrcA-tj)xbViEV^mE2WFyqNM+J3UWb@m8D$EAi0P0ZNYS7L)dMKz9-yKSJJBe!^bL%^~A zzt=9)aCNZKLi;%l5xggnu7m^p7nG(gpHGKB_efrejE?g<1&%+r&`~B0@HlXUj&A=O zLRK~%{i}mhjqcImo4zLbTQeQUE27mW_Rw+jaGVNvn2u$^-VWZA8Q9>pJLA|42JVE@ z&TX5=fSvSU*?7K_JAUT>@y-Z^uzB&9_X)y!0?tK_`sb@gn+{nrEGXo>CcEfd(m|))N4EeQ$iO}G& z`5pF5v{ac}ybWX`v-eEOizMP+hZUOzlrz!hRQ~bdTP9Rv(_UAruy9p}Y;($#g{1LT z384}e+9&LNDfecfa(0_%Un~m;a*hnG%41>v@8H zxxkgPv30XwU2!1c6+1~;%NaJd?YZ&g=Y697Py|UipV^p_74-6=HV0S7#SNcla`0cw zq_M4@94y_#yi$0W182?XoZdnXtPNdV{X00g@_MACdJ-2pnPk6-bS}c~l@678b20t_ z_4oM{E*_{w$i+2Wbe-5ke)xy*O*>PyQ5W#?52i9nz~CO+$un&MZc?my<|aT;?!xSi z0HV&@FI7ne9B2mN$+v*~teKTM&A`9(e}5PJ1a{1@7AR{HE(y9A#xvtV*yU6`OU{E$ zpOcHG7Z2p6j+4F};K8w;N^K(gOPb%hGu^j&$T)RgP~OJF)CpV7#p2j5Z$^ zqCZvcwcum@?96OeTR!Rw>%-O%{p`Zil8i6=_;~un+}Gv|A2+;aZ}ctVBdg7<(2H=) zCd!6g{h#=_zQVhSL-fnMfGaDn6aBN>NUCW_7NEnIw_w0d0Ke+O)~lNdrx?+SOd|v^ zRg9v%CHnE|gfDusLIFIisEX_A1bDCVb@G%C0-Sjf^yT|M!avRQa$6lC+EzLSu3aL; zpLKEj9t(x|b!(sIRKhcB9fYyW-9lJLadLHtyb$MXGwOMb$Q4?xReeORFqwWLw(^q@ zv%QoJzblGh!P<1_fuRT`1wPy3=^{M4c<$$W2N5#+v#u2pc_usaL%7jl5o#YiX>__Q zf_QhxoAs3l+by}Z;AZIh%n~-5#z;oTk25_ z3Hr^>9RD{@f*F0Qh97e!Fx~fM_W~ygCaA6Rd+H~_%^tmmvyl=Eo9S6CPLv@1JmHQ@ zgcDc``}&FqA8eu73MwTaaSr@^@I(Uh1;Nk0wh+0~c8ghCrv$Ge0U?uvomtChngEI{tsQ855qMK3u+Ug|Zav5%S-eDpF|f8XbE+ zL5j?Vcm>vEDM<5tyu;L`NSWuVx?EF=#57N}0BtGe&s4g*Wx5m*qdaBqOex6a*sO_M?}ZF$Z;mHb0E)O4%0>pQPlxCa_)BQOHP!-pJZgP_OcxIh2Q>bDwgBw@0Bq* z_vO%auxmf{l-Q^1EKq2ZX>J?*Dj)KzPb|=T=h)oNwKT3@I=C$}wBj%;4dLL!Py3^MRSo4W}*|m)YBj4qi zT2b+a%3b+{XC>{w7+#eXl5nHIQO>? zKc>%^QkoPAGm_1%4@xnGYBhXvyA;_jyGW6QgH^M&=2_WF;nwrfXBwSw;EQkn3>HX{ z`a-_PneZL$v>lbNM7Y@grmXtA1pfxI>WT>GEolfolT%N4TThU*^|k~`s-l7Fs}hta zAAH$zPJ)T$Wo>5&_q~2BYf1^1VCT5rO%&qZ-r@YaT(DLG<^&fFH<<+Lw`S*UCri+k z!|B^HTLR(GtT^f<3D(aHq0jCg~ER!n}Ol&U!KKE_N*pDi!0PrnXW&;lWdG z`#51lUCH*(pdXJCX`A*88+*co70+{SFvOT!vtab%d@;_t z{ZN^pB_;q+Rafy(gss~~+zmd8kn!qwl0&@+H`H#iLW)H2ZB1<;ofhGVy4tgVaKeGR z{{D>i6v4c3EPSF|gddKdGg~bF|9=m2#<%Grl$tb5H&GDbsp*DKW!*w(?x{;#*dWAX zi~SJ+gzJ_sWbZkbA%v2`J5T+iLP$+w{`}r4#Py@Qq~Ys@*yc*=UvDo&;+x9QOg7=Y zWfHXp3n9i%MxR%iC&X0EqVui>LJXLlOZh!jh|9X#hhM7-u}o|8j+hYvHu&a#b{-I5 z)7F~VCZ7dp>G^)s?X3Xgd`jE9n*~tXZm-c>E5P^cz22S`0t6f`QK}H1C6kOn-JhaiQiFgiU4jkUGkTU1UNc5Vt=5K0F(81-VU24K-2!{zcFe8 zw4Uia?589^&C7#BuD|(kdu83L^OX;#-|*YwcYL%LJGZ617ojbEkBJ%F@ zF}O44^Q#+tEE}xUc#_LU3jIu!MLHi>PTti*LS zB=#vQZd*+B^FbB&d=(cyR{5F?=PczTX?nih2_7FuBsGUUDSQOiiti1Y@{w9BV16_p za)9!Yr*Eh5v46c!jg1l?>35U2D-ZFIbaCY|_g)?}wf0WWYUe>eG0sx_3B5) zcpfyqGRL_L0XY%83F;q!;+{!wRy_lpC%jT$c@q#R^_D250ez059J46kSetq2bRWQa z!+-iQO96XNo4CzZz@`+nyr${ESN_rYECR?GCQXuAwOrg5&R!dTo{KfQyD zc>mW5E;7Bhwg{JS@r4^_@nAd`Ps_~TMz?eD)4=7{$PEsrT5fc;NaCRTeVg{}U=9lY z>J7)N;$XuQ`M!l#9E`QZ_gtOI0sBFQ){k#&Xde8vocV+exoVs%J(~>|E_3CLNH&iD zNUyDRX2W~=%tJ$FY+SjXtMOZrjeRe_gluVIq2 z(K}DWA0Bk%TMh5-0Ueh+JGyk{&_N#OpZi>uj%hxz;oHB`u<6rrpLwk`Xc#SQoLxnO z&K<$d+l4gTu5H~Ekx9e+vdu~hl4S7`vi6b4bF#>>KzDI9sSY%b>$8k z=)&u%SGLoT_a8&@hIp>?-;^reMZ>QH3Xj6~)6nZUq(A2f;qlv}WvtUQka8Y#7iSaa z)9v2nmlNwI*d|UOTxO%pVmkHE5FY#EQ_eU#W|sA(sF~2gH}4#b7tj&@$~j-#iw=c! z<4)~kba=NZg)c9m!zZF_FFNU{jJq8br^Y~LbDY5?CIfdhDr|1}G2nBD_2$4u2K)wJ zh@+bsDEGMiN_R37zt*ng404$m{`&f}NiY+S&-b~9<}hJue6~*B!GyuU#g^kbENpE# zW#1uSVZ%U%UqcWJ-4jPYy-Q~yG$%jA>@f>p1zFalpDd``u4B*)*m!)U=yn5-4N+qC zAssI^RvzKGYsa#o@`5X+WU--};BYvjiVd6QWCOpqY;fkxEPwHrjnPL-Ol5?7qDl*% zH<@yXoRZ05!PZS3iuahDweZZd7~a6bB~Vjf>^%mp2gWEW>jg-*IqzaKNejHwP|BsY>@WxzPT%G3%Kb7gvwa zlJxAkn8Nz#rM{hu%I?td(Mep0-ByP;mT{4%(&6{6lZ%r+uey&Z0xxT@*l8-zuKbGS zWDHCTZ(H$(@YjJgd)y7UK$EFjJ=+c-eedeK<_zpU6_#5@)Q9h$H-}Po1NSy`1D!Kqm+X!u_%W<6pdc9F*YYmF>;`9$yk)z88O zhTzifscZ-jMp?6T*$8rcO=$|*XjZz}QSZuzZS2hc^bj^O6#QrXNN3}y&8O9L85>;% zZuggeChuD|sh5qgp{cvT5pyYci<$J<)fC!ye(}9$N1=PWp3LAO3WYr}3JGT^oSSH; z8JakdBF%9`0t6d~JX|TSw&i@-sqs&%QvEm|)M?rmZ z$M4ZFlH5HY-9W>&Zg&eALM1^uH|O!_L2TQF=8WPc~}4 z-ua!6#9OzDj}P(D*0;^`JRdfXex6 z4?o{5fB|Pr+1%X%v~A44vdLEf$;uUer-B8T`*Z*2_6Pw2e&_psj1!=1c-GmvMDkwI z8C4erc<@8++^s7DjK3P;ub3r(%6U6yhZ_P2q$7&|<_Zv+qvKw1OMu|)O5xo*0xUXj zyo0_gz@HzoQ5q!zSkM=Y7L<|CTb{3vd?G;a*j@gmF9kU8uYbtsjR4*!yz&C-1z<&V z1Qs_5knCr5G@?y_m^#jy{(b>my9z#El@;Rs7n?sPX9{tlJVJTw5+Uw)o*9TR6GFAP z>CA@>Lae*YZ5?$JV#`}4oyW(7Fil@FAeSJ-H=fts-kU=72bWY?Jrm;enLmx|8ii=m z__%PeSBQf8fs+IBA}DEw8JUI5Mh1Bq4^V1L>TbA(DCl32$?P2? zpLr&~r;6cFex_uMrWo?4&TN5+7&1i?A4(ub>jWw9^)_Nuq*2EroyAzfS`hVZj~Gpf zOUujr#5j4d?qX|*7(J7G60IV|81K40*&$Yp1Pv^Dbyf`i8a3U631UR75ig&UC`R+O z#>YA5#W;1^^QG?@F@E?Ihg^>lLv60Us{ctbVtWr2c?XFhv0HyN<&YS6;=Xuic!;5Y z>%XB4Co!ykw>zJ)BIA6@GaW;Vk!wA%KXZi`3~G2``a&@bru-gLqbSCEkLA|6e?{1u zTW2(*S%e|m4?RC$h@g|H9MyYE1gEdVQL>35@GKHX=N}Vc@~va8x~?Mp4pY%zAr|3^ zhnhy`G7*?Amo2_e5uwv;#Ic{Oi<*jPN=B^^_bj{2KNbs7Sz4KdbRnX1`;xSe3*moB zpBdpL#Kmnp&L-FhvA1rM(1j8r_s-hRUj{;~s=1=~TvG_H^z17^bA^~Q`p@q9G$B5P z-(wid3DI!-m|_2*02kd%IB{gZd4IHBl=)r&Gw*klGufZv(^t>fRV;vBs;qAh+3&x9 z^Qjtg9-iEQ)3Zsv3GG#5rSY-RkFU)+!-tjnuB`?q_-JD9S-j&2A2NE&xpTev;8#YQWpCpn zy>hnVtBrgNiT+d76!PJkHqfGP#z(w{_eXtFw+x%V|LR^q>XTC9-vSjrgk1Z;wG;S= z{WDOwZHUyv{r+EGb@GsTIeyoXCLS&ge(*`E=3&wnFOBY}JS18bmDd;X@UdU9&nkxp zgJlP@Hl*_~5UG4}%vm0sS2vg*KSAng@;*~1e;(fVbxt(e%fp$oyo>-B9ugMoB)zrc zVP3FVNv8!5uNsqNWGK>(6m53En1`7U_;>4dcvvFLs(Go#!)k{P>bf#%w||_Bhb#|& zYHnJE4ASu2x1uDfgGS%iDG`r9)94y&ZyZ)l<5X1jk>F=EdL2tgFBQ{pJMeeuKrW4q zCi%;TF4K4w;oupPKx6r{=cYeT(U_6Gfwm2zF&ciY===d1lb4CNJ$9oZTVJi7=RlKt zY(nF}S{fBisk`bpGJO^Xu7jB(#kOLp} zscXO4ao{(!;mLe+4pf@E(mu^6_xbn(b?3)%aQd1uE2x#iEr(&lqGuEi(BlrSx=vw@ zUsOk26otTpQx-MsrEoTMPX7mM3bi*ld@h5+uEU?37SE?3BNg-`ZXAVli^Z>GzOxZ! zZ?s>zoDHvPgERAPveC55cE4LZ8@jK*OQ-p=Azx*)p?WhLHKS)%|K+gJIVY<5l@1$` zGjqaqh=nVbWrn_ASSa6JW3BU=h0u_-9?5q}zIr~h?pOxNOK;>AXp*P$ zbkCR^_h%uvE$DXiP8N!{Sht2*vEcXR#vX4L3kE^9KiZeF5cy=qW2IRveAp*S92w8T z(-Y0r6Z?RM<1AhCFF?PRQDf~Jz_)&}_uKox?IOlbb{25y@3*|Dcp#-~$)H035WId* z#?UU{#qZEfYSuu+{>Gf;EI=#!-do8M;Arvi!{Mnw+FFkVN`IKpf0vNi`Iw1yrA(K@ zu}q{n3dB*CbH}z0?rPZqeS+Mg6C6n_$wFqKaVrV{p$f=UOJhhbVvKu z%gfDCe|@d2={R#dTasU-Rc(eM{a-uRW|%=i7-De7&kRn3xt2{E%wVp2`r;3LGgzj& z-+HEG1|`SiJuiMSaQ)8ypOb1BkRExIxw@Ev(DfDr=2scmaQE5B=XeI@hgH_(hA>dE z$jxxoAqM6oB>ns8!GO_6UZwO71|pPCso6O(AT>woWbPIQL;{A4-c|p?_>E5{7mTIMaD=W2$L!bR07k!Dy=RRqcYXNG@v zoGO=QGj!w>*`z3$V@+M*Ks&=6nk7@(e0P~6%4p_Q_e66T&&qvx^o2QAA8het{x!$` zQbShVVkTDBJ-mKw6BAbJi&mY8WWw?DBe{|XOcWesPm2D{1XHx3Z5mm}_RTF3Eo5DT z#A@evvB^FdR}gJu1K6ANs7%`pxXO+mK1}w-P(sA(y3@eJg}xl`bRgNwsM+-vaCMb{ z^Wh<2`sZBLJ+i;<-tsd2`xz*e50UcgB>OMsdrb3R;KG)^vn**AR9TvpM-*B3v8Ttp zc?Js?OBcG|Rb%17o*TOdG+Bs=oO9rZE(^>5J$re`kcI5qKmQ0!Sg@523u<7n@aP2d z?mn{b+m#ffqqrf|A7Lp?%gaTezW-UY(EQ|M~?0=4rD>zXm-MkNET*puZ}5BU?D5Ms-ylI3+fdc zMPtahRQ<0z?oK%imRXsl|A^1{9P{sb-^IextVg;HW7zm*teErc|6b#!wf2?<8y>+M zceJl$gQ1njxx!_`adz9dXB*f!8~0(^p{;DV-C#H_^JJr=X3U76KO41I#=C8aV#B?| zpnYW;8<(dm4&A)NhRH}+Q1VMQR+fGbd_?@`h4uZ`AAM|O6&DTs3%%2Xv3HWm*b{NqUBSHnNsuX`xG_J1%fD2T#|@WZQbouLpr(zdcNlY*w5 zBXjEm3V-}JE=Yezo)hLs)wWYeG0w4`Ak9I=<4QT(IUH=zkXc!~l7q_Ul2qw+94PR6 z%@TGK?zL#%9l^mR)v3Dsu5nNh_fMmS_|eWu8+O-z;b4-Vdf=jQT#WhP%^p?fLN?ar z*giHF`-9$Chm-n$+s#X5*)cBenn|y>AYK&xUAJLMDHrwPs~7c~xM-?f_3Q8$8pF4J zu1=g!!#cXp<~5VX`8C1g?KjhCs5f{HKN`0lR(BsiM`MoV#R&V|Ylt>l~smhlgs%FMBhLc=%?~68L8w59=ZWP5pNB!0sBk=O50)wU4nr z7ccR!EPTQ9g=IXL*7dRveBwd3;aRTlFc0b)30FPl@X=XlGJeKtKGaC-aVxytH-i_GSB)34q$+ zGc$?rIJdZZ-F6ee>W*yTVv^62PIs@Faan+niv2bj4+I!xgkWp~@tL9+e`)1awr|U%MmdOZ~-$=fVIddP6_b3wKNt5i6Bd>|ql)Gy5wTNKNz53>7zX)7YWy2W?Vkn30b zwk(F2c=y6672*#svuCVTaTnv9Y586^;xF?%drMPy!1qec+bhCbmGENkyi>!UDH1m_2$xXs?*0 z^g&{Q_Vm?`jv@=_>3E*|MO&cNe$2aI($2*xTGt9pNV{GNc0tQ5kmTWby;p0}@<+<+tNWs{|D}^F51eB$&^W3g7sM%-5t`<&ZoH7T@x! z^&s7uUrWJpR7#zdqNoO zVXPJ05MqAG;Ek`TLYzIcs-8#AbK_py&#?hQtn8dT9O5Cw3PFL&m`y?`nk#H6poNJ1 zuUNr!xe#Tk$KuOp3lY3`hH;gw5JN^=mTV?<#5XxtF}+cMclxU?)V~nGi`$U#E517n_^66EU$$~OA8pz{W%LJm=r_#E32WftxbupK*NBg0j9t`xG>L~* z(FQrchd1Xk zpkS&)yeUWZtJlO2htLs_?=g^82Qx zDJPD7(~iiiW8DqNGshVOjY1OrvF|~ffNT0EnB2gN!}WGHMTJN zEd|QaJioh~f^+9UIP(bwA2;UOnmh_Mnf=e2ZcKkmOwP!LR5VXRE}efXW7BB7;LRg)ZHuW|D6@*5QFC)TH>WmA|+ zT?*MwnET==b2;HMy&IVgSrm%4|J##7^5OCq`?Nsy_=0yt9EVsZr7bv{gbN8nX;mVum%ac+mu%m51CPJLw__b0h` zTg%~q!xRGQ+Fj=#q;NMha`Ntd6b`(xkDc#D=E0=+f)j^4J|Wd#*^`MD$jBFL-P5N zMZOomv9T(~(5tbI4I{4?Q`bFbV~JLR_izClGt{n$Wir?Zx)iWhLgo6CqI2Q_AeUht((WjtvtOHcLg>+8dtVD4zUm< zweKT-upqi{*46DD3-sEU;%N_Ac+%Rfcl;&`wQCM5JEgL4?CWd$HsU#Vg0v^sA7(+X zeo~e6P8M3frUW`$5g!wIr*9&Db+P_i*)8H>Z08=`#JMbdQ7G10qQt_d-81%%i~{E6 z=J|iSNNjC-Gh#)2?|IS2%_l2?U5OjpO&*Y#vuDyKZVvF^#DzX~Do_{^yHF+?;N+`q zX9fait~;l%^#LY5s|g+535Zn|-_v#k{Pe0#sw@F5N1b(^BA|OHE2xxs>7S|pw)`*! zE>ZX7TJ%Z3y|;!wYXSNE-}~px1Ewi@75+C3&`TaYjfuolcY0cSNCByn##%4`#YAsN zvUXu36Tdl&>CsnAOj>+oTrBb7*+%18aVxWYu+`O}5%=b7lyh_Tppiiz>b zzPVw+OblLdSl@q`i9_qN1K#XoB72Y2p+OHO29CPVc5q`N?W^}?*BwmUxM?2Ec46Yk zpByJu^1OMIdg?y%zBQp#j=zVA3B#@bP4Qzwru=q`$q6Qk2H)gWBr>5jz3)?QE)!7~ zUS2nN!Ng0?n+?6+nAmTE?$_f0qc-{etK|Rnx`t{?EdtKYv5}p(k}&c^@dyP7pPu6S zuLs6@e7U@23t$;8m)YR~jD#GVw)-gY{62c$I^ypg{gZxfy8^@=j!AVW0&K0^eTJ)m z6YV2k|e(_%IC8X60Y`L{_Lq^45f;jd_ty2Oupyde z*<8GYjZdRWe$h-e&h3?&J+g)k9q-)oRWhfF`1G&+O3ClYIc$tbNcq49n z;~VF-zln#ZSH#r}vaz78>+2b5Qb+1{Z|fBt@nw-HJk6jy@acO zYUDI3l%zY0m&i_tuWi*23h%yUfq^Xs+htT5paMVFU zUpG3%k1#=S_H7_xpP72i)L#@5|MhqT5IX3%^P7KD_$sBzUo}V}PV&q2v@{2%Pp8L8 zP2(V8*j&Gh+>dkq_QjRN^=&T)~jHhSM+78h^6IxXlg;o|A|@GHrcT$I^zG>x0Mc%-_+ zIk}4q`?cMS^TS+>-MY9kMvjKo;tf;JOr!B|f^*c*c{IN5VhFcr(~#5bt9M&Y!{=Du zn0KZ$*yW*Pwb(SOUi((72x%y^N;@rDNAjN9=;VZrG)8_hbRz9&Fy>x;YUoJgOm; zq>-HcW^&bD8qP1W&j#!#In;FE?{Z(#--Q`LRYz#(cs%=ZHIRniom0^rAv9V85?a)c z)9AWsTT7j!5qg#`*mRo4`NQ3XF@%~H(={2fG)}6od+HHK<9`4E0RR6Kn0Y)@-y6rH zLZLz_L?uayk|d>kn0@BXorxqQDq9F;sVG~t&|)h~NJ@oLQ6lXmOC_>IWowaCgo@PH z@BIFHzwSNvoH=*qdCv2G=Eu$#C4q@-=(c311QCu+>sTE^$eydB5>A-2H+JA4VN2Wo znnQ$Bttv~767HJ$WL+uYk+Tjt&j@F{eeU;?Fr(nbiUz`k52Ny%34h#XcC`|A@CpOl z{=e=4)0{5Ch$=?RCqfys7uH`0tApOA^$~s!;=dRmU@?6O^`%Rz+k&b`GZ z99+?Px7dcq!J5T;BRAP{FvC2;OxK+Q53^et-}i8EbM{czk3$@InXQQ_JjKC@km0(( zY!2==pL;m}76*fF6JD!4;lO&o-eKuR4t6j-hpRqtFz>gMjKvTK{lcu3UgNpgo$`bK zPl1a+PnE6f=5g`+k%f}eaxPLhso(BeaB<@K{4B8*7u^>p`BiV{Vq3-B7lVFW#M{j= z-*J$O;_k5*WAR*Uo>zV;;5-+T+cWpPE9ByfiPJytaxRuL{PIPwxac2y`1MpL7ed1? zX+wQn9O<3t+x?G=((m%EI&wUCpBCTxsmjCnS2;?L7xD05rm@$ARXhly|1O=z;$g># zvF=VW55^UmVbQicu=W~eMLF>hmGHwv&y5Eix#exm!jeSAfZMW$~Yf0_(Q{)8NB3k( zrkYZC5HWbvd}O z+MN`n8>iW5?WOQJ)$fXFBn6g&P4nqE3Om0TZ(E&7Vfo1p9rg_hMN)a6@03$eIr^WB z^lJ()!hJoQzfsWGo!Z_fDMS?W>&;jdA@q|nMY79LmMmmD82lHMl7e+L&a zt^^D5@Z!I(#)(1!Atn_zG_54sO{O{O$#1E$jZtZ1lDd%w`kgT|8GNG%Gb(dE)Maw?w2`196fMdxX3QaCwr zTp^8^|LiTR9?>}D@zwNcEe)M8o9N5$XdKwNPkwbT4U_o$fp31%7%}g>JyTMITQWS0 zU$P=>3S%AqFzH5!uhW+QCI4JX`xnxL98V?`L=WmKlifqc6-Q zZn+2!TSkZV33s_T9bBasuFm<5_yp_t@{c}XnS9+Sdc%}&UUcaA( z%Zadf!(PFKaU#s~zY%FSNaK<~M?dT%4dF{!ou)<_&8BmFlgepSgajR_yiOy?#yh4p zjfU%pQv1ZCG#U;*tWNW%;X=i`EpejZY^hzfSU^LYf9jov5skTctFudkM!@}xO(8>V(x7K8h2A>5q~paD-eOJS&`x5$P`;_q$A%T)#xjMaHXn>9#Wf6TfVEk{B9 z@yx9Ae+1}F=GR2@2vDlcJCfNVz=7=K{(n^hgl^Xwttt_qa^9c$<8uTsNPKzZOo{-x z_tO#zjtUUJZR-2)`vl16y*sP#DM0b0D5)*>0&LG&|8hTHfIC|~4{bLQ;Cy<(g(*4$ z;6hcKKgoN}EZ3%@@d9jgH1l87&xd5VR9Va$KG;6;l}#0V40sIK8x-(i7$mu_u7?!DiAEkuqFTi$?ILmv+| zId5+IHuA9H;>(e@cX$|lex{`&lLza6lUz%pcsLU58%%ld(5pR?mMP*v-*sK%$`w4U zo%qvhwh9jeFB;_D{l~@Y*q1Z=KX7sP#Pe6YYA!}XWVDQ~adETm_#O2GE@aAX4-W3( z!oM`jYNoD;^p}Pm@7Tma=vec{GE)wm2Q;MP=8}5Xp+1hDK)P+K(D|%)sNgIM^KZm-Rvu=-B;uCajomC%s7E>6 z+04SeOY4gT92N#$>{bUFve0H)c4*057RH*4oXg}{u&w#zr##9;mQ2z}d^Z!v*Ozr& zu4m%J)JogRyG;DsI9Ibin~98^&0fVP$o;RLGX8-~wDF~n%-O=ky@>`lY?w^Uh_4$f zSj5D%ON&NVPi4aM_Kn0h0}Q0N*Bu;gVj%kd{i%#n1}b(owRBg))OZV6<=q#!hgjgva`r-XPYYx=e^@5iWPxt|tBM933-ph0(v4SHKq~nI zkwXix7Nr?qn`41+PSKx$85Y>T&|UUFSqlVClHU+M-U3Z#y^`bpn#1{%#TECT<_J80 zW$}9 zHhTkaq@`NG-K)7_W`PA(Xx@?Ssj>inj-Q-$hXoW)D4+Bjw!ka3@SJ1?2Hf>yZs{#y zAks)9r;^1$e7)z`3P%RA78gF7w2y(`-^}8a;~D5NU6xRm!@&HDK~nk;8AzK+fKB%sgqMX8_vX(vz~>UPcrdUD(iUh87BI^oZZ!VkqI09wqpg?nW(Z?*){bJ z6H%hdT@{a+_&K!n;O=TB&Z+Tg9)<&3lU-IS$^4!B6-aEc9 zG2z;{acldTI1?MRRmmAaLG%!;Xbg-ZOXGoh)SiDv8nyV*$Kvy<_n# zoSN#Dt9p@z*R^BuK1D2e-WUgcj8*O>6KPLZRL(=cKU$6}Eav!sc)8}v?-+bMq+lYhe z+5d2r;$Z)LpEEO^IZ$GA#J#~Bd~vvZoR`SKt_3NcMfn_kE$;EolfRU)+bx46(w z;@|@D=8jqR3m*L7;#joO6Psx~{QH|YuS}l@+Yr|^JwhHf^>vE>dXaPe?W+N!V>~e0 zU;3Kn@xXD+9Z0F>LFp|wrLl*HNA3?U$WP|uc0r~|@nSya2VGd6$>*c(YD0yR2Olpt zUON0cn$)9=(dvXeKI~4L#Gk9-qa;-8Zfq|fDU8P5?y>^-7hZnP(G|dB=DZS9QU@2Q zr~g>*A;8YnSu3U-5#S#c8@2ho0D2=k8R?}0M4P_*Hvg3XW2dKklzk!d)Pk)bNx}Nn zlvC4GDJ1n-uH!7FaH2aixRChg@z&7aaG)?+S6zQJfY5X4)w#!rhej(G1f8c4c}2Qc z;w}Y7%KK*bItnqG&(|1!q98FKH)~*o!s|2Fyzk2jac9(5(qOg_V#&pI9~TP|xrf2> zStUeMd(iijOd&p>it0C`h4@m+J1T7>#G6klL(N-+(6QP3_m7JZdls(zUF{{rmNU~n z$NCFV-|~B72l3Dy{;#bk9wgqPIH$hhs1PT8%8PHu3K2fe$Fwp@h!v{iCyCAqk^5g# zuOsoHxo=gTOJ5h_6zi3>UkUM7gLyZ{%7hRWnqOS>QV8F(hmPKRCq%4=jMkEGLhMR6 zJemGah#HPobWt$=oBsZO8hKY?uEAARvN1JCKi1Nq@gje z;XubR8c+F2%PlU_;QHpgPbB{OpYzF+ZEtA!a6{Hv|E8f=@~dG~L4>7SlWc{0BIK{i z37y3ip(*NH=<=;1^ykSd#qAT};HnN)x052!A0MhuI4{DuYtp|@-x8r?Z1*bfry^)7 zkN7`q79sx0p}P^EMerKgHmiGBgyzTTUL)hhkl9wPn4mKb6y z*I8k6#CUly*P&p67%JC3#2nKV!)lf4)epemFx~q}1j!gHUT}j5?>+aN?|LjkPgtBn*)UKVjnZacnjrD0rT2}45 zr%1!#zoG3jNdFVIvQg8Q#8b=!Bl)whUTUd^5L?r~(^E)Zopg4- zmiU`ODpPUdoh}Nh&V79!Ur@NJCU;$hlAsJ=8LM z$eTj)-4mKknHc#^Ok@HC;FdbY);S6=PVmOY_W$S7aQf#h zD+J)1Rp$Dr3$T8=+o-Cv05U4iGsF7$=p3A!bgqdH)?HIe*L!^Y$bNJ+B8!jT?~hr3 zJj6#k%iPh)i;trwFQ2xH_%OXA)R!|P{k`6Nr_dRE%nWFa`!vi$;F@iJQd@bbRc|k8 zy2m4aH>I_nc=&Ja2I_kR4^O%(-O^o%pP#c^AkQT}ZW}P(NSAoKR9Cc_JP)B&=U?W3 z=i>c<*;%P0bT^pTAy;1*tC_U-{2O$RI57?%XI;PT8&DqDnJ&DHL0S68YbTXUA zSR9O~_XH^!aFBC3+Hlv|Kbq2qLK}&@T6<$ zEjHYqJU5z}%|_Cgm_Z7XBR7ejL-uLfP#MxmndLoV!{Om3M=M_WKXd zMW?W!F7MNDAe04%sXe0_t}LwWi`nc>v0yhXB|g-Eg$%hbT9U*=URT}o9Q(tBaQ6M3 zjh#%??z(o#?0Jae{;VW3~T`)uq%2CCw}{7c)G_X~?R^-ii%@&gzms_6>kG>U2@M0>JuJz6wkWw(mpoUVUh%Vt z%)8+%^(l|6bNsNRVkcQQSMBvG)ng1a#?7C;@iYULh0yLe$G~!fA|+8i1Mf@i=Z}!S zB0}-Ui_jVd8f>$TbKa8mO!sA4e<$-|3J+@#FRgGW^tz3xcm9}5?X&n0|_X2D-*66cr6 z!cvW#W9GM5xFLS2rCP(nn$#WovF}(=l{n|a`OZRQSn-_m{}I3ZCXwk!d{BJB<=-zg zHeNlP?oq45hRP6os-6)WYTX91&1P(jvpyN#%Oi37^zND-OE#`%79Jb4W8mQjV;T5Zh1uFI69TBws#L3=MuaxeI))^c|)O}7s-ZCu6k^AH0eJRrzdyC zveD>YbNc`P8;_otq$o_oc<>#Vj z#lhNB3%2XJanM!NSiB;LgY!W(x6U5tAblt#;b|rZdE-sxr3yKCQ&aUayqtshw51L1 z4IJ#WdAI26dkz{UO3f>WIC$_g{M>eFF7&dxp6jV`(V!T7^u7TXO+jC-2lKdS-YDU* zeH#}GX7;$n26M5Z;I?L4A{UV*ar+GOxtQuUoxb*zcG7r$fDJlsQx!WR!7V%j~2GY|7%wrS&5y9+$rRWO)%>JbmO-t2sP zr;VJKwzuzO|K;IK%n#8^RX*I@hegX*^Kne$_=E$td^`zEVYUSEF|BUgvy4xR=@_(jrT{))`3u!o31FVAyjXdo0Pm*Bx~GtOG1)X< z`RXYFR(1YqJWuM%q%*oPSq%cX%zUxl=BEIc3m0*HPwn6dsiX zB%AN2a3|%H-KGpu2c@r1q#jYQI;1!=^gXF(moHe-QbLr)KROY;P>2m%a$?Rv0+A;LZ*8NqcM5#qd6`Le{Ht`FY+U>_!egipfGSBWBQs6Tt0nIl5D=K;f$ z_e7Z8baBG_IuX{%K2uNqD8i0!PQAr{M39bg^s<%_<4;0hL8Ouxx`_{KXAtkC)LV7s zi2t46pDMkVcwtyTeMLF($QJ^w4i`!cb?;kk7dMGvU90J7<1EHN?&}IgA2Cu}f1Nc7 z5@X-H^tDP+VqCi1Y2t8F42|twv(uBw`W40VYcs_NIkfrN{>x&BTz5RRxF&|TdT+kr zEpmOscLnE;81m;G1NPn*quJQpN%^rDo^M-OUFBkQBx-ehtq`MU{>n*fD#h@1mzB>U zWaSM?gHXW`y3?PEu_M>D$mEF_t1`5%R+0Hn{70(JJrJXKS<_k$sPtX-rLu7vo=d`!1zpV$?3m z$e$7^M)Ivp{Z8_}rr(`2KKPRR*ArD1x{9&!d`gd=ofxArBis9hVq`7yIrEf!e_+Vd~4)}2uzLp zR6+vjLq=t0wE2tR7*&4dnzaai&nx7g8jDaalx;Im6X9)yYQN>Vf6D3{rSVGbuvhS28vaw>kE|u$99!PJ`=Tw4UzxQj z+jumr2Inl>vx-JoM$VF_+BDwxKCU%ZreUwK>99bSMsVizz*QvgbgKWx8WXQRaL3qi zYp)P`INILWF2tPF2@0$xA=LHdQq!LcAzAzI@~mE0tS6c`vD{+2-vJm6OQ??Zog@}+(_#pd}!u72aM|#M)v$EId)24a~1H}zB zY7Z$$zhC6rca?&FLHgq-X%r07Y4w*e6wDN4x|ar1P~q_8C=Uwa>_66fZOQz9Cpstd zC`cs;Ivq_YEXUSI)r%->HjO@eX%^|bm;3s0q>0!6O3S+NOMpF7mCng^3y@Iq_2;)H z0iH}A^;!K?fJaqlB)dcc)EpFc%=p&d`fZJl-PEKEFp>059I5m<6f= zs3#m!@{kuGZpk23IZlA_xh{*jLwu;W1wEVbnU592pK4X#@^MpMV&6b5ANBmJRu{_o zi0$miI!)?@zG>g#U03;dpjhvYOg?`0=4_2f;G<h&fuh+tU?|Z zACBL9?=%nn%?GrH_wi8fZOQ$#nFpudhrVNGJp9U1KgOEJgGjqv``maQ1RV#@$#-*c z#=zTSl+@STxVmR3SSs?I46nq}5Mmp{P4nz5!CncFx> zy{^X{HFeT5CfAa&z0N7?v0-SzCp?QH0{aNELM*)Yp>&Td@HhQ-mFrG}(oP6VEP1bZ}TGKEAtrp*0KBeVl#;8L?0l9d=^oR2H`Os}0;%W1(bDSFe#A z3yC`#QuhrzqAJ(A=3B2L+;0g6b2}Ze$7Y0i`oj^gyD~2*wL0Qr9WObl#S#Bnw|GmM z9U+%7`+*N>Z698d`AD9BWp}%OCgX1Y*~pl*lkZ=Bz7*f(h*vw+^``YZ;{1s_J3mXY zpg22*H*qWr`AVrHI_hL!F_*vH&}Bg|;q%l-rYtl~-94xT7Bmx%=Jir6tat9r?p{Oo zanGgGBaj7k3l&eA*;cO4lvqF!|_IJ%jQdmpBIe2Qk{rQwEc`_8dp(0Xls-yJqO zwVxbTuVdr$Gm%x-Z#Gnqm$5^}avf!Pl*8t3H@>V4S$}SiB?A!II*Dl};S6 z_Z#$;tmEK@){N&N0UV5UZv7A(!GYnbFVVV3IH+!WfA!S~4#wC#E*wecKyxnd<&7K; zYz-#7-hG?s?SZj4yo>|=CFb0@l^hI>n60+1<-q@;N%VsTqDwoQs14tUUay-N_Wa`D z-RsE6sy+@*UbYK9J;K4~_tSSAmE&T=(oK9nRWA0l4cjVfa4}h_YvX8LF6?||%+}84 zLhn!SD-}yF@}CvVuvx;zfYW1Mv4{)b{2LQ?xp5&7*cLSUa&b@9X-39wE+USu*jgCR zg>vhY7cy5!f07m@y2pjKQr4l6S}yW}Cky(1a^ZNo+01Gb4}0Reo4lrw_V@{Iq$v-# zH+9mF9C)ymjS7%i!GpSi&#w0ycu;FG*Xs%8p|xRKflUk#+ZSP-dnylq9OsV-&*#A@ z?bn$rPkB(>w`1?FPdpsxsWHFW!^7nO1E*t(d{qA0V!B?Jk1J>0-hHv=!)U?Gf7KKp zg=Gb~_r3Y}Jt@57{vJLw_7!{FOytAff4!SVE+0Wm@3h}f`B>&Ke#Na8KKd&3EUl#k z=r8QhikT{a$o1gfHX8xlhbt>btq@?o=>ln|?E>hsJWDRb3vjsbUZ27>0etfMHpW&7 zaOQpaZ2nIHN^hGUaT_Z{O!}vR3$uif7Nj1jLYMPG)4Gn>gQcxG&Zde zyR-8^;^Ydd>aZ=cI)MoIa089`Jui~Ou?_Z@W}X;6pkCDH0G_Q5aYHmvfYQm z;i7M5s{$xgwrEaUw2Ok`oTB>?Q51CJrqB01Od+!C+x3$P6lCw$MO{2iq0LWj`PfSo zUgRj;Fvz7~9O^0`dy9fa?KG35QVKJ3Tqyer3SoKORvtAJI@Go*3mYj=akAXj9~4es zW4Hh4qfpgUJ$suBjgF~WA^Q|)tX|%&-L6K%*4}TG{}dWNeX<|>X3%)3P=0>4F^vFw zt5HQ(WW3b!xY(sMO3$;BHi~Ej4}72I>rCU!8b1z|s-?do>ng>n z?EXY!{kltyc|U158H_Xrsduz%b@7VlLBi&)-neF9L6*r zb7sKre5YRS&fuA8o4wi^1|6&9z6Gvj;C1F|wfuSp{y`{;>p0+SEJ~p2ZPItysq4HWkAg#^%s)niV2<@jQ)rDMQ<{5{Vv$3-TNe(unOU*u&aIWABxA z_vu?{l2@%iaL7GdY~rQMkb8HTTGBIBNMrtwrjy=_X*AzhH(?e!+ zg5oK(NbSzL9!}vydvs{W77D*Bv+iqoP`GNO6|XO(kk&WB` zyPe5mq!(?;ToNh9B##N2%A3VF8aeT+?{YDw8QcpfT`b0+Vb$x)Mq*5^9P{$u1TpFd zKT1XX6G8c8^-aC6BJ{m!vW%}1VOdo})(Mh#^7ch6&PWp>^AvL59unbg3hPDqb`hHP zb2A>hi7=4l_ff_{garQw+;$@od{>1ZxT_|@nHw|PEP91FIe0?;zxP5U9*o+Oa90RF zqo@lH(uA;4uUqsqN{A?N>i$q~A^sd~@d@Axp?laQR(XyPcXwYrJEAPa;{~fS4|EE^ zS2JH=TrGf%&bpKpHwBn8-PEisS%3zgB$vyf0t~fu#j)H3s9Sw9+ulxqdHQChL(>G< zR`56d6UqB;ADdT5edgn=%r{Bj13uQ!w^Zj{;6q+P|8LxWK9nlmER4PQFc7mA#&GzE zTp6O&Z^#Grc9~nJJgF<$^VfC$;K5k$r&rG_9!l)I6_(%O;Y-oHl*}uno+%q;HJsof zb>*0$hO_q^6eNG zExQjo_V{zL$|zplp5mf9RAJ5$V=fjcuis{&!i9Ri(fHy&9IVwsQrJ5V!jJ79`f-N? z+1}Ac56*KCFvsYeB$|WWIX*r`z8ox4nLBTo;=t)vP3b6W4rbg`FY%j6zTdV_(R~~T zDMst}Et2LyugddjXcrr^h7ye4HM4R1UG$}`gr}yb=|7cu#)f=*ne*%tHqut>xW!** zqv5q6rTr2ct+T7gQfJthJ6NOHcbtvYiN$vsjyGTJe z8%IhmrAYR$aeaWga(_1)VaMLzsw92wC9E-B5rpfW*@mbQz8jVjs9uj@qdKy}s*}uH zt$a+j@+=$q4>FC8W)g0%=VaY4WJ7G){Z{)i8w<)>&c@cT@#I&^^Z2i9JhlHvDfY9` z^kS=wNSTA5y87qCW^hn8l>C83&LP@s+KuaC4tDya?%n52e8iQ#gHOT;ADVe+3KBUe zxqjqv^HmNqO7A!wDdk{m`L@zcZ#Zzc?qRCl%7FoQ`7hoe2b_&Mf4?Ym@%o>0%K8~x ze4--8`B-z2Ym~5VIk`V;)u!$mA1;jR-4<4bbFn>d`GLMfE?VUWR@}(uLd)gS{s*O8 zNNtg;{Zhll;;+G9l-ju1y}xaE;~*D9O_wX9m3WYEE6(>JdU{f@Bdu&M4`%{W>w~R% zaFgWSRCVM*d-8|FWnv!oyKFixb|HGy_QjUJ6j$8}P)rO#sux z8o%i>Ld>Dci<~uuD4SST@Y;;zwcOwUW1$ckh1KgpC&3scf3Y7l+^x)^ZwV3y&XCbEUCnTg70D2aPc6S;HNK z2VRea+ArBiV_JxNv@GF-ouQ*bOo9ksTs`E#*-hhOYh_=^J{r61hHk8lp&{kj?HNKi z{Wv+eX)H#a5$4l)pE8Q48tQZ$v$`}kz{!lhl z!ay}`_0w;K3^vbjcJjK;;NF+-qrEa2oIZI(RVST+WXZ6)Kly*j=;MDS2@K}%O>Zzh z%pgbAYDsz|gK>8qjh2Km_#kU-Y2r_~IrQn9wd7n*WxXnjA?Gx!=Vg|V@T=!~%Y0)F zgT_srE(3(KAH0}5Yx_I~R*8ajOY|AkShYVg)nst&tfBWL6>=XH2O|auuXeXhY2MmP z<6A?-%>6%TjJ0om^@iN5u5(?SMKuk9Mc|CHk7yLvt^Bs2kVaaLj_)L*k4tYj$EFeg z5b3gy7j%T^N43m3GlE9;#k|L1fkY3YiEW`ohg~)vUnE4IF9M&h&|OADMP4dGpG!mi zW7V^6qWfaA#?eV6E_#1?TU6@P;Joj>{fER;`$FUCy~GD)o!b6r7l}KozJ#TMVG8g2 z6i?F~6qdbB{1wqaVeX6BK}Qs zqHXsf3WjB6v9F20dqOupHz6E5plxM1a}9;B$(m1cB^1{E7jFBR_(dx{ZNx61h+omI zl$%AkH&;(FUW>x?C>sMd$tOiyOjKsdQuxk6?1f%2{P*z<_1eUEqws6`+4o|c+*s&$ zvO~ z_69LJ|3%L;a}mSS@UYhgffz&jx2DJ0k#Rexq(7f0hBRFiymqD-!tT;4nMq=d`T3v5 zdpR+BCst|24u~)!zOJIxF2dnmj&?4eL@4`lXaDloBDAh5UHkB%2q%^%-JVw=YqjVoZ|4CgR)uX06d7oa|!0%Xkl;_EY8ih0u2$S6q}VL{E7) zB146+%&`=Ia3$l~*LPLe3b9^JncFf|h_DHYdVT){7;`2d8_aytywxSJB-j zsdI#n`6Z7H_X^M~F_2GKC%{8#%i|3k0bUx=A)Dq2prQ6s7&ldb&TSSIU&jh?;=+-N z(*t~*5{}bwCiPSGUK6+V9UoI=_w>e>^D+6jY3rApe7vn2Rlejr9~(cKwXkFPaBFZn zzF-d@+K+AGU;6SPeIf8z3aQ&miua5QTFl1-&D5EqS$t#^8GH7Pg~9gH|KbZk2x2wbiQdwW^++<&Bc$a%OzYBSs$&z#pY4Ri$>JA=zI8h zkLy@2N&>cAcq_|=`x&Xz$x>VtPExz6|Br*H#i{}B0~`!~XKbARa&XaZ)dqt;!ksVH z)|K>fAb7s%kuK@~y8Cyk2YLVYT`lEH#*YEgiaO%~~b*2_a z2+wAioNP+rqLJyFyE~JMsHGd99=Xj$e$p0&2T#elX_~eUzvY5;cQD9@_?lg4vSRwV z=n1)K7^c93f6AZN<(fS7d;fXXIfnVk8f9k687ePUd0V6icV13?3wPsVAow^DyCZCOehrYNG{9_up3@%s8h@>xOyY ziT9mrp2EizGx}?S1s}^&=LoKe2_N!NVM2W1#%Vj0b9eEvw6SSJFwu3=4wdX%=lF;U zUXWm!NBm%LVSv^SmQ>39;tRX-^ZQQ3f(*^K8bIM@pYympf zkMVzLAwX)0tE?Z$bLz0Zok)O`j-h-G@w?ui8hwSn0=!EX5Bcp9K;=c`0+m<+emwBJ z<(@7;q=st6k6Qv{-M><#RwY37e(C}LvjD7tkZj8y!nM*m(IIj|s6O}8x6>lNoJGG$ zG9`T4Vr;Nsi4c>-WP36~CeNercFlvvnPLim|LB#D^`lUKzxD$TQwXWctKFMHp=us$ zQB64o?uX{aL*FP^HhcfPGm1v}2EE0m6KF7VAC>Q%K{)cvi`XfoE^l#)${1%)V^aS3 zV+@Z*pjYvas}dS|B}`)=;m@EL)qmlhgbPCkd_+DpQun)V4kO%|n|orJaxje+^QnfO zggY0RZqnHpNn;jEVVlN5!WpJ-zuzL_FMuDYjI??=SdnLPrmw6d6vfggZYy? z(`g7pAIk5$LO6Qla3wFBMtETNX1hEZTYF#By)K|}XS8?0wqn91o!Pt(_h|eZEgiV} zA>oes^B#UFCwwyMTuoUejqUm)G3yD>+`q}w4}3>>CvVwQ{YDx$uOD7k^p(cSd#Y9{ z9c2I8RQxJ>Xe^JoaFjDlV=j}#8j@pham_`R?05#@7QwQGQyH*TgH{X}5{}ASkXvQO zVD*`iiiLIzW-Kf@kU=;sGW*lI?}W=DU&^LTTE)OAuyOhW9|n0&ZdI{?40bJ0W^asO z@Hi{LP%egn+4VMJ7#X;KZ9bYyxUk%Q$2E^!!m~-{AvJ_whgg?)6+U8c(zd5`-%AGS z*JhW?)e~-fKFQ=+GXrcs5>npIpg8m5GS^-Px2BEj`!md7p{J``%NPkb0fRI3R3s=+ z{1$M0q6GfSHMvom5?oks*Y;0G0#@(0|7!Ils2`i0C}SkSzh3pJoVgN=)@o6|W+K6Q zC#?gk=1K5vB5#Z7dnMFqOc&tLA-&u>?lhm$wV%NU%eC zX>yLC1mfVZh95H|D6B|W|@Ff8WW#vS%<_ zYb!a=+I`f>TJpV-M#jz+gs;aGJ^0IG&@N?fvvUyx>qFL0bW9j{cvJBT(;1AU9$#xS zj@+aDRJgoXncOa1pG+fp<=7j0NnHHa`8#EYYy_m%1p8om=;COG(!c$*(%X-Rxu z^ybAu_0BZTAO6%|C#Df|_>Px6i^eCR(8AZ2#9ds5iisHwPp#-EHR40ZDNoAGCH^$- zhqZpeBpUaQ-)QntrlFtT+LtRsBQ~jV;C?%WY=8d>Rt<$W6NMe-B@~p;4tO|RrV!-( z*U0%81>2>1DMf|xbCp!GuZ82i>Iy{2Y#BkVn+$!{d7%u}q_SbA7{HxGl z^=G*lqati8^a%Hw8U(M)*Aqi!r@{{nMKKC2?hCH{5h|nA%1p%)WPbBHOsaN(7o#2%-bsjP(J)7+tXfv{{a91|Nl&wc|28Lw7`XX z&10ohlDT9`$q@DuC70_CWhhCKj18s+DH)OmDMh3-P$4B#LR<-n5D_U-gpAja%-%k| z_xn75eLv@{b=F>c?X}k4`>Z4>x7}1S2Q4vg&I4lR5I&p!QGSL3uU3xmtnHyd1X7yw z_)G!W%KN5k-cjJRYRW)#J_VvfZ%Epw7Ykn>c?_JIbre=Fs~2xgGNlS;-$3UoZL@Yd3yfLz88^$myu z##7nmkFcHMZAtCD*zOK$X><4<3e@B)Hh*)b03$c9=Z`l9;`3jt-3p?>nepqJPhO+I z6DRk~`uh~nzDrfi%A~-S+NLXAWfTxS-#mS$g#zX&vU$2}3M~G1L_L;l4${VX26W2R*ewBob(GcC-a$LiUI;zQ;z{Wi;0IM5tcDP3%S5oZpY=?xmeS?16Y9c{Sv zgE<`j6miL`%N!I>-$F|B=HRS9HKw=10xmvW5xQT?0v?=~*g8$M0EY-axuJs=p!gxR z;mE9Mx*EDN9=-~NkMV*$Q9jMGNGT7YR- zOnyLRIr^HT5K0a1(LKKUF9Yf7*9Qyls%+^)ZA&CbD31QW&Ep0qLc~) z}L!Qq!W=C>wk0988!9eL?6;%T&TdNCbDX*Qf5 zYv`b$-|^(U3LQ4&sr5$b(7}H{utrSi;FUJ@&5%Kd8M;71)m}P$$?07D$qF~T zu)MJQ_U6-c_!Yh_WHOizJ%|2qa$KSVe@hii1mZtK=Rc#95Q877|Dcj@4A&gN}c zA|19Yt^L-JOa~4ZlydhO9d=Ajl{;n9fohRAur8Ml4#&sin+oVq*lBMOUQCAz@toF{ zWpw!3dpSm-k`D5Q175iyUU#)AHx9mX7gONhYX-yFmTFv#(-2FuV%kI2Aq^$ zrRh+{fHs>H`KFHyXzunbasS4E_qukEUUV}chT~Sd$p`~%E}oCxJi`EmXwvIM5)-;a zUsoLyVS>!+YlZrfOxT^eQMpc*2{js}46*f0_>jQ2jI@CXJSs{4+?$#3=}!5FWqM2~ zj=d=N(truP7uMzv0ux@#JSBA-Gofl(m~-lOCZvm`6n5=kg8$RXE3p(N7}~2JzirNh zUqFkRz%0>_QP0IR*A>Su@2cW2 z(_wxCI`Svf1CeVz`dN589157VJ~&&zM7opi9LBxEanri1u_5ewz_bU2gtJ8)wm9dx~D ztNSzP@Opcs;?XBKj}4sk0`K5@yvjT_7Db1tv~s2guBV-@VPVR+zP{EfSuXLXgT&6# z-0!&l%0~G3{axw6ZLp~^$bk;aqnd8~v8Ka3hqu{LOI+uPT?w<>=)lf4Zj>{mgL|!X zYmOGKD}h5MqwDD~VbWqCEJKI9x8}6ErMP~QT|L+G)4{GHsxf4S220lOSwG!DgS`DS z9o8RckdxMa$2yw^3KKCo6?bT`I>AfX7x$lO&L4$^o;296HEQ+9iU#>p5`*^)F_-pu z{!*X;*W*65twJ<7_>{eBWYiK;`n66hYq12;jA5TymL;%`DkNql;yySd7SIu734bp* z8anK=gzK4V_j>d#p}Z?$d#SV~E%eqQd8;DHpBJP~lKks|cSD6(p7itW`Wl1>?$zq=6$;(1~$-QG(fb znQjz__l3qxrzsaq=O=G&nR!y7$Na^E*B*FZN&UPn*_{fPBiNjxZdB-6zdrGf3l*9- zxRgJ2rh>(#y0wS#{$e~EHCW|9g)M5?-EDT5g}$!gHdN5`uaIhIQh_sdo4JA|6|(Lu zrBzd?P%^$cy#Vi5!tTASeiJIpTOB>-wUr9T{JQ1rfeL>=hpfDg_qCF|9}yY`SkF#< zgP=YYRs;mZDs7>{yRLVp9(q(*(_is(P8W|;_{?RyI*v>0&y(4Bf4pG*p#L^z=Q|g# zVO4DR4R5&?=61#I`x`LLpCtZK!Ax5fG`|*8;EU@!Ma+k(ntL<_oXc0z*uCr&+xgrW7eWSP~Oiv%iXBnrH~CNnu*Ky-lhn4dhdGQ=0~etF@f5T;|P;UYrMC1LN*HJDe^W;B-*WLeo->js^qesa{8k1r&vCN3@GwHEC zF(27u@*nqO2CpbO?}wT6XykY(5zq9S&f%EhYRO0AFmII2nm#7tN)_644^z`yVmup@ z^u+MmYfL3gpP(wt9`&*CI?T~>GsiYev%)9dEtt-ilUjR-=avY=F3ic0pl(7QyEyy( z55jKSWpzSt*REMgH)fNjPde{3FJx(@YbU11j&DxCF{>IQsUyU=#onQUo!I}* zMqM(d$GxlXi09o8vp&dT=8FgQN@Hewt81*sG!PD%B$&ARVVxAFrNF+irIvscF*UiO zhlj9#`9YjRgx__x(_6kSh?5d+H?;}#!`ar~HAMW68SpnPh~IzIO#2z}0duf_y+}O~ zKb6{$0wQh~zEr&=)(aLpzQt6nFWpj%xiVfVg{Xs7XSG{1iM;MSAee@EXiDMdGs2#g zhH?sKYTmc~$pr6=-@JnOh&@@LFJO9&l7Sgew^}_3vtv%~ z(*t6CBn~~eORQgLcKLl`y+w?l-oPBws&Y=mB+@%;fq&_}X%fV`8Y(hxR}*zf9%y_= zmlV*qK=;xoFe*y$L$k$9uoQO>dQlXSDwVWRkFap|MJ@-*WUFx(I2j#&d(>F zhu3kGV~TQDd?dbWny?tJ#Vqc=AXc(qoyy-la;jNi_rJdMU%h;A{3}JQmyE5II%~oE z^y+d7@jVe%LY_LBJVD6$4<45&T(F)O9>Tqf1$oeV`c)?}?}Ssj{Y49&|Fg>+6BSIK>mBkGM67pq3p5f53^kocbOJg*MsX-dsS1EMbcCo~y^-lVg} zcFd)E=^5sj130a5>jmx0%LI%upAWq?+KL%<@|2zp<_6xhReOlKb=I<{VTv@Yi#$T` zw*6mgLaq?iW5%&CSf5b!*{_NYfomfA6?G`;`Nl3*wD|${fAt)r*2#n^!$Eh z>CcOTu85MxT?sL0!l$lzV=>qju}_HZE(Wr1mD?%;#NbDc`AXque6Jj1 z9d*7~qiH_Q;#l#>d_L+gYt{a)EfZ!FtU%nJ7uQa(8c!=fF(?yPXs}@D%|wv zFU(>tE?#MDPboZK1Tf2!JqFHT*2Va&dyc97V_#e@=8B~Db)A@eKkCZGJjkFQ_U^0% zrjtU~ZZpiHKaPbA%>GvCAuG%n?&K6_Oj~J@Gbb?fyvJ)?F)v@zxqFacDYsSt@txaL z|2fR~6w%01%p-4@_QiyJ?jt@Kkl|I=)wx@k*9v%d-o%`>ydimXfxXQq##nnXO?_+g zw`1bn!UvPvZVzEzEB3kO#tqpXvolB7}TwX_6%7!4pAIoR||S z%9}(nHwfB#FU8CASV(K4urMWJMNc%dS?rc*6eu2Z6zuoZD|{Usy1%(H!9Fic9I`gxwiIFG)H=e2v1At-x((Px|w znPTBhf3Q6AN5;J}Z!BNpd)h373;{bP+P>c>1HNs@-FZodWh#xN*B{6*Ws)Fo|A`E8 zE{?PzLdjxx-UK=dN~;^W*7}|E6G3{4?nFZ<9pYhgIf@ue}SRTXIy_T zSy=}DcwQZCGhr8TeO~9A(26o4!&2s1=D~ zjZZ5oNDyg7sU6ECL0+g z7zuPVBWK>Ulil24b;B|xHy!Xp)=+;XvKQ&2$ zedo^j_V$wCB3nJU`~!|tY1OB^ha`~fc-!xM8jrW6%b>=W1hy&nANJlNfw1du{+Agf z;D0#CbuFI+X&n;}>ajn`?d;(21|0VW`IE*iB)DbOEO_h(3DQ5<`AK2>@-GW`dge$_ z>Yr#GyBgOGzFu+3lEHm4=&8O889e>z^h*+CSpQIQDgeiiTV{7LcMXo)Gj}u7FaK{Z zo-^+5wjmPSh~Tm7$LkidL6+f)=aJ=q;p>A%WC*iXa#=e_0&lI%^{O2tsA~RLJ%{6G zlFZEF!G0Ytm07u?i3A<p!61e?S*>lb>H;DAQp z`44`0J*oHxb{pFd-YLB!fdpITkAF#z$MboAO#faG3D#@st>Lr7`PJiUWv)kp;;5&# zGm6+Qk?4FR@H8&d2^{5y@S=ifg%)mbJXS3=o6Zg6@-K9GBDrDA{aigggd22EyJTCr zal_;eivMywZivpI4!`2%hA2Ose9B)gSYn4Wua67lg}*@lD=w&i+`IZq02h=@He^uT zxPV7M$!$)D3yv0i-20@C6XMoAV=3(C1lSlZ(%-xY5>F_%Czvh*&wY)%RX=jT3W>z$ zIW`=STknyTQ9qA_#k8M98ORXV8PDd!^mNGsskr zOHRFS8ePnpSi+GwjgIfqGHNKCM#3J-mrI^cqpaBGfW7h4NXx0t_qgT^G7_f5x}Bau zDPOpr6@Q#TapGoUn*6gUW9cT%hpKa@8VyBVK-c`}@uG7flpv|7`%F~Er{-!eHW{;zP|A!LC(XRI#^fIAw#F;zTl~VHuxttTo zbk6&OK3fIt5#09&O__dAaufZ7I`Q`R^z|5;ZQbH-5k7{9?Yzoj3>oX`hYo)lMK4_! zwOIR%B59&A*o>lwLd9eg-chu<%db=>egwVFI{x+ip%LWS_hddzcLe!Q`_x?<9!7UG z95=0xA4bIWslj3xc`sSRe@Ji`>1NqK5Q$-0~xKne#1<4}Y&0Ey!VY2g@&M zYev3iqhK9;aBpR!xcv16``K(H{dr|hNj4ibob^zm1hdg~MI0z!HWDNnQ4|{y*QtY# z*eEJ$b(r-NHu`ryzlX=IU$(Vo3mawS5C`-jbYi`^Z_Mr?)xDzvG44ZXN-$YF@z4+wmsskhXEua__Pz3PlpjJ}q-N76 z&xg?Aqq*`tDr_W|$QAWMosDEp2ApnM!$!+rbSg`*hS0xrUgZ!PaahB9O@@vB{U(rO zBOkHv7k6WQY1NwLUEFN6m$czyPWlkiiVgcAcVGzdt64YfUonI>9s_e5jUjaOZeT&b z%@BHRzcM7s3XSxuTyyCAlhrI-6j<`fVy>MzdzbFfNXWlM&E53 zKr4mKxsdVzI=_{B)z;_%bb2goy5iXYDyY|F4y6pBkc;S&p3eXxu6JX-{pgyhenuRc^KQT?J$i|SZB0n9d&MDF{RX6$ zabY|oxDKgi``jkARH31(R~ozK-y$=O#t(b=U!mk9YI84@V*k&dXROD{hrJ?di&?Be z-|mau6|7>rHAcfuA6e{4$56Iw1M7bP00960OxbxnRNwzNaEuw*$_%AwMV3%mA|-Pq zBuh#mv>=pZNtPlZ3ME9FC`yu~MTl@nqGZiBW8ab`(b$)KU)THhdwlxq`8fC9Ip^GS z&-OZ_wx=a-AEgP;&D&(1Jj}ptFH9xp4l=Ou_79l`SD83+yl&vdi)P%r=L3%ny#jue+i+IGzl`vcAOWJdvdjSJLVA}Di8k{+XcPj@{#$gM94TamBjtOy#ULJg2(F$TzbMtJAjZ z?+a_g?6W`XZdbKp=Gy#DjdQJ7#8K$hw}BRX%s{DiFsTK5H8LVE+qd9-BUhC-xwc^O z0>O-9d~H~u+yU1jRliC=jSL{YLk@qh-~bHmkL_?!Zz!Ogb|YX@DXD*x!hN0W?K z6cm7}PxDN7cVTZWk>%TubYY^^x-WEL%_bRB{*PVw6NOjmv|l%lujlYFNb1H571sri z|LVp$YPb2=4)@^EWtJC}>wECk!+B8`PWED#&406`%6hR#a#o#YTQ5G+EEI8lpciv# zv)EQl_u^gmFOM0<{=ji5Pji;AfQz%V@AE4T;z)yQMpYjMaa_x9W1&++*jib(`C8sD%q{$9 ziL=CS93B_E>(|y1eBLU2XkYmV&JeHn@;fk!A9;k|A?1(akEcwtmQ9c1H)ni4Y`pLX z*OW`&u@qt917n4yCxThnl+TO{tscXQ-?*7Qug7q>wNbUC?l_LE=-zto@;JWg&ab50 zHjZT(Z>S+=6WI8WO4{?Z37oS+9yM>8#QCWi7AGPm@x6Sfoo6d1vAUx{NKVfrRy3p3 zQ>3Qws2}l0Q#gxRd`voF3hOmb3Et+P#y4^s+Meao(DkC?cP z71d-_8d^S|cwb72hK!SIdTdtzzkJux(AVn*g|9Zy(6N&oe&Irpk5Ji=91jiMy{T5! z#6?4~-@GmR$uy*_&rw&$K|>EuEOeU3abO$dJfO|!ZtRfmSwMEyQE5J*ENq>8?l zmo#J$DsgdD2@Sb=H8_8$rlB1%iJOvZX~>6qwzO`|G~Rc@ed)t5Q~2Y`DCu`jQ~3Gj z4!f&{Q`mngtCws(h5Oj${tW6);kI6}0zuX!zLL09w&m?4wr4~a{;-{hboK-;N;6KHy)c0btHpJy77&dwRnQ=a74DXVO7Ge62VYQ9xB|8Jhux4KR@zbtW}C+;p0_}a(Ba7cyKl8ZKDqhuTtGs?R%4jOV~msje}Tt<-17#8aoz_ z(jgmVK{*SW5?VLqS@^cJkG|SE77plt=X?eFX|+sQmCj}sZu}_s&fS8Av+~a6pG{`r z2WB3oyhALU9xu%usyv3*ZwkN1a2Uf``l3tqi^nieOYVbbGh;Ym^(@%dfg^i1|Upwbb z;m1|FtK8V9v5TBE-`7txbg8m6{caWwnFf}0etShj2}Q}3Pae~d!=&d~3ECT8*5(vX;rjmXo1h=hNQ-Y~sqWr^+iLr`Qv`s5j`q(xqk}7;XH?2cOc?0aM$Rkwr z?DauSZ4WBqqcpbEL{QN$xr@&@(y1u;HqWNi0xHtEZQa6OOGOIkF}Kht6`j7(aG;)( zhKx@B;J6FpT3v`dv&V>reti&|YImd|#k8*QZ!k}EX`DM#dltsEQB2St3mTGcc>ZUX z2@Mg$@aPd5!dZSZRd79POM>vQ0n8`!{#+CUQIX&u%_{p|D!O{!dr5aA6;0f2jlNbwMN=yCjEHwslyk5u(D)`5P2T!^YK=A( zx%C8;iM0x#=LwGo%q#>@#Y+KG+vm&BL0{k9o^4A}vhR{qo&8JEetODvp;UgP`th-t zQ6C?gB#(WJm*qq0arsKjeZ0t+7)b6sD6Z8)vUrpmRl@WpmBx)a3=D*A4s)Z2GUt!k z3Ui~}M46rQY}_a*mHY89i5uC(y@pj}lgFML@54T?vo3UFNq1&b5q=v+MT;W(H- z+nw(Sx(l3tm-nEgVCA^yUK)S*+Si>B=6hjsE2WvYw+;{{kJx}B>1hX6)gWiFQ z^CQUfCnIVQ6t$Jgg7s21= zPSIiilqYs>=3)U@v{q220@OOxSv5kG6VEbP4f#j+(y%J0&4OS5UJ%&|*Pn5I zlCT0N*K_vhgBd&z*f)b)_3Xmbz@rM{dAq=M24NBV!Q$V^mYyKTGQRb`;LB~$gF!Q^ z)wdsjbtgowMu3BdrXNOuy*1&lQwVu2_7;K{I8_g3fr(r4=W{^RQvae1+$J5%^_s}v zmVW&y8043HEE{w-o_!fllrvkp`#gBiZl%{1ut3qJ-h;>|z+A;0j10Q8GnA-TJw4HEM}QzJ-FkDV}3jFUK*r<3a~w7_(&tjKB<102_7)i zYv=?gd@If|z>oT_10-&^UermZg0p?63)h3nL|_2ED3@VZ0DBz78x6s8tue6Ta3eo6 z&IL;%Eo>cj4s>YDUmgm!-CF(n1(^0+j^_j99~1oQl?SB7X4jVo63>^E9LNFfgT-2_ zz-UqJ1`!@^)YaQ>bpSlm^gGl8bfo2N2nPcw4|YU=(O;g&TNBT%%NjcczM@F;Zv#{H zAfN$1&rl>)!4Lj-SE+y-%m$7KfW&rL?w@q@VXCtt_-&MD&wem-URKr+e4ZbYWeXm! zUHS3}xO)S~(nL@$C#=K;bgg1NBkHrb9|K!#{G5q;KoCeL?(c0=iy@vjs^9fC2NX%_ zkm(`vBR(+bk}bhC1RnFhbbbJ=_Dc%k=DpItmu#uxLa$1Q}`b} z(xo?Yf(`5fUgJFf(*!XW*x)+;e)4lO(Qd?s16;PrZA~|LlGJbW{h#Nix+lt|z@<&~ zJu+Z@KWZ=m?`WLYyad|b_Y3s~w~mF>xc`&>bmA}1eQ+@z1>f3=3%mj^7s#8Zf)_k) zvNMQ$pf`R3(?o)DTEQJ(i<~(4V7_B;9a%vrST`aMCWL77?F7rDPWGJzlP~LSG6ByC zt>>`^DFL^&u7j49Pv574ejL&|cZhThV|_Fz?B}ZC0nWl_4+DE1rVpEgEB7QN9|bpW zzk-j0m8n(rreJ%g=PBZTyQmhME0JHBWx5~u=IjCcE1=p5v*>4Fzm{-aHuxxYH|Y(y zTAU$X2bNxu_nZay50uv$@pGfb6%X%*fw_-NA|HW;R@YY~fUMGYD&e5#d|>Nq@D*%J zvp|6h<@FI@5`@vgprU&~xh)FSZQ~*d=)|7Cd1|pLZbM%irfA9pqiQC1meE^-RsxRWSoC9&&jR&vmc%IBx|? zVQndWB7Y+82UmP_l(Qxbc^IPy?oo-{tU}~hXEU-Dd>vtQbeivf?ZtNPV^9r9UjsXH z@Wnu{S1h;&vJVG?^h@I$K=B}5QC;vsIseriM8D&GGb0Z2MV{i&28;7b?@NN{+Vmfy z-)_y#Q?r78TqIhXQV8?aOGOil%aFd-oM^28<4Whww>No^p0?YnBf;~(aRZ}8_R2rw zeKB7DCru3J7vQ@Wk$<9z`77njuS=jJ$EMYqAdkL!f)jXc|Bk2=Jpaq@|Iah7+=cX~ zVEH2#-aFt4=w|Z&%u5i3k?0_-9;bdly>AYjUq1-SA1zYp0>dRV-*dqIZnp#SV&L$b zu|!_5@u|*FVt$J((EFYM^Y+8m zi_Ij&_E+Zc;~^3fwLhg!?IEFhpH0tpm5|WL<5%k|-jfiNs?GbFgmNFp2&AQw(Bv9o zMJAyGf|oSD?j@n@JuuSOk1 zcj;jg`g~T|Kl=m;nTda>RXj&Rr-=irC=#m6<#)uHB(xrum()HIa@wV}-F_7(N|@n_ z;#1>93g0JQr5)l#^cwHB~7hu!FBeVo?#veJO@4q~J0PIwBcsouuRMjo z#u>3hd2nH{<=raqInB;R2F(1NAh;XUT0A%;BRS$jg1M8fU)(@dSFV8=u*D7!p9fv| zU`Gyi-ib&`0^`RDMl->5zEpmr9x~GZ?_dz|oDSENf^_+nF(EbZd&vDuYrDzFNPE)_ zc}Pbud}+^zv;}orO&`b;VAWLyrpkLnHiBB+q3bLENqegFJX!_6W2Ij#R0lm>U#lvB zB0?1;bC6Vd@NFFUwRM+yaR(mI3Z{Ogwpx_fdBE#||6O7BZTClA<*EnvASSmK)9Epj|evv~s^jMno8w>`6vu z5)j$@kWtsCw1A=(EeA#QjhmT`8DKmd3Pom#ai76@PKp%pIh4XW->BgoAj)# zlZ*;$@*VnUfJruS< zH@GRN_=D9aFEI-8ydk^!<|YcN=xh0PQHFwghvI8YH&PIv)!H*UFrRKFHu&o($ntw$ zx6m32+B$K}w`MH`sZ=J5`-@T#ug*pf4yaFsn2@EWApEYf8kcWa;yTqv? z?3Dk;7bgV`Z2YV^PotoN_a?W0m!KfCVX}QNyr-uzaneZn@4Uo?g8bAnjwXWq!a2`g z_&`05Ebo+jLP2{EI1Fznq99*Mh#c6skh7C#(hRHvPZdj6bIx-ib60vtK;jZqt&{%X zpa#Tu7Q7kNm9P&Oaq!O2;XxM$=bG&v@t~(?B-@?7^B@_n4DPK%Jcu~1Qx@Sxrhcn# zQ1y7xbH~7x*%Q3TE#3O+XLnvS;bRlO=`t^J`ZgG%<;ja^ZEJ)4t$0z&LfZ7GDlcky zQTEfHlNU*rElF|x#Dk=BH_vrg@t_^)I-XB^xzYW)YRU;)*srBlItH{ZL3P?ZcAc_I zkcdJ?m8~)tQf+;!H78C%v9&Xn9L8j{c7ORYs}fGMuQGJkI~PvW<9O1{LXs015F48= z64J|4kC%n@DP*gk$fP|9g$`Yj@FHDnTQ$y{CH|1A$F?=+Jr%b%!&A?JHq7f=eHzIGIO}V0pUhZK=o+tSTz2P!%?U zNB7<8oADdL!Q4-dFf>LmS)n>}OTuqVY%l6#hH>O%>TPcNFT7#HSK)V&gScf>5_Yx& zc%OA!w?Xtz>>O6Aof+~2AKF=5cPF<8uQ=VcrbDj_6aS)^j z8!_+bUg(jHc-755rG&Ode9E$7NB3+a&ONPUq;;qX`zSdU?9*t%p(9%YKN~dRyIrYo ze}^?;f9q-1*`g-=AzMsAlb?Y(Y>1VPfn`sZs0wK?@YUX`Y_dKBk0vlYT(lXuH?B!* z)|`O_ta`bF;u$!?SScy2i-AvB*w`umVPN~_(`WW%CoN9q9sCT?4A zAx3->&!Rt-iF^zUQE%AwCr$X!;y`Y~AGdkIl-`6Ngx|jBu(1h0 zf@tC_TN7S9KkRA5hW2?c$C!=yy}NaiaAqUEulx5zM@}RDZ{2Lfx@$w^YCkn%?>)f- zKf0hDiTwb%3FDfZqJFAPcri|OYQpP?zg^EX;a=Ujux(IYx!mqI%axmOYpvtn7TZSb zCd%I-AK8HITj~%?tpOj}VZP9}wE^#4JZNvg#PsAl(11^hJ!PmbZNgpV!Z73*SmN$N zq~9zk?RO*ROf&xdIq+kGK?}b1ZD5V_wHD0YeztA9ObZri)f_TNY{q9|z2Y8=H)G4; zZ=A(BOssI6h&Y%yoBzprZ(k;6-=gFcGtR_p&kf^RelszHC-#o{s%9MA@55i@){I3C zFhzZ>oALVlOXDAUHDgDH#c_#u&3H8E*k#(IX1vUo&os`l8SD4oKV~D>jCK6x1w=uj z)z1kwWBx;*an*Y!u8v)I`SbxMK1Q8$*|?L5$5d2y9=ycFoSxe*e05~v%I7E9QlOs* z?=_xV>CV8fqa>D?AqMWuB>q5RV84|c)S25E*z+uLa>Bq{^XGF;l{H~L4|A9zo3I4$ zy~39t8nMdj!+|B84S2gA5qUS@n9cM02k+P8hd#^huJ)?O_d>;zoE_@%*~JY+J$8$D zy6mWNJ+?d%5gKD(k0(og>c0ln;~>4!QEo;(c0BDI{92>|4^VjWqW9P1Ldu>HS%*6O ze*gdg|Nlgpc|4Tg`~Mm4!AK}1sgOj`qD5)BPg=B)w28_R6)jq2X%SMWEQK~oh9>G6j!)qVp-}T=#CWY99xz?1!(sR^)>0!q@(xsaz;Co_Ttsp z*66KNoYMkfF-$F5V=LG_tTL_?ZU;|`j#k4R9nct?)azr}3D?Ktv=5qf!QR%KkHT}i zL1e4`e`aOfuqgalhG0t%tX_BRBU#c5WPMka_FNulz9`;D*XO~3?()88ZahG;I`*qv zdGPeVg)f_M{^rz@AW<0}47WQKqUK(>zfNGDlyWcV9V>qOd1()fCHqX37<9v_{KUZ- zR$Xu{slo+}JK@PCWxu+e9boJ9k>0xukJB;Dt2eh5Tx-Gk^2rtuJ74^DwQ@7OVKH6= zvl=0)+rrfDKm+V?j=$UUxDIG;#gT@U)o|%}o}t7V4*Y&qP@(F?f>P7d(mwH(PuUInJX>uV}s53T+Wa!$#v6FP25 z%A19Ty!ree8BObPo=Q$5U)^fn>f-Z_H0jK3b|Ui0lT{DigxD65E4)9doDDA}$B8di zobU=#=kEvIE0IicAWB6xPmV*bzq@qpjj$S0R?%E4K%t)GXxC{jE@&Xf?w~VeYE7hQ z;kKxoUd`lgsrPsEHn)=PRp(sx?{6o6P0rlmmeonR>21CxJk?E>%Lwl4RpF73N_Asj zDD{zId0*dJ7x$5UukFLKZ~P&}yF*U9t?MT{%x=7nr45jV=~@Be#RH^8N@&W?+(Ghs z?W#>f{X^upIcf)qMI+=)j@+qryGBWyjkQLPOvcEcg~W0{hjG&Wf%ZI`#}g!Pwn$0u z_$1kOF1TRllE35*_n6aFvjotd=M^RNFah*2HL(Bt0zu?4)Y16HPZ0ePV>{0q7ew1k zN5;$?X(-P}!61i6L*`+T*|eiV=#P33?{19{qGDB(B(DggpI2t>v1k)U-(#x2X&xew ztG83<#5jT4M0W7e!fvR++})Vo04Slizh- z49Tu%(|fYT(6f<u&C)izA~&T0yBo;%K~6R*u`tKsr%NH2bm{i0--d`OYT{WW4w4 zvbzop#Ibk3_+kqKxjZ@%?$RlS!c(1`e!Gbwk8wfC83JNRzUR1n`zcYRb^M6c>TD6T zXkhhV`eG3zkIf#DL`Od~Z_HvHrz7brHGh9-&{4*VM=cq@TkeI)KyH4DscC%C6N7_Wzz3z z2xPrOBFc(|^Br%s#Qi4F?fhf!Zx<41Q$}m{m0SYxr(=!hN8HQ=;8 z^@C6=F1Pne_Iov4@7~5aJ6%c%6t>U#+9I4^VUx$%gYyNWW+;}F5vX(FcI_tIkL;19 z@7_@adh`iCZpP_%nnh_mlR(#Q`!r@35UBWj?U3+K0?8zLS>4C&T{wEsRHlkRr>jZ1 za6FH@I}+l9ED(;4vt6duQ?v5r_& zg#9vbAmg3r-uy8x92Fal9a?`3G>ju{%G|)p5Hiuap%(;%`Z}MQ-#j1X?MPqo0fYSYh!Y zp)L#C?_hqA3$7P;_={R3_N#+H?upD_1e%UZxIZ7dh7*HLpkCd1e}3b34p{3IF2?1C zM1EZu$Ntf?Y%Wp3^Of1mTXhuMBjKS$br+uZX?~c)^PXN0*dM3&bY2w8CJ=vlMgPF# zoiJ42UPmAu@2!^2JOXW9e!0o5jX=qTDl*6Fak<3vE&jNFmXzYt%h)dcep$QAarv9e zX3eg^<%Pq3Jn9XXg>|5~R&NBQc%GZf|M=(yjvLG?{^)Ev5PZmc^U4ff-}+CoSAtrIdotVGbR z@r9Q0VF&c{H_Xi;QQ?%{r5jTrh^Jd*V}Pz-HxKKgELw;0kaUm<;QGXwQ+@omXJ z%Rnc?w=!OZGf>IXnyKRz40M1=jUO6hpgA@Le;h^`Xpp%~^D~YQTHI`wTdB;p? z9T9QFi#m4Q3+G=~u#3rH3+0g4>^ZrS4;(OF>Jdu6Kwb{l5jDY;jx=T>I&K ze6J``%u{+3{<(7*kDNC;`#yq^)NE3$J z@rGUFThzVt0)q_OP5_9cp=WQqRV%Ytpg7)a z4~_IT@=~!^SxsFF`D>nK%f^u=60d5Xhcg?=J3HIUK((H{Rb2i4X;d}o)O99N<|m6} zX!3VhB`J?a_J=PnC5Hn;@J{_nrq~?5`|{y8(tF95=cRrrBwnTYDuxfqG&wEAIr|=@ zHf3d=D*=#Sl0_MZ{D7FzrK7A9C15IBuNLvE64c$-ODwJoJn$hb*~4e?fSSE ztgX%U6}5S=&)kM~`w(lAHRHGk6eTA{2O!;z1>mQJ7H518MordCx+4 zuys&UWiGA&S3s!0=Ue1^sMfg`HkiA$?S9?^E_1(M*}JS8_{UmVQ771b?6~?#wga|w zd@wo6YlX6l79z#Zo1sF(&;IU?MktDxI%4fz5AuO_YtrQFfS9xF>`I9mXj^Gve&-e! z_D}W9U#ms|(;$o8lE(xSixaZ%zW@KUX5(1{uQVns@udzI461`pto+P{ zep*+=L6d4A^OGza{HkFER>!KxtHIiG{tw9@F6{mnm|^7m+ocySb6}1p-$E2*6zsUU zW^FKK7OYe(y?R{L3y)MxpidJ79&r-cg(=D9hY082J}x@78EBtSv;o`PMO z(G)m!m)*-LqkwZj#Ch{G3QkRLMEw2L>lRI&1AR6+tH(+y==VK%P4y`S3q53`&BQ5i z%v`hMPB{zaSovJBo2Y_7?_ z0@m^(6ozh8K;%3tW9jG$*r(SnuH0Gy=XhC5=Pa#+?Q7CKSkEir=JbRsVLI;at%8O9 zf>=3M!GrVsl~o1vT*H&B44JS&!q}6{VZz6!7oy{(S)lTky=kTg3u0{JCPTYf&{gA; zE4-EsMUMq=WMjifY_a3K1zV3^N54qVN=5T&n)=;;q$^-=| z!!b+ONO2&YGgu}g$bo~$4-cJ?=D=l>4=NEt958;9o;JdvAlsraIL?QHNFBb?q##eu zT`_Pa1qSE0yqA!rK(3})C2KYXV=0y~%j?*XSa&;HNQeU3UCG5}f7syiR&$$TCmRN( zM{<6N`olI&c#f~i#YUc zwhI%orumTxYnCgD{-m)XO5*-oH*C*x>FlD0@7Rt{*Z)B_9N6}dnGySu1C+3QFj>oi zVZ54q?YU5wHhk&lWiGtk6PWongbRHkT1v?axRB9uIJA<+1^F8*vTXf0z_KzJyP?5> zMpGIHBDFfri%lUmU@eUt&EFPSi7=I{!p9hNxx$Hne9*FBXFVyevfmiey zkGI5k!)IczgW!iw5aWZGbURd(US6BDtOcfZ$=XJ^nn5dlqFo1nyYzkX6DW`u-_|rR zSP4CgQq`)1%b?*Gdt*d=F$}C)DAi_=4@_?9-z!?*;H=luiMch&;6A12C%^eVC_CM} z!3>KgEdwmbT>2MMugHI?kI8rP*8_v>4*`W_;cp2;c6%xLw@_(ILSrTQJT1F9@idzZ zKN$jIo?Oz?@^I$FzBqM5w*JAG$?TPuk-<=6F}+eu+lqxh`! zPIA({I^jZTH@QEmwCUsw9_ihi8#iZLADJEKCS>OFhn&{c0sUlHweoj?p9AEZ@D3B* z+ClQWe~1A$c8L7i$oWFQHB1WV7CxP$G(s|7>AkP$A0fw`4+bzAN6D9u<8n$X$H)fd zhp+Q8u|9Z|e5l5Ef-K!Ad+GPpNz!7;;3>N^Q)GQg3NPc(U(!2x)2rZx0tl-c;{nWx zeePZr$;$*$OIzQKmsx`7jZ8dO+<=CR$Mo`@fre_orT6vh5<>3&nwB)C5OO(u=2N!0 zFf!ZOu{o$*7@6>e+)=Fm?O%2HW1W<#h)FgC>p-om>6&UHh%aOP<3*5UWuVRceWHkM zaouRakSOXeEU+5BC5FbzIIkbHh@nO2B;F3GFwkbno?`04|Mc2>22x!HGxG8oNMoz( z8~rW@N|eRQYnC{g-bd2nXnOsQG0>vy_7fSk3=~-(m^PZnKsB+Q`we4od+E}0vX>c1 z{nMP%>zWL-)9Hp3ElCWmkt#SnQ$q|L-*Dqha*!y(qtq%G7D4k{*VUVwil8ooH~k76 zI!bu#S52IyBevrX9$K+i1me_fA2@doa~XeG;Z!@I?EHc= z1bSSYonPQWp#6Rq=3WXW&@FPUd3p@yr2H;T7p&t?#SGq#z})8WUu)!WH}TKT!vvbG zIrGeI++SH##{%{Qfqq_V8_2-+Z8h$5)gQnd8I^EgYcqkOBv0(G#r&lfef?ex=9R9I z6;i_a1ez0eVQnYojjG11N?ptq8cN-+cQALXo@eto0P{e|*V+}QF-JLSDK8wr<&N=z z9COB1jQyf%1lspW?(~~X0_BCbciCVLDX~1*YK+^d{Qc7B5aubDI_rc6%onMhZ#8IK zJYRuBmm4t$3CwRP5Xa@eNTRc|@%)}^_K@1R9r36M?jXRYvzeIje zw{g8TYEFqb<~IqS7C}vHho=W=CudkkMVSc&cMbMuMnL~NIyk_34N><2~0>v#`b{_*t)zfsI>-zfQw z_1`fkHasd^1O#G)_Xzo?6KGl&U^|_rrh;s0gc!Uv16eIL}y99fFL7p8}0ox=9; ze`75Ygva-E3Log$j{z_1={K<*wub&`+llS4I5CoY>pk`Z|JoDVV>>rw4;_!Y)MZ55 zIF~^3F1c-KcpP`7{8zle_Wanj+wv-IH-{&^YB9D$MY(>RB=!qmO}OK4CO#$4U=B_$ zNZk^L{nNjBk+cHlQtw5Q+vVDEe@7LICpxg-UW5P&Jnyh!vC>~Msej$Njb)SM1O7E%zy$eN z==xe`pK&rO^hJThy|I7ylQT!jDD0*VhhZ{(Z$q4y*$`=bo-o{devn*yyFN(OZ-AU$ zM{WINiQ0W5UFm-EWsHYMG6ly-7z#>J|- zTdm|`m5B#otD4F00^Vx-a~sHMd7x28o}HDU{D{FJ|8Y$fxrNAfqDz#Mej9$Xo}Moz z|LLqBq9 zGHm$)b@3t)f0iBp#kmv?pR&K1snbab!0m@i8e-GzSs%c>-U(4Hg>_oy@#m=g&r6jyjgUG-2+%GsERWG9|!UP zM?bm#ejX_GbR4!>gZ0qlso^H8J{Uhn;~ClY!Sd#tiNh*=fTPp$rT`x3IVE4trFwyX zt@Kj22R2TL3kzy@L8`?T(^cFK2+dqg#j19I_0q|^A31ICTBtx;+rJgkbigY7YYS*7 zA3eMRnn7&dD|3y4CWvb;Hdv|H1P4+-e%Q3D5%$-G-gG(N0Q|7{r?Vb>lWwnGb)p{J zx-E0JxYfaLt!s;Em9;ROFo(gKSqu2oFJ$bffvxJjjkdnkkTa-`J<5d&b=BvU8@b?d z-ZX1@4hN2eoYgAS!#wbz^;~cP1+w${bsPLCXwc1*ouf}dojboE1yj4E=N{=}!`plO zhX%|O_!QRt$%gJf@sgd7*bv0}lv(|l4HAd);P+=X)XMU2BH6I$-u%2sU_;3rm(^#p z*kIP*xI(Lg4aWsNUB*PQzPFq^FP+T>-C)N`p%z@v=+RSq%()B??MG^JD5zGYy9I5d zU^*V|qCjfVUHy4@T=Z!{NWsR3yIog!QeeL4gtjl{9e&vJ^`l^Qq))@)DhfP*SAG3j zgX)bUZZz8}ryO%<&*tM-xD-@`WaJBDev!7I-Af}e&&vv_zCh9xOvn3~6j<@ik9mhRg? zO$vfe_phIU{cvv{Z`A588$y>q@Gknn0^03Is#`y^!0=Vli}y=dz^7`P4J`09cb)Zm zBMZW!g5w8wu%P8=&0)!BOgPi~FlDJX6L`^idv$R7a2EezfeE7XuZi8SVS>ob+w#hr zSP*K!UFzkA+fU045K&>lh4q>e6YrRShFpe!++hBXYnZUio`1v6gx!Oo7J*?*kgz`| z{(CPA77dAo$(ypFFO2PQaR&u5(--+1aQ~6&C^5zX{;_vwDHon9I_?qaay{C`0p$HV)bcL{6AcG~Qa)2)TRawMorKr@%2Fl5h=Ps)dg>=nHaxQ%H#zcx z1@*TMFF!QJgun;^f}~p4~po>1{99NceDJ zyA1#3vF0CFY1M@Y3FN{N z`MC9!*`%tC((mQ9zsQo$my}e+%gD-(|Nf(Wsw4--o{VtC*d$i_L0v2^>D?)Bay+Dt ze0u1D&ezlia=USuQPb`wGF2i%$!VgQZ2a-;OR!WM`J(G}w4g@^>FD;DCSKP?YB)Ri z3bK31bqmfXa?bF`lo1($M$m*Sr840U(ZP)Xo$EMXFqt8 zhGOp9UK8n~A+NN^vtR6lP~*iL?zvS$sM(@m8S|L%zjv2TVKi!J_166?<`@10&m@5k z59hbUreU4qahjQVSOjf8Il$FpilF1MWpd1;n5)Dse`S9aMT4(?*%^t6p>Vaan}Nn+ zs5NG0+T8bI$bMyomFKt^N)G6Z3e;izdk?w6K>PYWzmrSE+}Cbp>rlo(Yur@iR$>10 z@-!>Yz&h@m0SA&W2Ts4U$cQ6*1EZr2g5v0&@WbU7i?M!FD$Ws$V<78ivy*?iF_5y^ zGD>j?1N|QW00960ELnFTR__@*39{G*&jzGJgNpAEGBG9JjO8uQ71WH=gNf&R2kl*p72=(C&14Bu}8-B~(V&`&4OLD4}jeHMX& zX4+&?HGyE%Yw;Mqf5)ceK?=T3FW;yfRYRZ&D_I#9ww`8$(r;`}3i}1$t{{+OM|PeTbgG>SiCt2^>jcvnD zxl$)Q&oP0v#aeirt8|@Xd<+7WK!EWlJnxJ{SC$!m?&<`8@f9|Klm@RyQ?cFMcK!=@ zBY{p8_8668Kh~QUuKhAhppFv3M4thS^GkH75962|vh1%l9&fdZ-zz~p&*O&>+XVO%-kTUHUsD*Un~DkqTLF5mI$VgmggrwI<=IBu^bk1xmZ8C*+x zN5RkWJBc2+fpMBr6y__$as9M=x=8`!zUE4+{_$D@ZCrl&{sru3sCahQrY-`}zFwT} zYa&pm=TWu99s<=^FbTI_0&&;LpOnXVdT&^I=2Sg_o+q(p0sk(3MD*@HZ2d;($ivuA zkr;m)JB)*76|<-bk5{{TLX8`b?{w(blfBq~gSf6mWjMYU^`%`}tpqAew-=foA<#lS zW;g#hfxbSGR( z^mpvdc5;q}E@y^yWeN+Tumj6JSkVNL-~IE#l7DE(B6jw&<4+ng6jiV1e?UX=CbQ9r zTWP3`z9=cLg^CQ7FUv`JQ<3(O3j@;9RJ5;)89yB=fL6G+ZndRhJG!gISC1drC0&dX zwx*yRPhFday$SSgKP^n{7atNl&^9)1&W9*jr`hl1`4IhLWYkD4FIvFIz4ew2FEWe{ zatr6>MFJl*6DYAfsBE=0@lcls`PE9?QY+*}R>CH#soLC#a^7Q2eK{B6zuVnkuEB+@ zpPL*Vxc85|*naYqk@Xz;LhO4Dx4~bs@?r3+`tl;pdGW}l`>)dSZHLY$|_M-mB+ zh8O;j551G`DPNx?KW@33Anho-ioy~jf0zlO-`QtJeRatBE@9Nwque$rsRfcBBi0X~tD{5_;6@%5dVVkc?3 z%-i|oa2x4!b#VFE`c^U_`Lo>Wz-IDw?G=NW%}r!j>NQi3vU>7tS)r7@2%8j;ma1h%80k*h?A8j8 za}08CZ|MMSgIS52#$6yf@X|3(p$GhgBE9tDdSQ5T{EESa{h%52&U`sJ0IhlAS$As( zK&pzh?X&S9B*t%(BkBhsrb}DlpY#y84_AHJK@PzirvPR zWOT!PT~O_U2d-XX+a)@nc)IMzt+%ak>%g(w(|OIHl|YddN^63K=PMKAiW|zy7I-ADmFCizNGs&qYjz{ z{olJDsfYIu|Av{w)PwjF>ZL#8^&lwpBl*>VI#}PwKB)eO4PFK|gq{u?zUsW!$yZ_l zUqZlcA7Tho=+rxy3`wK_g2^Q#-Xy?S-V8Z=8TgGQuCTJ|qd1{rxga?aGW~DYW z;e;IDjVEha(Dm3k@Ms_l>a>|_F79B1(r4keaCbHwOTD4EWfL3BseDE(@5S7U--zcac0Bonx91t}`#G65&&63I7AsB;tcRmATdH>w&}r!%4VeT}g( zj)Pdb>CzS<7OXPV6Sk9N!I#ddDor~UcqA^@Ftz}P<~KDw6$>f#q$ zRyDD})7X@~#D@ht!=pAaG+7{AU?! z{jh)m7rCyw@cpF2K-twGYhOC7J>=x3s7nXanBvK&>U6N0FMxFDuHlM$t4W9Ly-x?d zbQrL`D(7%d2@|aO&5cV1*buYcNOSF*I_O*4_wb5WJ(wzQEwpg2hn%AU($DPbp~`0U zqrBNV@L3l7^ge#>TfJ#kzZx4t+LJ3(NhVOTOB0XO(qV`A63V&dba=x5LNDW6E$BAy zPw8!_g$B;!H|g*ojI!YQJ_g7N-}W?gV?c>sb!8om33ujSWP)6Ya6#r5CP?Z?W`=*o z>w3iPqQpKH_&KllU7W>&>FT6I-LKft*{CpM7gGn*R)as6_SeBu;S-B2H`IfA!;SGX z{td9{a!AYdBTe9M+$rIk(+ox~Cl;)ZZiTMteJj`fXoq*yB}tE)J0Y;>+MYMuJrJaC zw7{6Z4_MC)MQoG%;pv(cl_AhEGjCO94#EgcUB5VT z06vdA|5s$$56l4W3v$d}FgMxJuxeQklv+yPJomd3mY(*!adEZ{w%&9pIiuGC!KDsn z-D!~R4q7A58st?tb}oww$}%i{rZ0$D1c45_8~hCe+Bsr&!1Om zageUAu+t6hlN;jJ)SW$^ME0yRvp7u6B?+(ZuPn=clJjY5UrPELIUi_FsUS;26}+C5 z)sUwg))(Ep%OZ_xN(Q&RY9w_|3=4Vaw~)S<5B%JDzm1$+t)M!vq=S@ki)gFK=p-FU zTX0V9ChfR>Sme<9NRtnO4zErRklVJ5ByTVpA}wq<6=0Y=wa4w@+>;SvDmxU-pW!!+sryS%#B zXolR%vvKAAjk6@L(lZiketBk#s)hAP2RFAurec%O%nUUOH~5h#Jh40nqK1-TYu;uuIlT7GE{k2+Bh zOUnOg=s617k6FM1Lkcpsv=EEcprG3=H?nz@D5#rWtN(8q1vzjE1eJm^R;XXrn87-P zbtE(b>$AVsJI~p2bmOK!R~}>hmaU#KmB;$v($_=#Ze#rrh`ac;PXtPQ?o&^Ez&eD} zr{7{7Dc0iWfc5pp-G9Rso)f4|SM>9nrvxfEc)Fn#+nu9vs>qi>Zfw@KQT)3;MXM;z zAM4q6%7Ik@1p20@`SNrqfySQREy|C;x_u(B-am#wxk(qw&*6Eztumr&@cJIavNs*u zdq0;e+`u|{UDeyFQS8sY#8yD~zVon#Q#Q6fhKI_>uzq&orwH#$CD2x%*}U8o?0>7+ z<1l=EHo^XWHjanC;zUKq7XqOrr9rM~SWjzM?hj7F{xT^8Cw>}(BMHQj9sM|eedYo$SG*$-b*KBr?I8rx;i;}peo3HT*KIMy#kw&2 zrtAT1vnmRl5#B#(Tbl!?G2TWG234+N+(JIdWGY~r@3~y}JH~nUjY#D!80Qj^t-com z38WD|&F_cT;lc)qU)!;DcA|$X;(0wjhw5C%aj&Z=kqy8)F;(@~m2Wui%jY)}k=Q=} zs1U>V1Mjl|a_g#00@3y45?*3_7c==y#p7|_ELpuR3&$hRDN8sH7CF6r(2xBK#`1I_ zw!V+PX1$CeQ00z`%a`E&@8ljVZHV#TRn7>s$tKW*9NwrHmpM)u!t0@Ss{QvG>_`5O zj#d`d??r{Cj4G^iJ$_y8TU;6a1Nze)OHrppc73=&eF`Knvr8usUGL;=2*w3}& zVa0M-pUPx>-*AJ1;(f3K;}ldb7Ug~_jUOf4<<7bGNC4gSkKSLghl*~UJQEoEm5OSO z`V_NdXlPZzqL-RBH1t5|v9R$o8hSB#eVf*2TvvlXX16uckeri_s%0MyWtR_Ev|uaq zWPSUhrd{D6Tg` zUPtJ6@cP%iqCOnO^+X;MTU$QFo1*47z|V)m%#TT>`12z5EejP^iSnWW{|K%l*LV;+ zO6XBkGdGG`m%J!hmm5j14gV$*$%UpCb*Crra-p*?E0uG8%#nk>Ru9yx{*v!PIYf1q zTq)t-A_1MNqQnvDMsOz3dvNLAq z!tCG)QbQ>E^q<0Ua!zx%?VtKFQbqcsQWxJCIgf|NC`rkjAjVurNZjSH3&SL*Y#g;7 zCMQx%Jlo=i$ah1`T{{_rWWd_9Qstip$X#a0darXoc{O7?>EK*1IZv}6^pG_t)!9np zUF1OGlT!1h4)XQHi%`*-Hqw}r$ZD-*`-o)a)y8J>x8|piqYX{u<62LZf{X?-)8mtR z_%w@j+2<#7kX}pv7UCSpRFF|3$}@X3^T;T%MuR^#-thF2$PwL!T%amn`B!|X1n8XC z^(x@=Swr`br&X|Ko2z$kV-1X{sO&y^mkAqoc*bvkQ4gn*9(vVPHNnkA)W(^RR`~HU z#a`2_131;idRI5(mMmCt?rtxX2E=<_^Y4dUU5gjyXbi%q>J+ILSa;6Lwr4{yPosv1 zAV;G3$!)P=uq!OP#yd9zOUDlmBvOaLYV$rK_sq&zY`}jSm1PNyvERl4Vb*{u*EufuaLyLyC>>k>wH0|1GCSyOQ}~H zKzr(7n!Z*OXc^sG_Ee+=7(-)+Odqzwr_6;lFV42Xo=6F)3iozM=-$6yj@1FZEh@`% z*`2_6J+Nmuv2-qd))t=Mu^mu8w)o7expuhn>}JR{#dh%8`TA^}P8*ba_?@h_Z3WYa z)$b}^w?MMhmt9;f&EQd9o0oU8`9B?--UO`Xgreo+jj-+QL92rq4G?T59iP9r0dUad zj&1dzz~x;Tb-xa>dG}mwPG-Zkz`vPQuURnKs<^qwp9z{LYk%-qGNE`j;%enKCU8_i zTp0t7Q5ITv(-`m}qwZAfcRDx>#wtm7(80#ylKZ`AIta`YbUI{x@um!k)8VzKleOd~ zIp@^g${abNUn^e19?>apJFt{tld zqs`{8?a_rAlTV2eqkbzdQ(%f%`R=8rfq zc47z;HZf3Xn3?tKVI+`VQJ9g%!hAijO8^VoE!C$zQa~(U+;!!PFL3&M)uwaHzCx(y zaS1blZ?OH8@7P7LpPj^GOt5<|GF=3I8o>_y4yBM$Q29t9wj9hmZkg)ZQ~(z7 zXJoP~VObYz>2JYm`0s$e2C(QncQ~*Xj*R6NoWi=gU+C+WR~wm-fW{(qFR_5ngmWUv z1`moAvsAhc7GHXJ{77~kT*_&*E)c4RwD*}>D#rEj8B+G%`CbnqAFBIYj2a-*{lL}X zp$5>|E2!ou*$D2ZbDzhVG{RV&n(-QgMyNW>VNQ)O&;OP-g5Dz9p^D-LU}(jBat>&K zieCMen=%bh@TH|CwyqwA<+$>dt+C~7kDc}4{9vHu71qHzw{7@Z?CKyde|&JdlnpQR zeXcCK#)kR6y`BxzvTJb)vS4lI1&fGwCOjVF9F#GkX-kC^q0fXj-RtwW{$)UbCFP9z zJG}4bi97?8oYi%otYg6L!rr{dKNuI;Uq`eG=x{W+taVEe&d2!%Mu&}s<+w7_0kcev zk(W4cBxQ6Z%II(`h5v+$Gz0d2K9_5Hhyj0<-Tvf0V}MC~^P0(93^@DTFC{UC0p7Gw z8(w<`Y-4@Eos9wUP3hA4m+6pyY4qQRwRAWaBU!CMqr?1pc3~~N9_i9FIbQq!^S)ZJ z?%XDrx*IH#c;}nZWZ#Qd7W(1$IV)eM)|8D6QlGUI!~`kBfU))PbaM zmoDpg9f)E2Gw_iOb%zql@(;10FY>E=e>Dr{b>RaR{7C#BG&aeE4;t!9j=U^L%MTY- z<7a{5R&LOI&V&W_3Qx!0F`@Oy#%5{`6KHt%7}A*#e{(_M$w4OE&*kM6kYs_RHSsXs zmIXImRaBiTS@5P)e??6<3l<5cMLQO-0E^n6&+=Jd(Nf6kr@@AmRiXh7hz*?6Eqft0 z4B8#F47gnf-^XRmeZJL$dC@a(l-&pso#L5`U7F#vL3Bl%RV(DK-FSRQU^|TR8awhd zcS0DaOm6N0w}ur5xQ2Q`Tp~HMX0#vV?BBFTc;G%0s{Af>#|S(~N3Jc8MuCHd_R}%Y z@;!u^!T5jYGk?ax)fW?$$#K{*9kfVbY#f4?sT5BOP5gIG**gyM=iSr!o5$f!bf82D z{+%PkY)Z!ApI`UyZpU$0*<*kDvdTDcWc#D>F)-Bcki6?Z28y#y&OH)i5co_LGs;mo zxiD)`V)ZCYu3oeSoT8V$2W5+9o^ukb#3iA!7j+8AG~XNq62s| z@pkg&*q>F*JEFY(=POo;*ra|qLq8e>d@>$KIcC2;KP+> z<-!BxL+KmSclHhb_Z?vE5ZRs@(-z7YBE>OH?~5KL9Y4AcJa-r&k8?e}@Y`UN?BEG3 z2o@P5|30=%dRQ_>e)$w6(hxRIj&nZ$9GxIt_HH;DtT#!v%hc>!<@1MZul(a-TscMl zr?Y3s)yM45EqyvmCL}i9%XRxpR$FrZn<1(2%0GSE5?K7&$B-ApvWio4`lRsQDL9_otPG06s1?QH`$R7X`D6rxnhbBr5bSv zCDyHp|90&Vq994_2GtjN6y%w3dr7A?KYA)^*)O|L0F^6AIpu^1pnFGL=hPNak@qY0 zoF;!NlJ2rL)L~K4_?FaNs=PEbbF;#CSeu4Me%q%fN7B$d&#tB+#k}{6)(z6o?wyPf ziN%7bB#cj`Q%Vrs;2Z$S3!zavFGG_+3k-qVZ{8aiIEG3r7v4HZW| zRN*qCp+`1S7Bql??u z4J1`l5VKEv{Iw+o4GeH+D)Lj1B4_yv3AEw(HHZCJug-sG!@ANV6&EsB0-e0L?ET~m z0@cPovc84&x=TV=?PaVJz5CO`C-Vs;73_FJubDtR?u*u+7$H!~J!K^e0Sfvb00030 z|4f;8JlF5{|B>elFUl$@(GrqSqLMtXqC$iQ4Utsu(m>i-Nhy`K6zwQ2E6VC5l#EK& zYuS76mE?DxzVF-b^Zx68JFn-puXCO2Jg%2SV0m?wGK)+&_oF0zCX0l`J`Ni}N(4=J zX`jj>eEpek7KpQm&~=|-!%m8PUTAP6zJek|?}BtIhaw;QoYQP`DRRI6R=9i$MIJ~6 z->`p9k>Byt=gxXc5qHUuW|0RJSN3ZgDe`rm%<{QC6q(b?H#Z%m2wfMd)jmp* zZA}T>%@Qo~dPCjm)gmn7IpKkXRX0UUBV_f41r$;L?R85Q+m)867*@h|x9E#|rl5Uw zlf{o->|e8fM&sUMimWP*K4OgJn{$7y%dewI?>b7*gZ9*_wiV*p6mju6v^VEFMZ!N@ zP?NBHbX?+G6>R5n|B0E(k`i_LyqQH++2^u(=e!mG^vU|>W+MN=pUz(NRM&G z^kt;`@sdL+NdLFq!f8lB_w`%7$m*usaZ4X@a=894)84tJ)8o^Tt52Mk5yA4lj|7PwXzL6vQrAHncWJ>Kq-ytei|xp?D&xcZ zkwsy)J)4jflhQ}+kgHqe$pU2mk3zo{NELmxOb4dD3*!~mA?>#Zx>_K4n=hVZ%6s}7 zEcHUJwU4=S0x73s-4KMdUH9(QHRP%ZvWuT19Yi{yiV*b z^W7-5;SQOtFw68j?;?77AW|S{oVT zF_L18oFDVm)B^e2^nvPjWJiv+q60F;i5fhFY&ZV8<`Qz7luD#Ga^WUj%_yWg|C90y z3yh=c}2D1mr0ZH zo@hH`w<8-zZA1S#{6$$r2^8f?uv?0#VW#_;6HZ z8pe&&oxF&H=vUQ3zr6v^#af}ibMe0XbPOZO3>JB^@~CH*J&SD2+W1={kVSMKzE*r2 z%p#TDoAnl6V3Fm1t9(Y>Sw!y>#f@`dk)mSdO9v0L$Y`@ih3kD5863_!@GXZ$_Ptc^ zxoRv%w06CfdYLaqZcWN47Pb*5zed9S|Ky1i|7%)1MC>JqWZ}S6{~8Ih{=vzmt;TG! zHukB<3tu*oHhFbZuZT_T#fYGIo+Rlp`mk)jy(HP49or}6EJ^nGS2<)@N)lI{CvBmI zk|aw0rzuBQlDxW8v2WpQNs={H`>^!@n+UtQa<>ATgj*}Wy5++r+KUyNV^*@syotCo zRT3n7g@oQgCkgT>YrU$|H*vC+Sr7?v(k3$+6QM3fuKbGdHFsqZ+J0Lsv|{`Y__^Ya zJNi|7zFTOvC^3JO9{GKoD5-qVV6CJ-j`%8I1UM%`Y!`g52oMn=FQ(nh8hI{EI{u!B z-g;7)WG!uO{4iCRL=D1h&38fsgV@1~4npMdc{k^>!BN_0>OlQssZqK=1Ow{u2rWqU zSRXp@hrTKNC`f5wnC>f`r}d%YH?4Yx6=wKjh~6oGH|bN|AZ^MVsBZ(bMTe5p={^1Q zlXr^;Kdbi93u`&2&g=Hliz_a)Z?W&8=kcaB7&v#+i$}OuC)#$=#|&y8PBHDI?`#m+ zDW}~|xAMvlnFqJf&I-Jx`65m9its@B(C_thWVlYh9cl_510zVEm(eWu=>}b-UZV?gOgg&wdDJ`AQzFAK3T00 zJeKslT1q&uw~3u7Yh4CgT+=G{uBig2mi4oH<7*&re?nl|&pK%9T4`t$&;X@R-IudV z8zJP*AM3yEP0&$iyp%1|0ts3A#y7oNVDday-SH-^@HJ(&OTx)E82b2OW5oP+@ZQ3U zN)oh#zfp=;OGXD|_zw$9TXups3vZnGPH4FlkQlzU69VQR8-5+v0pHy*0g~zf=6J{` zwZoAW-nrp#TVWc#aq0rS7I0Bd6@6~p1dIBTSM7LR56>=0y*lx<7J}@z@Fz;wfZ2X2 z!GU+dB+hK;o{9-f-T;I;FY)-CJ6G>Z;p$7Z3(3-4D9F3HpS_C*XBS>ko9x1e^qj}55_|aYqgT%5u8#nw zj0GwI%=!%CQ}xO~-{hr+du8J(I+?klfZ@Qo9k3VU3m~DteqWF$Agsdu8<(l zhdJA}uamgIhq1UYQ2;G}V`Y>@1b|sotinS+Nae9tB_osEXQ)bs@}c_L_-B`__;9_4 zNq~9qQj49Uaf%08J$9G@@L*oX2PM<}T+q(iw7X&w&bxledx-%KFk$GU3l}<{e_6Zu zA{Xl3J+BStaG@gIdKv*POx7IT>X^g@`f8xc#|K=v6gV(#b1)Y+oR&TK zwTKH7)CUqkpr&{MxzZ6bKz~F+1k1`E_kh;waEVp5A+?A&80;6V4`gIp>8%GCdMdV=BT4z zES+s}`Ya#Dw$qRgK4TXP4@xIyw`$=!A1T}ue*Ogy5?)vz4z%I{UvXL0oFzOkmkXHp z$c6{0O(DwF(|PdNB41@M#RJPFj1u9(@0HmnNAY**UCR@GH*?{|k_o9>+qsb3cTZ*F zEiQyA^qIHEaN*~gDIUUmx!|)je*0teTkmlssa7zIIsk z-m&nkNGG_ZMT$|oJ0ZjL>_nriPAHS;cWS8b1lI%6RN6o%ysL8vdd2R7f~J#;6^c3l zLqNR0VOwI!WQjMOaOgtUJ^O@C7}IChI^j$~U4GTnPViHo?_gKe4s&LxRjqu`2DYg= zyvP%+ptRSx;ZSKa1S&EIuMsY|Y!|FPTLLbYpCw&b4*SO*G`L_pcF`8W z%6E3}mVW;Us4`@2Eps5^No@b|#B@mUyEDZgCk}dpo~!J0KTXd+^<1R=WE_0}!?De$ zk96y^k6LX-U+CDf|Cm*)Pk zYL6;9Q^NB3(XbkNDS&Lfw!0ONH_+#ot_YiE+(bX#cky`p@M!V zN}k8xOt)Q+d3uk1w!;ub^j;V&k;Qy#livQhGpxi&h4qy?hq}c`$~~jq`rhK?0PDky zZT;e8EROD$AbF07_Y=QJkl@A#N3STb3AbQLQO8a;S>*Sg_&;G2i?&tolndF!vCr>h zb}yTFd96HF&XOc~s?F5HdN$D$`2CR1V3RWOOF>K0*rZZxPOkY2HnIMZ68p%VP3n*7 z418OF<(Nc+D?v1$FQ3z}OM<9XmYT_BiWC0tCVIb$IC@=}@g|MSur>^+w0Jk;L;6yEu$zob_bHzuGisouEXIT7`* z@439&=@bdrQ<^sE8%4DLCaRm|QN()rugXNsyWe(dPwpy19duF6CbOC%udj9AbjAEz zcYMa0%p%O&nRE&3-7b7^!}BxNV=lI2w0m{m875I=>hO&#Vks1{S(1`q`2}@w<9+sr zuM`=3UVBfG&lej@OQKQdr|fXgPov192jbO6snq|?_ajB5gg?dp^MfM9RbG97PZ5_+ z-L^2~*?o$}v+61Gv)Hax2ko}hEBV1Vp1sSx?rPvTv+7PzPf#Byiroob+CdSEu|PwS z`{RfHVRfPYKA=3UwGHRJMrqCKI*N3yI-Pp09rMzHhNqWNM~D?{EvQGjD(pROhUGWp zzmD+hMP2OF5Sfp^^UvGL82zP4{B0&N!ge2jsIfwB+&E&q5hsafnQze#QI)*P#&NC2WuJii+i!9p#+}iXOq{^)apz`; z&B6M~m~DA{{hw~Uzw1@*+$xH=w{ku2qF+Cnk|}mfK#}2`v%M3!s9%5CPT0ff)Ng;D zx?y_~8Gdt^_b?3%qB)4~M<~H;<;b#UOhq1ky z@;~P+()5xFtajM@sOmS!@#d?r(^Y5u4m&ULx$+q_6Ae@%J~_ zBrRL?&(tP1xq7*{ezcEGf`sL)9yPMb$WY>rs0otfZ@aR-nyMs;*JypxC@e{ixvkpi z&qE#eXG;0&bT%0ZoWJ~D5SuXWzJRdFQI$!f$7>~s?LX}^t4>Q0$5I{6_+fD}FY=f5 zl5OH-Pr!SznUBQCTiNs_ABtGS@}lagDRWpvEbhTp@1y9q^s|bO-$jYtnXOVPYNBLq zqxQvk|8XSCGtuwoZxP~ScX#d^UlGD#(gOt%GM2wY3llq2jQnQ8q{z4A&tQuX@i;1! zx!qfc>^u|QSRyGz)Hd<0I;}?OCR5A|?f%kMDWQ9k?MG;ZgTbC*?tf@2*~(sR$6>m* zx6dno;cxo!#5V#-sUiB(67(F&L3)o~;4=mG0R6tOt`|EWe=Z+%Bp__2CAs9spBdw(tcFeYY&f*E_wjjaj}*~Ih+Kc0Y5`4OOZC(+$)}e}tLxq``AP@R6v88(PUkYu$8AZp zg=#^rM#wAr$o9eXp`tU8eBx|o@3(FvO)Z-)@eD;PY{fMlJF$I82)^o zXa1mt2fI$%FW;e30TF|P0j;T3Fsf>N+<&A7#@;uK>VX=2plXD(73VRtX@j9cBXBli3y!OiY} z^+h-2*Lx`DIdwx>oXMYzk}fdazbdT8p$pD6*H^oxbi&xd9PEH*Bh9}Z7uq5AQ0lUU zC9M!#pPi#~wiz5YFD_S}(g>I|>sYGQ!3k5WiFsDZl#0oBG%F#2kr^feu#;?EaQzqO zUtLuK9oKgHnaUS~6nT22$*B;knP<;~zd(Dsxw*7SA*@snn2;P$1VVKk<+d)xAlh(Q zqiuW%jL9YQ5?J^xdkd$q1mZjU614S8;k`@q+gATlSi8-kMvq$x8^3Bs{Bw!}-mwGK zm-;#X>Mt&YElH|)tic10Y~Xl!FmytnhtY4x=RLV8zpNP@M--UoIev zkNepAmqYBJm2(7=xh;3QmcushqnjQnltT!yXyuic!PtB2;WGGjm{GE2P-ClEC6Oio z>yt-jYiSA~?hNzb&Ij-4nM<^5co34u{K3Hk&kuH|IjF-nHz;09E9b)J&*t~&NG^!1 z5gBiAlncSEP6aa?F7!J@s--J&0mWCcPdW#D^%iWuP|N|t+fqWC1RN-D7~Jdeg#-Rs zRe90%9BBP4{r!0`2c%}Fy(o+3z{OQk%PyO9Kz*{y4&|?SQ={O=R8ylEmgUuvg=FWXv4*Z1Hz@i4!FOwcm@XoO0^Fz(Lz1Uq_L>;?s(39 zt2xYvK1-biAx#3<_CqFkOTPftjR}b|sGiQeL<&G(^4+p$iUMeE8M;>&$A?8}nVTb> z_>jCia4>K_A1;P%_$Gup$1pl}?M62~?5m1nhY6#u%+4Gcyy_VG$I9GfUoG5UsakH`HVy<% zHhmVkodcJ7BbuL%bHH}&A)Nykb~6E<0|`^*1~&gLg$K>o!m3yt7~9TS99Y*;J@R3s z6m$ehy1y=!f=j}XZ}Ig~_~-5_jYK@x|MwnI3SMIgcqzD+djtj7mI7H9s(bHtDO|er z^sszFDFhi$-<&x zGWdJz` z71RtQwu0Z88RUF$8z{20l7d#X!~X*S0RR6inRz@`&lksS_u+Z8Clw_TX%mUGFq0M) zB_T?rjglgYNIO!B?0r)tp@=9dR7c6a@6Tf2caJ4&_znI3n%CTW=giERGiN^UxgTG+ zlq}Zhg_EoQoV&1^3w-@D`Zm|OFdp+#j-Jg0-XENAR~GbvsFt_0%)CCxTpMoTM4mJ5 z^vx1;;=+wTeMJsmdLgPrv~ond2VO<;-hZRh4Y|ys{K?c#aM2Xke7~myR{EdTY%FR6 zyM>9Hzi70;hVHTxmlYa8tLdK7$apQh?!A2OVF3#^zp8os{6i`1iY@yj>6Z`GC@brl zUIu)g>zG^a^&PB(JDvvBM}V~3@{BhSh`dzK^0%M(be`o8H~<#jfq z+zl~qzrQ!5Yxzwr-;eI@EQvJOJb=s(bXwE#AY!*<47$ktL7vw?1}&ZVgECX3&m@ixp-VZ7 zYML8{5e`4#_q}-pbzZ5pd^s|TybKN$4lWo+dQK66ON9R-$(z0rJB$CK5v6a(?ths; zxfNqlp)r%lNb zKf#A{o=9Ds-OPvWm^U-I*ZJ`=5qsT19sw*O;AP$GB!JJDYA*Y@lEPkfdviqFDeM^I z(&O`thLgm1U)*CXh&wM6$BPSL(}Ac0%b!Ace5Hz!>KZz>uT|VJjQ;x3$*^N+W}fP)gxlUQ5)z6j69{#bm)y7KL-d#82rGyUD?A$z1aN zzxbx`rmcxe+T9fP;|!^F5PPm4xqlLSD9pT9BfhJS!t<4jTf_1wT={C__X#pig9{!P zog*lmZ_8?X5klc{zcU}dl5!jE><0%@+FGgYQYG(~IiK2O5J&x6#~2E8M9-;Yy`iuT zW8EVC1PZqg=9M6i(ls>ML46;jRVc#{3)#m!wDdYmoliPx|DDkojzN zE_oFbZ+~X z4`IX~?PT?aJ*0K@N6b{LrbQB}wlr*tAzUDWDo!3UH$q>6OAD$*{ zB7V!=_dU`!nZljff5WUl5JRU*k#a zEh|>*6eG{=mBLocj->F#HIm)8N&nY(?zUu;{^f0T3?1H6I5F*{uQIU{osh1q{)xic zDiT)lDP*3PcvK{RQTT#2*EO5?>&+ACiU#sNwEsi1Kk45JEp1FA?XylP+;$};&rwa! ztHkdI%7oSP-%~wsKH+o3~Uw8vG5;d;FGr^vmXzWdiTvJMmGbm(6l?-T*<%( zJ}19e5XZoK&KjkQJ2LR^JasQ!bq1E3t<2cpLdPbT70OPXqvOldiH;+LXRB&u+inuV zEHy`?x7P%*4c0P@%co%-lhO5syJ&c6)~DPrKZt)-|J-d-qwrG>nFvz=YhM;Qc5$Bo zmS|YPj#x#=OuSC!}*1R~!x;XoY zFfW!BpZl2^!-M&fH(GqY$b)zP8lI$W;K8}`GLygNPa#F8%c1LZrx40suHwy_L?lbf zT+^6D^?_rKdfpT0&e?5OoofD~8?MwazXUmdPTzO+y*iGLXl9mY^^BoBxd7wi2ggw8 zhSnn|{6~?j?#7YLts^L9Z|+?Q%Mn!K<)+utGK_4dH^lK_r1^m+H~Y^J3T#~D9_%-S zG^alkA3~)I1Fqx${va8nWd(mb22rbS-)&8iLDc!K+|Y2(0J6RGc1f#sKl(noO5NdJ zAChl&jvs!_MMhJt3MXrN(MI=u2UDK)pqoD1t)!H?Q3tNji~i7w>{XKwI2d-IyyC`T zm5DaAz2WKXHy*9XG$o-vZgUH|amcB5gx!RQ7rzATZ$x5?R9Upk^(f*CT0DDcE&31` zA!OskL2fau9IeSpG>0AS_25StDsL<22@fqs*C>wr>XdxMs}Q_%*Hji-+WcQ&T2C7K z-rSKXJNg~*8&A(D0cDzNM)m%Ejc9XAe3DpWaP{qao2T%#&HL zwIcn}<~xOuP8uEmn%RzjNd2Dngf{!@;>=g)PbO*+B1=mM)=9Q!Q|)X zW@wFWI^)3G1~ccCatG*doAyi>RM>dmNKWns<2e1r+)X_odHaHHNK+3m@9*#HqjSN| z)gj6K0~da{Fy?F&>Vw!l!bP9O`e0?&PP)>DK6vEwbRTDg3-V-n4L)<>R@(0SBFmM^4v%7mk?M*z z*mSJw_SxiSFdgbVdfTUW_~zje+XM&T^r8yug^_h3Wp0jY7xTsEwIyg^{A90$y+k?8APRbal6bI4e_ z8gAwZ3T*SOhP6ByO6S|E;jSQUp1NNRsLr2YkG0o8?0|LPL~=DGTK9aA7_Ne;F3m?- zaU9U_f38-IF#Kg1xM~P2)9^2Y!@7Ugy_{PP&y+Ze#>^^UXm5N!4;0&bneg<@n+Kug zOb{;5Pp=(f!jl)SYTaBW$S&O~e1pw|-;6KLt7KRpI=te)IWJjo-XyFU&t(Js@*6Af z1U6jlR92HCeokK41qBB=@Jpn*WW<#NLGR`f>Ba&5nSkfO`1?(I$8U2$Y4O(`6^}Xa zl-VQkYMc!V&d0qQc*}-uv3u>q&#}R}{My@yRqX%UV?*97@pBXAY&aabgD5LDc*a-= zWv*vK;*uTO<1H*Wlo0*2-e_Ec;wMFBtC=Br@2p{8 zlVQ$++zUF{TjN~c-x@aDuj}hJxzC0j3U|1nyE))3Tf-Ziz=0QOiR?7fD)>BS z&XBBI6|Ch|q%ZF0z#kVGiNh)!c*GOw(07Xs)7dDN#KqO!KeXOyvA{p2u&=m*2^IBi zYpYF|Ah`PVNn^x>maE6Kt<;$i<9h6T>t-e_IQYta&nzaKH_qSII9>@e`BRw*tj_8c zy#`Du_!VqFa*+u}%^J-obD3a0i#Ii%?3=#+tFdx2Y}kBPN>s6n4S_Aw0l|Sf^S;xk z+^c~7_K@Jm;A-gp_9Wj^zXo>e}bBzSj5_!-tg+%b9a zmjiX6aboKYi-dY`wEKGW2D1UUsXV_P_%uQC_cw~iHCrIrWtVjyw-pRXwn@uqhgT2S zDv$4VLgaRx9Tvjfu(z0h#eM%CcsJC3JukHvT8`~s_u~{7W|pCV3qjsHd!+KXAga6Y zrg{z+4g^KrI6J_FVS6px)E+LZ(de)rD(6DNwynFaJmA7*UGw|eAA8|k!_l3y2D`y@ zfB%Wv2VF4XDxv7q(*frUT!J1)wSoQ<)7gi`THsRb^Hz7~M)-3+YW09u9c<{j@Bm~v za7<}amWfLRlpZ`i&uD8Y2sPhamhW8%(ULSG39`Uie)99`eW@@_ZRb_vL2_o|_h7Tz z)}2AiVv(4em-`y;R5Y{vLRm=q-W8knXGO^0xl8`=k#ZDb+;%`9iiPGKd-KrYPBn_r zdQwzaR)^-UtLpa_X+&=$y;4_9Hle(mwjz>`T2NP2!qUi2eNqK_V(9` zZWOAeIw5+6+# z<&_Si!iz+4bN--96N4ejQ$vU^WW`>gxg#j*^x6rRff3{%^fo-Hd=wGy`U|#?q2fH> zi;Pu&QG~{h1sioHP$xOf=HH$~`S#>QawD8+U1WN52M>O*@**{BcZ1o5O-&^LVP+GyjFUF%YZ{{-a7EdD&ou3S>v6632=pzPR^~}Di0^kK^Xk|8bW$8D|)EYpR{-a?2sSPJwV{eSxdDsUL-dnl%4D z@+aK6>1fbYAmOG<4^P+-4lpvLEET^}SS)g76qoRfUuw&;9fY3*6RuJm!mlPCqOUIf zA^uIbW~?J+_Eb}EO&^7QjD0U_HBs0h#q_xp;V%_Qva<<~JyWDEz92e3rQEJ$JcGjK z?q^J@NEzxX@L0Z(e8=n7Tu5~Lo&9U|^6H5letTud4hnB@z8RxM__8TDw#SI@>&(6( z{A#z(rQC?<{iNDZxuRAIuW<-z3?t74_YClevIsAoH9WpIhr;gP52xA_j+OAZbflO` z;o7iCC)aceE8NS_eob_-l+CIlGr~o>gQ=Njgli@&=gi9^9Jsy7{3|bz`h~D<%Lzw3 z{bnb(i}>}q$?(xtEfiJ_F1+JJxZ~5!EaTWo;%Ad_J||upF81B@E_5~x3#gTSJ|#l9 z<=LOpa)LB$JOd^)Y&-I1A)Q9Uo>CVHic&aI`c6pwj+J876fRp|)bo^ZTTRxE ze!(>2k2{H$m4qt|S2nLMC*%DYlj0afp1(U_e4>%8M*}tg-38*e@qn!+qNFb6K48N~ zN|TypvE?-sF4`L#bcB@4Oy_w&ulWBx0_i6!--chkmcq*=evMqHBI_J>O<$S#{g!oU z$OKtmNwXOCbe$xnbC*f`-*IWr21!4~CJQX~lu@`<%>4Y0VhXRnvxZ-g)K#X3|C9J7 ztR=c>dVCy~p#&MX72~YE=ywWFpAIjk$Nz5bs@`uDZhRFg0>uD43P1wAAg~k*G^%yy)OAQSwD8nxlPM@NxSNR zEQ-Vr^N!G!W)fd=`zy77jFR~a7q7GtpyBi@b>+5X{bo3rtm`yZaOTml>W`s3AHtEr zvpjtaHEH;|W`^Ye(6FT?>-fpDg807Z0)^zig82Lgb&0W9Ask?DDZj;tj%Th{n&>#Z zy6uem9R_xtKGtd&_@k?&piCD7$JgCT<>wd1mK+7fz16~a&(O{QN=X=-DtvA6R2Rls zroEHbb%e3SzD4QL+QN87zNiZ0fSrjyAIb^i)Nc9$4<$(|tj|au`^-Zw~j3D+7OX zD0?<DBj7keJf@N5I5kDXLj~ufedK7^ zH{<+rgG&_dp%ou5ZV|wKmLZ;*Rs#R>WDP&wGiUym$W8os#eyHhTip3@jnUyHe(k(? z1?z-zp)M~L;N5h!E0qTuxLw)euEK*CuP>**X-}ay?z5t=OHZP$n#-3PN>3oqtF*nQ zqJL3V51$NGF^1}X%z2^IFp7>voRq2=8$pYv1DHLGEEkt*4<`?yuwyLsrkFoybirEH zZ?6W?kvZlI&7KXQPiqXX2YU3Q(+AJ#GF|)7ju75I=6+oC?BJbKqjtUM&dVT`#)NJ( zWfHQrv$PWhXh;UC_P3*%dmX9`jVSvF)H7NTPZoXQUZp1VY1WnZ9>xvmdECU=$6j@a zh~coK&#KXC_vE?Ql8yN8ZFTxvQ-Mw`iECObT8aYGf44NU3y^EU^ud^oG@Q*cZ{Pim zX8a|QjFKk$vme#JMl<(fkKN(leOnxyvYIBNpDY>MRGC}ucBMiPf<6rWr8FC)lFFG>W3R|9ZC%zhP zhmppi+||*YK-0{QwtL(SX4hr1?IwDlC097ktDqM)1U@Mky}$*vAOk{*Tu>NvFSg6& z0(*+*VmZ-8iN6NFyVY^wNF{q*-=7PycViZ;Kg5OZZL^2xcmLBve>-4(f9C_HSsOsl)z*it&G1TWWA!SxMo6-qj<9;@FPzoDzr79? z<@~CwB;3=eqp$M*9S2qlG-dr7BI)5tKa~TuFswzZ-1DT*U<3JX?H}o#%-OmEjJMFGN3);SA$m@P* z!{5Kdb%|OWXqOZGL|5RzP{Qe8OfqOqlJVOFUHxjQKV~29}j@zeao)k4+_b+6CEs$g70P zF{#iEt(D+g``S0Wf(eZm3)j;Rvq4$NE+vrkmrAidI-78SuDmNsj_Cg_JmT|K##X`f zaeVz*6*NA{lfJD`1vaKHMl3ZsP^zPvlBmrF9-n(PM0MPRe(8Du5-&m;-`quWjjsTV3OXj#nrzGl-%cbjclxe zukkGJj_tMJcQEN!%86R25TA~O8sI8)2aQKp!>xBATNb^m0_NTwtbD>#M`wPVu%T`) zno_&Yg37AmDccP!h+lGzATD?DtFxLC? zVxS5e20k?VcV1$H+0|(hV8hw#T^8{oY%u?EKScEo3l0=KR7>z;!L+gtPq(naPgFiSZYdl7={PoU-n@<8}gS=Y^;3EhD#Y2+}HkP!(+?&y4p2txDu79Al%J{mHdwOqZMqh zuX`~+oW#%Jru`+#zHB(}uul<_cKLo4wF~YLj%0q8`?Qk{D!$gAlN8y|8s+GjMf$bA zEibl7f(?J(OX%= z1>Fn3^VH||LE5=RD*Vg(AaZB%jyqHzOgtFmRQ}|``dQwkm3Cb43tbygQrHWl!%G*> z5$J)&$EOYz$##JQIWCuUv_rhIv19gB3wUf2KkGBU3F>>^SKEiy!;Bu7QwK@Ey#=K_ zs$eQETvJbt32cES0jRbVZt17p(s^G9GH9e_y~?vM{)RAzwROR*U*I241w*-` z{@>d9;YgFnB-3?CXu6eNa~jI`;ZaVs%05S($aGP{oA*L=!Q;nLgcDH zsE#vefffv*i7@Mu&2q!2XwR;UF#QoU7$LPNE07r%J!9(4%^iqVd`3CCEM6VFe_*+%vr$)ye z=;E!v;dE@GDE&=Mh=Kdo@MI|MW8m%jdOp{#6CKlOW;+ z?EfE0bf<-}^q=6I3q&6+K4Z2#bE7c+E#23Db&fDT82s^hY%2q+=ML2MkoMfgpJbvn z70me== z>?-?Erdghbt@4kW_D@k*`_1N{Orn=b5)pVzbn21Y-+$dpA-c9C(qJ%>=ubS{oEJc0 zx8tSX8VPs7zVo?Bqbmi7vL+%eg2+ba`Zl1nUIh z7LIGnwkM=Ma~=^MY7$wV-AwrAUj2!*S%k}GfSG)!m2JD=0O?2Iy+MjBvA^@w;fUg< z|8q3yC)HlzbO_9X{X3wTT;jO+D0?};tS#@@9QKAw}Ma)Ok+klp(^ zITSv*?|5{00fh(lebFcf3g0zzSa2?v!j)${RknVmFf;f5wdHvfUe>X?Rx^vjj)AGd z%f3+f>aMiV9TgO=mI(L4Yzp&({+*@u6dqd;x3!i-;ZP|jvD2*-o@`KeG3=tSYG(ht zoxKz`Kkz8bzn{Va?4E`t0~8Ma?#BOYgu(}^M|7DK4I3$1^n?h}aIj$4=;R*?U;A(a znT=EUy!1d}-zbH#@q-PINdFhIzb@D|Q23FS_tC;8@_p0%8y3Vq&dv{(C8gA{b2~RS zljj!8;tHxL{E9!|g~>Mx{}ep=~&ceaxH z2lW>VmR3@Dbg5AL?jj1$-CX(oc?pF@_PhMT@m&nWfa~X5Hv+6eb_{BZZr@M>9<-Ic7E3t$4bvtZ$ z!!U*a()wx(1!=e(q-mCuXVBquHdOzDeVBjQ4RmG(D4BXV>dCa_o zfvrA|*klbdaNU7kx~zN93pvY6C`-gbAK`^~@$4o5~j zV=-{0W$f+nHw;WkeF^ikW8kz7`L#dz8F(^aXV9VxbZldyKCziCf|o7d+-EB*f~Bhs zNB?ma#z_qtcr>4e-Aa0{>PXS>qJf*&YlA49Tdm+Avz)?Pqc7BL&Je;$(X{FfmO}WI z%pSc#h7e{cxo=(nP7t#Ot(S^y5X3RN|K8d6QUFUCIjs(m7r?)I(+!QH`Ek@$Ju!7L ze!OV)<$rIT=EEk-b3lai7ZrJh8F=MPq02|+Yw(gLQTJ_HYD)eDLj3dPcfb6DTH7yP ziT3@CBz7#mx_-|%s@{~9XTE9-6)Kr!ZRY(##%pxHEUOtoCMzDeIKCT3wm}6FS`j~y zmEHYUjgN*;H)Lbt&F4Jin6=>RwO{?{;n1>IvRS?8v}30BlDKa4M)7PY zGoT9{H_A}F9ny(jntSC#+nHcfFhB038W%3AooWah zYJ{RS<)0S)YJrke&A2Tt?a<+S#OTTUPRMw+R(*2m4=5apKmTQW4-C#JFllS-1vP=e zjEmWQpnRp_oY<{?IGo|{o_BWu3~yAF*Ypg)F^kfF+WriH_k%1qbwwV`d#av2<;nvO z3kxr+H#}Hz|8MBUOdgzbkQR$i=YeMYEXg)+9;9h#*=AlC0H>qv4o2(y;L(TI89P39 zLySuPBB97GSS93UcmT)gmTCkNWh*0s>H*s#WK+9NhNUbQ5IW_4Ul7;;(&uWWhf|(Gd zGUZcnnFZE59+m}09B|xyKrgMB3(w=43=O3l;K)Y#PZ}bPkTAVEN*lp$i1uK7Hu1~* zNYLLijnHyQft@tB5pqVS$VpcZa$B8rolkI~ux?YJT{s&wX9mcGI=K+{J(abPJ7=4Z zhII|-sK*|PYN!VJU-YO2hiYIK)9^F9vlfDuo%((La~-6W{CNL>#RR>Kr+Y)6vS9o8 zFe{v&4Q#q{_G@uAn2jhzikGwCo}P`go;V9SMP!PSzcGPiF%NkMCOCOpTfV8PgQPuL zdbJ64a7U|uxuIDdyiAwOaamsnxJhb#Ema5Qif2{|)Yd}&eupN>>{{?uOt3uhxE8o( z5zlYltOZMTvw8EJYhl*D0w_kAfa zojb|-{euMyclmoz^V!fow|*ykIUBxlUV2&XW5bm^jd0B~Y$$l;+UN6z4Pz>1fi-<> zFm$bES&4Fh|7zxWNf{1IxArP<;NO|V$ARegHbxF+9N4&~`q-(B9Iy`ebWz&E0d|3@S)W_Hv7qjD7UYYjU8;*v({5}_6QqvpQ~SuT+4x*0=n7PN%{0!%?d9a4$PAM zy*kaD1MmILBss?ryJ(B5Lo5fD9HWBbjuX50-L|uAIgm$W#tTvx+V0%)p22~r{5>nI z=^S7M>>3;-C4D@~DY=^siz=!l-Q+ot9lPz{+ob)W-`BBGG7j+z&wTria-j7)2qzrj zfc^)$z2_V_V7b^;pO#MS#w!r%!U0D5o^pRv4(#9k&)00SA02X(M}EF!fwHTuUqTlX zBpf+Y_wF&Fi|Zeg;md?}WyS8h^<-Er3<+8Kht{y_RM%usq#)Zol92(#B zaDZ=1h_on)lgy%(31!5teUi~SS@NB}RL|%YD_DTkif@fcvf%KL*WruJEV!&Wtu)vm zdVfDl%!9lq7aHiJUJthxXrxx$YXm;^E$#(Bnqfwl2)BWEMuuIIQ3uQ~XA5Y%euu|z zJGU*j{sEVTOXDvn^gy1-w1Vh^;LwanpN@Xma^1gqker)Y6UKLC5_sTgdaY*xlLza* z#te!M@PKnh$Rl~{Al%KL-0@Op5ZVLj&kxBAf?(cGct2C544z{ zeXY_4U}gD;&(@v&usfl&z@VfTf{PM^x2W_$Z29c8_y=9^+Rc3Lp|B1ROmgcCt!afJ zY=3)|RWo?c%04Nxr5>(XCk2I&c`$z?>h;j329kSs9X&m}60%-3BnWta195M$0}(E{ z;IuAJesJgmkkh)|K;to#tAv=kQIRNjjmYAr#uW5o(}tnQsIxqk+I_YeZF^wkYx8d_+N@RM!?&j${o9pk zaVWYItvf?9^O_&1K+1nnSYi)aDctKaG`}CoN_I?H9^%6A=5hWE8Qf0N4JmQ4}(LOn)0g z+0)b6J&r5}ws1}g{z1-dS5wC3PoNEc7UzEMn?zFMBRX!0Q%LFi9?Sh7|DrtP_M>ti zA70)(=S@v7A3nh2&S^W#kCkJTWD2|ZvHY$%@xHbKxFcm=#_m=DJkgfr;$SO?RqeMM ztgIKr_6HB^cOMbL;U8KTGMa?2*P{|I3ug-NO)OxaA-eRo-}X%Jw=_ICH;8|?u`qr) z7k>DcezqA>AibnN<2tnlYJ9iQ7+dM05n1MjiZE?Iex zf!`(trfmGkz_NM5o)b(4zP>>(U3H3qC-`2dot!6%t8Om5xJ6DBN3V9+qq9&HOI&>Y zbc>`Y-rqE?M<+V*nV-4Z=^_UHFYhvNp7uNE#<>i2zH9?4tBX zM-jYX{iV-}X~HBZW`Qc_--}PvIW9<5z-W2!C8Y|63%2=<1s-Nl!_=E;OyM zDwe_v4Rd*OlPKI5;ppc{-v6GPEF?p8xLk1udhwU^k6pNiH=Bl8x{gX7GBhmo*P{65 zEE=Xc@kT=k_w4nm=*=L0=qW!pKmLQlvm1KF!-#HI^Rm7tN;vMeXj$_BlfnwmGFOxl zUi00xZf^(vq6qhX-cB`YX;lkOw1qo+`xPAZgdXV^aVXk{2;gvhR zb6tW+d9U`2MkV30X>~fc)EOt}Bw#SMTEF91_p9hts7Wka%`$$4!Y4JG*baJg-8=n>?KkSropqXL`UC7VFT> zWDriA(S3xU)jY3tza#NZT|qWJ@!!Db5a%`FVJoIGYZkFv)+pn?pR~_<9qo0G*cY(# z5xh&<7kdz;MB=fwwDaTw!mID?u+bCGbNtW3L74&k+WzkfO^ zNgS%PjJv-Pd(TD-=J1jCwSI0pm)S_+Kk{ON;iUd_`}&$kB>ukXQi}M`|K?qSh82z- zwsn|K!$G&LYWk&VxM?Ej8f`5NC-n7&w=bn()yPP(n}jP%`ipb56=}Hj)F*+;O*Cv8 zyFFv>0UFkpXQfSL(J)hTQw~>$>>GWr3v;ITdpdWdDog}FJv1-sr5YVC=(k+(BZiJ= zwr39=)0A#)me*lm7h@}XfhP>?U1Ob)*v!B{vcl@+=#3K8CM-hH<ON3L{&gN>w=SCsCRpr)1_EI5CW-+}!N)S)u)OvYA?DKB-jfz_WxF~5vtYwTJ zPphc&xA^h;v?aVROZo9%A!!AdL_Qp2=yFWZln)zNMcQF<4(lIr9oTzs3cVcIEL7+) ziPX*{Bh%v(s9Q*NuG*(RD8^Czg8(_tD}1&kA6fPr=`7B^5vDkfMs@~pIoe~$bXrgu zjv}}Iu1o0$ej(Wt3R!9vBZ%JYIB2_U7@59`z4fJO2!+ne{Fure{ErhkJT%({QY2Om zApgZK+zr9KXz*uK08^WOg+)&$s-bC8C z?3Qant6sHOm~Y`Ak>w$(gR^VVb%SY-D^T&dwP%aB7NM(w1Cz5j*{Hd$VSDYeWOOca z*0>YR5AA5r49l>80si}fyP)6%LqW3U$NzLz4_tSus6g4hut@vfBaMna z*i)5T(QQ8f>t{P%+`NMade0mhP&f~+`o;V3XA!;=;UAwzxG(M<%i7a~2jlFbvwIB) zA1cg~sNwZNhSEf{cXuz0N3Pn`Sl0tD+H1Gb?7Lwa8++=zz+`Ff{I|3&h<6exT>qyN z*2(a_NgM2d3s6ZiQwP8rtxL}e+aZP%+qN;F4Z@7lb22Sk;h5H%fwp5UV0}dLRsPXt zkeylJP2lmc+F@f-1I*n&w&~NMdYJ9HE+j{Z3zB<(td3}4gQxVGwTXO$51G-_F$)&h z-?^Qf7|R4BLuuQQ9ZYcE!^p^bQ3r(T$;n>}Z8=3T zjmhP9VUuWa>dxbVyJ<*MvzXsE6wgjNHF*|JX6b8G*{ zU9~VIe=%QHsSe_Z%xsFOgA$Pw;@X%AyW_6wYbG%NcTd2Ag3mPIA=bgXBO<5ecvEy~%>R}E9Y#RHM@5TiSt?GFS&$)0g@rKv?$6WAA zlOs}#3$wXW4r)bQn8|A=x!|NT^-#;33u5xq3Xu!NZ%>OAS#hDj*o$uL!-cWDfA)WN z;zH&5X)@x%s?F1Ha$)b;TW;}>xG+mj{Z-ysE^MpNabKvRsz2;nRxJDV)xRjA7+n4#8|t@2I?y_=*iIy-L9)0c<#Ekp#U@NPnOBkG7ZC zP$AYTs6NF4c|$X$8`dmn@$NQ{8D_%crQMo*ubD6(71XB$GQn#GbeP~y=qk0G3FXn} z)-^w2L6BU*3%JjQlq*@LUpzU`F)f1tWk8z0;<(VEW4ihL=6XmJ{C<5+Up;Jc`D~!+ zSr7HKZ;QHo>*0af`qU4y^-yMVa*sPe~_V&d6ev{;j5LW3IF~*Y?a=q#({$((+ZRW z^^qxDB~>n@#I{GUbhuzyU^GkhDHq;debn{Sj0^g!cfT85$c3jR==UlkF3j8$&f>!I z0#~crLmY^Fa?Vc6h67WN;>^S=$vU8=hiuT}!sue9ZT(>+o~AN?HQSm%z(D7Q_MKKZ zr6$K;AJ+jdCdCsExOc&pMd7rI`??{z#!8pFu@}}_-pUzy)d&CfOmH2bA2zr zz<;`)2Sep#A!PDE!DYj&+(I7Ap6|8#X(JCx4>NZDSu*(F{f)vPxW7H*4%Zg$B zOoIFZd%HdrD48X}dRvx_;qMUmr_7xoVk|QMXUUV5MW4`5e!sF8M)@d|ISu@!=)Zkf zjaml#js$$JLk4TRe%&cxqo6ZhB5kn^Xj88KA&_Z7eTp64Nu#YOI9?QOUDAP+1k3ik zU-TXMhps;=klKX`cZ6&TO7BKL(l5vBF6~3_rmv}N2T+Q!<;{apJk;``S$ z<|lagJRf$Q)9I-^%7=HZBwBKYoWf3sZ;B6wSR)3Y_Ebi9#Z*Trl)?unCP*$FVPpv6k_MM?~O z-YnCa@?zjyG2%x|fq`GWc5w9>WZ?dDYZ$|HQT)M^d%06q6z_>65Y03vOr3khNrW#O+Vq8kF36A!acd` zKb(G)PvPP-UBjO;DNJ4Um)V<0VR}J!j2+>$ElpSZ52aH0>%ya*>S+`XFl{WX{6yiG zJN9ZkB;1pvMlu7@^-ZoKH@^|RFWK%S&mT6u_Y#T+?-9pw47GL?{NKg^7F z)wL8+m_UMDEGg$#=(2c(2jxy}s`pJGTq0e&JetIZ_Bq-jfyAR>&HFl265j{Y*K@?r zKj(Zpl%)Pp)24QHw9`BoEtF_^xX zBz7-d^CBl9;pzewU75tyY5K=c3WcX-`xD~#Z|itHQ8M30PtSfre@Ei5rf=3~QlI&q zLHO1^beDb^;kB9T<_ZcMIZrC`lX$PKSUt3YaJ5Paozu=EJUo3-OyVwn$*AttcM9{2 zH8nmG4htQ9bB|7Vuz8;EB?H27ZW_~>i^69U?*4vH`0U_=&&)Z5zsjWM92O`2X3{XJ zs|i|$DiW?czeQ?3joA4|-rzz2u^)L^qmM_pKEo*OU?-Wclw9k(n;A5G_Fb0A{$(^= zW6Rsnr%t%-PrS&~eHxxQXZeJ&i*j_|gY&{TvqognP)-C_3Ve9ym?eV6A6zjUC;ON$ z?&hK&C3MVu_UKNWJOh_)on>~}nt=(7N;!lx@HHQSHToYJI5{=!XFlPlng0eg3_N8+ zh?j7cQRV~33~5n3eXIR?jwoJQo7g1LL-la@n1aMhXptjH_ zems5sa&r?u{uDY}+$Mq#$I0by>lWd|nqkL^+t&U?Ftk)d&v*)nX_gj;7)~O1_&_Od z-2{?3&73!+^#?5#tz70|{~OsVYEoak#?k$dG2@c+V@UN_*VE?cQPdL>_%Y(!FLYog zup`L)byRe>^ay%XW=z|$YZ%S&O~6lN-pcQ=H+~2yJ72Fes~tq0WriCfdU$B%%%AK5 zR4M$8RZ-f9#Lg*QACB%pTDmTr{0~3S=2UI-8!Nle*QTuJ1%aLD=wg))or-oe=gfyU zE9KhIOj_90g4V8hSgT&&h&;#Zu8in&5uUk-XQG+>U|WL2r(^Jy>rY9ZX(?z_;cvS2Ff zfQzL|BjmmiQ~LJ48UDI8JfEY|1}kl{*Ebn=z|V~R)vp(H!8XI^yFTsjhWFEPqr8wF z_|{PIJfpA|u19>b+u7O&V#mbvW)*Q@9o^VrXcia7mX9)QY`Jh-Hu3WQcU&;PX5L%z zkqc~@GBNi)E*#lP+?L7Xf>MSqO)!lM*IefV=gd_e(~jyMbb#=zcw;6WlhbELqyv2JV`_E+jr`hNO+hLZy-#AjeVN z&got)2+aK0z`N;JndHxav1hyey!06$z4L^s_ZtTM2?}ss{fq&UqV?nQNesAKV3_Q; zi~;sP``zTGs^O!b-EGazYEV|u6_4Ll4QstevI3^7;CEvD%c;**kU`9yN9I?7T=d_4 zyF9A_)uJ2j{nfy`v1ppO$p9yT^-H!|Ga+`%L936zgs0*K19H1r(6q@4oz!K6kawh6 zYzG?-n3N9AJyrunjgNLIht>f8C?|?r1Ha;DA2=pj3l}PXpIi5-26U_LiMz_w08`cL zsQnK%tY2L1d-oik-z%n@vmqPwmxOHWM{IClO+9|RlnvE&?_$cZ{lzv~qv1Fk#L0~> zwGXhtB_&N$*NzR(EE-m%53%5CyNpW5DmE;2is^g!iw#%*X~~!lWW#)6WrLaM=hwoc}^)78-OH8|aVVKqdb zjGKJXTLs(1%2LAIs^Q|j6&e9W)i8C%>cc)62Go6U+T-BOfKLPK*Kamwz-+h0UX@E3 zpvul#^nNb`su}t@Oy5a<8@3I0uk%=k|0i~u#@*Y-0Ko>v=XNaythw9zNZy`b5%dg-KY7gX(&_OS`Z{$c8x zm9VrKObkY3^p4fTK|S#cy<$w*WKi?mgi-<7tsfoiAN+tLrPb;o_tSy5qRQo=XBcE8 z9Qh!h@`5x!wzXJg|7Y^i-F#L(GmE^uIpiL#(1ru5H&9wsDp(i$9iObGg9 zSblbp32IB7y`FNIa7ga{mBYAvRd%$bGPV`Q52+jWGeLUw4J-EnCP0|5$a!2}Y0iS| z{2?Z^e(A7}#%RDlW?Uwu-*n1*RLg|aOP5M-v@)SADX-{c3logh)!bh;|GynM5y^Uo zZD-?Ij6c}+^RcYRz;>Tiyi^Frjx5((;<)@q*J1-LjBO7pxBkFb$;qiYgZouVKVkC* zqe>U?vJICzzufO&(#?cnwF3Kd(@Y4BuwDRoJQg}b+r8O%+=i;A@qd}{IBj&>g;FLY zOFO)NQNaYU%A?%Xy-e6GH@&4fhY8;{^8N%gF`;-{`^3BgydKg!CiYY^;p|`6mkS9N z&@6BK6KlnSHRhb?=ff=E?yNXLwPwRxQMOtB2##AB`_2@1*MP_d^OWtZTA1Sa(f|Ca z1O2w5SFDD52+=O=&Q@-KUA)xy(sLSMv-7dfO8XmNjFWvjB&7lJWi1MLxeZ|SFxl69 zyaASc{@n56ZX;L+<_s;XX@t{u(yUFt8o{K8Rd?372|QPJeAB$u46A&ozY;uKVEp{= z2fSsiAh2<`Cv8U?bmz5RA|l%1Z(&=^eA*|Ec29sm|thY#Q1@9U|y!9=>kK(siHG}ay%c{v^ zO(3@Q@?xX&jgZI>kE#vuwOkADU@ctPrnvUzeKxqxI4~1F&iiptNUaKN=D+{mU{?X* zqC4lB7L~!An980T2Z}-UP0{K;N&(bJL?lQ2%7&F63Jgp>r-9@A$=6R+6QSYtvNF~F zU|^e5FYAT|lQY*uej>T{Ro%U?#B}nZSV;p%CYNMhmVdS=x{%zuRBn@)X9oaFP zFDK*PXRj4sTt${$mpuG6iAid>T#l2It0i|YaGV#kqk*(&d=eO`+(cTwc>X%IxtR=o z%`=#NqLtiMk`sRMQadRnx$K!M(M3khSu?Ja-$NR&$b8LZa>#{BOr^>lJkq+jRAT4T zei9$*r=ETTgDX6tlU5 zhRjCDsA`8}DoaPnwX7KBPo<+|g^$JL9N#hWbbs)l3s=X<89$AjAonxf4Y@E$io|xc zy0fOp*iaL)QCt9Bj~Zw^6d`~P_J%#Ek`+WA2g>g{`w61UMULs=G$C|IO6-bZh!E=1 z(^IpQ6GlyZ`Vb?G9;>x2>DVrUCY;P3FiJ2^9!;^|Paxj*44oHZ6!da)_EdKU1*rse z9G`cZir%Ki^n6vM{a2rcMopHeT-+&&OoQ6TwmcU_;t6SQrdvhP@TcCSb&7PfioMH9 z=_nmNE?@I4FO-g?24y_*3h9X5U@&;Pn~wa9np!(2=t#w#Vc;-J3@N|TxoC(fnEySeW-%b(ktap9LA?#y0rIUR6Vh*?-Iu8P6|B(3N2>aDm*T}gDoe}-OjCX zQ#1m_-Tx?cI7bA%_SR@Dvl2m8WuC`q4ZwddQq4?}{e_r>o6D!&DhbY^B%RGT2`K3DJfLRJXTelp5_9Tq|w`=*jJJ_#Y6 z9pi0N%Z1UJH;X0S#R;S7_SHuYBN4Q2xyvVs8WBX{3l6;gS37QwJ&~gzieyD*+Di(` zBVO%EUrR-NTCY|@MJK7&2aC7UP^?>%Yeo(YWd}?P=?RD;-SUQ%l-Z)_>$7*-ElWj_ zki>d7h54e0GPLr1dJhe$xCw>P*feyZtLVh#IvTp7rgQRQEe&}x#E3HmH1u!Wp`pO3 zkkh{-XlRZLZNKA18p5aC$$10*-eXayl%yfq9$zQ_ek%I;+Aw9HmWo#L2g;-(H2zRg ztC)%+$2Sq9X;gHvF5kf@hKjoP+h0IIR1|=h`Q~{lN*^W$b8M)n>mlV!vLO{o-0@Vu zx{QjHcBwME=2B6(YWQbDgo=8_I(#<&r69!#|5us=6qM$_+AwX9f*iid7Tp=9paGrK z&8PAIb6Q^AdWvoA^~NtY& z^wArM9T>CRzTe|wyuH)DO$hgU`}XQ<3oxF0wCA`iMlJ0nqT~Gj5BdBOz;^QZelHHT zEmyD>wqtB|_Pm*gu~Yps?K{S;kMe?CalLCl^1WAL+tuu#yE;Ze8LXU!D9F0KUSk}i zsm`l2MSOdc=ZPeYmoJW1-Nq<#;Yi6D+&;BX*QS<-C|JvH#U zB()VBvBc&3a<7@iVSAb3ioZe_PxI6S@-fc%53WC>|FGR18!MDNLP6PBJt$1#a)+CZ z*1}X|oxf9J?KB02=Jsv&ZKoi9_j@ZS|LrFQ?eel49f+r(6VK!;q@GYvy>n8t?{x~A z{wxJ)U+}2Af1HBewYhq~-i6~$b=s*l8Wf~Z^CFo&i-OjAeL**cDCn@{((eWB zIDRC4N>QsLke-1f>w6`E&YPeeIo}DiNJlD6IfXzW`KvO5A_;W)<7$IlFA3D3G4A&6 z8G%HCJ~*pB#QyC)bbZz%0wr18ZCUY}K&^&L8>-*q`g|S|PM|~^mWu_BYcWrg=RJ5r zplI(5g&i>jN=V(fe8WfFzu*bALkR?Oi*1km8&4p+{CRQb@OQTb4^xh$;&|beG%bkj z_YK^een|w<+3AoGkFm(Sdve=X0uAduA*6snRk4K~UU>xaq0d_7SBU?gy1ZaD#!X>L zE1;M_StXNA0{N|yGTi=+K#_jpv6pfQwB%Wf(FFd#mvbht zt_+tqsI{2X66jn}%@w6F0`XNrxda6TYi=n%EKNaY@io+^KtUBRC%4bR@j~cpn9lL} z6!h3=Lrw%H?k|rbrg|!qK)>}uTsrW4Q+(Q^j=mw#R{d!anOFkN z$alORK0O)te_>SlwYY+X=X+ajftko}0_`}5Z{XJd#@U7AvPjJJ*`gHWEBw!)ECUL< z_3YmA+)#XOn;XhCRjDXurQ3t*W-5B$tSS8XAq_Q_Yqrac)6inctL`gIMUl+21N0mC z-V}Hswe((_DB`RAE1T#jH&x!?v=1FkL>XQU`btNQ$)@tN@O>%!`{It;`C|W`zx84$ zn=ey$ilN7hScwzj!Du{(qc8m+!#@$X}w6`+y+r}{Y=neUMvmG?ipD%TLj0)YqJ07Xj74BWL`qA z69vu4VZ3j-FB^X?SV$oI((s>^w?xqX6UkW$1HwpavwvN*tuR_WTcogzCxpf=Ll(Tg zE`%ORMEdU(6GAgI|EeHbJRo?Zq(uN#N_HvwmKsI6pSr3vHstM@jW?kI3xa5i-=b5z~tiQm;DG>+r_EiWrViyD&}hX(1&g z?IzatHIW~p2i}iB1DUF;cl4`g4e3xzN=N83Nd3JR$MkF}NfE48pT(4tN{$hwMsfw@ z=KT3GMy;8o|AHO4+&R&t+7l~Fi97y)MUJ2T`Xq1@ChC5?%Y`ME+jslM6vNE;&zA$E z{7rOtaTWLqrFhR7XMz6IQ@ty;^&oLB&Yyj<3DmdQoaR)tK;PlMM{m5^pk)1qx2ozL z;C+X@t3A*O!g+7?pz0_Oo%Yn0*b80`I<-%YcJ|N9p zxb5VxC9lkbRBeH#gu}f5@-RH8vdCe{ZsvhLW)HanJkT|Gv)S(j7c34Ej+!GJn2D#k zebBOMW!EF?UPv)=P7SQ-241!OeGgg}lsEo!?`3{Fq%#*U`{L9J*MydBds5s4VJd=- zj?4z|j~-&7&+Fd9T~&}Wcrr$HpbDVE zKA&w;1(PQ?9zUD;=ij{HXeIoLi^7qt0w|dgR*9YE(5JX#kH-CSsB>H2@=~q>igK!} z(<>`r`>1iUSwSUe%m|7ydxpt=-jMgy#3^LrNdKrL8GIn()EaeZ^k_BtO zl_#Da-{#*Z(*vw*T{j9z|^1tl9L_V|!2xIb%q zPUZ_1XxjMwS!~Aw{^|0xXTs4L;?0EI{&x1wC?*WZFI^DXz=X>biAgDI7I>U%id}^J z3peEK%hF|o?SsKn^Cwxr{P6bEvK|)1a3&%|ur0kx+PAQi1vB(%nguI^ckJpFX9L6d z>LFG%3&K8cX$@7!^;HJ~GmTl`*H5fewq?Sp^UvA0JQ<)_YGTQgV1R(Io|pI{2H5Np z^)pUo!0*SjebY;raPo84`Q-U5sK_28Z;#@6U+K}=DKmRmb$=E8tZ9Y6qvlI+w+1 zEubT_&128kMxg&K%Gh6B2dXm(85TTQqVy_fP8IYH$hJNW`3(=U@9vHF`3adCx!2Qg zCBbjhqYhh`7 z6FD4G`{*{&O3tH}amF{alYIJ_V%teRJnCg2^}d@lnjz|ar1DV{<=>`Ua^k)3WOyi# zTv5Mf?(5(Ehen{f?>_;-|Oh8^w@IaE5ll5;3%l(|j^O zTnts;O3HsVKu1<877I%<=;$Q+Cbtgvr}ZJA`Sx-;@_y6uXVY6zq`*(pD`MTGo_6

b&eM1S&5cUx!nX3dUaR+3!d+QP|usa zUkLQswka?I^QgX#>uJ)MZ>?JvM*V>Ksm2D`t`8BIhf%RW#O3^3Xw3%#Ve$Ib7TbO9 z%jkpA1p0DCSw%Mv^RK;aZSt6}?g-c%<(*8Rxh6+wn-Vc^O<1NPf_YnuBqiJv+e_=u zoIjS1$6=^`l#xxK>;l{G(NzSxxVPxE3g*`*`9u)&QrkFZTUX3CPbO4sH^qGWy}~IM zE6isL!yfAOP#Z$drt@MUH#EUpfWLcjeEG9|LP%ydC*vjZL~%f zfu7fJcF)88Zq!s(m8vGtdj3NW=8LB1SKRu8*W;)9){paXyTlUBC7zh?%I%YX?uU73 znW29E8_X{?;^a92c%E9V`n%WR@&D`B1oBnT^f-&>ae8*!#Z|ap840;S^G@84^5q0h zGamO|g<2Y3_kVTSf9t}*df)x#WHpmOj;kViLst3`Z%1!j@6g*LigmbMVzHImBFxA0K0Vbp|4E>kJozsIy*AxA zD2>}6(F^-{64!eY)T$hebqvkz;nqWVzQVRT-oDu8rx8yz;{BU>r^31=KI_4sUINW& z7}Ti48JrC(9>Ud<`-ZVP$Js6}@T}?-^ zmy`wy>*>hMW>mejnU46=UfWJb(mpoxbh&gCueI0mI_B4d&in^~|K-JW^j6|_)D7$( zPdd9Hild@|x+p5b?im?CLw4_T>0dIa$j<5B3oh21 zXLp!cH0fbKNxznTHk3f)!N)$OPK%(KH0>i1WE>H)M_on)6@GD-7z+|cKXDY@q%4eF z7evsnzZF8ZZY|qS2nZp5I%>lyL1Z8Qy7DmQ%|vdRubia-n&DT^r%Aq?RE?Y>BW3uC ze3C4_oS$ibY=UghAH1caFit-AhhEXSW8`suKrk95BRFS|-`O=n>fGX0q`Lnl?*={C z&Q2XBXVSB*A#x@^Eipu%f8C$hx_^+=mFz2FISr5-)g^Ff?k8vR+D$ytawv^;calqn z_>b%=_TZ2yRWhPZn|jF|^`~h8rrl(wrieg+LMO?8#TXfGBZc|2Riu^NJwu3^NL$4^ z?dgjRWYyl-!~}W`xh?Dx^-_5?NiC7v!;-HgWlLYZzJ9ZezUtO5A1atA7!Abz}H>jhdXsP2&cRW#fNx>rT8B!rCxm`fp?>LNN zdtiCfg`jwiKF~NwuKy9p0d4*QZsbDlG15QEj|+Et`vlWDTyP$y7CB*l%zt&ATFL`K zGt1Pttvm=>)U-I|0uOd-$Tl$5AhqmzrW6F=9%Z24roeH?5Gkb~hvvSaqa0{F#Qx3BXmKR>gF9Thd7}3vEIanQJI3H{;2Pdm! zne%@t!0!8`5REG=$cT@%z;YZgGu+qyWsnPu>wS~WU8>;ctnUw=Y^i}8$6w!Xrq@Ck zC+pY0&{{BFlNYuis1~O3l3o|N)dJ~k-Hg^6c$w{;c*dayb{TeP8ERBRtU;xz%N8C; zmF4}Y?&pGa^|yu%H#x8&>AiQ3EgR|+-ggDnuwc%oea6;$Ea=w|rpmQf0C!ega;XUm z&Q`F)E;+K`_mZr4IxcK5U$!x0XAT>toZBx_yOsmh8Cw-GaG+3FRCoOV7aBY0&naCl ztUZ+-H8O(>Ch2Q~M5l70Lhp6TiUnMV`q^(&=*5ANguU@2&K&saTzIEylnw36ig%n} z#euB$!(1m)-@i9bJwt&5FZwRVC>e0T>&tNcmt!1o)oKp@BF}+9ll_f_svJm4)>4)) zV}t&yX=15aY|!31r+r!?8@SbMG$xXDsA^|9;CaBNiMm&|kH~yO|9}1Ijvv zoow)O+~jlLh69#Ej3b{SIgmE>GGApK2NXZueXMYw4f!=)@=0oJc)IX{_bW3NT(U5^ zsP9$*jcQ}Jz^ej|912UP@2r4>>f3b(m$9ItD|@9!T;d zObyo5z~|ks%m>x#z%#2Q)nBIpjz;MGGuzPwjH<8=ltl|%S}dsaTEPbe)`E;WK^ye- zUC48@?f~VVv2Z7|6O`tPpZECN1-joarCq)vfDVWIt@h0V&}uV~E1`rSCNpWy1x+Ei zvXV8EOoT9M8n^bjh7g8-%~Wyh62PV7;VQyJ0m%DoXe~wpn4)IWea@x}b}6|ntrY2m z7sDd4`ls4q17k>PbsZmQi{|fl|JwpLs=2*KP!srQ-qoX=>)|FDZSv(BAd7xeQk4s0 z+E-_=iJyPhI^7e}QUuJ3n3JoSdGP+pV$G7HSy1=O#j!Ug70ULyEG|9p4EEnz&YwH` zAu8aUkiXxSf+XtB{JX--M5izRIhdD|gPsH_kUvm>);8|@qg_#gR*gzYh%RBFKkQX8 zuQperWb=UfzmsZ^BJ=SpU-3F*s`&o0yIupTQyp+WW7>qo--^oCZEivLHkC>lZ{ef1 zI{n$-Y}=9UV(n?I7dw&9!zlgwWdg)IAa^fSM2I@)tBwTM2$9|Rj~nbpw8OKv=+Ju6 zSF;ypKZU*M+x**FO*MVUZ;{9F%kF-pp+|qI$QeLttMtW$X@jV%(b$k#_!mvjzP$Sn zZwP68fNON~9|^$$&X(9)j}@tFsuFni__6R>0(+ZC zF=no&aHA*J+@D3^3tC1;J?v=Mo&WpD`6?Pd^6{IpoRcJ$THDauHzJAW6zEhBh0$@I zSckM0je)nA%RBTPVPId5Ysb1@47}a1w4+^{iF;N|YI<{$iG8;`H2v|IiG51a&!K!K zPKw1_hfX@@YR}>>rpl|d{=(I%EKWF4;7vKU0F%tDQzJ(2hu1U8IfKf zd`ICMBN^XLzoBq}V_EaDL<;LC8t=9x^=}RI=4&KT_)({k@WCqzZ#lf3wVu>BnvMi5 z|4iZUpWeEBPN(pRi49I+*--2L`GpitJy9Jq%Av5wh&)}afx?5!!zF6@6n^a>jLIZ7 z^Ka?9&8-yfOL6^ZLB?~#uz+QrJ;a ze`=RYbmUL+T=^Jx@ox%SX!~QGA_`v{P}~zr`pqp#jgBA|FHu^#x`4u}nLwXiLgC8K zr*_<}ps?rm^nDch@4sGc`lMD&;cpTyygc&!xSIQ&EH;II>z|b5ms0qhvsbzrDSx!s z8@juO!uKj&H8FgB6-d_U_Rvai^3Pbuk)Qo*5Nr{nZ5TTh3~5$N3*_DcQ6(ea)=CsEB)I_|#L{`k2l13O=d9~L>pzy;A~7u0+ucKS2F{nMGaVDZOi z(mRMhuWXqr?ajnyzj@7r@l4#u7Oj|G!o;bwT)s6olYL=jcl8*biKQXRg)J(DO&pID zt(q={#SXQwOd6Ru>d)kWmAOnjS4lZ@@D~%W8+hsb;QHCUH;B3S)p$U8ZE5j;)ehHDpR41q@Zi|&7;DCl%)(W$!xeSnDrprz4c4ks2dIboFbyQN{AjCEiApSESLeMh{UFDd2;PXJsPH|8w9Q{^=@3iI5d6S2Vw@W+9?axAE3>~Y|{mIBIym`o2 zF%~67iWQGaUV|MI0WAso+bqsLI`<8J*Nx6Ad72IOhr}+1%+G`W&Z#13JXB|8GN~NA zdIN@YUUA^r^y+Pc$E#o<+pFxiUo9lge=qZXVFLuL?hsToG=aVwFQVI~72bG@emQxh z4Z_{?8lpPdVXjA9;rWnGNL0U;CLLBUN!|l@KCtZ5vv1 zO$c3K4nFH{3E`%9*x?L6A-p~HFWq>l5GL2VOnFr%fJn(!EjPLVbfY`&rfGLV&iOGF z4fA%mnfB1T(S#3CD{lmir8h%a{QXE$Y$~<~-P)ZH_8621;FI^22=Wa08|4e2Ci>R1^5HxnyJYiw={)Gpe>%xhFAvrW7dS`Nb-T63)>7px8}{YJ65F!_Xt{+u!1;La@OS5^^eGAWZNDOe!Jv#iLv_ z#D$#5#~WfQ8nZ+l6)< zxVrrI`U8Y>{m-Ue>mpn$y45D-WhNVb?wG%i5z7WiyUeGb&avUb1EN8xN}qODc3N@0VV-O|5~ zq&{`zYA?5f4L%=_Rrq}%@4eT!oM*`XzaOvxe~(&zZXX+_TSD<)0SjV`dfZsv6(IVw zPjEQ83{vg++5!dXHO`LN|kbULmRsYBoN}h$DXUpTDp`{?VPFkn?QVM>p&m ztLK2qlVLZ_rX-@w7BIDxTgSV~2NnOe?J3Ib@GkDXW_xr8^kjd~59#QHSj$DNnvwz_r|iQh z4*~p5n>5z?Qvg|!%3Jyx1i;UiD`1NWVJgQ>=f`v**g1FYv}_T;j>*HT-{lKnL)Wfv zt8WNkRLe5DeUShp+r|`|%(_5!c~NuBq)upHc?O&$`}tz$v# zNNfXilU-6?S__TY^nU4MWcvSQ&%J>m9+x+`a6d^mV9P$yNrXq2b z5)|6XFf)2mj;tPGmX;L<-E)w>5^7b2)Psj_m`m28o9pkNlN_u=Ygah3Z+&Y(-#6Vy zam$+!zjdDA>f>fqWhry_s(C94^{5o2JGG(x?*f7=OFGbBy{6Y{^9AVJtrCiB-d2D1B%O(;sn$$Mh+yKOg8M3$HZk#jrEHnoO$_{cy;NbcC*%KR zI#ySZNoGx^V>t(%7aYP{^9%RyY<@@PGiy6XVJ{8;sE@W;H;snn9u>B2t)p;rV#C3+ z859l*58KGSOV**sWufME!ZXX#d|BryEXuJ;%0EXqaK_c8;7MTzU;kUnE>U=y+@$8& z0fb|*Uy55Kg|BPtg#ISH{^Ui)A~C|Do9{Xe?=B}C|4x^EPC&T7IfG|COkum~tG<48 z8uo~fo8LBthL2TO?prNQ!^HWwT8h%}r>L5!IKq)>&WyiLnkhW;&ms9x8HHDUFO6K8 zL*e3_=IL7re-dceGfFu4YFvA-FVPjU4Nv^;5k9?FwyIK^jH85QFXc(}#RucYy9-}a z_{Yv0%Th@FgbpU<13#y|JVn~)?sp)jpC^Pv=3 z2kpRi--SfqhzYj7nEH&YZ<$i?iEyGT-sIYz@uqO?#c$%`*C;%7dO}q2W74h+T{{#{ zxIet*@HFyX=bFMPW0K;}Ug*``<829Ry??b8REv{2?|<>BZL`(*B(K zvP}z#PWYsmWTO6;!gog1UYKvE;dZhul8D|6*hMyyjU+xX$L_dIt0bPH!V>O#LdPY2 z>ni+J7$jeV*;1CL{T#Ty2`eOcTljqtGc7kve7JtkgtT82?=%fxlz^%ku@#IFl4 zsF>NE@oohB!ils?@VmsknZI}^yx%iij)t_PkNmi z!^9cxHlIw$J{juDaK59@#0QC7+uX>&idwewI~*BUZ?BTbsR}y&dM)`NUx$tjPW*Jb zc1#lQsXx9_EQN-(Y*OX#PN!iPxbWVA_~}z^+4#{~2~1AeT{G58VCO}-YgRoM#|#5< zGRcbLT`C)^3?syFhiOpG+XZ4ck}qcOm?DaI+I{;o$yOBS_922oIlyM@X-Tc_|sRkAg5pT zPJcz4kn5CJ(@%sppe181QOhRRBT+qud^f!oskL)AtsCT_8RIyt#6kJPV=E41mZM$q zE;^&hB`D_1F49E-Qk=i;@0A%p(Sv7)3>nWpp_z77im%H;QPrwr<0%rjHF9m=yMRyd zAMa!$4PwuH)s|-G+zMprWT=>LKiHX0KpDeU-rh`*r@%#d};gTy^&{3rS5>scx zP3F#EgF|oSn%$~w_;-c(_QZBJWS82pDPJ~(cwXCZb_xg14m!Wzu$lwnp0)Y@H#zYA zNL$T*S1zFX%*$a5E8&cx+8p&-E@b5z-`M_$3q&+54KU<_SH^S0^Q8SU-@$L8V{9M7V z2(x;5dk$=Lp0skVI|r^m6ij_E#D;SMImyBNnGsVrYH_POc`Hb4veb~ zZ>vf$^j^I$X>S!ceElpke6$9P$o4z>x)x3u+Fx$jR1cO;!Oj=r8i4(F95fptG0A5C z4MsCeq#aJSz(kzjx59;}(RNd28%(5gFSdb6^1^+04s?LUzJiK{ce-GdV2;%(0sOEk z{E)>ILU>zTL`9Gg;;oZxmUHMNIL-(=(KC2E^ zZ}#Z=zfS9b!?kVBcKkNT+PmW;Pl69y3)0^`dD{%1O~#445n3ucJe`8-;QF9NuBTo# z+;NZaWlM12Udds-cYn*^rAkzT=}0le{`9+RmXHq<$A{uin27t1pTTGxOAo|>kzU)6 zZ59!zL5B9oOC|}G-`LVU?_vgOs8p}i?#V&07hlyGL)K0^m}y_e(2T(#moIT5IEU26yNcrK zAH%1HDKTt(eoy@J6JmJjsP|9*dNC}ORG9B%C5{hKFj?=bIQETcC^J--z`Ki7?w=2r zz~xr$y6Mdlm@)3~XDOV0xUv*4rQuh)M3HpTumxG&ANM7(!Xin}_$_pt>{IAD*iGVM zLdoTqrVKoCVrv*Hlz~Ggxyc{kGw^sCV)`N`{^CN2o5XFo$vXto!bv=jxmlq7m5Djc zdcT(zFmXTDUVNyJiJ$uF)D|j8;W^_MI!aPlzv1z$EW)S8x%SBq%bD2aS%u@lXG}a1 zXGq-E=g*zZo6E%aJ$b5&lNmVR#iBD|@(lbT$K&f`PdbkOS8fpzD~VN{PTJZI(y+C~ znpUZ&G`y(gi=KoJ4ZpcS$k2|4-(H{0YuBY=%>Z9Opua_Xtq#c1@XkFio<#F0+$BDK zqekJa^T;2Lp>V1J9EiS5VX5Nl>q`iqDj62fnn|ppr2V3^juh5f!}sVvLt&oUDXVoM z6kgL-`)A!v3U@qyF6tXgVej#daw)8DyoX#cR(eOWiqlEC4 zT7&PSJPJ=9Yo#$ODeRMyxcg=i;jo>`JUZdKk0EF~yO8jpso~u%HH1G!6utUMyOZ`0 z29FVL9iQf0V)GLU%B z_Tg9Ut$Yd(2D8I0Nq=p>Mq*rx370NWI22CG6ZeMMgiBSQziB4p7;d~Z{X5}fLg)9z z2_O2~8i$8}rEoGNt@b4Rd1)YYwjAMD=9TPEXUTlDjE(26Dxff|*D!lkLE%>cS*s(f z$ar$qEV&&N9_@I)@9Yqn_jrDeaQKlF(Z?!H6b|v~QBWuKHa+#aix$u@9^4kK=1Rj7 zXMV>h)Y9<7o}G%47bWq;^{5!}$6EV)pMvN(n*M^zCjPK#BJs(<8qxb~5s!h7dIr8T zS0S8uOip8f_+{gyA4;yoFU@zkPCovTiO-FvRdShFWwFe??ph{}U*_QWxS9Fi{E7YQ zG}P|X#>9Kyw3?W-GO=JBA1j&oXU4OG`AJON9{5@conzwReBI53i124`toboI6VDqz zCUY4$okY*6L^nCjo|Y#*NXO{MshYAKbj-W&ZmW7n5-U;HuFNW-;hr3oNk;NCY&w3O zW=r8fPZH2lC9u9qML>|A1fH)RUu&Bpj<+@k?O3x-91oRjII~h9hAXy?S@-yg;p1mz z3cY8EVRvs8>8a78xJyipnlVQd$CZVpWWN`|PnMNx&bJo9AyKoB8aIz2&7$z^lI~G7 zp-;d4LrH3hs+F-LsAj;`{=vCnH1|f$hTk)W&@)}X2Loe+D985o#p6>4QTqD*FJ0#h zpq1kDbe$dgk@9txhL1xZvijs{;aS~-Cep&S-DrtNrrF5_-RO?dqezt%LUdI1_&HBC z0h+kS&g(!AFW69SN=?Y`p+ni6+Y|`|e8;e@g z1in2lZoz)Hm>iq6A7MNzt;^1YO2-9R^Mt=)_;&u)BaC7=chKa(wzzUoAJydNuI55g zaqKjAuWHy68g|(zy%sFiFSx!)q5&rI4)i8CreiRZPvYG8?e1rrR=`z>R_Y^s_#XfO z0RR6jn0GwY-yg@V&*fetNg<&kvMU);&JmGOl9Z%HMIn)vlqe}h!z}cThLTc3rFhd& zAtUQ9d+&Q~BEJv){yLA(y64<;-tX7z`F^W>zM8Vjsuzq}kG$tq=mXB@8qc;B{h;Ny zg0C74z&67>2U2A?uqAmP=V$~6HafYMQ=2%@y<5EKj{z5gsO+40H!g&$I<|Nka-ph! z7jGVm10Le-r?vGtpnB%NmPeZg;7;7btKJ9uAyxgqwsV|b$Pky~v*7Ci2^-zFF??MR zI9YaIA+R0f(q>M^X}5x2SGJj!K{IT>xV^8E+W;fg4na;Lb)dG`Bhc+U8#=zqGr!Z= zP#h$GjJ1jlnQ4E%Z}ekBP52p$!eeYmOcaT@yNeA5HfuK**t0=hI=YJL&W7^X`oGR= z+3=DrTteH#21ZYv!hi!CEO?U-6iTu|NrXSf`5O!NtBf2zn!v53VBTv#BtH15&& z0VeqSG{2Dh#)O5wPaY6SOenTFI<3jegm|ay8YwChf@M|rDD^R*<7EHo+_enoJ}+9} zBf|jiDq7{(Vg_u)c~@v+49K>6ZICcQ2PZXe3j<9C$i05?(|#udvUb!*oN!{mB1y{O z#akEvD@_8EEEsTnVzZUMGy`sjbc!2DFyQXqqcYFO=uo^lH^rAphr&lYJ}>a6!=pXv zT_z@U=wwQj3!kAwYEV155<2i0>3bC(rGu2Yzum|EbPzTXvx+0HD>aS2B2PNJ{*kWW za+wanP0n9L!s+mM@#uM%L^>oMdQq&(%YgME&d=RU7@+>>PMP`x2I$`mZsd~xQ{Ov5 zvV8*+e%|5hOI(&LL%=Ap7!-eIxcVFFOz^_h=FRCZWedQN8IXun;zMFYIeY@_XcYE6`jzidHdn`>TcLKlv;W$s0X61akPUAd%?QhvEE@`KS7t;On*B_#B;o8^|$B1nlpgz67+nRR(wD?Q6XC(AOSTUDoX4?g}PVdt` zA8Ci6U+c~)uWbd@*h1}3cbnmfq~CeVmPWX6%HiRn%XP5!fl%}M1O`|yU2)pWy9S8y z<3oj(mC)YFJsfox{(?szKQg+#hI;)S-|=#ZhG ze|>lly7d0Vt~(XI=-4P$Uv;P-1@(l_p8tHUT?Fnup`)d*TyZ7g?7W)yv!m7l+( z=xeE@VY<&4a{d_+j;F>@(c1gYHw(s*Yutj&p9d$9SwmfsMBM}$?0TcgUpk2xS-Ew0 z6aJvRo=&O)zEi04NZ>>E=oGSgdu|EkSs2g`~tdzB!^i~E(9Pu;l0i%l$ph*fR8ILEpEeY340C?$d+q(Y=n{V16gzp&ezgFunORp7TPuL|oA%v%mrCG8VSXs(5(Vp>-5)J{ zN)WpX$ku{~5H_0#UL>)KibJ0SDO8tJae>@3d-)AC+#*Z+@1-jZ&z;j{8h(-aP1iV* zhUuz1ML#Fdu#3&)dDTxe+_CLyYFsxBueZKEe;cnbmL^q6OGFs^_(k`>S|E&-Zyq`P zM_d^5N-A2nkJGSbXYOi&MjGDZzqUH^0}YFM*EC)@MZ=Z(w~o>0(QvO#($M1bR6Nvr zpYL9-5KfOV(kb8w;%#0hmQU&mVz%~wY0?oCJeRf<3ZC~psvi^B!F_4WuLJ^@i*8|b zr4abS>HJgQ(g>`fsW|e0+_$$T$};O-5ZFVrWTO%JJk9%n?<4Yi^WFt`bq0aA?G)K1 zm``AXk6AWXzYw@uQS`V+F@ax7nXaoSCGc|Z50h_x61Y)3wW_y({5=t$v>P7@%r{SD zX}}Kx^XfDd*s=*c>7RGxLob1!1_-5^4-oi=DH&LU1kQT=Xh}&sfu&b;Y7ci3`0xAa z!Jpma{p*o`1>2uFEF~gF z!EAc(<`Fpxj*s9uzDS#b`IS%f95<%m;Kg|%r(7vG^G?sxs8|XP=~HnHpi}UYjnVfv ztP;fH9ZdpHBL#6Qqiv7Es34vY-x0oVixB?u>H9t9n?gA6TDEI zA#sF?E#$9h{JuiP8t*a}OVkSC#op?T7d z{kja(00L__mG4>47Qo3Whqs#=3E+{C+e3eWAD5<mh}6`hk4zjw5F~3 z@U_|z;nOX=xUEkph4ALZD=lkn@+Nq&)JoOYJXd+}nBS@IF0wqBeHi-v+-6W4^-7{k z^k4MSBXdb-(lpBN9Be<~HHEeYjw)_a`h!@Hli!SvO(4;*c3zFaaa5-m|Dt_j4Ea@6 z_~;Ifq79YSHxEyapnbDAAvuCB`aHMVvt$^pGC+LmP>B*Zk!fA$@;~&eNQ(B?e?VLPY zt^=g^XMPtx+66ZyhNb+?df>y%55LagUhwzQ+vy_T56@D|v4-pb9v=okYkmf>?#mxtMo^c@bY47l5 ze-12PckjIe$psP4`cFR9^n-YYM%=h!A8dTvQy)gof7Pk-Q;TF5n8)gedg!)8X3N!v zE$>=Dwz><~R5n4$zU;(o^G0yx#(%aV>S4|Y?z5oaMqcn*S0+3m29R9dp+`Cx3w|1fuGv9yyU-la zuweE5=sweW^8Gm>W5K4uXl&KX1aIrsU>%YtPn{KNN%3KU#z3lIi76Y-@s|V$qBMZA)Mu_RMDiM$ZR?gRaKKg}2u%f$=YE}{dbWrIUGLKQJ4Co(D!21}n<5vM zd!F@wLh@jN(Zn!)5f}18ts{)uI1njE?qnhdrt6H3*$8n!-KN1qNNfOlpGMVMb@su* zMa*@-f_uUK{CuzPJGy}>pW9^Y+X0u8&+*&{Xa&)fl3)7CO>k|PRU34&9uA$`wc&s~ z6C4%hT{xp&10=M+)Rw4*s5Q@%MDr`a^?uhrm62jN)cvYAxZoQcw40w2>6r^n@lVUd z-e^{VBnRc>x4k*?n2Y)q-znGC45Dl?u~B8pFgoE}xJ7jB2)YdW zOJX!e(M-2b!?C(iG~YnN{q^%PjrvEvWg z{_bu1`X5s$;$-}Z^pa_mq0Kn^nwUX3R%dD%t9Wo!?vn)V8XnxgBD})z7%#rtF=@P{ zl^0u`dwHdQJ0DKpSY(@8$A?#G1mj{1EBBiOaJE~F zz_aTFz8-J?lV=+R^UkK-5G`t~E-HKX3!-tkXVXP;8ugUa!%zD!I z1~Zfwjav!hfAz319(ho7)YeiM2TElhQP&p6Enznv`I0_(D{RInxtWGVUT!VjMsnN* zQqE${Y1k?EOJ6yM`j0Qds940&cj1j0A?zbZe(5TNoity6H%k@7{js(?MaD?((zfjg z^QGX*g`SEJL?~G1c5eOj8v+{=6O13x1kR_JT~iMw@T28hRTyCeer2`%&(a$NKD~W^ z%xUu4L*t;=%|rsPov*h(m*lACohBlFB$o*9-`}&H_&mQ1uGF7GE1^1O=qGT!9(wcNuK?=6hc^uYEa*S_d zwXYk=PbGo^hLJS{UYDg~<3;kA<O`b{is+adH)_%N5yq3GitV}(ePaR!Hb49 z=KZ#BeNDq5dyMbit*7DmG`o2fLc-V{GiP|zg|W8oMr2Q(=bZg462`8Bl(-2p4wiMg zJ6JPmc-P+0V^+V(c&SvIG<{3M3vVhRpv@GO=}uPt(v<~HWmN#aVkEC8Byv1 zLb&2olVHbNL0qxygi?7U1?Sm1Bn25z@T{y&#S;JOl4${~uxj4D!5{%V@4%h?NJ#)o zI}hHVBEPsaf%2efwqd*WdAA z7f`8rzJ>>T{Y(|o-#vrG+`DMmc7M?=FPRfD+sXWNH#CxQobki`}ef+4d zQvV=2tJe6S;}#e3N*yX5JjFrjW)CL?=MSKX@hiQb!uyb8(VDMsw0hCakY&D;likRy zar481r(MW)!|%pyy-rko$lyWQrFLY>|HiZZb}QO#cloGvUNd4W`+LxOUK9H7)|zI% z@;W4}{C8z{2_0P^=|*c?CGt?Q+PK`S7-=5hd)MDyfadrvJ`;W05M%6T5{{G&XCvYX z%#$brQlQ>qca|i4(lZ@2IUBDkHyQ$`WH-waW^h#9s{_C5R_rtB$ zL51G~10e8R(r9rg2MYC`yQfWapjYw*<)9W9ivAefSM=b*T$}0@7burK`a6LOD_*%e z`@G?TXH2nq$0sg?#960i$8+JsY&mYig*yQ&ZcBXRz~&}@$yeV8Ab7TYN9zaf<)P=U z(Y^5ZLSYDhQa5ODFJ-9i>V$vwQyV-3+rHTG;ccwI1R z%Lf*iR7$8ny2AwSrrCmz0ZM8+^rZr8;jigrUr&BD7;L2t$-7m-A;)jB_be*GDKR1G zeaml%{;iYy)v*!;I&QA)6Rm?;LdBVP8D?%QcsF1dnEROp0-a;i@ltHqDbBz5 z4<8!_V_qo4x3WO&0dVHV{~_KxNEGl3)Y>Sz)D>7g_)B$Fe|n zt{`E;(YeB#32WyLjtMSo(d4XTCX}tpdLlN+1dU4V`QC{vXdTm=X53;ykn(J!mjz3@ z&m8o~X2NXR`A;yQt17x|a6J>w-Jy=_-em&ki^;|)Z6-{7JW~}X&V=ks<^JPqm~cO% za$fgxCKz~d^3>9B@75(krw`D0ptJkGr*X?``5DxIz*Hx2Cm}J zVd}HG<%1qNgx$_bywFAmd^JLDM>8FK|0+u^Z=?fr_wZJNO^29hrqym)7CsWmR;Tr2W3RsgnNxyrP3seBr25IUNG)x=I(6(V@oIO4pH^` zd7~wCu<$F(F)yb7%fFv=5MwPmtoMTsi%HrQBFDa!rFItI>F__&^ZZK>0000-v;qKl zoGjA|Sd(QN!0|U-GCLTbekC3XK0%$RYr1rVsCYo8VhbXcMBx&QLIyna0I`@HvaAD(p+1i_HkS?Kae z@uUAfeg7W+cU{?E5IR5dF`<(%F+mWzKKfgk=X(+}x=+6Y(U1N(m5YHr8&MY>7wR)B zuN)h%_73wYnVXC5{ddq<7}wut_RVsP7}RF~amsVC{^>?^jEEcPGbXnjLoW1|_zXIk zi{74%sEmvo5memMrYdk-PsX}M_FbqAw!;)ar+ zvmCSf_mPtKr@5&6`wmw8FYZP1n_rH$)4gTHnV5^lk~=6~A2*D+7s^o<)Mq&RXX;V6 zw+V&(L^=JsT8Ylkke7U#4(n0Y`4_C0CXS%arIlE5I(Q`KP1j>fX%hzKCMxL9#Y(jI z3W@Mpw?mIDzc-;SEb(RX$*jbR>flJuovcT1Q4=bcB#xpVUsPgCw~#32v_+3GcbZUF zmoS?A(<{+!4<1AOQF=7yHK8OtaV+ycR*8}>A<>*;)MLwyCagc7Fpl^sl_<6ak7vJJ zk5*k1nnDsM@ccj}X8jdBk$46@y00~%DlG98pYdgt*wP+6iRY{IXmU59p*mqQeVbZ| z@uuJy@*ki_*_tNw1}08n9wn9NxEDN?y!3h$zHY+!@`PCSkFP|>$HA}iT^~J47BpdW zm&9r0r9OeO2f=a7bA=v_$C}W)JK;6rjI2b{s^EC~6R1b~TTNK;bmDaSm{*C0Z-Nsz zFHMi`6HQpxl9rbtj3@dk`&fG^3gWC6|*~%XVS-lY7BA>m_>b|`KYnC zV&Kl?H_2yoHQEn`rSkmDTGY&IMWM5DHuqFtjn?nORNRAJ`6%1jibhj%8vUF8B?hhu zn?qhzYv=gyM=LsiNq&p^mQ|zXT39-LcqShuTUyaukUSS(sK$_GVQS7lv=$v>S~329 z@;vHWRE@?y&8?T25E`+yb-f)f1qURtogi`oWl5JgWh3Y zj`e7K^$!&OoRvZT%T8goQM!P8dA$e&)$OQ!dQK+yG|Gv#bv^mf#U<}4)c zdM5_9N*D25vI%vE+fmk$_AdRL=tPxXx|qDr7NIk#9c}-ly~jK@I8k#$`aW?6ZbIe$ zc9i{@wuE^|oPPh7WfSjW5!TOYNAXj0KA?|vPBchgT#DT{q4TeH^fsj}qYt4@^v;tm zC(px0=#6ei)19;x-1`@u=sYRSA%4Inv^Te7{C8<9>HCjo&@@-7qi=hQFgmIo?bp+C zscVGO?@{T8+>-}I7`Uz-y|rnpxGxvZp!H4ZYWiX=!kD4$n0+zrBl7O!M3YUbC%@l{ zFlcQ%W}i)4L!Q-VFeFxL;Jo4@bRQP-cyCjq=2sV19ZM?yM+S!)}}^N)Opmn}jjHhTXswbL`E2a68RIt!o0!KMHL5%=G^WZwVP1R8 zXd5XM6ZeK1C86ihVV9ej!vixq@&q$|UZFUBacepUxApeX!u9?voChXw3QjN}|E);& zLh&>5L*(_k85@f`P{>msChj#Cs^-YciDNUPxUB=7GW8Mq_^AtZpASFE{^e#gnmSOj zTz!nZ&%4mkLteqYZDut5+<}e}>Pq$s0 zm@%fY107SgWtmjGuGegK;t0w7kvMY z3ms2Hd`W$U7Qa7;PH{h;n~#z=J?P${_=>nAEq-%EHPkhCKE@pOpzML-G;`c&LDOZ? z8QurXM@fPQHQN+U;z}*(cu(}T&!E}!(R;vyb*+lC#9d**2&d>Azl#T2bWiqR#a)HV zXZ%tNW_>9-&$)kU(Kz0N-U7u1p7*g}y;gLQKE=()tSuh2)hpc8x6p#(Vy^nA?9_n`Z-qLw_;Eoj{r82zEgzrLubBi<|vwv>vl^Sk*(i{dcPb^kq6++f{ag0@#gH|gsyTC`_-P^eMd z;$9?J&|wmNLq6-YnBCihE$NDHsjsC3Wurvj@jLidi!B)*v>#E_^W9_%3LlHUryqK) z-~W0rBvtVPbN#6V?K07i^s`ornmHbH?ol)_k5Lv>eki)_{~c)2EApW6HN{WVce4bQ z14MU-b3u!aR1aqFR5Y?4Zo$TE(OvqTp}p(B$8NMwQQRXxPYGK4ihiaqC$*@I^PtJ1 zXktDR3r1v$exVMH7EQmpF=UM5KIfh;L7}^-nY_!j=$PO^)jCBB`FvA?EpLfh$w#S0 z_gy#Ey{Pz=bC;E%<_S?7bKa{(_gD|gbc)|N?_vqoy&?LY_tUgkam$TC;fg<~GphuJ z2c7>UuWed%4)b94GKH5pI!n;;n&>ayPt>BV&W(=#ioZF3UI|9Db#5o$O;h-;{72DC)x$9#- zB|9=vkYB~XHBp^>M!2`5kleMi&vV{s$mfR?j&x$kK(L1f{5mIxQRjQ#y!FL?p>JuX16DO z#>6j1>&+W}rQ@C=pT>RYez(Wd)IaY7w6}eSj`5Sa`BWC}LtU>P&yaWJ2WWbw9ve4I z3S{56`_QK8@gJYEnIE90@jEo0iS5qwh5{WB*G%SIW@4CFoh7 z^$j`b&Ag4)s@Ugc@N!RG~E`ER?y`8_+FnM&sF}FzWAo z0)tY*`m?@eK%1l)8^1~#!2Rf`LW44FAoI9oKwbZ4l$=bGu>Y?r$-nysasDL(%KA2A z*72lp;{R5K#_0nF(}!~gbo6dU?~$Y-+@H28G-QPi<@sp?>Yi;z>(L}BeYjVJrYT`B zvfp7qO^;@@?@5wTM?)1#rVJRy^C|-hJ(|(ID`_}=sINjvbeNp^pEO`y*Je~%l3wDR z@2jveDQpCF9WtQ3OS6A%P8!L)Z&smU(f|eSH=rPHMq_bO1oOREh0#_0UdHJLG@0(B zZFEv3eOy?D-q?Pl$ZMwo9RbZ4QIHfxe=b*H(2RbgSx+#aso*{uLzBjk|J*8cCx(rs zz6l1udH2Wq?`u*teNk7Tds@G7%r(-0S!?fOeXpePJ_A#$P%<}s0`K=1pz-%Mw0@W} zk^0X&P?8k>3iH`lfEB;Dp)xmR5_Nv;4E;Opz~~v_Q_xa? zS-0CT_6^6r#5^V_o=7=CAZqpo}Cg$9Y-8! zSB1ZZBMUHlWg8lLrNooB(t*bL;nUf-t^h->wqeDBlmwnHu0gSUNFu*yOCd_`dQn(C zdj`LQFKRGrr8J5DjW0x5z88hi*{{>5xizSoJ0zKNMipYqN8V)r?{2n|e$1}Hig#si zu>Yk()U5RSy_A~5{8DPrdvfqh*24<1Vwo2sJgKv|cS$u^u~hmd{T)(>!V)h=yHZoR zztd|lNGF}mIRgvPy3mUuXHr$qGQTN>`KLnX_oTHGCd@DlPVV{~;P;(lz8;a~6$R z!`^28-OZTQ_z=aT(zUz~abd+1!{&2daWP7Mc!;u*>F*G?>MTnBk!3Ka4aHc0{UN%C zrZ3>!Luax6p)8Yg3W_nl?jcqTPS5i9lf6q{ z1{b69Qm4fzc^hT6i)gZsc#k|KThaS&r}xR@oCbBDT}1b;5leU6}5~!J}yPm^?>EXkt{%GSuJLrj9S6D!%I<> z8<0a?%^9dnuSMr$qgFDX@ug_H6rkhW;01ndwHSRaGMD}~Sg~Sc`iyFe|PWO+Q5DbFV^6(Resu9eD~1P-m#cma}6Dh!w?{1s7b4BX6H3vxE?_ft-ps(5(Y1apkz1%|yA@-k0b98zx(rm-T*l~AktOu` zp%v{P1z7mqdNQ!0Pc4egQQNp5#a3(y4Y1OOMHzmNU&e^zk)^~rxC28*Kee4c}7~#-zSS$-}rDZFhe_-I6KC zh+BOSC6k`3@ZbC8D31T}k^ct(0RR6i(|=sk<=Vh;R6J3S_R!dpa_W*fDe*{YM=DDy zHbx;#Ah#JRDxRoFsmQ)KEObc3W@6D385JcJwt?6~3yi@;N-8W=O6(wPNV@5?&7qOm z@tl3uU+>rV{@y>X>$<=1oZ42h8+&GrE^vj@?hng|A zb!uDCgt0BCPI6=Up)`9?-N9y5@0;4r_~k7qB)YNXskDxuCGE}VkV+kVZ`z9GC(mI0 ziHrlB_eC@6X39E)cJJDP<^5-{a#h+v<{xOr>TYRQ(6CcmQ1*8>M(fhPBA?HiG2!&I zuY=|dZo#qHZfwa&J49XTo3Z}qY288H{adhQrW?!a(!OEd@6D)LDgBoC`nOx~ z=TZGe=D&z@s1<$g83W9-m0{%GdQq2}>7p(hTd`gt8>SBFW$3%)#p+8Lr||h!jE$3xu&%ZYYv1(ZSYqZc z#M9M^y}dI|lh-?CC_CfDoO2mxsC!2%w%jUnQ@01o&{^Td%ApJoeZI3D`%`9}C9V}F z6s&%fa?sKqu-VPn{!s1F#4n)3mn>OobzEj z7Vi*+HT~B`JCxXaS-_k@3x=f)VSlPeN^BVr zFu&J=1F9kHe?s&(@>rw9(W3$;9<`u#%24P#A?muI>MA8h9uctTumwvKhcQAaieP-L z5^H}FP=3UMeWD?ZxL0(2(A;b#s`m(3dBqYMzi$Ywt3@{iO{h`g)sKp>>!1aNIYStI zIqH9cX0KGDuuDMi1S^Uk8p8TDqDkCKg%bO}5zyOdL91^NBjZGqiFc_It6vu|?xF>q zQ-&}$5OpK*Z&PCLK>_>ETX1aJ5SE@6{V)4{qr|WS0#>(MP<^Kpv$Uc};;2_*(uN|; zZ?j;%cnGEUh;E`Tb5uC`rGVvb3yS@Nn7>3MqAt%WG4FE$i}zWuvVRbrVo?AI+BzE>&n>U#n%_{xH9=LgXt zin@h&nySX60s-3&STNc#guZamt(-egiC32jSp9|t>kkcL)p*fV@>r!r-zEX`f3;w3 z>mZiS6-k4JFGvX)Wx$d58nO9+3lpxFOe4=Pld)yF0T-AX(d%$we%Q^^iSKkWX1!p* z$nA|NUN?+7tz<^foZ(~~TW`R8QzItcJdBm|B(k7|CzEl3-hj?e8__2o#%7=RHpXvO zV_ty)g@^W{_}gL3Ssyi%x}8YIntcY$+uexfK^JO#;uy~RG#TSI8A9LXdokYb!m9OA za?Y=#De{<(EkNdvFy7)86$KC%;{;w+9|`>_N(}I)*VVl_j&_H z2CO)C&4oQzZ@z;%ok_-$OapeOHeh_83r8nO=CIGfWUS6Gpm%*E_C%b*zHmt#@3Au( zol6baGGfKjRu?+PN#;_g9m!bxk^zMwD;Bo8Ff~H*clvml3a`Fnz{mkBPHJ_bFjq2< zxYJdr&N1NF2`g58?!suXB%VB9RAF?E0mF}5F>9X-$9@stNq#S=P^ULwUY`|9qg+@& zU2+%i`%x7-Qw$h))QZ_(yU=`EJfHQ?s^*9K)_^rXSm%f8?ZQPK@q(be52!F(XTaiL z8c;5AVeDn`-PB=`3KOyo*mt-AM+6sUpBDdv_3Knvo@T(Tml|+n!Z13{iWgGPyH%+B zdK2buX~eu{7Y>{eCy?hl6%M>_!2FU%O!$8nn$L>wq0Y~%Fk)E|7QEbu*56$rlO^}E zZk`IIONuaQb0b>)E({wH-xoAdtHRtDi*T%~5yK?In0HFNh@!Io=Dee7ygF*Y9LZknergzeN{MwE?r;jW~ACF#48Dl|cFpMRSNs?JNn1T`K4CokXMCXcOOf8nE z>Dv=2A=?btJ$WzI-ZhMcS&|g?{WJx=`wcjH<6f-VKZ1EjraVF&7N%m{{V!qOg?*Uh z9Kq&^(T@fd=cHm^-b)yVPzZx{cGIpfY0gJ2s3Q^5CL~ zX_>@7M}yAijhMC3hHXtAbPP(f@NXKdf5?cHc{YsQ>%l6w^s%5#SJE+eu@SpA*s$+Y z4_c2&mr=jp(lPpeBbMaau(aQUZ8uEQ@{Z*sZl;lf@JI|A+MPpvBWP zn3rcno!N$!pLlR!{Iu+#J<~NkN2CVxW*Bj_z=n|@crfCw>1&Di2F=>P`Wa&% zv0?GE9?Wl%=F;D%(y{6mBSsh6u(r~Jr6;88h-H}FUnWU$YZ@Z1Kpo*!<^0*>@$0@D`Ccy zyr0K2aA4~;6wbBaqMN)ZT|46`@-Sv#T;nz@JkWw&lYLkhAM-Tz9KQ^+7nP$_`z4MT zF5o~~Og{0tv(WKX1&Rml7&gI=X0`ko>V8p&NmUite?vP~O$=c3GxGJs^|lr(?G-qB z!j8Fr_^@lSd_z!mt`-Y-n=tj`cFdjW$MC1+1wqHQYf;u#ftp@Bj$ZPG{y!vtmU~#G zMd@}E%Kx-unB*d6uaQ4Tes5?oX>SGQcH6OQg&*tQmp{+?wR#lFE3n|29TV^Hqx4C6 zA@5|X7QH!UbRM*$`K%A63*|3x@0nVx-fu$TtR1VO{1~s7Z)Bfh?Z&_6p}E73;TL?E z^bh%qL0dAkxJY8gfzx&@kH3he^W_5fv_*@fXH8hxWyijgK6Ho6i`Z|OHe^i&O8?!C zd2xOmxLdv{Xvsz`PWsb?Va;~bobZMI{~2ST50bR#ey#$mPunqKoFDTP@?zfW1}(h9c!cgSU5>u#=J5uT60b4d(Mt^`+Ybv6!Qx8iq~RIm;X98IKj$%9Y z>eXZHpJp7r*n!f70A}|oUgLf~&|~6Z^J}4dcc3*dfI^jG2k)jwkGhLyob;pvM>GK} zeL_*mdpM%UmVg=6=Q?m~K>+jhik_6Ipk;?<9OH;f}{f_Ig*lNa+D;=nLIDld66}yP*H9aPtFz*Vz*A6r<31HR3 zv)>8oT&c&xPtDkOxdY1|2%zpsMGf_MRgZ1GX6*j914lLlFyaBlyMN`2njg(r6X*zy zCj_uygW^5ry=E*t*@1P}2e56i;(f+*^w_`Kj9K0e99tB?niYy#`l3XSJw0YD z?Ce1GbpezwR(wEx^H$&@%?>O{>BRciE@9GFu^&?RUmnMT+jgMT(244UmoWcy>~7xC zgV|XB$PSE5>csAfOW1NCwvM=6k7K`d2ae=-qWkqrs5=$=5$|hUHae9%P*~iFak4S& zSH*qIxOpYk@7ak7|LQ{Bwcl_gan2|7)vA>kePSn${N9E6nPcd9Vop8x_sU8fIkFQA zuXUm0mNBf_JZDeP@XD3{^*;ar0RR6i(|=seXaB(QBhir%g|@ZHk(JfRDx#xer#c9^ ziI$e!J911VX*x{^?RHE}xtm%YoGdMM5DS^ZVu!Vs#176Tb`WC6${cf$_WhpMx&L}T zKG)~-xvuy1{vi+uzb)Kf8zvB_FYD0o;2CCw`czxh%M#GTaR<)t)S+>h1@nwPHCAOC z6VPy?(B^3!+P6Q$s&PIVtBQmKjQybyD@;0@ZWf#$=X1cS=f(t77Z;-6cRKWa_zVli z_#Cv_Ju?Ag-FBe-jt+&67EJrp=MejSl7Lagh1goB!yw}`bRFwcYgHGXfUzeFQT;%N zzU~%Gj`lfhRh*W9n*2hnIHp6vTniSA^f_X+F)RUtju)cgSDkHLXu+s*pKq;3uS~## zrG;2@Ooz#>&(QmIpE|4A5eb;My%6Pk9XdUKh81&sj#@RPCZJ+jAqG_Hu;S`7G!FMU z#=g@M(05xQHeA%9^w~4)p5b$x@0TZ_{h~sYmg}(U{4>n08(WV%mY_+!69xBwLglbm zDBTrsg6EPXj2`CrN@ylBC0vE3Q+ zxhxPho8;)ez6=#-Td;kq-C6o(Vj#9ImZN2q3RR{SG>GkfppRsMsMsM#t)dLor&_Qo zqPNbf`OZZ2bY6k3eRiXE-X)#wo_)@-|EY6g&?)4u2V?*2rS4_bjv zXVqBOM~}+g!XK@=ZJvy6UBdEYLdqOdj$kW9zpm*w}Y3dcLkldznMC z)x7(`*!)WhMm9Jvvu!VhHCu96~DVS?gW9>RU z1`T((NS^nEV3Bl9};5XvC6pFG3tFdZiCAzB&*xc3sI`{iN41;3QZO@}Bv7pI-QCpqbn8Tn@EZC5a z$zGLczteyf_xj)9`|?n<-@6)vD)ynJ$$)L+2i(NnVQ6@mj!KV8+xqxlQPI}_cjmPs z3@t0uQQ=XErar%+v(U-NeKb>1@hBa;lJ=pl$biY$``_Yz|Ab&|NIFV7tI#y!I%>xb zx^30z`ZUbFl!1ODs!+1(I_7K{c!%?kzmJ|zGBEqeH(2F%9o;?{*iIjIO~u@E87R|K zqf~tZ=XW~awe@ENR@5j^`b{;en{J@cZSXzv^l=2**DFwXzXmm`8<=5qzR%n}l%V@B znb@(b8dX2uzy{aB9rTwd0%HReHp{BfQhEcses_MrzK!8FBQsHUqXzT7zk!X>gCDX! zR)YF9nW&vygY~;^pr+T5KbQy4a5Rt1L}PI^M%UfM9Km1{ahwUq=2@B8QCN+Vzi(jP z@6L~`mehr#n_7X%#nqTG=O&t7I{(Rj<0L4bo{7G9s?ij0#Gs=to#g3Q1a@D`!T{+3 z6s$F(Uz|%9_s)+%_v$R{8hQYoV~l9t@A8;)K99ip0;(S2P3fShb+wYIDp~-Mhu(d@|5$l zBQRrU77F_vz>*0@G$~yECg0ygV9}{8wC{TWGd?t;UgGkMcveSXUB^1CO|L~+;cbk) zJ=9{=wMU8t9@*%(y%rT`Z{z#{!=AJ6xanAB%v8PiJDcwxH~g)Z)~+HpA8qa3+JvfA zYQ^3oDOI!fj=h5_wReit-fC}ZOA#?swRaIKgvasx@I3eZ51c=o$NRXh^R?cuCSWP+ z+sUFu`e4Ux(!UMaiPDo!so$929!)octfcojw)`}QidOe(0p3q5Ego!uwt0q@eyuZ&*0_CsyaI#Z9I3A)-fBW zh}`z{dhPGSQeT+_jX7_|>_fy{^+dDmTzmRoaOptN5w$6@xRc;NvK5Q1gr~ZleFa-d zI(T$n=ye%bXSzbk3jqMWYIT}iRDN4-As}M>Pe0aR*0f>H2fXqOBwt>4LhqSfOItr+ zn#$=7cFOye9C*hZ9?Nb965gOGTiNRmkp%^p50}x?2+ha+ej|Vy@>)Q#s7kp_%tRWW zML*lSX+-}lpnfe!P5x(z5>O=S&d0dlm{Ga&_J|(&ro6G2(7xKB$hrdHaW@;wn_~YI z?bH!GW`I|8Yt75|qUbVld7=a_^)aYXd~0T| zaXJs<+dw}N1n}P4Ria04I2#*R`kZbzNS3Hg&{g@z?aS6KR4l`@~ZV zzyIrL?shIGqx!7_M0hRk*({wl`22^Ks5UKm{TZG>)PNV1_d|ItRZFzuDLL2emq;|K zOlkQvh5pY{?C%MXiy>U1zu?r8gK^GY1ggu$o1#>mjA0_&^w`cK(gBLXF<}n}}N)31zu${$!n&yswbvp2*PBKd&wAFdmRn2qs6Q?E-%4R1b+olgy0y03qH_j+dJ)l&ZtP`p` zw?t!Cd&Im!?STkYduD0p3DxBdqJ5Y9jJw?V8OKq+kV>q>%S4X3~TAIzLuI-;PRoI{GC(NC_NrtNy7(lRqEo$FfyBa>X$y zggvXzO8XkqQhpmBCNv5E_l;0&Eog{3cpf~4cY8c2CmX$K0z}Yn-LZNt2=w_H5c}Vv zBBWf;tY_OVZYuq&(+i7B9yM-3&zn1r6y)Xa{&#LwM+2mwg`W;^regPc%y$Ap`&&$- z#*N}?|JYLVKJ?d-ld~o`<4v~d$sgbbVj@`K0Xoka9`w9lXFNd+wx>188V5g3$h^SCt z#^uVT^=`}CsHhU~SZ2@zTLuD=3+dIQG#NGS45K)56S|rY)z&0qkX zTd^ykYn`Ra&VNk#Za#My^M1DbO!z@0@hGxc+14!Blgh%vKiX{ESdOaW+i0zTUgR-3 z9ms7?Fzot~wvyhAJ9ZJ?JE%$rdX4aTiHX+e$F=cIP5MxZSGU3{cja^sr9QsOI`}Gb zG3(+PboUB3e66vSmzkpDW=m+=eqoIq8Kv)No+LYu&x&}ZP&dBSRx5Dw3c!ExIz^g| z`0eokZHA;fr8j>YtkN&2XuEVErRIEqq$0SHX-!d3b$$~h84tY{rC;{>4(@B-K;xrX zz4ChJ*MTaqL60BY+s$;d9aZQRF48Sy@?XS*Xy6ZfDZRwwq%(VU8kOmMwnvbOG<_QT z(OUesm2+8j$+GKTN4t&E zG@9DKr|R*JG(zoBwJnM9l_ZZNY}!4=)Cc!f6_uExf@Haq&x$@7yB|=~T<@!17&vdY zf1G;ucV2>AEM2~*6?6?so{w^7`+1X%^NoTa-3iMa9d-CFSrT4E1uDt)_JQh@LwhyF zw*CHHBsqC8^TRPJ5fHNq0=$ER4#tnVFN)k`#Amt>)T&mC4Zbei+}Cuvb^QEwwrsAi z)+>*|g3r-uvLqV;h5UL|er~gB+-4B!mnmj1=S5B0N;H}o9!+H|VipS85Zm^=xF={a6q%CcR%(rK~sw^jx`G;99DeBw6-x=?$q)1RoqzV4=r@jJQjj`3&r4 z{|^8EWA~K%O6FtDbntBqNh%qw6T{C?Zh0~N8C!&L{YR*xqBso=F>L@h_eZP1{)Lne zr{0{8UIKWLWcnv2Vd^8E3(xh{)&H5qsE5Tx`MyARV*X!!U202itFvm)T=jXfc1^p7 zu*!2c{{3$KX*7R&t1F=Js@k02Z#FEmTxMyH98z!LZ)qAKHtDJ`&P^(=z4ylC5bZPH z6-?!Sz5#9?4kI6C+5X6Soj008Tx}CJ3BdaP4m+k|LASf@6QvId(G_0J0I=D1JyA0h zW0frBTWxG~HkES#EVEtD&tVq&yF+w>pg;hf&CP*1EYn6|`ZvYC^y*#bdp|hQ*)7q9 zWE-RAo(p98{o37}?HVC@3FRy6i|kqZdFbMS!5#BS+Yg1t=m%nLWy_}<&C5-fuI?ra z#R}EF4^>o+;2%bvXZDZp=)CNw3y!*zYCiRfjOEWpN}X~#d7Cu35Sun_7W!d`ofJ93Qs57?enUlNt2Gaw5kV~gYO{a`J(97d$)SgBYTuO@}Of^)D~A! z;DPsy?f@5q;~Vl)|sy9E-S3yi=MjJ3t`wd-iRE5Qk3|264Y$Vt;4o6v>A(Jj6`} z%5PJr8&IjCb6k4ck0z{R8Yn&PsGQdCUZhO5GB~B5+n|dJ4*IDwB3iFFHD>dB zo~yAn36KCJxt;+UWl&aQ;_l1exQbcjz#}IOQ2Y3SzEd- zLCa7aR$Jt5*94n!^+c>g@8s&XnI`p`&RQ>ug(Y9AwnL&JI}aqw{4lhB=LYVxD$GxrtE7Ro<|Wmp9Ap%@6@B=8>GGG{B=$g? zra%EQ)OwMV0hDiukgP5(xD1fPbyyGONR}?XFAOk8v1;~+R};XXvx$C8Ifs6>XgX}^ z3&NnPEx1Dw%fV?b_c1yCx9vqCjVLAW8e%yFtq05Shae{Odjy!_Yvn#&i zVkcEO($SI~by%kAm5u%HSXs$>I85J3pB6mZ>JJ051C{WyFQ!E0X%Fg2LFNWY%Cx`x z`kg6<=rQ_O6Qh`{8~-u;G()%Gx_7X&QZVj)q;a}=Qj_UUb4~yc8PlzKcSL8%)8w3g(nJRz1>MO`{}b+uwInR<%^y9v^AF@9LlGk)LJYQ)b?F*sh}S8oYz5 zG+>oLpvqAibm(eQwMcb{cTCwh093#}?u?9rwD7q_I$=oS{>uwsATQ44y+=|tEqp79d|N`xJMN4fgl>@~ zhcCw0j?IUBb*qy;lzRQ_VN;3CHQhkQ>9MjWGvf!_B_J(is6s(ihnUD-5IlAruGQvr zo*gxOXB=M~_iW$FpX!@Q_{8U0AN!3O)4OeS4&K@2 z6b*ib<-hQS5aG@%hX%17^kz#DCDe+O$ro9f_GC~};O3FCnL4$danx;hX94~GzDZJ} z<9QMOl=I>yxzHPTlg@zNHcxWq38>wl=F~T$#3$cuO(-p9G*5{J360ceP2H|e`Qu7# zh)_V|B$1r}&?kqt!^lE;WV(kPc*euEP&`z3TD<*4g~y8`gd|Bsy&Htb-gRLyzhknx1qC2W-H{|`SRxMHYKrY_jiK6mN zAI^}B`}kHUXzE#fry|z4zJg$_%gJjp|IGU*HUP|uirlSzg&=^V8o-ASk1!Shi^PGi zL)h(@>TbkxC8Ei{`FFbFrj2b3YeFb3`ezmGflNpBNf&7?z3`hPe@#N~&E}#?RNHv* z)|Ig+a3KWrgZ92vDNbaly}DNJz5(s=E@;Op6o4tGPu~j4y>*5SZ2I}{Czf}&<{63_ zx4Zt-@E$C};K}U+S_mLbjbP|E9~rO1q=BMZf6=6}?)`qlvBkgm=+Q4H#ucq?4-D%0 zgo7OU2AQ#)YEU|eh&7D${RB%tmVIuDW_Ma4SimGCv-qfOi16{UrOV#ux!KZbTa{k~ zqSe7{@3mN!8uuB~v`$)-@zj6UTW!6#%)B30?mn6AVqIm6wK$go+IGW%h7+d(+qsgF!*Z{{q{vl~u0~v(b4dYj zZYrw_1@<3`dKyBY+bqqaL-GC1_97#4Vg)z8Vo}3~)(+d3mMhEU@yMpW5a{eI{qv4+ zx1Ke&uNS=oXde2S3Ec#S;AItysY^MW{ROxo2;6M2 zA~tsxGkE^s^}6%by$t3ST3{N>&^F#j)?wtYp# z=%zhLDqFd-yotnlv}P)^`&r+{BdqbK{*r`J;p-2ShCy`PUOV=h-MaEG#5)2=W&`|d zPW}Ju}cRO>v;({Qlgv+YXoxTPUoQ1SH1i}Px!NXrt|)JVR^ZKC|s zMOO_WnO=r7%g<^(8-Mq0)M%ROTRauMO{0CEe>hNA9Tp|rWfH%eOOVys4DNHLn#SnJ z9sc%!1H`x<@wa^(D7jz-TNb!;dj%=SgKI-twfN4Hw!J3#Qv1vq*Ba;p^t(UAl8tw*R)k0_%$pOqF4WAXs6Nr9O2P1C%K=pX?dP3MTc%Zdfne0+;RkcIap%$Gb^Tl3`3=dnI~z;`YYgV-^Gl|uWx=ubmKzC~AN=m~+}b^MhYe9?ezG3>U< zHx_AC>c3>8b;kuG0AizrWatmdS3b|9%yncZ1An5N<3a{gP+ND0@(l-iTK`q|m{yQJ z(>c-R!_mZ`q3Xv3*R0dv`|7z-l!=J+54wlDG!F!W9^Z$j-h4K*R-UYX&gscbfXs~P zWP6e!cP*-(7;Eohq_LidqXu!%)i`~l9bZ&xFxTVur3>aLN;iMg#m_gm9-9$pT$x3_MmV67wwzZ9#%B=qc~V*cFbEln|MxQ^dr7%J3d#BBF$j%V9f5K7P<9Mra!vrinXVIUSJhQ z8^1#3W}N(-nQgAfttKR~*svnNtiNcIhN?Zf$JA5fnXu(2TyxzXxQ$qkWGi2tX7?N;P7dHPi(tpgQ)VTBu^2bX@e`{m2 zF*;kP{|hj(_VAT6?VYf(7<}OwC}j)4UtY(V9A0#i0!wlgPZv~;1OD?AcT-CN=^yqY zIJR`^4ykyPH1ZTJ#rSGOKF{4<2mgPnddkM_kX!c;>ecR@iU?{d4u4c~Dx0DR6|u;# zG;6mf56M}k3uCgoV+kUhc)Z^spO*Ybpc$4G5vCBQ{%#~mVOl9hSV2k&+(?od*LdVp zo!ga{w71f6jWa)*+^VbP@hygI>{v5p|5Tz*6T?NCVkNoyrh;i~0zW+V7ta#5+G-vt zx{zW(P4e}AkE5W$FGfh^U&(z${>vom%jfSMMo@^B-6~C%2KDmuc6}?nJ$}xd>Qk_& zLM<(N6=kMzsT5Ti3@GZZet3GSfe^e1%4_v}MMF;tTK{ch;VNE;)ytm+Lxo+>iDEpA%-~7}pS6b)iScINW;CFzk>#rK`hNsGjEZYp$Z+Aqy=mgSa zzlEFy3-pR#Q;?lW*qHn{VvOIhc%{F>qZC{A@Khp8xTJ?GEO6w*_Fw%E2Ix@Rc#Un7 z9XhqHa@&k+XLdUhX<>|gFMaN$X*@{z6c0S*#Tri4ZSdxhrx#8WC>4 z7AD#9E>LoKiwp)Rr<}4gs7M2Be*4P!16_Ip{NgQpreBT8_|Ol?H^WQIi9J@#XcU7n z$*cdu-_rc_GA0+dIi))C0x-!Z7mlh%()+fNFNbMJexA8Dz_kXx=DcL<`M!}$zv43Z zN>z>jY+?nr%9Ln*@LOw!F1zyfFPmzW0139!80Io4s1Y>p0+h=8R&bm_pbQ^CqfwFm z+HK^3Tx}c#$4(d*6%X=hCI!x+J5;(%Z$tvS2+WQEYkyhoD9`X31sLQz>bfXxhZN>QYO`iOI$Evnnv*=s~^(O{0f%s zIz4#)7v1(uB=9~j%m3PXMWhF?D@zxGTT$9Gb!VQ9CpY%eFR(tW78u0s#d06>D(7}R z0GbiT0%*q{Y!@s>ooRmq>*YLnA)&E2V!mV<7WO{Y{!*1kML_h=KfdXv znce+LM9`WfXKq*2nw2(2!3s8M?X2`n%UM2=qO@xD-?k@*hX`%V$Tv0aB`;>C>*_)~ z6dCQ7-#;>~Dy?4Zy1UbiMcf?BWs$u32INX9*Xr7A`8HQ=-P3yrmo(ErG~vS2Q!d^K*Wl)IF~cjJDR6mKc@ zUWsd_!sTin&oV_;>&^YJl|<*k+>(q6%p53Dom?8FRjveX4X+s>MyeFb1rze2>Xx!by*Fs zTH9Xm(Lvp&YySA{<_7nC$=jp^Q>-*P{^9bu6!yqlcr&ozZTeh;WWnLUn{d1t_Tbi? z3|-cHW7NpKv>dNTecrZ{%|q{)j?nq39Y41hfIR(p-F&qIQQ$T&=`Cw+w3nTYKkHg7 z&n#CB*Lhmli!v9`Dmg2RpWOFBU|a}^1VJ_~O@Q*MbMS%oc>sT0C*|A5YLfCi*-)vC zjto(Uu5`STg7Kg7-X4iYNx2Tn)2IUvfv6Hfo8NQ1{Kl2aeTkMd4d|m6`PqEJLZ*=- ztEQeSEAhl<=SRPX3Te5&Aav@~<3XP~GCWpp<;Qw_Mr*xWN#LobWCFVbAvV{t?l}w* zJ){QP%tgxSsg|%V*E`mWDWNCJPWlMrD&?I*OB(&L740sf@TvKV{xKZ^lE5~O+~2b)4{2LxRqJrRTq!QE2a3%MSsv;C|+UHZ@FIbOJ3^;q2c67Q!`!%Zr#4+UN)GpjI(>%-+!_1;UbH+J zA1aja8&KvLFIlJKmBpTIoiy-Ssk)Q*_Rt;^3+YauBD>+J?&p&sb^VF`A=Fu-@{K$n zz1RSc{iz}cZ^;GRCIKFWs}BR2=7l9puoW3kB`q{2s-m@7U~3yZXj$`EA_aNQOG(y^ zU~%?sFMdMmG$Z)?lmDSQ_w>hr9SmVD9#*QWyADp~@*!~@S{#7BfVZE~8BxDEW)a^g zt;Z}&Avs2M&mhouia~G0DEcX_CjzvJ_XETpQ4juBue|uqNM21=(7L!I>Bsa|c;{MF z21C;K3`2%pG7o>Sz`kcHg!^&_q)C)2WI$)> zgu4wzPi^i*mtU^r+n});L_~o);kHB3pKJ8=ool;kqTJ*dwu739qT{1#ZnIV8>bC7j z`W6sm8sBCM6p>H;o8#p;wHH6@2Yj^l&?QF&i$|#8pR?dI84?LcUri|*hL0pg>CACT ztFcM<3ESBa*_F%{{Q37ZZb3<`-G_sWh2T|3uaQu7|}VjQcX8A1r+0wM<~`G*Nx0uY~{L8E3pGY$lYEpK$*2%pUiL zRTKi?C5P6hDIU9s7k*+WwqL!dR?~KuR>;{8sk8l*pNwMB^*R^L()yz+Q;z5}vaQRv zalhNGgWCwW+c%>=zX?dS^iiuiYNwf}h_8%O$v#s|c&^_~+qHizQdG z6ADYFGw5E0t?*RQZDRs-J+H-?zMbysR5SLdFg3?xT`eE+iXRM?mApnvNX5CtFJP(5JH1ySo-_Q1m^$t1tD&BvHbwg&LJOBaH7C8uu(lXdvC z`nY$sTlSiVGn#QRe)gQFA9VGYGfPES_BIKMMcplgSXM#M6`n^$Nk(8PRYFRIb3Gl#v!4NqR<~4KTk^*oXR1nt+ufEOB@v`I8XTBtp^C5 z)=YP5m#Z4tMfF&FqC>qaQ3bMH8MOT;fEBow!0mR?Zih6cNm#)g^v!(Q5^)cu>hK=N z$3ZP%D%lK2e^c-L_D&^V5anbAmyeAuj8QBf&4qFd2(|xHqCi=lgvD-diAf zOiarU4_9FcKO|y*KDseKNA=A7g_cY1;%Iwr%%FasoQ7loRrEEqCxr0ynm?`LemFfS z3dXI>YMh22@z(cSop$lnZU?cmb>x_K-eLj_>-+IDMhx*B7w7PyK7ouQiO{g+zpnf$ z_q5k9nQKscCm~Z1r?9A*?3=t&h}#JYn&a-=v#LzZ?Q0R3a+=-`-mQ2j`4d6dfzrHx z;~Y1)`$z#2PALl}ng+@)9%;GIVTuxujhR`OlJe?Jh22*l#ia~{1FG2)m6s#&+p=)N zggoku6@J#gx3v95eUGc38XrV&JO*9c@ReEI)-3$|C$ss=<3;NXo%P}rtv*yf@``E&e!rZQY+(0o&P_YZ zUVlbgYEQn0`M{lT_-07-ZXe$cneFmWWC zaV*FzY4@8QnW5U@u{oFOvJs=c%Wp_f27?(jhrDpKv{V|_p+c@`XzIV$j32(T38*`4 zpg&AmcV@GmO=ci%%h$Qw5y|j6#qhHUe@_#K!FC$?7hAM0gLQn2PPlkh=d=vBe{t&{ zHRi*T)5Q!~uo<0bm;v1lbhR^Wq;~)7;4VLK^D@Ithx6)N;O!U4n|h)(yKPYWl#|$m zYYs-t9oAOV6EKaH{PS^ea4wMRas?#S+GzjT`Wx%4rCrX*MVo8w(HG`XMo~#IJy)+# z2I?X_tFUYI`nH!=IICXnwtzUqr3mx#nsyku2_x#;+5ugDXP8AoyO3Q(Qs<4V3ZU<- z9He90Ez1`^CreyI-P)q`Vk@!9d3LZL|E|MN^HL#d9Ykw~KH$tYhKJyr5`Mt`H;7sz zQS^}yxU!95l%|t&6R4Va%;r#WyA&(_{BL*!LDTDuD);>h;~$0jgzjM7c61GNdo^LbSU z&RuBo>uKE+*@>lnxj$pKMLZW#2|ZiRAKh*>Z;j7>5uW{C6MG+KJ;@og%zpNAjtR!d-`3RZl_SlqQkH9 zO>s2abq(~5X00F{+iN;^=G21YBa#^bL6x1wN z1<+VAH9Obp1NUcy8=|S1^*S*n8XWyi#Z?nCS=@zX$4*7uQ!% z`J>6}=x9~^rdAhcZFDpyV2!hdOlMN{>W^XSz|7z7O)X}iv`gLlfb+nyT}&LR#*{3@ zvj~TGOKNjk5@*9hm*T?ynR=FZgNNJJZY-K|%|eFdot1m08;$c(vBX1zz}31Jjt~5o zR^rnBnO=CPaS?UNyTrZM!^l?f-@7(mJA&%!s2g1qvUhbGz2vewF>z4^rr1y0ZmjE|pd$mJ%Lp&^LjrULP0zL<9NSd}BvE6E!SV};*XSd^`0&rG2t z(ZkJlSQ#t%xvX7}d#uru<7Qj8OO5id;AuxK4 z1XaMe_YiGDLi$PVP+8BPQhs~t0H8ATqTd=Jj_Ei=688MW+@CHp zI-5l!KbQKX!UHN&@vePZwfuIr1RUgwn@J`vvlGDo%hy;bmk9!Tc0=M|$l_By>S8@~ zPCVHPa~~|+*n7*L=|>PLf`Lq?5qo4NRsYpNn#9PlatZsz(neEiU-IGIP(k(;TE1%(rQ)Y259X-cP!8 zY8msX?=0i8f)?1MVf>CceNFf${ORe9c7gVH+Daxar53Ceze;|2q~wtcaG|#%BU6NZ z!FGRGlB`WXMoxYX@{gHsvnsnLru|%Spu$>;Q_!`0HGJ8Hyi??|lwNasBjabogEk6J zc;$dZnrs07z@Hs=rxj#~1;?`FdFB!L(8rg-Un?0dSoI(%t_@W83Cw(S_Y{Jrc5e`J zc+<1u(qR72qW8Kvt?)xD^J_R$&3k0RFnK5VTxP&N`{mHrNOF7b9hCzHOmTa#4?~nz za$D|VNWyg+XlAVq=J%6xP?Sw-(@@kJS>=MAxg1RCYPHSS;~0Vwl1m=_$VU7)(=4#+ zq=9VsN~r*+Lm<_j@M4sYRFH=OtY>uH9`t|@>G@*gzwD~X1rOkYo{&Ly%&hMRo+vrNp|2rC%+Mc9j^bJxoO$oTFx=#HUPknea~T4 z=bJir^d|m_MxAq|7j^~x)ZZe&+L*;6$vb1SJYl&nE$b%`DSL23yQpOcc7IprLnoH7N zeusf3M@*=m7g+b0X#8p@#5~rsvX+y7--{kPx6a?@H=SFUI$fX9IA=-`KCK02aLdNm z;l(|nB4^6!&P^|w^O_$kn|uVlx)mguBXlWZ4c1ne_v27^5i9K366BpGkeHTl)2-=L zjx8$Tyf|gTZ?iFHDCY<`>KK*uFC}ID!%5%~&xq7xUCl@qc1kRbnuJ}T}hxNmX z8YEe%>J8$eE%+)n4)#!~K(=pTY3>}mtywi&!Pg)rHtw~X92$NQ59rE*n&ftSDC@FY zVCl64VaNM#+-=B+1uGngith4R&^efdD3y2FG)qSkl_Vw-YGyGpsy2`NW6mrtVT00< zHysFV!Olg|=v(m({+Z0ykw7QK*@iBfr@5*tq`ZwKG|H+OUrAa(cOTqT0}0`ldf?#= z&Y6n~I6LP*S8P5ztuqP?%SDEvQWZpVo~~03UFoOd%jqj)1rE2o!XR{e{w*cVdr!FpJAfr``AIfo&MU zMb7u4OH&bVO;?41UIm&?c5cs|V+G#L%y^JoEg?LOtOx_`!3<9$^;3flU|wtwqsUXwrxSqMV+K;-VQ50l_Ub<8Ah@llvEKPf; zLp`geJjE*ddjU&em&o!#qAu2T8dBx_tK*z_L5=OhcetiyTo4hEELlSpdAHy;biseRP0f&XG4c^9NZL$ z+74FvX!c7k-9}zr*rtqR&#~mnAW3%%Jch&v2iQv1e?W{W`NcpMzdT zEi#I{(zwOrkxVBU5Br_X-qe;Ct$4MovdutDfHMWpMh-OAESbbWttk^Y|_ zDF)fGe2}|mpoNqo)3!`SKq6rd$76Mmw~Cy~NM64-tzGMXVrWU?mx6ERaFx4cGwpO9 zNR&`n@thO-o+G=IQgD&NOJ+GAmxX_UkfU~wXB? zYOtOZz`O-EOnp?SCVFkLdpAPlR3)IQc5SYk)stak?P&F1 znv~brS>gR&iAv@@GoiM#j_A0Sddyn87gNppXDP-BE0wdK0rV)5>!6bc|A)IMgP(Je z2N`Y~a!vUEWJi45GSNAvp>sZsYo8Z`u-jA)F?}-Bq|f+jHr-|HnwEx|WO^a}eiwuq zIhL!Iql=*P;ULi^8dk2n=-0InFG5rIMNoBD(u({O`2uaW5hW8{LY%X!s`6D(y9*V{ z9O5D5-M=AAD^O$}j>2g=u~6D+;?rOA7GlR+lSsdG8R6P32^e`M{Ker} z_LP}Ld4!2#=Q#$s^aXyf??lXj1WluPyNVv3hYm&6^&rx@7qR&gWT~{ z-?mr~T}-#J?;Q(h>QM+0g-`uid=wShiT3RI^~Lt@^x*aVF_~M;_NFYyJX5 z@f7rK706Xf4DlTGR)dp1*N^2+mwx_^hmPXPIa~62#geU-2_xYu{E|m+#t;6H?vs8k z`jpEUO{+p9AuW96?OXo-fQ$!cRBpEHVWaeI=!pA}RN|g|(4DC=fGgN2dBGpPHdHeI zF87QFSE&n$UWw_sbF)@+z2v|>w}?ZDIWP-|x8j#WL43~zUsK-dioPs!b4o`ZFg(WH zJza^C=8>jODwt${;UMSs=j<|Oa(iw^H?A8X4{s~sueafxu9LG2a9-YUOsMnUM}JQX8>Z{z_!8b64(S+3IK6=t!p|1Q<7xuALx4Xn9(~5k{9K* zuZH)Ve#dUe$MW}YjSUXQIEYq=!tczqQpr_TKL4Pc=s^@XGzdz-_iL!Lk5q5t?;AdQ z(5Vh%W}ohRGPIa$Vml$2UFMmwioq%lJ7&2*{b9H7`0iTL6O8C^ub*ZS@nY~IbZnXeNCK1a0q*547B!Fw@*3Ik7Cqr~yG>1iPM6jCg)%6UaE-XA zoZy8axbvnuTEsd=kbv#QQXA&;XP;mjYz22(&5 z4~BEY4Evb4r7a>89Y2cLC%sQEuyPSKU3Ra5e5L51sWfg~E;gGI%#GT(FfhJMr8wPc zl3r6!&%e4u*f(feB_@PQ@5ee0C{&KpDx5}qvUk)g#Q3t5Ot=iNCcICwR`U_vyeW7) z?8{=ttDHfB7WTv%k6db zO|C_&uc@Aw|6&%8oAa?Z+j7?vMmjS}Yn6RQTST)PR7x8E`8|3i_G~6YAMtOd(DV+- zYt(u(c-K*CvnE1|gQ0A2)0Nzo8^4F{ewV*;JcnVKSFT#xUf?FyjYg6D_m zJ=mVJJ&WhwmP{=TKF%F9-$2LI>Wr4zKW{78SfzJL93R+^WP{Jx_tn`SJ5L1b$2~U@ z+-yAbT5#!`32?bzyN4wcEqAZIwF(f~`br+{p-TSM>H}Gtpz-QV8{_+;Nx1zmLjJPT zj%Y-C!=``Rf#2*i>phTZePLYtiYO)fv}UP;aq;CAsMCAK0@oHyB<^e(EA{alg6k&K zAg4e0b1?@Nah+DzXx<;H!3bKfuEFmULnn1KCPq_+0_ma(W+JlgGmV6$UKN+Zb1kF`=BV7-H8geBENj9a&!>`iaj z1I zF-FKz_JhNGX?gDq!!1(|CeAqW1jCvjwHf|p|C3RfwbqVc!RyLenB-r|p6Bzt8LeP! zkb|h&MwK#M&-E8wEfR=YiWL0)B$Fm|LPM&enF7E3@F1?03{C%O2%9duOvvXw1fGv2 zV7?g+iBj`+GTxR_*AYtS>n$OG9f=f3{W>(y-@5u@J>ejwg4YfC%ObYzJCcZN$zxr* z=ri806zblMC(=)9h8wkS+4q#alM;uSL;|om;Af*3O(jXy7;}};+z(HO(N*kjxzY~t8 z{>%^#4rKk9KeuHaIm$Q#^?9nu+6BYE%6AJ)7keyI7gyugK_x~fQ|sC7BYXO9TejgP zU7>F_Reje^|8KL-(3~w9%5p2dw>z9KMkYPMy#kmnj|s@BPKs&7m9omd^h#{3PaxOL z8H@OLn!@(}7!)LzKDf{4c~Gz~Ym@<9A+(X|eWFj%Wtr>Ki@*=8C6hwEd9*6bx2~nH z4^PPL@>C}Ks_5c`p$SyBY6~J?FCsxo zWd@3lJ#p-0zZV$k%GZ_YYsX@ozvZH54z6EbbiAe$tB?CEJRNh)<_%U$cSRILLj=<% z1m6x_L{ACNBtVaEwM9Pekd)@r!jGdBxm)HE=Bty4`^X3x$p+9jeeBq$c-SV{UFk5S zh2S6xJQEoFB%5W~K6B%aY^%c18hr~MyFGlm8@xC8^hfYd>lt@KyCXi8ai8cZN7N*m z{Vd5k@fEH8936c7FFSVkKt;9nu6}Gwnh+JN59_GC8%%UuHs(G~TEB5396aJ3tf{87 z>78{M%lj*z>0zZ;aJ6-Bg~xrFK6KeP-Dgw2Lvi2d%;@*J z?eq^%DIi5nALHt^A*HV_wyc!=u>SiavaqxRAexWmg82yO5vq5TAc+oqbY@gtXtgOx zd|}r0zf+cC^itrX$F3HN<9lmGgtU8r0&I$|)8*k4PRo`klv(KXudUyFXmN+vriLs7 z%+=Y5u4j@KHDk9V=ZQ|e>vTy)jVDAZ4Ug4_jdEhHK-tK(5unbcE^!1~M=G3*g z`EkjcUeNxp*3j@R0tn*hA0NG2z-#f5#3G{=a;G}NiSI59)%OyF0HRS8ym*jJpC%1b zvBLP#b|kv=L|~X|KWPXJ3gt@1`(nz`mlFUoNo36NoNJNQNWbxl)k1kjy*H^Ho2%0G zY_@NZ?$qf_uzqJ7Ghb8kiXc_v zL(4Vn6IvpjleNc6w1c(Zb}^Wy4rJHtP0P(NQ{*WI;Zluj&EuowHR#GkCtBC@Tqr zp3Jrq%~Vso+yvp4o( zVSVr`yt6-*C>g88{v?xgeM29{n}ZX%=ZF%+Zf?b{2`03@+=u-ega5(2UP?miBU&{6 z!-T^{edyI2{3`R;sKmsdwqn9K6Q<7Z!$L#wLi+Wk67B6u_Lt^ z3tt?-x>ccz$@_;Cv~-lA%)J>S6a#2|D|88Yb*7-+`+dCb)r|f51L(0UH1)4@Q9a>( z6hGUHB`XI|c`|e<@AiunY`9v6Uhd5(&Ktmpk3-Wqw=D(pzW4yecTb=(X8=R0LSLsp z))cI>m0`snCom*t0Nc_-)9ITn1)J`bVf^3;R8Jqk#$}-y)a#QJj5=M0J-1JwEP4PH zOG7hxUuRQLak~sd`cI%ZeE<_b2+g97=TlH>ExO4mEk=UDhM`um?W?7F%G14Z9D<9G-9<%O&0>#;O6 z_v}E~h#AY|4$RLD&*40C8p_;uqR)^S)v*p7TphmLIS*;raefC@ILyoc`VPg};koR; zD-FY1cc91kQy3s~pe8f?O+oFEH0%%DiA}f7SUTN-39pCe(Wk>{m^!=zE&XQay2OFv zrQvT;Z%rC1%{#FCH!~(gIZ&JuzJhu@l!;|`D$pm^f`+0Yv<*hCq#u_uFmZk*YByNW zuW$%EDkAgg>$e%$d$$7XA}!eP_7M909$CPCmJHNOD$#G21?$%gVejvetEkth3`}%X zpg!7yVS9$K?)}Ksf{t;SXmqVaS&;>$tB3IVuaRoz;$#Nq4_9E|a~3pw{3k|ii~J|& z-_O93I~AA{Z9(&bDCbk|8YAMixom>qRo8-t-Gg` z(y!H7Xx~tYfo^B8Jba||ukSW8M>$z&8TAp$E}!1$tmiQL9e-{UbFw1~D-Ks;#DmkQ z4jsYkx~R?MotuRLMU`l|cN*(MMo?2eStBUP$ijHXE-YDMMXxOn&|Wun3w`Q+0~JHN zP@ZDNUd;n%e0a(`)P3wS6br=NfKiA*DsHwX#JK!wltq^Gi8?Q}8 z$)n3KF=jU=j5~|^K-YH#L*`4+tj|H|9vya^Z$YuU>o)TKS2T)O=HT!y9hT2;#g5Ug z@6o^CqEVTbgZY&@)a+?-uDiOHaj(xMsHn_A^9~(W?`pxOFxU6_-@#~1t<1rmMjdvY zX+c@2>j(7jfCQ_RDhzo~=X7@qN+-K+C;nW5KHGE9azuw+rWO?4aVh70giBBpqQZs{ zJ*NJ*1a$;h zrH`vnvrgyq%NDHabE#mz8_^i`k_xLzb(sA@3x-W{t#r;wG`3w*p}a_kimzI*|96*< zxaU_=)Q?x8-+mq1v@Iy=673Q!JUShfJ}R{C(_!+K78KWrs`&2MbQH~0p+m1jNlgpZ z*+jc}H_~Znou^3IZCV3Z1*UfY9G zeG59i5b3GIk?GhJslw`{J!pK|hS^8Od)ePI1ADeF$FN2{YQ#3wPICL0dYzt*j`x;h z(_uXZJZZz;6t{ikJ!S?bzq=f-AJb!r%7&7c-Kwd}{TW#P#d0+MqDT23-=k!r+b7Kb z@ffUrJ`b%~pI}h^IaGGK?`IAki9yTMJgi9m1bgewq2#>#r-BJFF{sJN!_=&OXjpp= z<;y(`DXGd*g!U)D_2UR>df*BMaq&5vl9<9UGjT{Rmu-K#Or zegOSmY{!Ot?^@n@p&Xkpt;XJ;4q)E=cIt$Y#erVtj3D-2T-kON7<*|2gz@R z95w%5jiPf0u&$#6drUr`QMZxV*pc}*_Gl0OzyAXO0RR6i)Nx!?RocMuS*2oIDwZxb zqqNe5f-V^ZOf%(G$z>1`jBGMgR7%qEz1G;f?#9@tloV8KFDAJvbj1-1>sqjo zj)8?Pu4stdWQ=TdFh|8A_U-=0zrLSy&zW6H zS+m{@R7TV$^=k(p6^6+U39vSF6!`qYKMtM19P7 znHhEM4)mX>#(~RSSY?X(g#Gf(m{{dN?^o4W8R)`{rBU^o9h=PH<8 zn>p_fR_sraFlLR6CEHch{UUrxolaS>Fh#=P8X4=}SF!Yra7eTL7AuxclTi1fjLo}M z9Ow}av)>5|is=%@E|szVLlyf@3SQzqWW;`fiNxqEb+f>|eRA|-I&v*iZCJB>P z$f(<^VnJN=QT7kBqA6Lzw1qPEm8vMVRKlv2GR9S@xbvv+4ev{5#gxBF zIIu#-f^rob;-cGlr&(5vogtySP{#Fs745$W$8PS2spBQgSS({*nTkEP4Li>FFe?^} zmr$82qq|(ih*QG9c`w_oSUg?A@)a_6yshHSBSJgB8)C)!84~)#_F(LO6-`Hk6Xf@g zR;)8g*t$=~?u9C5vlW;rDq+|{8QoPX z4tyze@lI~BV)37)uABRz@P>*VZP8~nJBL~^>17GCmdhclRIC{i-K|-9&4R!EZ=hHt zW6EbL_MQ+_es|r119K(y=KH|*Eo#W)!gu8Rb}Oc)Nw{H!j61ifnARqoBcBH>xIRU~ zbxUOI->qVvD)f+_Pb_Fkkgzpd#=`ehOgbj`=#%{xG$l#cyFdU_qf}ei8 zY{7!j5|(7ixO1b5{)56r&B*l@>=`9tXQhnw8&z~S2$#rjxdn^XO4x0aF}zqsw;}`> zud<*xO2SH;jBUkg;O4qM&4?8ij9e>WMW&2#E)|mx3YXdMdkZ$-Cxy(AG3GTDTib-6 z$dBKG!bl0-^JVn^UB#3`(O2jjp9PagO4wkNvF}wCt#v|>x~Ue7xKG0RIWi_)SF!bg zaFu$Uw_w7bB-EG5sJPUtH}iZ=v-Xk&!$wM&Qzm2D>~mv z<~i(t&CpN1UJx;-!HG#1JUB4qJeFn|ZqQeSBBtMPqW821?YEyt>m0++{N5pA!(JzD zIO)O40Ur)z7=B^iC1U*^C$^vUp#5hbCjZ4SKpmbJv2DK-{l`7n`MdL&oNoA){#-0# z>ux9Zp7dbLLj>nOBBK8}Co20q*xTX5s^;N$P?upMrcHKYxYL8Cy*?bcuD_G| zOc62T87I2`>A{G0AJ*MtxJ$D(MZ~lXPVBAmVB#?!_UH|fnn{yHjLmkUxZ8sT@14g= z!SF}&kt~MHa$>^{4@S27FzXIO)Xn&?Zk`hzh5N9g$%m!)81AO;6GhB_&xuvrJQ)7D z5B)#t1=Z>zIWbW;(I` zT@QK>_(JyR?;-E^ix~H$6MGsxn6%%AI~(mHTGeX3e6eni9?7{pRAC~A0 zBdPP_BBo4oVx8o{{ttZEdqN+}ea46wk?h2p^&X7-hY$6!hWqHp+eK`h;6%O6gGKNA zFlL0oNc^{mSe5L=y5~Ju_<;|t&HDQ_1*eDwW1U$0ln2*u_uYT9zH!9$>}=e*@l|Z! zQ-_Xse!%*e5u6t1zsH8*BS!Nc7tO}bO|N2bPaTF;U%=K2_r{Y~ z<5Q@6WCJE0IEW=J0c;&GCUE~ZGO>J_3p@X+V9k*L#srLG$X8h=macJORk4C?clM#~ zqH!$s*_eqnl`d>wt6+mSfSo@W|IF{EW@7RJ7dEU`LgS+W48LMbq|cw2hqZHE7_mV? zw>J>7$M^tsnU;wI=`O5yC?P)$V8EIEL}SH{Vlcf*FU54$imTfy3G0W4`V zrf7@VPydG_Zeqs z#&y{+KiY-XGzIgP2C#XrF-^13G!OIcc46#v1$!O}VC$fJX+yo>LfupaTb~JF`A(yi{GG62T$BsLrYPuL z7{L7P#wXbKxD5yHbYa{>N@$!L2#vQJpVTz9*-(Fn3kN1Bn71H+x=Q0r;y7%>^4ndw zbDV;)#{-!9zERXnYq4SPZ7y7&pkTq+0Iqw^IE(&z$A*y|#aNiAU_wR!i{3HLCZ1*+ z3PW6&Hdevd*#UHy8Ruw*8?sP8Vl#H8G-A%uAa+#6r_+zev$1tm33g0rL|tAmH(^_BBj!CBL~(QceDb$1 z8+%S|!jh4V^F!}5h~;JR+4MtWHl{7#g3TiuG2a}-&e!7?5dY?E?D1^EhPXzwPYebr{n#W+8nZmAf$XE=n-+ zr6x3OyM_^?$39JbcjaPgVhM_?ny}~}*HCwMOrB=n9l0osEkXO*CTz~`57{~98TN_D z#mb}-j9Afxai!O=s&mXD&5B!c(fU9MhA(TvwyoDNxnaz+n(bk^s2EEyc1aV4Z@Gs3 z2glfn>*pM_7nNYf@+S0}Z-mALiO*?vAAB0a)HgBJcnEcAH!wf`!Nq(Zy$E-vy@mC! zdr|QJg7$Gq&y&xUi!g8cTj<#6#g1nOQTM{ceEPv_$Hb&^EO@8|YjX#&`{9X8IQO_6 z>mth0J*5RrPY>d{trM0~?&O<=Sq8Cx!GssdU%egUPLyHmh!(6g4`T6_iK{gAHFj*6^e)CqM=^Pau825uCS%Ew zC0G=!z{=mZVa&XtFLCbd6x6-51l<=ZFm6g4R&E};S~Kl$lW?GQ3Fd!afyv|Aup@iu z8tR)q8MB&}V3oh(H~$|10RR6i)_qvh<^I5N2*O1us1w0)k^ql{Xm~=IGLRJGp(U6^ zn2=Z$kc)>aRN~<rzq9v# zf4#2zyZd{8KTr2{&CM-nm1#$3f}2}Fwnw>BpC@Bn9xp`c6&1>_eusi=kC&b5H^gAj zzCx5+RVZ6v!tlpDD%ih4jFX=iV$%f`TBeyWINYPssqt|!4mT8{{(=fs*T2W$B#$b7 z-z-Mk7lkg*sW9NqcNo6bqnh(AVieAjp>)MTR7ifnGMV7-PV4_6!SSIY6pSCj+}UQV zN)*(vzcCiOKPp1m)FI3ZF=KRrK+gB}#iDURF(%$RgeCLM*tkou(`nY8SgiWK2&Zlw z!tNk5jz1%)b=tN^g1R$B*mV6p3=1@)X|v!Jr_EbpQPEa}tu<;4ax-Jt3W0)re~ClG z1EuJbszFu3AeQO9Uv(;0#A8NsDTckILCf2NF0XjkVSgMt0!wjftpjR_=wFIM8#NeSGl*iV_im>HU&o>C*Ag6$(x5DT5EJ%$?;)R;S7Df; z6sI<7aJ*s=1*g50oZGnyvjR)8NB;rpZ9k%I;q<-aF?|hcHgCtWt?f9Vw7Aw*-+wSC z*3~GO+=i0)c5JS(pyRmjKHeKxjgITvur0A2^R`$p{WISt@)}x=VYj!T-->or+EU_`)wOqB<f798*QZ6?3zi71`F9ed{<#xl7DO#{B~aL*@KWBRP^=$F-w&97N7SMU2S`^Hz} zsB$|Bo^D6WD;8`#>f1tI2NSWNxZJhYA4d7*pRmMZmWp^btVPGxa-8ZojAGkQsPde( zpLkzdi@gWRas21Q*yjE-mMoohfcY$5iw4h1Jd&zKd5INUzY!i}ZUU20yrdEnw`s9J zXT_>-gsq%=E(r_VDpA#<#oPl{%z8(7i2Oa0G5di^G*xL`KJg1C{7a~I8sL?T1Gg&B zq|jnpz7^~L5WdIv{!GH41(n#eQilSi6{U;jXvpho5~km%z_M?(SoMq*oAwCbXMHQ_ zeOJFLG4XjVcD-&z#WCRr{C+tJ9imF?5^GVJW5uaX;fLJAk5f?hdL@?RYO%h~ijkiR z+sNxw5+*OHMEz1Ns-CoBu0q)EwA_(|`Z<-D7^TJBC#)#06@KJ2>enRfT2zT;VlCz! zvZC#<@G$Xxm4uD93RKS3qN>S?lU2ea%(p!WvvMmjp-zio6;^aRF8rADzevJ>;R@7T z`UIt^R#dz#)DpKf30u7@aVk=a`Z6mHsDz*J{-;S8bgKf>y|u3AYptkyN2sHY=aaC? zqY`_=wK)Ew6`S4`9;F^vk}%J&5@oZs7`@Aiy0gL#`Z|<^L3b)JYJnC93a#k&r|?tu zbta+Pxe6=@)?!J#6>Tb^p1J=|GG^SY!1VjHsC>?fT^@5fiPxBfx`7HDovFp_byiG2 zCOpRTGfC(Ch)hSTa`OT9@e1 z(lLS=F>^mBzV)dX{$e#omg+G5(-E}P&;5e+;#8d4T8-In>d-Pgg2A`_zvP~}rJ^mq z8r|}A*w!(E<$eAJ&IwP&*5|6RsZod0y*5-$`X6WhSEl0s{sv|v zm8!$CM{L-m_y2~unVE|6)M`||ti!esM^JO#zlT1WQ&138jlqxTP=08{<;VV~iRWAj zmfv5E-B0SU>G=^1I_m##`hRySDlb%HzzaIe8@q_In80swuM{1o8l1e=fx`ipF!}kw zUh>!@#i+g-EWh4?3ja$eEDAisy?b*V_NZzwvZn(}CN5%BTwovlXq2MmbPd*D@4)Wa zmr(Ii;CIyJNht<5*I;gM2WC4iVnRfqiTb=MMN@YTYA$zR*T_XITN?O1>vAcEeN}^= z7dtS|`;zPT^uV+1PnBZ!J2e>8-GRgBE@EV8U_bM`O^QROYB1>M4pezwa`|ZB0R2vp zV)yPER37a>iPDaqHj&wB^VxOSbF~)z9`3}9JUjNz7yUq71M5(+xE2#0?!=5-I}RTg z4bsmmX_%f+i+TGy(d`X8_L@aQ?DtK>wre}lC%zM9o9w7KEc%iCWohULt;O8DPRy#a zW7zkibL2C*4x4}5iH*^n7`4TY2DRus^%13^@xEGY-O`EOsaG)TjL5~vbbS59CY}=gw%ajCEE=Yd^U|@k99aXv=h5aJ29x# z?t0!Jy2#uIrD3*bErv-uvAMvG;ePjB;(7jh^r=^1x%o59yL}bQ#P?mMA2I7MyY8_9 z_47Z+aK}}&tM9kdztIiY_In-L)4#xh^}k}`j^HcI&7T`EVCie9iT)BBhsRJgE%YjV zPsv32?AOu$l>vh|o z%cnW8>vo8PIa-s6%EAU5_|SkQgJYN%9{M}|D$YdDy$#rV-hkq}99VWUdddv`UUaKL~;H^;E+_mJ!K zHzpH(avHGdJp)Fc9>cbP&>QUEoQZjL4Jhd|ph4=u#?g=o<~Ax5jT;+qpw)m?#xb<5vjM}}4JaNP!?rDV`oK8KNiFq+^p#D7r zmRub}fi2_@>JXlZ-Rl~#r_6v+Uyfno)&*0%_h}YRo_hn+Z+wNpiPuoxvfwszoU##n zpW2O8O(!tp^f;;}7TzJBhc=;f<8JJ#JAulx<2V`;{wMiu+Jt4hcB8)I1oljfWBTt4 z-Htiy7`X{EHtfcpniFXI_c)f#4tIBI+`I|9uPRZ0w-E!5PGFuY;x4B_wj7s&y;#1& zh=Lsx*!W_E2j_O@V8MAM3N{$A?U4ygY>x1Bs`@1dEna(ZXps@KizhI-Fyd~fO-FOk z$Erm6?USzOk51r`rU);-cPR&jca-Q@V8qs~6KKnenC4V>I0rLKN{qa55+#xeG;N6x z@EzZ$aq^53r^ZjBY{di`cSqbq-sf_#;I6%>SZGAI=O)l`EW(?*ypn_Rvr4r6b`lfg zC$Ra|hvK?cO^GF8MszEjK%cA#AL5qhVAt15baR|U+tLZw^PLgXor>FXFnB_V zlR-wTDwsfhM#K!Ky|px3Z-h~s`v^`=beF)9Pq2*1es5^zZ`)}cJ-{M)s8JvsqX>Xx0>NFZEr_j^# z;B4l6`m-o$YR0LKZ?W9-PgIE>5;B*;&tX`0Gb-2iVb(79In>uH2J7F;$Kly6*c;G? zVVm9kol3RKv8gW~yZl-(FQE^8UUQ$zeAGo__Mv>to!)}YGyBlg=N>@4ZZAW>v-vpe z+k#=SeXjM(?t#=}`7%6mARpTVE$AuibFHQB^PHwnMq{@zA9XWY&@-kFm1XWC=Je(= z9N(Xhqn<5TGOZ5_65WH?w>26wl=;}}*@8`8eVD%1{V&A3W;rID%txI^i_0Z_Sn`B0{;+=8^{nK76pd;vW-?MJ)Z zgyZKu?q?o6#AuoM0(L#SAH)A{!o&|fLbxX(G1$0Yh9#E{Vzz%jT7K{fWe#;Ku<3gl z3TC!qV_ZLmZ}bY|UIeVffOljV8PJNx8T}}T@LE8>o>+;=Mj6Uxv|{<+`Y|`d>#xjv z^h!L^EyH@>R#e3FW7gwd3%U2=Sd{IRVf}@Jn4uoP+z_vD>U3ZQCL3f}aBnL*{@Rb8 zPkB8++;J;W@wN;dLkC?>p2fVsctto3+7OGjf6CCuy%k3n_2Xo+*CO8YT#3Ru8D^h9 zh(}iTW7UIRk$msn6)0U$j8%ndG&P#ha$K;OxU(gwc(fR+K2W=!_nT39QLw~m>%KV5 zTU3mZ@2XK+Z^p7?f(Mz?^f)X?DMr5{H448pV~JG|ML*WY;n2Dg)NEB_#!)jS|14Na zT))R+*4$#0J)*`Exf%6`1%Gp@@|U18p%@2p)o40w#>gK858>5V9GFpzJ{f9MRGQKL zp&*)jQy7n3vBj?S(`uajz>Hx7f@OSP6o*FdVr+XMzzaR zX3YLh5X1Su#A1+FF?udiqoc@-ru_mj?|Dn`$dY2rI;ci@iy3>q7ObFOOC*?nrw9Yq zt1;?bGlm%jE2)RO1j7~vx&a{)Hfx_!de~_eT+q&sSsHvu2#yCy;QzZ^oiZ zRE*-)YBbfGQKlEfagIuYK{txfBvRw(CNsLdA&AFiap({gqdZQHM;gpHwfLS@#PfbE z_FgH%EI&0SW|&>i>jVkJvsi*cQ86|psIlzXA5fqdJj^^EjKzYBMOc218kHN(IQ5EP zHAYCVOjwM`v1&~GaS#Kh-MfZ!bK@HmZJPi&HwyA z00030|18#fT+8nl0Px6NlvQd}LTR1E-LRqDTgpe*IzjgZk^?p6ip3ieT=j`*5l1i3pF~4UfC6!2-$sV&*-xQ@h z3_ummW{$TTU!jR>W?GD?VP}dK1qYz1tFqA}DR0JqFPddJrdht(xL*#SiI&+Y=foRS zs&tmsn3=g|=%n5QsET>$gX%6Z&qYX{GK;q!|FKpCSCj@0|;h}*;B9v23 zvKjMg2^*!ThoH9VJk)HL2(3&Yt;g|&Y?Lw~1g)g-(0+Fj>T-^>Va#dWY*d9Bg3>H` zs9Bt7+)9$|m`?ZE=#hb7w4cmF9YBOuo+WJ@GqRJ7MyrIN$u>OHXSWD#DI(d8*?yai z_J0XRZ_4w~%rzoZE}mpRrVPPGd*_Cr1}k}}$379Nl1FmD^)lJ0%$H!aYZec+H4vex zi{u@#znP6{kV4RD#yphfDnd*7q)lTgUty!s6GBjv={&SwBtpAFNt?&?Z(^ekb3@P( zQy%KHMT8b)k(_Y8dNz7Y>FOcZ~>D_95-S@%PzinJ^fgG>@;p>| zl?b(pAbH|^nQS!hUoh$*%R?1RMd*EwA5AAIhp#^~?FU;>NY&5bV7_AiNqJgtSXuAbz51xC56QjaDB6{fKi;nFKr^Q*?j18?k`+2a4Mk<#^HGy09jN*<1s`;&6-sdk9dEnl zqaPDGP=&V&`>;O$S)xu$Lea?Rd~~F=1Lbxr_~JZUt$fGxHxw;(&PUs$JI33075s3# zh7~%rE)@0Il8>51cc88RDfnYO4O^l|)Iw2p`+U^=YzNw2pb&ul-IgdrB@`VA%SRoG zI#A^|3j4?8ythO(UWB0ztp(%#f-clVSLwi*(buif)=Ob%gzO#EV^SAd=AaZf=CnX- z)aq&&>Q!_HHIVK?)hS8`F`ntxXz7J8G*J2u+BKmIm7*#I;d-goXnS=S+R{{jew6A$ z8E2FZVIAjMqXzL|=umF~+HTv02Ci2M#&|_qqpf9OD6gRaE&Bc*HCv|?g6l`DLup-M zsMkONs=mAn?TuDCJZ8U#H5yzRHs1bKfLf__pfnj{qKTkYvGdT>$z2~5%%ebh|aXxya;v-6HA|J&%>fxY6MqE_Jn~$2L zi_yww$OR2wu^my2H2<)hL2#As_8`Pi6olWfpw zXSk>Xm5*lb6{D1T@^QQ;5eE(a6OP(4_~ZTO#i&_1`2?PCf(@#y$wk%e_-J6f7RWWz^goW!WyDe@V-=ROX~ zo6AMLw(!wtM={D6Qa+3Ja!_McE*hc8M~jY%QBEN_3h)0v4muRfMSErVXxv6I>J&zf z#&xc7(4x+8bZ9z%ygx#WaixyG%sK1*S)kq^>95a&Op#5{W=uH(q zntV`LPf;f$@wi`=)3HB=Bk@v)>g@I! zI<&j7G*`Z1g5jQ|Z$FIbAX-tLk|4(b2lXp!BhslbfmEs2epDB3nbbdd#9_knJ&pp3 z(_(mch3B-0NriZq>(cd722gmxD!O!?0n8}p*-Xh^4)^>|o_U(T5agFV{Ms{{2}kQ@ z%)IT)1jY-+)z>wc(0@+^h*q&UD4{a#l~zJLcAA0;FyY%4zr3^z793y|i5y($ zaIAaj&Bdxr;7;EiTPfL3eDgkP)_f*7s}gsjZ!;kG!c|+DZ@SRq`}|kRK0R2lt77Vo z%``AOS2?)8RU1k*?SCkHXhWiM=Ty>heR%OJWYwSjEcko)#^o9L;3fY)yOW!N9|!CbXXSM`<-Jl0n%YjHDx_&oaBIqobd?VU$AxMcukOODAJe$$5h zPtt+Ob^4&W{$bX;N+w);`07)-hCXN%vnHr+ph4rERncS@26$*k2gR*5fQ?g{O&N3b zz{tD5^vn%9EDH7ZynB!V1i30-ETD#0MD*_0gp~y$tM*7S;AQLaUk`3DVN=!q zGnw`b@EMU4ZoH@sPbSyq{`yD(c?}0mZZ#9`+rB>(Im80f#X7#%rqSSZi{-tX1S)8H zG%o-5i2iqGg0=r|p9DzAnHu5vrF zgFG1Uc~93jN{bF`&^LH__>m5@H66~8jbT9XMjz@Pp&=NDggb7X#sa^;TV5`)V*x9B zD@jJ44lZuJwpC0WI6mFNY+xx17CC!Zhfk$JyP2OhnX3!knla>8Wx8;ivwaq)PV(GK zX*ah%8r;$KDSsrxgv8(8VNacykd@;bGpSw=Y`>hoeEF3w?CmjBdSCEU90sRQQJ@}J+e=@7tu`KWdg6U>t?Ka6jb)WiG4b4eOB zh#GYB%c*35{o})PVkPrZ8!hFh7;3|s(E#6P&#ACoR#W%Pjyj-V5jx0TL(1ZEW^>(-b|>vMo~gpCS3*nzpxLnJXPuw9-57i6ArWn5$t>5%u1F?xx+GYqE(h-b{2eqJg+l0$Dn>8T3dw z+n)uKeeA8~rZQl6?Ll3oC|#iYSF5t`QDAXO62x4m0zGco74CFBxRPL3cj%8P*!})| z#+b)~Ar|>WOAiAGapPW>>)LReU-W6{6&0!;PourvY7DE*!`C|cGNAu@-TCw;CT#gx zB_F+m2^ybHZE=!kKzfTx#obkg@M+t&l^Yk+V4fmpdIg06gS*AU6|UZ}&flo!7( zXoN^t?cN84zkk)ao-zY>`-8pgABmt_-#%+|!ySlU5qj6r^@rdr5zl zwtGhC=SQHfy?&wLqB77pEATTke+&jHhG9NY51~C?WtB-{DRj@Zy6Snj912I6$5{52 zFk1S@COWeg-fu1)YAL9KZ(gkq+=Ln^u{==gG`SXj|4q_hr_}-xIc)Xgay`tRWAtF; zY(4C_WPP;JxfYZ^7Uuj4uYiQA&8yvCmO*`eYtM$aPhj?~noPBub)Z{AThme{DSrbk`hNZ#$GIg&;DDMyLgp@YgO}!f(vCZPp0&8cg`bl z`txPZGygJ}a+v2iVp0yHdETDIr^_L#y8d#D=@XFpc|)5gu7p_=`ejZYs)Q-5scn`z zRq!s$V9-{(26~<^G=Fba3oUlWjru!kVK{E>2K`+%Fh}Fy>blk%_?WG_fY(w3ofnsy ztd6gR>!wSTrBZ7l`M1vr_p7x~@2qF2notYJmTxUOFWGmbXJ0b?btMeg+T{7wRD&R( zEBN@7T5wl*F!Elp1|CbF{MD;h4Wf;GGJiv>fRQ@rJTa&e>}~~JbFi*}otG~0H1wXp zseiSf8*Y??;$DlHOPb1IryBXpdyynwQpwu`_C5y7KXX^rJ3oTp34I5S^_0Nt6Gl6B zSl$PjHty%lQ-v^SBU&VPD;E+9RH&WG*Wlde3v13n9Ax(X4&>K!!OD>I^QK2EtgX}i zsPA$JwsmwJpG-D|gEO^zxzYyUYA{%ytxJRM>x(1L8EAssuh&UUP7Iirm$bUflL^Fm z^`{T-uwW*&FjuZ@8T|9xfA`-K7TBLjxvlz*0Y9^@T`kpG0+AGl{2$S}5ZnH8Kd%a}#mWN5Htb(Ol`M{O|A5}HrGL4no5Qa8=sErFLreRI`Q z$$WX6|Mbn%hRUH`TWctEknT(BO!Lu)*GlxoDy|IB7PWdSj%Y!e`TRMulK1O>_T{O< zAT5wn3tlkALGnMtm{RE(#eyZd>C*4 zhwW5!!KU{s^x9EjZT8^;%2WnOTT87!SfT^(y5Ev3>RDhOJ33=`ClhEDthD^AESMp? z?CaV6i(qeJcb4WsT{ztN-ruCy5Xv-HO+R>o0lMj}PA3eR;9(Nd^x%mmoOxl|H#wFH z14jmQX4V@(!XVoqS@NDg*OKY~GeZ~lob_~Bo=$_wk<|Qo*E=9AdIU zACdz)YW37uu&3l6KdM3-P8*&so|{UAHzuz_swL;kPS`Qst(XN(`!6vaB;V!FqPEeu zQfW{C3uM(D89>{gA^nx44%h;6_^nFoRl3mM1!q2Hk}Rb)P?zsT&Er{LkNnG z3yE))eDB}CaXk4U6Z89|=bymYABA}b z$W>tTV!w_WyBdy9>`oa?s|NL%Ju5aO*1{Cy$u;ji>tL4CiTe)D^$@&wvs(CQ9jH?$ z?|UMshs&;>|J^FChg(JTFS|a}!(GBPvgb$x1X`_}(YxarY)fC$@blXt_EHF9xhr-9CkQai5k|Z{Ou)YQJ+*~q1PBGQX_-j4uyxTSMSBmw&kwr7}b zCm^L{)?)H%0_=r5Tk}p5uyL1n!TCc3G&=oWxby%4x>pdt3-LhgPoB+AM@HLwmJ=0Ra^J8&O)VAQpvf7fLpSn=$i(7y^{V&vSItEL3>DGXmvX^`YgXnc^9WSs?p z7e2)Y31O+mwKVPNLTI-;q}Ht=gp|bXq3Lcy$dLVaYIBJYb~>hgnJmep^QIlA?@IRl zZ=Y`M#$F*bs(KJ^146LLBUi6IAq2v~S@=9x2>UN-TnqCRKUcmJ%@f@V?K;D6+=HTcD0*Fh-1J1Gp zoa}o)HC=^(MK&2vUP|Kh-^il1!`EKILyb?TEgYI5z2a}iF}@^!8QaZSDU#2r#d)+`QrB#go^!DT6vy~%Wh+VQ=hL9o(adHDd#w5=ua^Kda_7jXq#k~z+I(m8 z2r!+#_=c)cGt_+1%A&jy!V&lLE-Yp<{0{&C|Nj(OcRW@9{|}K>6b*at?b@lQ6lsY> zNj8~Dg=9yRR45@^84;o+BBQeBJ?A2&zM?2)q(PsO-}(J@9_O6>M|p7|8C* z*%^70f$REx5n(Y5m`~d?9b_Ja@Vn0QJ7yWszRX!zO4V_Lcd72HDg)LrO-DXFWwGDYj0j7aWF6L+<7MwtQs4)HwZJpe|_Dy)Al67E!u5Pc#*i~Ji0lOnR+gx zJvGlkeJ9jObmBFMi)$=QPEmFD3_kd%#KM3;P*YN{1p{mL)F;>Yk~sf9bE1#Bm;Ch1 z_{0hWin{^|Beyf~D|biNwk8IohDYc4Qy7RPD@=Wp893n3`th(Q1B;X9d^3+2xTh%F z5lfBtNHNv?rp!Q&7;O{3I0KeGJV&qbkO&cNNMxn1f^`B~>*Yuo09rt$zrVh?E`E%F znzrV$J5~QgMP%cd{|HFDo%JZ1BfxFky5(sQfmJk*n%E}o`2g8mJk-aIa6W zZ!UpMzwTS{5d<#z#Lgto5-5098I?rgZMC_mgUMy&O*eZMr zTzQGlU8II@Q7>#C>V!4c)8S$9uItt?9Zsc&yR_K|XzHABcl}F;A+086qdI}zgI0fR zsQ&!*2vd9doq%=14bx^J29~RYi~Fg4?vso@^~I4yDzX?v|5VzsJ)_h*FMQ&X{6IpzmcRRz z90ONRU6s5yM&b(-zixLoiLFcgQ8GtJqzztfIM77ELTI}5;AaBfe~#2E$&*OP6SU21 zpyRfH?$u>;0)w5pvDvZ&S^}L5&lM3ktao`OQ1PIrexK50t=se_%{EdBiXiQrKp|ar|n#8t}X-a z%*KDN*)njHDWFfoY!H8C{U7}sCowah`og1t(vxk|o|oGgIPRD}D@*a`B{BQXf~x04 z`Df?*w+QT!yYi~sn}lYg$ycR*62kM|(S3(Wc+fqBW@7HWF zexyV3qGQ-NLd>58e?S12q$G*$x%ZCjzCu8uQ7XP)fWY@rH?Bke1jLLE7lf4%aAOK- zzFR@S{j9O{zUvf!uSCmKH`B4h_0$iuOae(}6`^C*1S&VozteD~nqR@xHj~MY&QWWo$7veNmQFZ)WDODm#hlP%(K0TM{Dw3wKm0r1*Yr>`E1d zb?peFF1YXCCTOUfI!_?r*bvaWC*Cey9*VBH;3%%99Ju!eQas@g9b^}Oa z@7=UVoQ~4mdZpUGlnx5Z)0b~j`XIeI%D9;7OYXDd#x4V3+fdS)P7Z*bwO%UPEE1K2ZF9{4(g;`g&_>2d3+^*1}!rBe8B8{Vx^Ox3kJ>tmeTF9Jg6>N!RH2H?Py zXxb9ni^sSWrlZu0QQo({tPB14&3;F$X|fNz8dWaG5BGvIoXz!xd^a-3T1D1Jx1)fm zbwu#%OBk(D)H!$J1p->nC@t1L2anrFdT3rF)?KK)!I@G6)B3J6?T;RU=ZW<9iRenC z$1Heej#uG)R=ehkZ5=9Iv~7BJw?OWNuS{h{JHj(`JZR#7HbkbWoP-O&oJ=#g5t;blrKd@?}|Ntn?PT6 zXrb~mI<#sx$9ldY@XSud1Zq&RH0o6AZAQyNIj#2Xp^gFnH zlOn)0_CfA&Fr{~zt1g|SzPG}zd&zJ=3GASFuCQ|#Sjv6R+X=;s5(QPH@I^okQhoh>-zRIiDz}s>$#|TkFtC^TjNJU zkNZ#fKFX&;M6_>Rk1IL@Za%txGSc{k;;y5Lg&^s-qcN$AH)Y){h)mP=8g+JLzI6V z%eLL*U{1pG_*h3~8G-Vme6jIR5=Ok2>?Rfn>}rtAdY(h+w99r`&oxxuTH&yvd5~Dx zK$dFXcyjqfh=Ap#1i} z)2V?b3fIbi)63ndes-BhW{YJL==uKVAB!%9A2YgS%4Guk`#Tqy^9U?o_L`if`lzti zxg$}GfNxLl@r$k$j@%FW@GBEA9Zk#RiK9a}vEAcbIsrQ-{sV{R36#eBy*>GmL~8OU z-P#TkS|+yU8%YAeXT928gh?3wU3dSjHq}4f>Dex7pTlFzGzsc`yW-OwZs#aHV|w?$ zL<>5u&%8`w{GdazghxV@n?TVwpD;R=`%HZzZ|YEaCH}dqW1l;LYTkp#u1Juu4#!AA z55+4tky{!942=DBDu4Qzj=js%S$_6(xOk879akNI(c083P3{4N${6+d-W))KiE?%6udsgHh`YS%+bQe0o0$k`D8?V0Hbds((7OKp*2ue5{G*5ePhzV)1RGKqr+u< zGou~0Ig5NsY^{iSx^ef=r)Gq2EbxC+RSAm?E$>5EVqq`k#ik+^iy)c+!&*HML{%C4 z+nqWPb|2^-Z`Obt|CmbAX+6AU`^?EzqKy$-_6G+|HE@?N^JVH04LqMK?zp#F4zf)$ zdRIrau;^Rl_|CdK)y6zd*ln@qq@!_%tQfs2L!!RQPe<3pFfF zSdX93QO75d*!4ordJwj%vCe)dhvT&|Dz|;Lp{6=e_uDLq1SAeH2+5p+}|DHe@H7A(g7``?CWz=3l)(^oQEGioRescdl2$`RUfawqqI~Mi2N#2T*;;W}We3 zr{UGG{G8TTbr{G5v^3i5U_hi=HKSPzWwTr{W@=gp%lNJS@|zawW|_Dr-6g5>p`Ck3 zpcW)TMs8Y_Xkoi)K=n66J$xNFFg{21?ZdZ9u1~YNXzSyE_a?q!1zlfLA#-L%)#}H|((9PXVsH)sfF z{%>U*p~^Thoc#Oo5vp(5t3BTis6$gZY_yS68r~D@gp#yrcv+Rg?`@%jpMA39A;)O= z9plNEa;Krbe@!q0npk;surK1`A4}Lo==aD^fl=sa8kdv_pS!) zpJ$TlIog;xu~&Y^QW2#W=(#}@&vrpC?M0S0Ov4B2;OfuOYssgjQ@DJQ4G?4FIe&%|sJ}iI7agqKy=4$4eR-me z!j;~kdoNXxnsr!v)JqBbl<%1(2k0U)GJirsL?11y-b9-IRK{bsnHRiPS~%iVVR5cN zABXLPpJWx$@K{@9t$emRvM!ww-3c0$978&fsT!i=`>P_h7+r|&z9M(*kPP|~gB7hu zL~*ic|MaFNDZKbTzsos70@vqSaw^}cpdrNIx{!kcc0?C#rowqks8oQ1dZ+es_fbW6_ zj#<2xLSJ=qHPMj4;U8)LO`TE3Egegh8+PJI z?ia9;w^v5<^XV^Jn&nWraku1fg*fhYw6LdKqJe`EuBuTigs||4$^B1M(8iLeT=+o> zwbfE5u1|~M&C+6Ui?2E=6KUHnw#y^r;$zjR1qE2L&PX>6i$PCY=gNg;Da6f9{ma$S zfV_)}6X(1<>a^}Br7~0ca^Iv=-cSx#%mXD8MI^9#eN~b~lLkcQmfpWPFAMrqn1p(m zIF1+yYU$AAkSbi>yM{#o70NZ$7U47$dpok8dQR1&Yipr#N);+od_wY>;^2JE>V09q z6b{>SpIH%5!yivW6W$6b`0f3@l%A^y8=0M^S=2s@s9ULKt(AbtfwkrDhH2ROYyYjY z3F2@IBYN#s#V~il^I-g<6mH8d6&i;~W2Qw!#{8}#{D|vwJ69>7WnoxfZW zF(H9z7iH$Cdt$IkystGGpn?wlvN-+(IbnWC1k+dY4uSvUI7_xnLZWYlu*`A zPuP_%jpsd?p(5V|&?P?FS|uZd#7AKczj;(}xv=Zo?NS|;~Om?B&@_u0Rfpe94yAsr@6QZpI6<|o)+_`&?5V{@Zd?%L` zaXxY--p))8szZ`@=9#4+yD^k+j>4g%l`tmM`gHw% zNidfl*_n{61{uQ7oKII4EkjmqYU`xY-w|2pc{Ls3^-+O=TDYN!+vM5$H!DU`Qv zJ7ixf3rX!|X}JhVxczm#;~uS!2^ZEBZv|N#BbVz0xIVyRr4RZtBSK>7o>K|DIxi6j%aX&I@}M?_btvzqHC@( z$K$&Qs#)$3TiYZM6Fv4NiA5e=2DvOVV#3I|BJ#bHQw(pz6&EzmNx^pN_3JvCD(w3f zR$tFjhP1%1gt%x$G+Yg#izLZ{c_P!v$6EofbnBjMEl|XtGmR`t!gAn|H3q6YMlR99gE+1V=B^4I!&uK%DcJ9CLdM;!f$Mt+H%@P5z)*o>ndVTnoCV zrXM1LmBX#qrwm&n_v_RQ7J(V%&L4&D!{@0yJA+<{jWyA4lk2OnG17slRK5~E88+f4Vqa^0CIGxI;O-7zL004r&+P#|zPY zHoJaS;A7}DzyAEk2rm;#eYmCuSDT}Ct~oyhU)Bt7%&tPTJowsRVNijH@u7!D%r1Z} zLaWn*-vwUPDd`#JLC|XP_gcUG9Nf0Awx7-mhBos%)BLY{&>J`>S@>9!(!CT*DLqA4 z&-(9QJ|YZ0R+aAJSBhBUMsj>Rpo*+|bG@h0BDj;tzMAx0ZdkCc)|G^alh4PDC0XoPs!kj{rizQUkB%QB zHY4-TldL~iB$4H_D%oIA0sjQ{-ASmm!ZD`jm76u}@ax5YY0fUTh~@EpRaA2Tn?9En z#nqVL&HbZmrJ}b%l`H(@vNa86A{K8Ottp@SnI5-2RtDA^_ti;y$zboEAElyA(qNpg z;Trs@hvBQEUqmULnM8g*;Vy&I*HrUfL4rCzZ8Y)FrC}yuap|O#BA7htmGY=_%?5I4 z2OmuVEE&7LNPdt<#z~p>c`0f2)qal=9uO51^G>8Si6Q=w-hF}o+itYZy5LR=Zd*gJI zx^hX}e%3Sy)!Xr=eBOijR2}2{>;eP1%tb*tDI|oRxP@!ElHgI1-(5dLz%}C5yJ(jG z|6d_MX6!kMT#bDr52*Ts4@jMqjU$mbwT4SPqfQuXR**(&RVlZZc=dDrwkiN_nQ z>ivdD_(`0e%w=c5N>|Uw;R}frTIDl=T?~}*R3?cnk~kqFAqQ;N?mwG?7nZzr8bD>c)1}wycQuv%1XiHwsDLlzQ=uFEt(ftf$rP{>z zSu&8Vev$WJJOjah93RNaGVs{bY3m^#YQ6^*8$ahz^_WcYe3~O6bLIq7T^)%(d~aSk zZzb`tyTV2}iiEk6UF|-q-np*x);sTzpvfAn=jc8f|8cz*)w5$jXtUxtA!SGMud5qq-d{$5%i#%_Dx$~f7LO~I}08!Eft*KzrT6*l4> z$~9fc)m(RCg4P9tUX#^Elbx6edo%y;dONfw>q711+L3nl$kXkv9eAw#<#c#f8~)R( zqA>}zqG@N)v#WM(Xy8sUW;JL7`^&GYbBV2x3EUqxW!jFjlMdQnb-EBQsKv$}-Gz!2 zTqsrOLVnQMvMI|Bd>ASYKeWFSd^>7SRsHRP{)l?GC((_tBzK1l<$E;9=J4a+6to|pZ~UwK1a!A=#FfCj(wMOO|5)dP&S_OekHsa{XMaQ@voY( zXX}g9QNtHF`5#Z2T5&7HroRfG%4tJ-pq%Rb{&ujr{M#~6)B$zZeYXk=I+4kA@3p0P zJ8a}u1f!EX@I=a$>(b>;d`Npv>_WLt_s+`Kop3PX&YE1)1=+@?W1)eaI69%m#iZK-k8>8| z@E!;(Z$rwFmW#K7J0Licx6Acl2eO?+ z&U6*FV|wstRB~ts&K9crvL5e*c6*)DcFRtTeEz6iE!T-#cj{8BI6GiKR17{~yO~Nfe=Br6ff9B0_qpq|8#$9!im!?3pB5R8}ZyD58YQ%DTgygnQ3zl2k|} zGnDc>zrQ|@^SPgU&gXpI@AG=Sp2>H*eGnJ--K|#$LsEQu)#|-S#7hC3GFzB)RN~6oMCthIm~6El(B_ARKmcA z)zj2ji(x#s=luT-%D>T&yzPl#N)nJ6P%4}&M#Wjgevj*8kOs~__DRy^q~zK zwHXcik2@N{^H3OaOrhXpkm&9hpE_(f`>vy|stz0DQ@0t{HejE$h{pOjDsnIMVoo3p zGbUBDm11e=ew!%U^O%aKpTx_<%c)rHKWUZ3qQd&p-S5xJs4&}NSeyNVilfiOEE?*m zc+z6HG4&A@`DGp#zI9QtC$HeCQVbPQJ@OTOVpRMQa$EUTl!}&mohq+(a%?P2bzDG0 zuIe+ROH?Xc`TLFJJZQKtK=#3vbg+c!Z&$6QW1Xa=Am=9yEw@)bSx=>*mYQ)ydNB=m zGDLlwC#m>$H#iL`g8;qlI&=U0PFd9Q&d@NNBr6$fL4*CQFfMl+6$0TaI%jh!5NA9|9G;=TS;PEgkr@?lYoe@6|D!@C zU>{Awn1-_}KQ8`zoDTad%z$GNbjS+X&mod%2(RaD%sWR#^c?rT*hS=dCHoGE@hSNC zWQV)L0VlrnYb*CK+>?i3B(bK2g1w3G}T0 z8Tm$)KrFImT`c9pN#l`O)K5N&zX%%Kya|X%){Ax>7GQ zA_n-l^?QD);$Ct+x5&3GpWOHL>7X~q32exE;+>}{0Qaze_Z@N{2hZDQJR9XB$fRM@ zkyJiRj04NQh47KN#>qAI4IlF?lFt1k=jVLd8*%6iAL%c{&Kg`Huy1|Jri~eVbS(WR zo!rmIU!6*qRe9un7LK~uUf@G&%e~FXJNP(Mzd2>5l6=k*pYl>o9!xfh7c8yh;lqF= zw|6-Y5=yjH-Oa67xWnRsa#s`HM$LLL(7}XF!rsx#muct=y{ZWo1&y+|o~_tc3-^k` zDXoy_V8%UK>nl-)z!i&R^twu6?R58gR#+MAw1!l2^2@PykJjuHVs%I~H1hjiPr>z+ zhfg**QK3DL)1iEx0y(`+#r9nkbdQUFnl(j%AC;N^QHqM+y!9=onLzo>48>gqx&n#SphOc^ScyH5K>JfUK~?@n7eM;i7zt~gehOovfx-{)_e>9}5S zTe;7RhGnaj^C>rI=<-@{v?H8`kGf{#3ajaOo?-D*`Vk!gNjrk|Q|aIgerQe*(2-|e zxxuED3Muy5CDm6ch*45l*uJ$Mr;g?p6hExS8<)4Ac*0e9;-ws9>0gDfBI>Ru$T4jj z&%EkrHO64)^CiCqE`zQ{{WCT2zNludYh8z}r+t=9@#?Y5)mJI9p#e`1h{8I!0e7|V zx7?^6oM=J)x6d!J(crP+L}@kd&#Ts(^R5Q|Yvf%6G#fD5wozDr0R?l%ZSKP;S99bS3Mh7y0thLk0~pL0?ie`lygFU*I*^NyQr4&P%yz6nuI= zQ9hqZLHvQ_ObHqVS9moN4XP9bbSbqfR8e4evAeSM0R=&)WY3p;qCohsO_w=YhXf|m z|8F+=|Ly?)R(&c`5>Eyn7N)~uM-RQ@0S(W8mFCsu({SqjpT0b@4*FUJf43}Ppg=sj zS|o=F>HdS2d0-=dZ0om|n>olY&N`TThmETJ8K)!KIH2XcsYqSL1!F?BCSooZ718q1 z>+HGcl0R3}PF@FmeJT4>l?&UYhqpP6aS?o6Cnj~Ai?s_ft&KCAKszHeDxAWFUPR2g z{{}hur+UrGqn3rucSgk9ud+y;4mD9d$bz1w8a7p2SEFG8c5Z*ag7zp4=xvSh~B5$XhM$T0>h93|4 z#*Z>#xkX~-HYy7z(wfRf`kBahh>7)+Go?d%EQpP~pAJ`LK}gor?sO;%cPy>L zCCK^pAtt8WUM5ad$oxofVc~2b*R%UD3mu^bUX!a?2)f%Xt@@7~AM$z(#@Lu+`Sx9s z2M3}C?A@>a@4I!|i9-)K_*%I-?&UK!q)excU8Y!&Tznq0ew|gN6-}>Aq*B{`(5XoO=Oaz`K!m_%V*mhggJRpe!gO`UbRP?ymAH3en zjL{6b?xOJGs8^)ESh35UTd;RD?!5WlR~Rc(y*#n)72dm0;g*nI z)Z;CS><8qlbfsh}c4c?Ht?xXVq4_e9lo1ga-lMtYkFWr4_lz`@P zHf`BM0>2u{cK`GcK*rgjX~0hav3qyiHRJ@?I=)!=p{W2-=j@Gy^aPj}8NS=nNr1Ug z+2uS10Ti<{)O?u)N`6W^9M2-)@;-n0=r{rWw9$oOiUR1g8w(}%5qLhrG<{6I*O{*3 z51o#Dc&O1$ANcT)S*YX*f`=F#;lXd|JUpXDxNpAAL!+s`aLF?svTeSZwN8-h%52PE z?BYYg@rNh-BM)vD0-t$X3o!eLm4`|o0e9U6+uvR!kSn#fVp3Ir6gm3jQa1rK;zmPs zR0No5**W^xNPr~&l@!Br0{6n-udyQic*B}_r^ga}e0#m0a+2If;pK-%*X-n>PDHtJ z>D4wY`%@q^H>?#Y>3ZEs$}I>sUq4ScvKa;s7O!x;+=Oi{miOKBxOh-OVSeA+3_VG) zo~r&PnCupmdVb{~KBYr6={*Ok2HHmcQ z+0n_uzU1XM98uCJr~J!0RiH#lNgALFijZ`F&X?J9g=_5uPVm zY^TIQoq5F>`T1=4Bz|a#Kg>q^(VOcmp0Kg{kFupZ`TgY$T8BIlczsA zyzs=B6b7dE z*;qXC(LW@W1(UZwhX%+xf6NNH;9SfEUuJj7GG`Xv{j?MNe1!v_ke3gxr*csF?vtkJ ze_TL({oz3d2POf~=nox8o5TR!$$HZ@eY_YH5mh!Xg%SIrOBZk$p5f{#NL8 z7YD5Ku`?=V9LV{pY*|d@V&k)m5kI0i2=ksFl^n^!v9PDRy-P{mZ}+cZv@q~hXm`2i zAPcuB*4nF*SY$33$+3{+qGYh)Xu3NGzweo;XUma({khUkuZ4}*?VWAG8cisk**NEm zDhDk#uEe?TZ3a+9w8hw!#2MrkPEeTi3m+`F0vPFxHJ>TL4jw(oRv%2 zn4CP7xh@_yuilmsh^QrcdAK6DMErzU|^EnVX=+gUOP80S7)e4^7X@W;;wF<+h z8Gjec{q0I>M#w15rFEF>k9o4IRd=-I5UCR;<=@Do;v+>E4 zw*X#ow3mwM1S0l$d*8xn)ux9S$O~|H>m0@< z#n(7_>-+Y@y04+RFLn4)wE$^zRQ$p-TamAlb7!e17b|pCq)XEo2)fvpc)OnhYl`n7 z+qxPU-zq2x?yJYICS6tes|~nHc`L3LNI{jo%wYUb1DH8WQp6WhV7nwjvwXS%&(AHO zcmHdE(h3ph2%-Tms{2b@el_4-MB708A_^|&26ycoZh&PGL!;S=f(WarGb0XU4t>?M z@E4DQC!VP##T8`!-8XqOC76QDp6dRg019S{)K+}8q=1+AXKSP zRCthrr9{Zuj2#qI*hxw(>Z3sOIMp#Fo{9^7mId)I0WUuBvDkfYFlEuQPxOOz0 zrDsKjNn(cF>u+TKmv)!m;6sI>&Z})ql6NWR*V?QgIaq3YWL)beDtzVcb?n|n#SO8$ z2Uk-_ele*(s5L~xR|85CtZ3L)|8@1702&I$i%0y|(y&LQ$DqoM20vRpqbtfZTEq?iY)z0qa~A6JfUdes5lL2Iq6ji zy;P{~DcEF{MujeW{a>CX4RrzbS6s>W(C*^g*JM#~X4CuYJ9KF9J-W}%=P?Z@xtdzh zV>GN54e>bln~87NF08Ridxf0Y56tf+w_&aF1xv>#JZKzD>lIPpBP8PJvQ%w828O$= z{4DuU&-9VL<-|wwiKv^MB*%L(?Na3X_|Pt=`NU4~5wlQY_Qps)Cf!R89XZX%&VIYy zX*Fct5EmY+S80R(*pBy0D_S75{^`&Q%@*AJvMAoeu@$@HOzm;56{F>s+IFrYIkuLe zof^@Mw40Sl-OWuHe{MT0AUWb{saoCe$0js7A1%6B(}d_Ak*W2S95~zftlLBST!)IL ziAFdJk%by6q6=718B9|Ce2LV-qz2DcJ0^^#mAfC!W??*INU)U3#Oa;P8e7tj>_xA| zdLCv%A;bUK`G-u%MNT!HHDy8BjM1=-%)>L@IRn$A?*5*oAl&hm939nH*pRx~zy95s zm!yArZr!l?SRfl)%qb2Ez@aYc*T znONV5Pu_M?(z*<^pPmZI_hv%pnWTp2i3F&tkwWUD^I*IukYgy~9iVIY^%gIvIMu3FjAI ztA3ipg`?ofgARW#4t`yj$1iDu)0_A^7v-Cf)TO!M)Q%>|yio|?o@m0Q=sB6|^qgVCTXweh;;(GTM!jS&%pv_c z(mS&JG!u`efB(7S$;9h`Pv7s5zW!gct>x@ z%X(?QsN>?Dl}u#BZ4RtOoJ>^s9K60g*N`5=#r%_M<4TF-?`3*7mTYQ*+}zZ{bQdl@ zDqZR=9&Cc*c9qRZAGjEZIJ?ESkMwPy_humxTvXTmd8SUjXKc_&=562VVmDfvkHRxDk05Kat$8^6I+Vp5G(~ z8xHkcC3!QdXkUr*J`NTfbh^J&l7pD$jdAYeelLB<+;jatnGd|Hzh#|og3?O63pe9h za9(1uOwEHLxxKrp6dcBI|sUV9N3#Cb3Ogo>%KVC%g)f-R$!6?FAZc;9!dQU8J;iUlcMyn; zqn)^Zh7X62Ed}!&cwo9!Mu!fxq9;nC*8NH={)iYSs(xw3_ftxB+XZcKvo|uNFXe;t zTIcA%4?aGMsg_sD5s=oVN2P8jP**^im$ZpM+>e7sM&$E-Y>t}Q`Vr8Y-&b5g=BCsl zw-288$ehG;b6uE0;6#<7{JI1JA7VNR*X<-=chby&3@B&{>8E$35!kRK)G^hDz?Y&~ zhZMXB2t?C7t{x%KWwYp>B%IZB>j5lPPcXp$!mvAmg29~6-#OlpFiFQmro(!^5*=r^w;kJLKu1Zs(UD~j8*%a6Ug_O3Ohga7iu^g7 ziFS;Lbn7#*xvu6KHH3}m*R?;5PH`Y~^K<-flH03SztDW0#=&0a63(B!930Cqe7=@L z>PEc3qS6ExN93&fd957S>b}z5;=@GLzTuQS^4v^1qo-?on{jviwR6l62kuTArBg|L zE>cNcqb<({r+m86tb>VJDyB~9>)3E@pEpNghJ_cgZiRcC$i9es5h=QzgOKP%Hgq@&bzCa`;i23fh@XnzwjpUsm$q4|*x z=BGm|$MhJ`TlywBfXpGsv-4JXsFOT-i#eWqngy>jOT1D#7)Xz^YSDYjKv~4?_p)cm zeX0M8xBcA+vD=3if85K!DqX4ISZ5}B(kBB|maw5>kPuK`$wr#&gqeyT3w+VdPcN2` zIp~$MTDlG!v$WN7atSsXLIuZoWS_+(9###Yk-18O5~@Y^(UJv92cqV%P}<`fW#iAp zQ?otr{tC{kT*E}kHNRFK>BBXZW0oRh9~=l8UKB*0$F3a*>dt&;V@D{z&Mb@# zzTd;Od%v)!hoq;v4jC-#{&$*%l`oR>4|$vm|nsddo_ z8bmp>ExiO(l)T>c*0+^P`rrHY@Bh&dVd4KefvorK=^%ZLemXW}sjpmO+=!4jYxE1B z(4pk8{AfEt!~W7cnxg77Bw3VO52q@8r?51Ir@n@GMLUi;w8)=AI&~e*#PuAQI zboksjEyU=c<3EAD7c%KMlsiUv>C%yXV~_PecRIqJkG{1_p(Eg0{d$KLjZhtwx0jP@ z#OBG^IQu>tF0YLL^TUV^Z^`{FK@oK5);k9nllic9U2u5b&PFV<$oe&_ijLEn7ex2= z)9_empU#XF4bwHD=bsmleDOWdZzP)vQIRH=co!Xx^TVxHR&n4WrpVYC--0E%?K^tI z+K@9;b|*KE2esK>#MWNt;peSdj$RcH&nvnP6q*pYoBtp4qcQ=#x!7hTK_)tu|Q>};~$rgnbRu%mhF60o(TV&Opshn)w%G8^wTNC?V%*_ z(fs^v?5_QM^eg;r9~mQkaYD`aU_H4$&;MibWj@>`|4!)Nqd$ISH?VB?z$0> zXj!w^Dv`j@Y;)cZa&$QQkf9qwK;!9^j?d)2Rib$=!>$C@N*pRM{~^Ht00030{}h;c zJXCKR#-oHnktiyOQfWiVQZ6Zqv}hqjWGyL@_JpKlX+f4q%JNfL5>bj-%szveGfF8` zq!JaC5_zBZulYPY=gf28=RVi>y5?Vm=)9}=Ij$wm%BTK&4vjsAVsG6Sn3Zl9WE$`s z?k=Vu%BrQ1EkEYjlS4tHsVC-lEQL@}lC$MC3O9;|+!ZUxx^Ti9mLG*<7EH@)wiNo@ zp0v=ljBx9d5WH6%n*e^l2gIUzI)-jt8+=cD7^ z=`LM;Aq4U7HpJ)(!F)S`=A12rsrjDzbdCshI$OJ*xQno)MS3_;RfyrG&cfbPe7q|4 zQ{wL8q2p1>-kaMwxOaAe&(;N82!|lByT`@N`NyYJmvFFes@Y_711=gB!`2-#<>CYH zhwbqI9yZ+k8~nV1kLxuNss>U%aye}I*Ufz74fdu>D+CBC4P0`-iH9zw9alr>d~ln+ zmOgRk~Y_$Ht}Hot7z#&FD@A8 zd}72GqHj9_lM)jNzjAsJ!p@-y9@%+zW1&RrV{(*(AXV;2{Jg9ZO&)^Nct z-tp;|78f_F=kJ>TiG$MmK}Sms9!iqdNd1d>IHZ{QV$5b9oI?VHo5(p@&dZE%Zs&lS z>QE)$#m4W|n>1dt*f3u-{_Lt6Hr{RiWB8uK#?a<`9i77*F#mKPR-eVi%P(hDeFu1W zQ+VvA#TGu+TA2D?-_Jus%y^dT5Eq(CUil9t0_^>5qgtWOL)(8=+}L@16ub|;I&&i* zEe_dxRYUnO+xu8meKh44)x4uLm_aQlgDHhcz?PUTis`2 zB&qe136G7Fsq1KQ$!rMnq3l18gS*Asb#HgFQQfXSx0vvwZ`C|M&K5kom zFSb6$hn?fCQ>F@}-|T-=S6K7#F|zm0iY+`C?EYooeU6Qu#eB0v{q>M#{PGLZsmGCX zqiJnB>LFQl+;8rDCTgyFZuuR}KpxX0`0q;wdN-Uhp0t{UB~Lxuix+Z{d0Jr8Oy1jZ z-($5;)Ce$m&+i=kgiuj=wlF$F2$^Ft^PHXuahcQpsHRc?)e3v%$U6eOE%f$@?+}17 z+r31;l+-h&Wnc1;0Q;gsSQkY9U)u&x*eAl5kTD87(;Bejhu?$jnkKyOh@L9`CdS92 zx0Oj55=;&?JiNA(!v1ai?;bn~vQ6rDH|>=oBlpker}h-i)+dHt8>aB@boTnxF;eW< z;ThAuNs6N7*69J3QmE^Vxp^U0ir=d9cC?b~?&%~C4lO1+IR1C{toCL^#cAHWS|UZA z|DTvrHqphJIn&SdNiq5O@7)m`Db}n?9m zMq#$e=CH~66t=4WQE&^Suygy72k|>7*v$;AHatr~KS@pb=2OBYo!(!U2}iy@J!jxt zE)DtJ*#CmUpwOjii15;N*6!a{K~g;a6qf$s423J4RjnVlNiq2Ma<8qr6jL=ljA(Tf zj#s)|Sm!1|&r-d@=HVu+mkBiqb!|e7M{Hegb0bn**$#cj#ZcEWWdcgZ|!g- z1I1_Op6b5Oz?M(JJ3X@)NRU@+dRfK5i#`4K&UMz~WEXQPwU7nZvQK$aD%hBMJ88FK zlmLsdq-y`qMwHKaeE~DX$oMwj_*bA9Ww+#9ub&XZG|NuMDzOQ6g;s;Vdm9kr$lUN| zlMv(SONK{x3bEjo{OIeOd|X znTc2PGmgD-X2Eu~O>5*_Ht`)(Sm6~cw6#vOXeT;-LjQ2V8$%9)#~A8)hjAhQW$$y3 zMh?2)%Eg`T<6*`FE&GLI`7qk~;PU79YZu=g!((=RwCrIOjh-E>z}0ZQ*nt4%(iR zt+C+Y-1GyJr`=)0H@})QiEw1Z67z0V@{vOq7pz|*fKi3LlUa#?=wR8c!o4DN-&wY+ zu}^@sr2#jN)$)<@dB@e$mE9f@}7|Tzfv+UbI)H zuHeJri+sl2aeO=)E2ZU5<3nX%i?v-p56s6GN{UzV@I1>bOtOg!Up%`E zE^t9VSv=ulBNwuw>2IAxY}CzkN$s1!waiI3Lc}+BKu53o)a1^H|exA*QP79~o;T!shxz-NM%*^k{~kHppr~$h0r- zYMv}@;^aQYxE@jHvPp~y4xOXkb`q>s%zV{$TY~oO zzo*njO0cyJB^)=33~ga(hKNGH^wzzouTo4&GC8DEOJUmA{+{qu3SWYq)=aaKqU?$7 z*$PhzrdzCc4K9}=VD+Hv-6{$bM8Pk;hA32?wH{U8MRa#pQ&-jmqL-c*8Gd(&j?Z~` zZ)y((Zv{{HzeL}Um&Dg=&!wHFLf4hSHDd@r1j81y z7f^VvyYhI>LJGIW1pmxAMq$^Ri^)1fpI6qE+w1IThT~4{$lnGweH19G@V7GmB=FDedD{{| z!7N;F+=4w6JY6?9n#M~pPT<<=f1mWHkOVBkFXtzxv(1a7FjP}%U*bgSSarSqnjM9R zCe2w_R#6BHKK`-9h4_G6J4Yu{msVNg<+mRtXx);|RwUe68-7wI+ggI$+4HVmjFMp5 ztrE-lLJ6pxMW+IWCAbqIU+1Pp>NHw+$8H0K0-dAXZluqbO#9+p9#PohqO#XaM~c!j z*V$>)3CE`ub_6k6@Un2u`CWuV*FLU&T=SLG@4c{5j-31Lw=6~*$zKC)(pG5-h47R) z1<$-GeADWvUwxFqL*7wXd5vWMP z%3V{4u3zA(X#C+~^Id)UuvtwwW%s9=TgOAM`C|7VF9G<5ODnpM2r(2QQ}lmd<`I+= zbKK{I%LcdWc!1)IiXW3eOL?3Hz8ki`=Nt$m_RI~tjw_DD6 zzUAY%LHLdGZXSLua@(0pbj$4l9?rN%bm+uF0c#;2?~jd{yMXX$v2oJ25JxVeBP{eZ zB1kUCo9V1K%E8=2U-ri%kV; zY~+3~)qBrj!PIKrs&*SL2Aqvv$X@5*Q--E{O%xmArya~H3&OXCxKnZq*o5ov=j{B- zf{T3JkX16#X_*O;ceyOw2n_R9q7k0Gve`F&EgR$SCY(vAs#|nwvwEMcQlg)#HXvhw_UV3k&9a;`xbEm2(Q{+&h(?WSee?}>adoN z`x^3rHJ^E)6}svCWbp7-b&2+pojj~Gj!lWK^pdA~caoe$|bhKfX20MXuZDj{5e(H+w_{?O-Q?opq8cZnX~ z5S;sI6vV|$g(o6b2Nz4qOU=xRcwpo$(shdA;@hP&f-|Y4pOoW;cV9S&6U&{SzK@G9 zx73VY()if#^TX&0@e?{;FPYZgc<`zZovOkm`Qz`w<%KG2Ouk`QXWha^ZBCSf@lhVG zWb17$eM~sncVNgOf``qn89OwbIk3E6-TCM-;dJj`zci9>{U<#eJF=P&YoTG4-zVY+ zl9Q&%Ymxk_{9k2uBoB!>Ero$wNuS;o^$!uwmmabCy`6BZDIz<3E18$2M{K*N{N#XE zQeko^hn)NL4Yu<;Hf%iK`+oYyf}By?yh+wvs8*Xj2ngoFh8Ep4yOXRpDh_6N60S}+ zRjEngf|7l{t|Fd?nc>XNOI|$KFEi`B{Em+bb+$zind{!!Z#ypK3$Zg~!nwD`WX>-! zM7Q;YNQ+xutF&DR;gC{t&V1s3Z`qW7tL-rj8( zCxNcp6~6k(COq76Zo??yZ)SjN(S~%Am!-?%t@C(D9|&D%Yso?A;kmB6Z`WhNJ=K(| zPA2-NS>)3*=@{{-`@3#+9Sq;BZB3t8i&*jMW&YRdVD-%Ct8I9-tAnNOjC!Pl;G zX{&=#)2F#Z(RENde|2u*i#k|3t#y(=T8A&CChqf>)?pLRFjdW^4qBVmUQ>Te?rS#F zc)kS=to41)+cDr=Qa(v`%-+QTLX>Md$E)R;L8}oQpWV zgtPt6_2=dNm0%>i%Rio6H&aiziOhnZ+bIJ}K!ucSMT3HK!t$$Ps^%t$*K@n=mQEIX2_H5XtSmGI1&blx&GP zU#uv^1BKP0*B%Qn>$TzdUWN$D#oDZ!ks>5456cgkCxU!$m2{eX1Mb@$)n$JWfHs

fX9^TRN{C&p*q*<-xvnmOtJP~zbbQ8VCAxp9JF^Edkf zcY*V_poB7#5X*6H%L82~v)^mIL!=wVU35r|C{d=l!=@w|=jrF{PID?E+)fBEQcZ^91gdp()GdBZ2d+;fh^KG{*O1 z;+`|kl-$}{cQVSClB=3ZuGeBHQ@gxofkZy#x~l)koXn$S&tfYRozs*_JasB2|12dL z7P`;oouOo->FCUT^^_F#O+DLRNy+?Ty{Q*YQAUT8vHDXUCGi4Njq@@oxhtoBWfG1@ z9nKcrWw0;U(VG&ZpsJ`3zLfbG=2K=652X3{oy0>2fhe9@H9i~bv+um%os>wR5s8=L z%(8*g^y+(;ei88Yd-K$np8~E{qZ8k%0PJBIb8kXdA=_-DHouxV{t`S_kt*rxX>mY!4ZEvo5HFWP2+j*E<1>JXiR@EuhLgLld zuCoO^aQhxnp&8Kt;Q|-DUtQ)wxIcgYwS-c*ulQD7s;dg(e10oTo6mzv&iHfR##O?` z#d4PB|I~oxVqxFI3u<7o>ZYZO18TryW1--pJ|1LZmt-2%0`KI7l@H2!;Ir#dV1Q#K znC|*vtLt3}J&bl|i8&8c^rU}_dsV}fI;ZdF#Bsit6Qi;nY9Vizo8jCSRgm{}y^eKz z5%9?tmEEG%pc4PMj0vd&6?2s(Wl{}bzofMEM_L{BQAxnZ@CHbV8(UkTQw#j3uhZ(p z%Yc96^+ZF>Qt;Lru5@qUf#l7#F)Oy61~O-&YEO49^jp09r+HBgFq+H2JFN!zk5>&C zdes2^;wt?szYLg~SMKSp)j-bWFJAkL2jJ6^H9EZtxWWCqdCw{V-ir-HudM;{LvevJ zsRG7zOYRGa3LrNBes>tG0wVSC-uE;0(Em23$Np&p({4yEo*`M?!n`|o2r4fhCh1UUIARA84h1Jlmg>D|HtXCg}~n$T%0kp5SV4# zLG5NPka)G0v&NY~L@{l5lYq>Nxil&riRVLUX_G9TBjZ!5SuM$wSQ_7#+PR04-+fN> zLlh-9s~Zx!vnW}$RDY*?E+y|Lr}lj-qKu&9K#z76W%`>EvSb=4x9t4frwt91$k(2F z7*Tr)2g6;=xTt9MwKi>k@}Jv_ogz zKoBL<+Jr1$#2~J+c&?1+U1Qf}7sLhA>1`^XPSXq#{E0OEqt zuE)=fb|Y?I&VAapgOU-pul6IJJ!{Eq#&ho?Cs5ex{=aj^JtOaXNrMto7fyPc5fG1H zQ`0zHhdW-$;yT-~y2wN09@%zUQZis5Tz&xKeK1Pj-0%SsJH5Ak82O0#LT%y| zfCRqzcTdn>I<|q`59TGo;Ek~AE+DB{rA23Pe$peM|4s-;Uf%Haj*H~szf-fFoPpS{ zvs!M0xG1hKzh4k>(|%w|;VTQo$wkU7O7^(_CZcM9eV}rD$;>oAN{+31BPVkN@$B)M zG5^E39~E&+-)Q8$14iy$fs{mL8kRS@V|}iVsDxl1e!EFX-okjNCC0l=!BMSZ-F9o_ zE#ZOTUs-!F{^zl$N2URh)M(6+vw<<$`K#VLARqK$TT8?O>8l|^OC#EAFJApJ6wE65c!@M@E-krId zl9{0=Qf9cq*n#!oza*_OUgrnD)10tBGfu6zrb$V^`o(XzP)B$#eieTq0LILDM*{1x zzP$eRcG_5P(p9kTrZLuazu*ZG>%aYoaT1AqgSK^)aQ5-DFO7`KYsa0S7BO-Q+X zzQq-BYu@D%*HAjvS86h$4*RS8W2dnL_Nk(-xls}3ao#nJHv_R)w*ymDogIK#vMMA` z8u3BlhDfP*DlqFi_kLMk0`@X=$lzE#FgZ46ocem;Ud)RYPCz{R?AsI8(g4&T^+M6f z8sI)QpPU&}2?8=PKX&$SFjU&Wth7Qt9yO#a=Q*dHR(V^-2& z%4mdk9u`gkBJkC@I~4g>{`t(C^ALw}+4WK=G1#XRbr<8DwZ`A{Fyhenm}Ocg5Jy~& zS#JGMjQCWw>5P0iWq#jLca`B$Mxj`&_D4NsRyzv4c0fMf-u`%&=UK`XPwu+^8ToqP z+|WTBiJl1x7{sei{MoeAlqPP(j%H=y_@77S# zvIzkSpPzsErbVHaGS~CNXEfGPuJBP|84nyUvHFrnxm)c8jAkKjeiQS*(pW{wx`4=E z_i;WWX*}7d5GP}D$L67)81oYv_qYt-8~kz0s)q90rEd2Mvh$f2ZWls4Ms;U4r=D_4 zwB%o1MLf1L6mT7@r+j2x{#;yVr~9CpIgT~2wY3-5QQ|OF`Nb4mm%C!_8m$`2PzCpH zUCcwyo20C#)s(zkT=6;>^UT7l48|dBA+f9ud7v??KdTt?Fx0zdbx$E>e9U_T)|XO# z_M)8naX4RRe`Dhi>Y&>XJZGH1JjGu*Zr4^z$?2^kFQ#IAv+us<-otuzE0}x;XrRoW zbC2sjab5A;vzGE579Xn-#`tH5>Av`apOcinE)~JwFP+?J_5$a3{-@8x8t29Ccsmp0 zxc=~TRA?#YM^Kv)$NX*TIg=8LpM_`Nr*HASOJ$Q64xYsGi}FZx3ZC--B||@Fdf?Bw zNCXmoJz7XEAK<@am>HM@{WChm0+dfd-bt73axd{byzH3Y_q`YrpFdQ1s8j(nwNJ)K zW!6EGPl98jX+0zj1`r)~(66D25o>`>~@?=xMq#vE}Sf9L= zu4ah4ip}=kZHV8&#*;-25dQ#2K)Ap9H;HAKBM$TDXoY*BpBV_7)0T`l7}=%~sDM14 zux8)niHHv;o6IGJQ154M^HjftJe&E>SsxIm2I?|u(%fGD6oKzJ&^ukKMV1a zSkBex)WGot;{BJ43pMQf%CIfl;JC=BDh=qQeQP0gu$PWvqS!;J~1?C8wc;q$1W3PU! zLp{)cq40VX`j0i7i9h`vfZXa{7^sWNp7ATzBJWj6Wjsg! z(u1%kYfqUXreRC~-;-p2U{Cq>>K@jqLBPEwZ{BCj0H^tcrqik;(64-X+RM&Z5U`bK z9-N6d%ZYxwrO6ik(=pkPN~k;P_}l&7Vm@zb)W&>6TvL}WQ)xuKb=*NB@@P8Naf3jC zJ&sG+dLqB}3tu^V2=&DfM{B*r7Su^!iq1d)0{+t`(d zG_-N-xKp0)7e$${=iL;DULL4E8`CU1F4>2}KhqjL|U z4?V9XB5)W?Lwdxn> z>6ZWus>ak$!SHlKYfnepQQ$TSihliqyxJ5M+EI^v?H!?|u$ATQxw6aJT_`~{zOW6? zjl|Wu>ByHgOO2-KiVXbI{FqcX$m%h8`E*_R(by$~2tNB`*;P#2nNiRlE{VPC(? z(Oin>GLPk7?8lB^dgmzSoqI1q+;=#L|(4ka2aY~%OU_YSvy#C1}<9zsWEYbkG65l*rm^<;lRUc~d#PCk2wqB+=p) zg5;+aO#NPjkLZKR({%f(@(OnO`KYfG#aZ*fCge>~vA3Yg}O-G%)m#VM8;c}91*1PvzGm+91o0o;illHRC6j(h*;L|q(M(`iGZA&|&3XCG*smA)m8Pfg zeEjEUW#my!`I;MEG^e62`(<=t?-bN?{pTF?15q!97;4zPtEJp4`d0Kf>Yq4av$o12 zH^{RSz8_;j&Ni)3;UQL zzx~kxh(|22pdVS9rLpidt~Z2oHa8N+_I3WeejoXixATFwr2+D=)TFIL+Yn!q9T+`b z8T2KA~Nb#JsS_PZoXHNPO=xbL2;p>cvUD z=wC8h^th zeWj&M{~%5;-?71bCB8q`EWinI`JK6=9~bqCDQg6fZ&lmYn%qG@ACcnOFA;_K?{;t2 z6Rc03Mdro(TzuYMynw;H@>&1jjq`H2hmNxMzhfG=GG-wDzj|b8YKeWS_dRm@3iSQI zoE^@wK6Cb&%v{9zOn*0Jb>sm>Me%=C*?VmJq%W@Qz3Jtp4f{|pb?gh1mDq}Lp$(ma zb=DE8_4p6#B-|Ifs2Sti_*2%t3ir>fKKcDF`e6~ZSN+E^4&JTQdrx$*UaXIl#d`d6 z>WZ!l6)^p@ApF`6>^l>AA?|*Bo-%v=Jyw5uSAF9JP=OJ-Qke_*T!n1&d5(I{MGTcP z#wTNRWoQcOPx}ejNVuM4SG46X^u?vDUd4F3H#MF+iSZp1ek!Vnb!D&Tv(Qi0C~USe zj)5_=Bes)FgYi5^@0_NU1Y@aT+l9yCVeARZYj_SiOrSI#`>W^V!96;=fpnS{COICW zq}(qcd(vU#?`OW}1#$g3H-g>1qOKOXR37{tb+qcc;j3%*15-VCMO!Bo`*%jYe8n-~ zhrQGejynaH4zV|)h+my0=3io}Q9lLG7;LFRy}=5aVqhk^jZD8+1^tnxk6Z5W;8Jos z|3+&$aP?fhhNAOf?5s*>{DW-xKRhS^VmoEjOTG~MQu?yn(qzofTytYd+-K{9;y@eh zkJYTc#QyWn%>Sroig}eYTPKY18WoG`%OeiCZ+y7>HR6HL;#&6*Ul*`q>l2VlWn^{oS_VB(-t6}r93G}DMCN#*mi>xfd2KU^{v~JSp3S~ zsB#y5!Ciwm0w4o^5lE3~9@$t#e*$vx~-vcC^O5;#3mdIP^FUX}tb7}X9|1kcp zVVTJ11*jkPx~^JSj5=+66UQ3Ir&-0fCD8x5>#0a6qhGZ;IBb3v=ex5&|MoJ}Ax=-E zFOA`Qi9apgUd1@F1dnI0$9W&6-x#+ik23EH1|kx1J;OSQ4cie<-=X}PjrcunypxP^ z4rM<0Ur=3-@9kILy#EHy-(r8Q>|Xi*{CQ%@%L&!^`JSig&nonzD}>TM4x$g`&5;ud zDyEDti>J76R(@Gw9J9<1`KV*OG5loiL7dOcdD*yA7}s~@BIQ}=Z#^$xSmA}=v&TNG zh{czP`O|S7lfh@dnyTpk{lBCd*T3O6@THP6TlRdAds;!6ti8Q*zwy1e8vkjpaDElt z=Z87Cp2g=m$%B|Tr75MqwK0yHYy%<>u`<;H_1R{j@tbln&LyL>9#`V;bJtib*24K> zn>5nIvECC+!Z<-Sl<9LJUJnQj2V9`)sEoJ`btQtyOQm!n@E=9b)J>)#;C?&nebzZGP zop(5M>ZUIk?@Io--a3r8i!MxCjNcFO$>kWtZ@)-2jZj}2(R#wNUnvfG%WZNdjyMCErR3$38Ye<0;WwWLPzfeDE$| zFy0W){W}ud9E|7QgYBFBG_U8*>h8f~z&W5Y^e`kA?3G-0I5?%koshf#M%kT!yvip= zMl%Y4^Lfp)q)Dm3UvBmAfMXnRn?)Bx*&+1hkAj|Qg#6`YH_8aH_g=_@A5P~DUq?P_ z&>g*!jy$)}Hm6-0^}m{2)$#$<-^HvE!}!^Mhb5p6|B<@8t_k%Ivc?<^`iW;Zgp$|C zq3*VREQ^k}n8M*tK`q*9-dZ9(^`ve-z|Ng}BHnq3>2pJ}zdn z7xIEw{*FXl#`-dM;Lcn(zgW)~#zxLRE8Bp4!e#w0;^N3tj@-ZMK=vFoTH$Mf_!(+v zQ;vNzZLLhq55)7-UQS8^>WXRe`z6bx{--lI>^%eOyjUi5qBPb?mA(J>q5LgP^P=CP ze{}Rr$R1+(mG#F4)Si{M3X#Cbp4>dQ0{O^)?}LOcZ{V*`LuZclR+McPOJ(n!*@JCG ziQRE@etv)d|6oD6YJcVj{;XLqlrQ@Mo%2fVsV(Y`vogJD>8J;gollHI9?bJKnm%kt znOvWz+>Orvp9irYGQ0lw=jyB=S-IOus;eu%QWj@UnI#_9;w|;ncDoU zUlEbm$6mW01;&8=k&fHlZw~=k_V#zJWEgPY<%d=F#{gfwAmrYvVCYxxdzhKSz*ze^ z{niLu7?ahT?)q#J5Z}jREfaNtF+TZl(A4qoy)){Kp|X?TQZa8EbKd^+#yXJue2a+| z7{5qaUoZCY3-(?Nbz4Vh`=e^~{WogAia*78D--nB)!-;%YSwx$j{ZLY00960L|J(} zmD|_fq*AFQl_DgSh)|{m>ojUWhzy}aNQDd$QXXSSGDH-03>goOSta{4xhfTnDoUC) zQIgwD-u1Zm^Zx$YpJ&>8?Y-Cf4*MaB57v!$O`;^c`>*ti(UcTbqRPUZd`xoN4TCS$ zAXEz)358m?A7z%(Xo}FxhS+z-KH3Vp3a&QA5j8+Q(nZ{E-r(P25ol=m0S>3g6M+MB<816kq^A6-fTSCG&pOh}fa9!gI9gZ; z!+rBCy#tFtas6HO{qriJzNT@5`>h&i4LatK6I=z}%B$zL*Ovj$==$(%^CI9mEH;_a zl?TGQF}0fnh0v85v1@e-A2^4Pnx@&618>T6`A9|pT{B}_#dRyeY-X{u>W~0L{B2&Q z9p?jg_Ft1z*Ym-wrc><2(hBf)d}ymKr~)&GBYQSg;`^3`UK)QYLGeqEmCJqsC@6Wp z+G1G-Wa`81qqbLoaI;?QDsBbv`i&QBrD0p`Z5wsF8n}DhM+rn~fZQ~jw)I05DDq@% zwg19?bUr(u`cMgs%W<BhNj_)s>f;(6X+>F!v*8Z#p#gY%f zIUg$_tmD-F?MmgqncJ{ZT%-sXw@n}SjVlDse3?5sErlRtf|u-R%mHT6*W$4)DIoHL z$CECN2f|_VBnk*=;l^)ROGOlK+bqrU1R^?7*Iz!068*s|F2#wIw5)1vD-OW+X?~#n zeo7ANmKa)}ri@Ydn-BKcn5Sdy!sg^sMkM=3uPf&H^@OJE!{wA@MXmhYTTVG*a;sBM zRZueR)o&A(YD%^{n2w97pv>n(#p5UPDPfqJJ&*G!@yl9or+StWdGqWG=hHF2hm$Sy zV<=H+z>48w9Vt7Wxno7if%dg-8VnHL_Bs5f)j-5OeFyWl0$FsxE&OE&kmwHwCteN% z5_wjiIUEY4UpwwiS^yBg@5kPs!TIvb*67R&0>bRC*nLis5=o7154d)ecx=cOU2u>R zcjlg1E{-?S?@mfqbOv=B;QhdT>zu>)VBK4qNcvBvB;eO7hdgf}sy{`mR{H=sk+|X6 zpdS$B{U@*4;&uDA<-(M0xV}Zto>&`F(lwZUFJ?E^bJ1kwulAJ4v;`PZ!c zQ?k~@=DKVUuKQ&@le32?+3)h^%#m>GjPB-Gd;bGx8V0JdC|ILFSZ*l75D~I^8R{kd4MJ6%U_dJeHgz7*PgO48hX^i_6vTDLOcS;Ji?2N2- z0(qZ#wp*V8k>)3*uG;oM(l27AI^nvuPg?(J6s{}ZA~^p5#?^Pv#95P))|>;XU0!tf z;CQA_Vh<2^wtmckm>u%B;%%d(f9f4Cb?i4$>wx;4eLwk@5#~?2U$3#dGbI-?r6f}rN|ruM`P&HdEeful)`R$B?5zh}cVRy1&9sWfycG6c{E%jX@#vY3|Bk$(m|8bCQx{0{i^$btIG&A$ zY}R+oqfeUihc3AQS-&pRw9+5PAMC2xyqyx=H{-whVt%=2XWd_f{a<72Z5OU{Vpd%R z#?>3~y=W)CucC91H_Zn7N$GH!x*Ld%jo$Owwm_Z+3a)!$oJ$IBIXkBSQ#)zWzb`Ejkk^bofQbsvxqo;;S zBYxN#dl;70P?D-@K9E*RnL?JYv1Pv8%J_VNawJ5A6}##v)Bn>VuvI{r>ANKS!po>I zYu#5%VFl%UiW04jsG-8h9X;<%YA8pg?(@M1Rg?_w!;vc~Giv)h8@Wm!|(R=?_urS#{O&j7O2W%J26Jm`VO`YHZn>D<&=35EmIzZI-~mN z?)-z;Ue-C#PjUTv#E?O-eJ*mQ+PjD{TH<^;JG?g8%#UA>-}61={#sW`Nyp9)Yi1xG zqsTEfJ%{zEx5dA?lnNVJfq-#ses{G>tca4GwJuhXB~-|K=3XC7Xg}?6N#S*d841-GceJ+iLT&n@PYC_zYb%OaVnJt<=L;GN5Y# z&kf&jxf_33@IPR6Oq!hdt zow{Q>rT_xVYMn!$px$cpo8S=315V&L(?g1}z*Icjm73uTit;laD&@og^S8@&Z~sJK z^5<<^KNoSzb;!;60vE_NjX3#1eGpnNkMnzgb)9*&=IK?$*K2~S>HSA2QJU5?JsfeA z`%?L~f*&RS%#IU1luU`J%KEexoafXBz3Tk!h|ikeD(CA`rko{m^Dlr zL?C}lsp>Z*0;f+El}{K5b-QnPxkUmo?t0X@0>`m%@|e?{L>ZQ@Y*26i;?9)4fI39I zW%cp`#EtYE`&ksn@4dY*-JMH?deNk-Jp#C8hdq)Nl0b1pKO_QIRrjs`HOvRBTH~&0 z;O-iq^|(D1I9H6H(Msga_gQV*<~h+W$pqU0Wfr%31Xt8|AV06KG%7?sX&*EmxQl$8 z$MPNK9qF1ftr&SZWx0pa5^Kam!&g_ryg>*vCeA#L>nUXQvMD7_p7B||xG&A}*=`$< zKXYN}_t(g4yrmCRl(Ap&3zzb=kay3F@D=jhqPpr?zSw`~$tBNF|L|6=85Xlfo@IGS zpAzX%Y5%vT*uOO2N7vy$UJIbZUE2}x@q1zD26_nj#;jn)g(=8)B}yGGmdFEB4;P)) zL;b;F>&uifCVlmV)15$M@$=))7Gr+;#wEP|wgvfv#YrE;jhj+guBaCh%gg;Xh;Uh;caXH`DYKp;Ud5a_v2h~e;L0`nZclP4 zG1!?twHouJNqb1D4}G4gt9ko6tfPODl(hL+SH{bZ!SFJ@3OFIqZ88n40FOOS>~<)lFUe?CuE@&+{)10p+qi`= zHF#)a$QJ?ZRCBj;b`^kH?5BuD6VL~BcNcc7Err8p#z-U^mV%1eHKpj;WnlTtq}Swr z0qkaJ#;gPcmNR;_ua-f-v3s(O1^TkC)A@HNRl|lGte&d`@2CUkW4;O?@ZvlJu5}gY zSBtbW;x!=1x$WaMwG4zmoGzKG@u5qrtX^Lg{l*Bs3V@k!zIbqHIqdMb#Z;Z(gV5Zi zH2Xn5FiF+2hgu4NRbMmzDF$AApVL5PDYUX>kN!||_Og{8gn za*&kDLBUu7FMdCBrC<0Ec1keh5?>CjaYL>@Usr%+&-SgR5>)dk9h2iGJogZfwgOCj?u@K0nkS}8YoCPv3b>UmZbO;mP(DfdB3OFBB z##W6(o(Q6M?6DxT{R9{$issHfjUtC!QM6m0w>mI~ANxzK`1JgLyRM{|AA5AZO} z9CUDhmg%>jcBdj{Yr5q(Bc745JJOBuKIy`FJTUx!T%OPROzii4?)8~hQHRIxR6ZDq z{WDwqzA4Sc_vJoz>;7sahjo2BPvAa@ubsZT8}W67PZ9SO-z<1&h}VPhYu&}rKfS*i zoVyKuPkS(JOTgzUzd}w-L0(Y0PGaZddZeAWc()Jvo;?;Ic%R`GXVk34c@BIuJ>UhT zdc-%taNUQr+1)$PPd%~Mxr@GsW2LEDv;>9~mWd^ZA#b#Nj9H`0{O|k7t#9ATB3_fg zdskeMFS=Sk1nI3uAGNXeLZ$^JnM-o2^$_0#dRod0w!-jjxnw&P)(;C_Q4acH%gW5i zd&u{LGJO4q$V1J$g5*0qF)#kH-gXN8e;IFgY$_Y~;zsx5Mu_Jd@AKSo{TM|~bb<*G zxsFHE&)_}>>Tq@!VjS*fODA)kuz%t;eKE$-<=Y_IhQ2y6>b;~s`uDCH-p?jYJB|Qj{cQl$I}L~*Y(Qc9}z&_ZdZ6Di+Una`H%%<49(Fn^TDMM%14!h4tqhsxeF35%c`+r1~<{H-W`#yrMDAbCF!DOPRnt zmt8}=^MK=?a&-aXAxY5_wj4m5_~VQMxf-~|_ohD{6oBwUWqNxEwz*d7A5_pc#odh7 zNj(Rgp0ZEjm(PLl;CI>iv+_Vhufxd8Bo2rMt7lM0f)@>`MEx3=K5%;|3W(|0$}@Jy zfYhn=U)GKWV!u7mQ5AWt@$!uMThTuS6y_^`#JF?+1V@d=`mSm-fa|D_rb@h<O{^Y4p1wEit8Rxp zEXKFGI3IO>T>PXBR}hahC6Mu}DAO3ebSL^DCjF_!*dX*-BfNv-`JKOPb_9LL_=Qk3 zfc-R?pO3Xef6zH@V8=UbN6y30SD6U|G@Y@ZU9GKf8QLwF3rMzHc5!89YH_BE|($pbNWqXn*qKT;33xSk2=HrOpw7Re4lIcCj@;Q z^FC{Q{X1N*apsLY^m%0Fn~alJaa?U#m*k`>Din&SJ6y(i(>qiuAL0AASlx_%Ps99@ zjsW|MT+sh31@9mI`D)-6ju-YZZsyBU%JC3*C%>(toWPKSk9pY7h5>P%HMkyQoVPpBHDvqw6TQey+%bpWt;P_kZLN}v-YS^D5BZm1SbLaP-N!Vcg~wnE(1o858W$N7X*P>ZpR(g!P@M=j_9`Dr~^}F_S+HF2?zKNGzMP-^p zSfA2qft)8NaR0sEtIHz~qZ^drBR(&x62HF98{^l|Sq%}uEDbf@dp{6*!0KP&gm^UO^s?h|XF;<~arBlsCy`H=p|U`Js4q*O@*L+a zrSW=7M>-|zi!ig|5Fdh%Jj+g^r1H}A{^vMu!xpRTFvK~|oc*oyjOo98<^7*NL!YKL z`QFyocs;?fe_CD;D54ux+JdJu ze0KbT_hr0*IHvJv$|yKIP)Hu@+MxglEaAUv`gR|{M3 zs4EgzeNi&T?|V;Q*)-Y}_aUiDP=Nj@aOAud{mcm8;&|WEN)(W{P z71yA3jpt_cQ@>^W9wVP}*&jd~u}(&JI^MIP#E11w$k)R9V`F;JKa-)|xy!Ksldq=5 zoWVT4umq8K6Z-ie>y=#O&B2E5A|v)(xfXe_)$rfAZIO3O=Z)eZf4|RgbYA4go{y?6 zs#l;S_M?ooJ^HJ7o>odB@^9C$LCZ-aoX_+PX1@bbAGqymTRshWwCV8~TTx2x#udgI zVmvV;-%+w%B_s1G`oFFxiJ@+0SPzY;>{*^>6M7-?Bzukus3Yv|H@rf=XGZ@VB`*Vv z;mTT9VGx|HotUc_7!UuR)5n1DZE;XS^AR9MEFa_i)Z(mdpCR9l9Lxn!(xDq4-i7+{ zQ%Q+v4dxfJsr)(I&&-BqvEP_~hO+0qHpSxp%njA-jYnPbVb!XI!Ib&yi|D-3ZaB{$ z6OFxG&~H=)$&HBsA&))pjt3rl+&(o5yvv-To2DiKZyS65jqx~)%m+m5*#kUdAdzh1 zV*imN{{^t_F|A|}51b0Gj<3Ty?AVo>aW985EUbPmq8#?v>oel!og=%(X(OKI4Gu7a*>7ES$|BM*Uok zVSh(G#V@zaQdi^qgF#kgYaAO`+ zAKje>!mz|eT+ssH4TbqWYb*dsk2{x_WEX)9`+KUT8hU3`%_~u=2hEZ5l^Td)))ZP) zRROPU_O(0GmC#aW$k*Fb0Y{3|{SzOTfXe5IjhY$7kavasuUHKBwk)0spzgM1j8S(5 zgt+)UTw%nAi?Md6w$I^%eErR-;>$~6{2@X7#7;g0n)eI;;+DdQtdgz(Zujw=I~`RZ z=Xa)J@e=_wH)gGk3@w7fG568o@*#b7*@G%Y)IG=dw115)1x42Og;zq1gY?Q?t!n6! zo_*sDRKs96tFx=X?5p?krHjgdGyC-qt_AYM)Y`N0eHDlgI*u1MRs-kniw7R0qyJm# zTA=Wt6nG7(27VPeA%xF z@$7#CKevmkw;&(pf4QlF_||x)+*Sj5@@ZM?*jwq8`F%A_-sBu57ugA;K3uBmT{#hT z%C**>*Al3U&{g|xLY-LkMPWi4>cQTa@egma=PXicxk;!;-cQ@I@?Ie&o7w--nBPy> z1DP~R9;`5WeGz&30>bfh9IuHLH0ZCqcZ|I=6Y)m;%^|tl*gjy-2N0JB*#9`_-&#>- zr=!n_3z%kc81?u)v)n`%)VaUrn?&Tq!m!S0?d3-kkcThrZ9R#8v)&+8g5W$0k4oRX za^Qde6*wRNR7fK3vi2q;1jo(uNUBDD;HK#G%wc(h{cnoCtL1@m;F@6ie*gdg|Nl&R zd0b7;ANNEOLZW2P9)$`?=yORSA+#!$l(Mxd71g1ljc!T{EjR7^Z7*U@q-05vN{T{C zNF`+L`P_V;=lA?IubFdZIWwQndznKFbLJ(CbfiOb3jITW?Es=PrE9XA1tlu$_IPxj zq@;F2Np|E$Ahlz!gc}-RyZ=V>4tp3nxZK_?^Dqc8>FT!U)&WT`7AewVfJndB_~dB? zL~WooOWpwp?0(KqJ`057qT~O;5D3G6Lpd^(C~%i6XKe-|UhA!0){?Fvoltf?3yi?~)39J69_5L18bRKnxs2>L+yEdvs&zurYf>7BgB}#&b zt<;J`KtxwH)w`Xbq^nMM*E=&Hy~kHdzCJ)ndi1xjXeapBe?O3#O09?ajzEsceT!(t zc9{des-<^PQu4IH&-@rAsUhL_UtqubZAI6kEr5_B-uFrcT+fifthJ7mm}gCncwBXdcrKhRWKEy}C8zr|PL(m(-z0faIj*DSGoI){Akj{}+BW#Tq%~sY z3q2qT?zZuAyD8bK$hkJ=1d#UA-G)g%K(2|Vy?A~e2-iG4su0hoNoy{5y9p4Zqq2ol z&j2x>t<<4zkK^-rQ?l@UB6rId7X$z?6ucG8i;a+nt|~dN{$)bT7D;(5|`ZrY!#Q1 zrUd&9V=;bTcN4!G0hC-y)EY*%wUnnzg|I<~hpkCF{VR;*DvWtQA~teKrb$piUKxssWb zky@U?pO%Vo(V6^6C5v*zWz?%C;QP(``89)B+V0{u^<-1#{inwo>dBP37n*o<5w3Uo z&FQ>VnUwU8%UR%-jq!bbi?Tr$C3;hPmG0pCzgKz>ve@38V_;~XLpgn0%ht!_Q|8o{ z8H=VDP-0Sj@dAfWIbT#?bI0@XJKSGr`xa2fB>jn0BbK_m%kDSlQN|wvRGsoE=TmQ^ zaNP8oQ9#b43uQL@dcFK?|p0F8`hmO_qZqH zemv@I`Q)BPIZ8rQ^AgTGzifl3P%dS*4_(qtPNhtRVY1mgTz7xivlAO~DQ9Ov2Dcyg z+mr0Ms!~YFC6IRQDWx1aDpu)NLRkq*VO^CXO6J*>{>;VaaPi%}`?&x459duWPNU?$ z-#AVJt~0Me=g5j{l%(y5Zu!ik%*gi^Pqpyed5P?ZNNlf6q!G76aUA;vwdUTGXt`zi z^f&^OD5bS1B^-Js{bIwmB|)tq4I`33=AqeKCo3L^iy5_cuZ;(t%i}J4ElU9%u2yb> zLn;g%PEeh7?+Slm59rbG2b!Hhz%)wqZ+sjMy!NotADW3EE(ka4 zYry!@IbeN5OzV420<%6&=<6XLXuG`N@mCK&coly@ zv3p-2mAwiPumObvRexZVXNHS-A|4PmBSn*0h`*Cf z&+Y|EY$D_PHY4u79r$|s(OF9L_i1)-@TDYtvA9bBmKTptvk%91{sq^(t8Q4D*j-IS zJj$H$`C<@0&yJBDOdL0+81q*7(Yl>=SZ4MvpW25!usJb#zc!vjn@!btdJ6M+ ztAvjn<}({{+xyUYN~Wy5{lZ%T`9|b`?RT6<#S%{x-?z6J$rnPr-rB6&Iv;WG_w}bS zi#;jnJ$F1%3G3pUr4GN|fVe5cId^db@<_<(gP^I|Quzj)`Nnu$^fu3A(C^`P{`U_;?EI zN6JowZl#3l?x%TDhjIk;S?7lH8{{3FuY))&m{%L?6{B5#FQ&}Io|@+40$%8i-@M(F zGP%3R-FrAcBiVN2kufDgFGq|CFhktDX!LCX13XFTyz9@rfvL?m`daFacs!NSe2;N{ zr+1R#LhQ$Gd&;w!4dnF0(ZZ@ulsx?SMY_Wu&-d}R&odBLH9vVuwgpnMGN2<|AM-^3 zQ%mvO1{?eDe?3RRY*7IBx(DuKWAiUv4N4}pn+acV1ICffUbM>%hCJAjBSm)s9h$W} z{<=Sqo8(tly%m_%NQv*87!1T^`r))P>~Fd6YUMZNQx(ZHg(Bn`{i6q@nsFV5<31{e zAn(2tyF1Gc&s|~ry44YQu1x~mv8HYErt)GT-rzM|2^j_TLoGWib+0MzqhFoVI2>2E zWVY`I2g*zs(0OqV_n%luEPty=g=`a#g%lh`{;KLzPr~@2f_*TBq3Ep&&mQ7BY#x+O zF~GRB$?tY5w8C}BP4-OlqQo-kY(P4eJV9QdZb;oSy`{m0vPU1wkI``gCZC@&>o4*l zAK@>;hMsw|^S${WJ7A@jVZfXd%)ep^ALCFOE}Z&;ab7>&d#5PIf8cK1z%WVzj8>d; zOh-N{JT5&7`R3r`*a!6`lvx{o^4Un_o%aW9oE;J0&j+?VeTF#fD*7hH0eS6fQ@D_I zJo4cqebfFpN~Dr}%=Ka@8Mi>zGbjr4WYrdZ&%>BsX}Dk)%+HVoq6U~>HdkjnoqULr zML$o6O~Sa^Xc@BTWe9N8WNM=dqJZ1xCHFix9(dz_Sc~*w>7H1A{CGU{zP&OcDhBcK z;tbCMK5UZMQ=Kmm+@}xyjNM!CA?~q^7>rhXf0eH-is5@3Bli`JhnYq9qtGFM@0=9ehbCcCM&^F|7+oz5X=D+5cXEo#e?V~&Q zR^>r??zfXgTXKLS^nJZob1IM!jVrFBQ-Q5|a(;Pg3NQk?xS9=&d6m~0nF5eGa_#Y! zX*j;RG79osU`wfcOK~2w`JTXtDhB4$;)ACn3qh!JM%{)F>A<{KpITpx-~ZPFg>EJ= zJw}Z-Yk5G#3`TQWE(06m(Xr9}8gNEQ>d`0h_+2C9&PzoB(X6>0>*5Eb@^9X$e)I{U zYuJY;vE-~-WtFlEeSiSZB9O;tl-g=xoGzBUP)HGHuDB>ZIuS>ihC31d^AZt%lFcvV zBY)eK1h-ttq@2mUM;DAi{V`%m?$J}I(;cLZr?B({m)qK6z3Vp+ctd` z2mH{-RQg12Pd|r#NJ}`~3wiq=p96XLwDek-Ir^n@nYLfifA~$;zSDaE$Y9M1ty)~4 zKt_B+++)Y!fX4KHI^cf1MiKID(@Bk9ig-9eOZ~zo^c7twU&rG*+V*`quwoVZ7y*u; zAE|69^f_%0Ke-C!fH?9*y^W)y2%cY;%Zl&S z=%4O?UKQ1c-<^ItuKf|}|Caj_F;@6o+VVlaGvXiTopZ%p9!p#>H4OUO8J5`ApR zmq3XD{2s>V%3M8NN_yP>7VJj863C$#^ovZRbxr* zguMNJf7zV#Fl1V&)E*H4tYq@%)xs%Ie*IwXj-}~9^bQ9eJ)I3Q>GdDa=obKc+e%V- zB$g?T&3hg50De~p4gAUm*7?ubR(=vNr?#&(`xpbnxBJ~|yQ@HQ?G{gJM}F2lu^?gy z=NHhEF2=csz>tIj*=4k&aq+VVN>KJcT0-t_~lA?0|u14H{?8WsAq|8Dx6t)z3 z>HEmp(wtPvCPlCKW{N%lU5T6)`hey&-wlG%7exvDEb9MBdy4aO$|&Jamv`9< z-+E_L*5F;%^$9pnz#BHB1D{(gPiwZt=WkYRmi&u8N_FC6@eqXS^%Z{x_#n4Aem37H&#r{bGgMejQQ+}rs`ae#RR@hA( zPj8Z~Qabt{p-HdrKga!fJaN9ymJG^{-gjnh2KuV)&O$3zqR(r0OKXb6@33Q{KDVJy z{4)@@8ql}e4k*qMN1wR7TIj}=0?HA{K6PyW$?2~_f5$k_1l{R{l%2Y%=GPFeS0JY) zaQ}XFgi7AYrEGa}O~UJZ%B~&#*k=)b$4`whKgZ#^&fAO^0?fe^Ajl}Sf&`( zXMWrvR*ms7N&3T#$Y|WR%=UTT5kD10GiUBYJ#_HYvaXwm+mUFaej{#IJX8zbeUXw| zN33qIz<6{O3;rXI_?NV8N!K^b-^^Ke*LFt&FXDJg)}#>NPpLK-u_PY2vjm1O9bSpH z9qO}41AC=6$CDbf!Ee~_7C|4d`wEX<2kFXPZ(jZ`0)^GJr)yfXL0tdfn43UQ_6?1|jNNgVV8!}na2ry%>(#u4!l)neQlDI-{LsEdX^_RdoZ2~W_HD6-iQhAK~N8dhuwJGhdR4P zaDJ%2xx4PwyukTx3Fb!~oa%e2I_(1H*%DNQh}ZSGTJNLK_psYvXZj)j^zPNOkwM(k zIlcJMO+(80&+oKV#-$!J#C1f;c^~n{bqwRZGcfb0r{8$o$C43azYZvZP^(7dHIsda z!@_A(*6qXbSaSQk1s&2;e?5CU@;2KuV&N!F%5gSuDQ`o)Y+rTtx72aWe;uW@h2GSw ze&HMGYQ)Jaqxtu8ynr`*$5+e0xGzo5xn75KfXNss)6?w?d|ko4ML2LjPC9Z6j%aOb=TBhePNmwc8q6*CT(*{0`(PBEAj=ZMG3c9UX3Z^}=Nv z#3?$?I3M?2RKO#sYjsjnf>|@fYe9l^J~gK&8Ks zboL4*V}^|hC3hy)q+BeeoY23fV<#3-&gPbAEfGFtmhS!*?wCv&vA54Vj8XSXW}qR) zJiaDdySN|o(X3cB=qu)%!ojf(DwtnJ--CU-Q0E&iO-=oYynRn+XF&$)f#G{e70T>? z@nTtZ2r##;KeU;rfUEM`xM>ynV6IT|?&9AY&~&|C^pEyU7}Szk=yLo9gbZJI+<*t; z_`y5(mxAj6H3^g|0Sk@s$p;2YV7}m3LQCM_=4-WiJ^7&j=?b?&IukTM>#`djr$Fk# z%THF`%!J50J?qX@WkX`ylDAqL5}@t(Ie(EQejxPw@1wxU!N4>{ZR%W&e#yl}Nkt3u zJ#sjoDT$qT-tVe6Wj=jA7W|TjdSy7kC`V*?M#_Xg%q`2n{rSFDZC`XeWqx=)3z?sU zIOH+(?k?htjZ3R>2#+%T#wYUXuOSW!E=ZCnV=NM#WQqFnRKx0h6A-_Pd&_i>A&%l< z%Pr*q+7JS@TY zbe#IszSi>s`%!B{l8?L`rBZPzF{=q!BC#Yj7xW5>I^SylF;V6uytkoX% z54Q*_@ZF=a-!rvY!5FtpfWzNKx>Tra!m}_-)TbQ5I`t3_#wd+gYJ%}uDRp+HC4QFx zClyc^-Tb{X)Cl9QHMeOI=BfRh{_qSlI@H@Y=D8c{UYWS+ziwKn%k4vVTcHk0jP&Lu zV7`mc@rtIXKYRbW=InDrUHzT3Mqu4WIrxq_#>b`{@PCYWIJ@y&fCJVo=U5skV7!zG z^pHF9?Y4>P83z%6cL|j$iP3i1*ZeG**cq0cdKaL~0yoz$RrW}g`LpKZTiaX#{%;QH?#woet`H_O96^a1f z#VRq~$~fq)4ruQtJm8kH9l3`RfrqN?bX_vAE53e7o|gpX^OBygpO65&&hl2H8%e-U zYR%8Cy9Vr=ThCM-qM%%GEg}^QtnbLVMr&XDchsg?xtde=TK>qrEt#zF0Gj}xF* zOW@BE!M&oZ)Hgd3On*isD&0+l*hMSRNhQI4dl4@hnFKAL+z$tk6p$%h{k~{(G9(WB zH#emMGi~}VVTWXx6E^wN(!@;Q z?9DM2u1trv-HdFcViL4D6-xekkc>Y1!f4}<*}(4<{7}h*-gB##+UMm$@APG(-BWWx z#ws-+Z6F^QbQe={@_>A+OOuPsg7U4+7u4S2cX&i^DYDq2>g8xF!gl~tMd|oGrYiS=wC-%5uFhW%*-%_r{CgWDDPB1UkCjL6?c3& z6amCi5QwM)vJS=cd7xg15dh`$M*MX~CN+Y8_u$C);A$)-mIYY0Ax@u+b*+)Yx-t6gDOidXtVMFMAwzUQ={cwn{(F3=Kz8L0+A;(~jzfC}N& z{Qv%ESMW!>$Z4>H%aPBuO-fVK(a19vy(flQrnfMEq6Si!FGFkXMwj{3SRA2_HM zBT}=WoO`uh1pO}w44Sa@b}Zt)dV9Vz;-F`BrS~$_71u91+`WrD@OPZBkP`Zg;d@T3 zy9)kmBM&hXKMtgSDk+S!owA$Rx#&w`b5}ffMI8!NTLM=iPP;9vcJjbDxv@pr z;87?gVQFV~Z$lp1skN~<0^fJFZ4P>hdaFh9r}?x~|NTcs{cfWAZv8`bCh3 zOcQmaZXs{gUmt&jBF+!rPhfkCXkdT}j@PZKyZ4gs|NMdFnq$Uc$b$-Ce|a&EZ~tSf zmit!JAA((tL%iJs#MM+4OQb~wH_ULz>e*T)* zv)q|8^UV2t-e)c$trF|{zGxDnxog>;KbnLYqG;wHVhP6+YzUVH~zlTDKQ zhyS(x_i3!^e9pyw#3>;|?CkD|kH# zuLXF`(Pu6?YqdPEWit?!!lSn|_EO@wt!O~W6o}QkyAFpoQ^Hu~oh_Hc{!e7-U)RPsUF5`W zti=1b-Nz|nYsL1fj`weDE^+4K{jf3Lg*AaRy*;ERZ3kp$?I)cqYap%joYa0f0&!%T zjWVn#xi!l2LE$k<#vSz*R}H1)otBou?&FjceB(_U=SxX%x8A}Id>*do&>wk}lBT|@ zih045^vkijtO!hPS2o`^O%q{i`DIJwcD` zT5n1+A4ONzdQp<}Wt*(%VH`(xx80f`N{;UDdT|>2^)(r4pJb2YNELXlGN+{SzcUla zeo7=~Y#Hsj8H8r%Dco5d0OVGg`^RE8oX-!#Z;jZmeDRqka~n!HoQ1EnEhrg&D>Clt z5fGAU8CY7d4~U@hq{zSyTo-noB&^5p zVsNP{X)*|@OG}B^JL7jaWU66h0ffoE6Io#o9efx`XheFg_K-%y{Ns`2FJ;m zX>Dwb<1_}p9;*O^(|vXLlr1IC!xvpSi|gfK_d2245r+FWSb0le{42K2oqgN^h})|} zxvjn+bnk6xVrwLj1IzCD6dwVyd!KyyG*2L9Ycgdx*m_(y&^+LP{V$wmYlZ9M=56bD zBZLxJ`GL)vCvpDr6(9WZJH`)$S_I+!!CT&!7={vcU&}M&aUE5@Sp+=5ab+4ExYu@p z5NTChQmKsd2strzCGHCw!(aXiIR0(ZH4)ySK#a22R!!OqLW)ke)uf_;Ne;Tw_aqsZ z;n%y%NEVQR@Ntjsm4LwHcxgpk1qf)oX;DQvXx;xktZtnL%*4jYcB3=ZM zt2O#-LefDXz2woDt9XCL%Yy3P>A)m?i%Xhv9+=Of!j0DwfH{BiOrpaXU>4bL)tMQM z>+n>wd+9NZ=alPokG()d1im8TINy2B>5c1gzjmkZ)|HB-Bs64enb!r%-vSG%MNDLG~=x%PSqW!SWv#HU=Rp&N=D@b~XVS?q1)Q6{Y6j8=Ir6&R`{?MuWs zj)b?AohYY_-;K!=<@uC(JiUEd0=|D|dc>NS`2Od4QwH`GQ1X7eoewvUk~^pG3+iy( zJAWkff{Q34qdD)QF5Xv&ozX@x4zZu94t%`cW-h3ofbV5V)-8y_ewebN{kI(5>@PX!-X9W=3v~)U%y>e;GB({aAn~&f z{inX?oxylc{oe8Z7JiT1qkmF%@+pa&bX>b0=Xv;~oK|HXWfa4>N}f26`~ugA+APXA zj7xsfimmZi#pH?El<9gobo4mxhmZWbhE7?yf9kZvRFf&m%8+eXi28MIZ`G3xxUVK( zxm00>`7`Qqp81p*U^YB{)w}p4FhXrR`1ccmGkFRMOD0H4D2MBB$^aFoZTnBTT!fC0 zmos%p4j2zz4oBi1Jo*f9$_jqhYGXd8ern!i!=)XwLzw`vFyQVy zxuD==FmTUrzmQ)T4uW?=U!oOGfk&T`(N?R|Kx!_Y(dHZkVqsvuJPP$SMZw3y7WKSo zUD5fiQMhi?aRp=0Z-jY5ldw&Dy5C(7TdO^J&C>WDk$af-@CYSQu{W;PVxDmaoG+`Y zV!NI7QBBgkLjIg6>dO-Q>76?dQlZx5k83}_895$rDCr|n0{*p)hY@`ow2 zrSN*yVh)Ip!--!)GzqVDX;bGT}nXRJ-d$J}IN5Sj*Dy zH|A4m%I?7Zct3TjOlcM7{gwl&8FR3m`Gme#&8B3PhP=EU_80dJ7c2=mAlH6hAnq%b z8o}x)cg*+SF(*awdyr-|rx|v@d~1jyE5ksrM9gSgeLOI!Te>$iqpmM$zO_aW3tXSE zvSKT8K*ckkBT`iarzi3gT(b*dESnbEWni3Adah_u6@*vcM8mIu$`_;CR|J+qWV_Uk z#W_6C^^1_5=T-`trSg60y(J)jHmPm;#Ujw(ID1R|!~$415@#kTEsKAf5S|UOQC=$N z2_L2pYj)iT=E1gu_R}U5<$|nv)|K}zIlx3Ou^Lrz5gLB0pPR3kjd}m+li1T-;B8{L zt^g)jTq%3S$%;dd>r@8PE1<^%sIlm+|6PVkOWN)hWB*hX-6UuA@dk zF0}u&4jpjJ2j1ljbZU%egagZ zq9aHV*B7E4N9ireL;ejmJNP9Nf_^3;U?(H@?2PDEJPk~UTBdPuECf%Ip6a>!ED*Cs z$*5iN@Q-hR=+0SUtAl!_pVj(69r;@6JFzM7Kg{!En;Wl`pl>j`Q{-)s@2mnA?Y*Xt+|2&oni82?q6dbM*Vd)kzkmZk z>R6pay=h{%Kk}#~s~=_<_ri`R`lyRsGf`20TOd;JO@5{zulGt~-QtAfxwS<;L|(rd zhMbs*=n8~}tgwB+@>)8-VV()*;b2w;pl))?W?wh7!}vJdqfwhs zKju8*wIeSx18KS&kpmlB-b)7u1DUw4ZweP%m3Gz1X<8WPo2gqg(EmpCJOJ~2TEMwj z2ReK#er-y;J92TZW5J(5AY*0Xp?xnM9^nLxgUrae+S3a zRozmg;DNgAWpu-k)lJU))EhXS{H%guZ{*L{pUQ>=sCNZJ%Vp+=;PbSgkP}!BbYF?9 zvO`}O$p`c^Mj$La7WJm3`T02OF#6ALFn-%{kJb0#y0dkH3$_xWc0#z`a-D@=+|e(7 zc#r$c$Mxe_YL7XF--W#QYfpR$c$5b|N`wZquIobJyM{JxHfX`gh_ zZ~nH*K_~L7dB$t*#4r#_eRXff)eAraw=0?aEd;6%{dCtL=A)R5`Ab>M`vnJF-7Cr< zb;dV;o8(eRT~S%MbS)pO{(dO6JXnhHJ~A~OgWT*KlJlFy0eSW5gZYst7>*6qZL4ud zKZr4XBZF~PrWEf|G6T}#ut!}I{WoWWLhm>HK2@mu}#^Lw}=(vFw$lop+I_i6ocg?3A_Rz#Qg`U2DF$c$;)j8+VAkH_);EcRKp9*g3 zAhBRQ&~rDnjpb&WZ>1l~aJ=ue{*UhB`UV$d@36%Ag!#%@q+tI^*Hqi`@V))}Yi-VB z-Lgn|xe!I2n#qWVOIA>U_0gIsS{RQomKAK>P~dLmm4WL>I*Tmya2?l9R^IX^59^3q zg&{K75A*q8e-6ecIws5UHO4*Zri5)Xa(j`!q0vo@_rBEX;u2h!<{ZJDRXOzk^&hT_ zg523hYtZjI@3`$9#5&8fGk@0Yvy}X&E%Lb!c`?yFaHqQukR^4E>x$6-4c^@3k49cB zlk83nJw&+=-eg2pMgvpsx1~RDjG2e$fN3GO&{DIiUPK7X+_(D+V&s!I1`(+Ek_kZ$N3XP0U75xHuu?6(-hn%r4u|0kbl;)Aca1#%lTTnV*>K#z0TV= z&Bk5UI{;@{f{ClzX-GxYpVATyVD-9b-ZPAIrsUkBq-2Oz=;8D_BH#b>GnML2 zj~>%l5Xg*TY#R@wpIR(l)e{EHUG`i7>wn+1OTh!{_@T_Z@W4_4^{p{HW-5(B=`ND!Payc)tHDC|=RnKy6e$Uel-wPC*Dr;c`!{aOlr)KT~va@c_bQ4_fXe{I7y(m$C zJ+9x&nliBwHEr#O&_70>a_?V_^E)45B7^&AVC0+x^PL409}swtH$Tn|gP_=z@8-@3 zgw(JDoB7-mz`bSmrd{a->NV@HI+Rc=H5W5Gj7P@zqXvH01lfZIqR0Ukbthko#Qn;# zDr{Sc->Mwv zGbVrE`3pIDp*wT7KL>_ynqP~EEP~2?+PiI=%E7mC)(q*4OW-?^ooEFxM$@ozs6e0k z)_2*k9KMUC%Iv~=vma^p&`jh)m!9Yr?GhN%-~G_mtO)v7xhF~W6oPi_tr)NGCGdTJ zN7AIM67XcVQA#dc4cu{7p)ecDonO{0$evXA$c(NPuT2b zennu-;-O

^z;AdeprHTG=uYxp^#$J2QE}YlwT?KA8v6ccr`~ky|F-&fY#n_k}37DiTVw zys@rdAnSMH7#})(MtksmalD2`@l8)lfGidD%W=i~%~M_Gr(i#GT0dEGke4kkzg)Eq z$0_r?wL1X)J;ZoJGE)lN_mTZ4HWp(2AA>7{^~lNjk2|+v>%Dk7$-`FugZOooG$8sB zb-aiKVE$^KlF>*2qR0xzF%Z)B#UA~D=&^wv0pik#l^3>L_B=)pdFPSltWye@C!^h7 z+(RBSS*w(%hyFig+;Y}GkrMySe(gWbp`ML-S{i_ye588i!9nzgEpZ4I=qD|eYSj7? zY~@sUUM|J8~aa z&~R{I8^&Q;YC9i!7I)dTYUHxiTKUGShBz;|2leuMk$1~8)YqFM&)wc`-_F*(W4kA> zSE9pPTyu|HwE&WtqxwA>x!;J6H{;`TzgeDjB3>Xgwx{=#|31_agNLb(5;%{jnzX~~ z(Vv3v{`ii0*YKBn*)@og$`|#4UOpH{>`cAK26Q;c=wq-D6EOPW67IFgY^HrC?!q&vL)$7t+lNUAm% z`9105{;ig%>t$;ve!TBT$xhpZoR`jY`1Qea4Zf()+@puUG5{VS%#`UlEf z4|4w!l)o$+tS{P~lPi&<_po&(`o|At$9_?9u zvJAP;p!i;m0ejBrc~R^c=G(Cd&%X=ty$F_1uwNY(`0#mdnz%p&`EK#d$0pLqac!$2 zLprdZeJwgGs`4q9J*II$-_lO-=v|6@cjq-^wxe%_@y+V($|!ScTJx*9IIpd2K4Cup z7pP&$N59*lpz&}ca%z_T^~uQF0yoLRsjkSG!@JP&u|Frz8kI%(Jk{y=nFkn0;xWUY zlGvKaidrm1e&4CS;Y%&{lX1FHk>%D^b#n7D4(^rlaZ)?+J-x>>3_h^u&Bnl>MYtBYLUfO$Y*=YP-@w)=)R-FGcTH2h6{4FBk_;wtA zpD$}G*X%=%H{N^1a5=`Q851-6DE1@9<^hiL*4lBu7hbWz9ob`m#i(CjS)fG!-qd<{c@6HL<)cY$N;39i|Gb5Z z{LA|_e}XXT)YXNVD@9y^`{RaPo>d$Oax%J{?Gm8F?Ml<0>|AJSWY1ZPz~g9Vl-kci zsQf8DMSLsz->`S0vT_-ySbWL5?_3V8ZXxdHH2EOV@Vgn1QsD5*CjdhZNxlsEDcH#!TJEJ`AM0`S9M}j z*733ZEB~%R1N~*>JOzEgh%M0Z_lbkwxB6ne-KUK!j=B~-Qnw=SHPl;wccr9b_Xlfb zIUu3z0UYXfZ_$G8BdAlU>>owj{+&B|Ql_rt>x5U1z^oTax2i$jTUWY1XSx^aOZ~bx zLq7j}K#4N{Kc@yk%OR7YcGN%8>^8V;4&|yJp_UB?Kron^DpeQ&WWgNVu_nMs3Co@1 zS_89cB2SDnv}0B-%4j*kT=VYtqxckrqi`W5@fGVU8) z!CaGE_r}DkEb7@F6{T0a>niOpRbenXY4?D5rXL6hO>enga}LPP{y+oM1Ta3AeQeDr8|>}6cP<>b49zzj z#n%ZIfQ!}8xzH{yNZMvy={{Hvg!A@}(uXP#T`FX_HmDL5xat!hhLnP^dhh7FkP?^| zbNi1$b{SMl3U;dnl*8I+=Xm!MTrkmJm}aq|5bmB-^7&m*3fvMcrULh1`cb_VnTnsYH>6AMW1wbUV_b%R%10Lg&gy*Ja1JKHV;fHy^OxS-X z;}aL6pY3=$en%NZ$0}X$xm*Sw^Mt-z)N_Gn&~Z$xs2I4Or+?L?mq0U1Fc%0moCc zi|>FE;D!&D1ivW-V-1z~xl>BOSpNKpXvY$eS!%QBi+&mK=FeK%^q~ZJ4%e@e-&|m# zjz#GEmIJfZfT*6X0(-+(53Ya1_WhDta@lz8IjJ~#aS;UJ*Pq;o>ymKsHC)XF`}BH(|F-oOjXKLZR+{pdmd`2&24QTtNZw zbc&vo$z%d)P+l4SDjrC8e*Uxk8EmKJTX+iYasPi|%W$EJ}i- zy5Iarr=(SGzv^%TB@(}W=pKxwq|7K zD7+oWzKUOgPaS|5!klf1u0Yh3jy|$rfXH;`KDEI0i3Q}QsfGf{`+B~~>?DkuNZolQ z6A7fxb&<%8BS6mfp5APB49J=bnmSD$K|Of$as`ixg)MM0E|*cEM@ z?1A@(vUN7#JVK7l1Jh%aG!L{2JU>DSvH9Y#auHsgljpXWP{N(HJJ`gIlD>Hj#^T=C zPfF6y$^`c@BXP-dJxZ7>$Hb+Su-*H_f@wNH{12@&-{S_PTt!ZDqBHgz_bks=7s%nk z2QK-0@Lu^%-S#O!60(IojydDLEFX-2#UIy2+H9*aC6WVKRe7oMRxQ>xi4Ph#d zKxUkl^pQLXr1|X`hiy3je-1p8dJ|3wd!N?0Lnvua{kVND z?#t@9Pw^4Bf9-+GTT47K4?k`E5?}_S=N-h|_XXg*1Xd~^JPhP&(gsHr)F+Q3hp;<) zas79nr&`U#`3#odw8Q&X!lxtEqJUWt1S2CDhes>^NfgNj_OcPF*99fOEPfSNKcN`f z{rv<6AC-Xp6T4z=dnHh=ijCjBVqo&epT3!x20R7rz;pwQXRkL0E>+|8{-s2FH5^aa zrf1OVA}}q}Kg)$)0K%8QuHztZT}s7HJ`k7_mhMj`#el#bokn@H<3Mid8I}3@Q&OKN ztSW`;-1nqnPz%4G*{Wr^voP*u(u5tCDpT}Bx{udP9irIbwH<2>n7 z870-4+Iy~)QC8#b%1f2l{$*pivk;>jd-5nTf1aLnp@5Pdm!tQY=TLHaVa-T5 zzJHsr^kI=4%DP%)$DNDM{md~vRa!-vt+h($Cs$HZu8}DzQ$cxKt1Uhh;ym_8;11*U zP~_c>693`$LlxXZc@o{z`B@z5M#5`mx?>9M;Mj2NJiI?hlpQbe~ z@F&(QnI&5!n{Zy=cD)HdS@2(caVamXz4}Zt=69C!u~Q}Gl-E8vCO5c(G9@cpk8(>W zbIw)wwi?b~Ogklf7V3iM-^F5bT*^FejSh6etBd8C+Gj!k_KYu_i`*-!92XEp_{ z48?tXFDzAGRz+EVoSV+ktCXm^r-*&HhPtxGLg;BNWi;b+H}&EEEl7*LRFzBrjlUeq z%u1}`y~q1^;YJIcvMDjXS;fWo5WTD!%D?e_63?Q14YDco>xC^llS7G@@r^BQ_}nhl ztgGf&zxDg*#hwVtti0}WZgwz`GXohuGzr@8`m@-|>A>3*aI4tzGVpq8tK?Rv1G(7W ztGpr;WN4q!g^wA)`Vt`CekBX~=Fhx7q{;zyWpaCRb`IFjdOYXkHV!nWt;=f(;zIK> z<*Xl7<-oe48!0fe1XlOvO>ERH0?Gb;s>;LZAgScHK?&IKCj5nc$D&KXs{7mhPx&dZ zf6+26aBCQlo3;I4>yM(|xB9%CvzijwbM5*K=0I52jkJ7JQD4P#S5>koOR(hNhv>t= z@bO`nJ&+m?nMIRbfK@K=f)NhF{<0RItyq*;#?A~j3q`%VJNZ)|>QLN${f{H2sG}De z#Jur2kGWIZmF%&OsM|`+I!?*>Q0+v0)Gc;sm#CT!W!j&5IWKkrGHuq>oqhP6+J_^z zWHnH~Pl+7(sZWU^zkr~wbt$mK8d0yRO|z8vdi?Wxe}%IXet&!EyVH;Smsh7zhkEA> zWQ9`()h*$r7mStt3J+jGN6)i0e!$%G*pMa=3hnhD#kXtXcOo}y!lbMz=@j+!UZxI2 z;i;DNxurl>ZN>_3Lq}(1?(A{dg7Y!HB^S08*ZJ1e)xn$+(fy|F`)p9}p7YE_@ZSCV zolOp?iwcMn2^(?T+_qMW-B>4NSYc;TA6Zq+7ljYwy3fZowC%up_G9W6H&fh?j!6nn zyfN<*();yLw~3{+`r}PNPLB-BuEX!Nsxa)9rVs8Pn>H_uqs&Vc*}~Oq%8b03A)a@c zGEI38pPHjSygRslTs6k;-^UqR_b`8tmV4f^#&#uE+kt0TUpKf`*}7o-BGu{UVBG4S zKKSuBw&(SZWQ>oZOkLLA2g;a_hT^yL3s4`H^W!X&l9~?R7NyISBt0Is8ONq%g7F!} z#2Bn!+r7WZVV%><%(mSU12Q{iozQAvLwknoyB*6gzKi2Dlq?tJxb>~3y+uJup)e9lAThe0Jyb=(XzV{w7iy_W0zerc51im=7?RVAV!m@CQ z)(1oR5WQeoR6=VpsIPU*S@5I~IKI`=b0qSiS-&WG=k9#qWYvh@I8XoysoYzF4MiZT zXi(2eErf`kt5Hp73&0pvQogGU7^4TLG|S6Ca<}ODB%c!KN)Qjig<9h@+L9LILGW34O)u1{F5(h=l7KWWc;p*-Me zgs(BZT>$nX+q-@&DFFdgulrR+z|v=hE;K}r3~#+(*@ENTkqDj_%LUfvf;0MB#lSw4 zQ#hlJ3xOe(DVseDff-WQvQELglrrzv|Bw!=4yh?l9jOMEdGe@*bPcrc32<|1D22M` zit$koa)G7kaB5;K@}f$i*ti4CA=d&sh5454a~&^XZb?p&o6;Y#R06}%eTw)h$RD=azD*|ava8u9(#BquH$UM z$QsEQV9e5kEZ4;V`FX|nNrEwu&vDXk7a)g@oMx|%L0)u;xw+&LUgw+mI?hg^1a5n_ zKSe$MIQNleH`W!o;ffzESa0Y2^GqTY>xsj!?}zGYDLMc6;QVlYz2X}I%ohpe8*L}C z{?m$C^0MbKuaD}5evZTXXoo${P;%fvtF;~S=$gDK@7%DTu}4XU5az-CAC-xduzz(N zDvLWMJZYQ=>gX6(2h&k0A9O;f3+3;^-fTsliWR^4Q~-4`zx=j}7IK+k#J34bu^`YH zXRiC!4Ms<$yWg%G))J^b&V0SUA9Zxvm0n3V)SU?-&u*d)UM-z0^xPlFyeR+O{irAQ zF)E*Bk<-_9g*0m;H!664kLtqr@zg(eRim!)ZAce#8Y6sH@wgoQmp}IbVedK$5Gum;%a_CI#r547oZMq zQ7MZX=S9iloBjSmA;5gl_<2eYeT}+y@;oinoz-@`nG*#d)3S1g`z6d<@2SdbQ_;VH zv0K{^`l>H_n+!8CuRc8t$V7k1_&#&H(wqq_QJ+Y&lNgshL$}tOr9$Ap90*L=!l%9g z=!+B`rQTZN_siiYF#3r_GjS$PxDR9Xf)Y;M+9?arhlsX>TK++OfAR9SsW|!raq>=T zEym54TBljIqt2OeiqCAW9j|4WAQ|7>C>CPX>ReIMq=Wa$F zuh@QfuMqMPy5k`MLTrhzGZr5?#}dhkf`y zn>o0#oxPDVPN3ASwD?4`0FT;lImQ6{JOFF z9%l`%UqR=y&miuHZqCP7me~JrV$yhbZ0F1WO8g#??=eAfz3c8fUiL1fyaTBVzuDsR zJ9~3e2C={KTkj<=iYc$E$uz`QG>xgwj|Z71jct$4XF_vQLk9PB29TDvw9{cJ;PF60)Ovaj zFvYTJE8Z0WG4lU9{&z7XoLP3WdTu$0dIzsl_b&yH6?||l1{dQ)9&*E2=XBoN-CvFz z>Sv*8KR+0F#^NTQmZ1K4ydJ$Pg8uHRk?-?X^p#gNg#~`0k5%tGP@`-Dqf7Yty8`q3 zzWo_P)BiXG^{ib_si_b-aTPz`jVY5k{9vV#2k;E}K<^C#w>zh<`fiJQf4cR8nI|wW zDz3e{;1A4>=a^8A!01on-8B54Dd8aSXQ;hm zvkm5F#M1>1l9X60B&NJXt~xWuUFe71?Iu1zU2E5wUl+9xV5;+hl~0oheJ zEB>7dFr3-`NinF4M;`{g7e+q(yCiVvtTm9kVg;V-Y=Jd)esmO=F-|;)x(aK*ccLB> zEvwbLUTKY*MD3nxjN?82YHI^CY?o0_ ztTw~_@!$ESrT-`;3Wf)Lr{n(m8$^k$_C?-WzagX_`I&cAXzCxn|K}T1XByb;mijpw z{Vl`yW!98Qm{oqSV=s(G#BE58a|a&PKK`TM1K54n@UKw#m%EWKB^R4axQu$5u&sL? zCyJ5=$pua;k)y3o4w=<3l=NJBWG;_7zAK}wQI5~A>4Cwg%_!-6zFe_-0T5%=*@11y zfni=5wxRogohOpOBQA1z3QY!vi{>w zypL|R8rX(@baevN`GERV(7D$)2=gRlvfp@ByyutqDX0?`1s!rj$h9U`Vm>?Y+7|j@ zeH30de48lv5XV~=<6c>V^If}1ajCC6kf(AP30JW`YvfNDOhDiEq;~27iurSx^Cq;= z5BALy2k83NR2fscJjKr3a9Zya{`#z7@tLt;XBYI%J_@7*OA>p{Leo+}LxYnWN z-4Q@T`_Fxoojd8 zDHm4hl!&iY%7vdtyRO(+WkA9)iI8tvsnGc>vu$P#8w{Uu!d(u>LsyY}=gHJdAQ#s( z?}9Z4ls@jT_-FMh^H7 z3y*Ys%mKCr-vAas^O#=dff`oJuAwYQu#qjeGcy~0PA*>LSCj+Xg5P&_4kNGks%f!r4GlUf=%hc^MdSm4vVk z^tXJwppgme*Cy&;mga)Tjj0$}Gz|4k~$1tO4@t}mMi zyq{YJAGSoJt{j`)dl$L!t;Xu^+Zc5Z&4R3_%rE-yd?^>0<~Z-AMR{O9HZL|X zW9QUq(5@lw@$h>w1fm<3*pv@%n%1diFF`IJljjm(@^sJ<7XfeWMyBNo2Y6!lkc5$= zQ&}&Tn&bS|j9WHO8};_c1}FBKRA^7Sr`q-p7us(hTFX>%p|0(uX!OclVE^qgh^#LM z8O4;$UwdnzV{XNbforuedein=G*C+!8~5f2doIpi{%J7c>PqVw?Zw3GA+TgPfSRs%-Q_&w)=A_ z&;P-zqIj%pqm43JT;z}XPu;(gYUsaQg!e^DYFCUPhy0GN+VuzP=5O=vTko-+H8vlW zi$I<rZ@VVy}m@|41|xz9|Ir=pEt-+i>}|8;NB$SOcF3QL^nL~F16ljaDS0l|5wRzIN(HEg ztRL2LWDcvDFH^SIAgA?2o!H?5CL^hTP5-?PP~wJxCqD?qfUh=IFwf z^cJiyzYN}F?#KQ8UrrWPuS}KQh5V=G8~g|LSW<9N5^D$k&e!{`Sa0~}q$;>h{`tUW zL;EC^Yf>AORgHe{jyc^x$& zR2%0}&?;ES#0G;uVVXGX*`~2OG%9mdCq^_k8w%r zRJW!{QVHuAvF*Ab>;pu&vxKdFJifKFY;u4kK(Z${5{xXg4pL=N&;P%80lbL zy8B(q*d6(Jh2$=8gEC6u@2tFf0eLk?Q~u*E255|0Y%s+@m9v&>SjO@hq zUE~)IoWK63$8-^L?S2c{_e%;XYjOK?!cd|=VuOC4maa|bWRsa zJ&yC-WAM(HqF)G@UFozO`QGc=p==%8*QH#NJq7!Z`F-5)?`l&%6qjS2*Dn@QsGy`* zT4nJq9Crcxx0h2s<=yQ)G+c)7t9`!dgcZ(5^|#>rO5}i+ZB6fm@VoGBdp!F2Yy%U` z#5Bq@-K|L9gZ2LY)Ufphs4oTU`GuX5afXN9cAllAxa*ngG4zpR=Ti&OFMNYvSHgjJ zj<+D-Z!(am=7&$Z!$8}rP3+w1B(S$Bp*^XY(4Ldm%u>vU_MYjnZG(lV+x-160W#+` ze!)tJP6^fg(pLu2pPCWmilC2w-1>+E9EY$wv$Qk85UEzw{4zw3YGmjfi2+7X^GT&c z2(X40Bu=}8K6Z>RY=BiW5TFhk7D2>>oR0A^?3rg1-<|e*V}3 zt-ga!CgA_Ljr_d&HrD{TQq4GLLoMcw=vCRMNe3yJvavSJ1Uap7)mNcM=r@g(Gb7*f z{~z^woJb_KY=>SQhbv1!4|nx zHFHN0|Nl5!uer@YeP$2ZXzV~f96Q+BgL?U5ntsnhfweF7J@Auc|bv~cZ_ngmppYwj7?*_k7?dxkQF!{M|KZ+jR}uENi8c2XAou&Kh;2m$ zION*mKW*n_4E#0d^v)15Cd4n#^1V`l9yvFv$2+CCC9vt4V2v2ltzMwb+-t~P=S4ki zsKQpm?6mkZl~|tB>b160g1_Bp)%eFng7O{Pb1RypSpIHwdtF*3DlEkWPye&rMLA@__X-JS~Yv}5~r~I}`;~B{Jk`{h8?(DMi)ZkR3b1#i$mXA1IVvL6Oyk z-4R>qU3`bqPLUXS`Aahzyvq?rb;s+P%TVsW+I+B&{08iuTCP@!{G)|w#`mfatS6@b znplm!@<;20mDdn@PH(r4m7<)Jsnps_kSp|bv3-z-@bf+IvAKCDudhj3?wg0){U4XM z+{#AYmIE^bQ$;AhH4*;wCf&14np$=~1G(>OYZ@+`NA9-H!ERL=a)Rp$=6N0=(Pp;q zxln}YZ(3^l4l@Xg)1SH^ogD&F`E|yX>RD;~Ut`?tnY|w;mov_-etgNX zV#WpMEY>Y5WY8Ud=N-F51|x6wd&#t71tEg7|YS<+XSO3k{Q=ZnFOz>hL{7w)@@BByq6_Z6Dg#%@m-jVK8W-Vi&@= z(dyl1p$vNM$_B2kLug98p6YdsLE|PYN{D9vJC9^gQ;=!>*9itLlDyEOlMEIVh&r8* zGT?@C);fEk>b28P5vr32BZcz~>irOs3ubw`(>=kg=i}BP2vsL0nlDm3^RX!vPTt7f zQRq9A36Z-yoBw2m2)T)828LaikTaETcyF)>MYc;`NzJIfM!RGUS`y?4mA9*@?>;%8 z-4Q_jxeYd}Yg6BB^^6Png6dy7NffHPa>vS=ei1@lmexnN$gh>zvUwd;&xE4Wj`LCx zx;CyIHxeR*v|RdUgEvCvD&_PUrx~P2*(nOYXW%qF+eu7$rx?_=sf92ICfcf>We|{G z@G2~Y!J%Bwn3PM5=h)6uxnO0 zt?sJr!+m9p%jnH0Y!)*v`KHF^lq=Mqd+$~2mr-4V1TQbrxp{NVoG`NO-vr;-L-y>! zq{KG5e_#?H36me$+_-8Z>9py! zqVLB&!j;cU7*A;y=jK3sDg5P;&kPyir~c~sD~dbK>*H_zh%ZTJ4gF^jerYDIqrPIs zE6v5F!<7Hskd>Fz$PYiv&BT!KlM8vLTuT|Z@Q~GD3FUY0qpV0_8Iz|fJ@qE}Xmil; zFB#QsQkK<;kChMJ=~-IIc&B3DYJNiap5OW7Lwm|^vHaT%dwS=D1&r4f>G1d$ z3E^YWpKy!(zFhyM{|n-Ohu`jnPjVQ9ezYecKZ}9>Ah>-ap#B-I-{_r0@uz6<8J7|gfi6+#j_R+1|kTQ&8^S;7&rVDH>Gn3wtuf&7eW2{_;a(~4iV-YSGyI`Pr7S0 zL)g-B1$Bz|8MU}vM(bUZgQ*OY{j4r3Hc7F!J-<`0T87K_1mD(uP=P(lpWpJTOVK#a zmR+2B70rcOir&G?D7tXmByT0@g^%;u!lUO%55oU2`!pSuHK88qW9jJalbtGin1TGA zDsgjWD)Kzt4ttIhPisGkHyIBn9r^jO`kLbmlIHK9SrE%WPtY-{MQhXZVdKZdqnNbb z)@kP$=+wLQb(4NMq`Pw7wEv_jEXI-W2$&p%9E02lNO(hfIv>=2#|G?=|6J)6_^2e17Q>DlC9 zh+&X??d2j%XN;8Wby)F!Ac_*#7e_Cm??32jH_VPhcxq#(*-d(|U~o>O`w_XH3t1n@B8mS^(McHHv!u22zQd|b55)$ot``IW5osr(@)u)G22RZ-~t-449wdc z=bp7dxHvgaoDr1TRpRv32r?((i~h9;j`mCUTy{e+QN0@l8%f{q-YJdRhN||Md6{lB z2Rx$QI-T8yFzbcleh~RxzJKVp{%h!&; z7qrduHb*FmGJbl0(f{`~5teAlR^%Ha3{{H8>P-=NbDlk1HXWh-!M)=L^$|?Ja@9F9 zi`KQTqYU*>O_?9N3}z$r){jIlG@*MBVaiNF=>E^&(Z_vH0)IdD+`(u;h#A{&fKTCc zE(Z2)LS1xRsL!mta%{TVH_WGGUM{*1+(Bbu+(4h%H_I_%NWVeEDbK}*C!5eQDsC|6 z<(6Z}g}xG>L8o%j+q(&sk#R$OT9=ih=1kvkpW=jE)a|*0vSD#UecInE#~^p#VdOhK z7Y)1bV02F0aPo7OW7fcaQu6*J7j=K#!HVbNo+rNraq2=X4HixzDPcql~_?79Lc#;^yn>WM&;7PG4$i}N^I>B z62+Xh>M`a{GwSLS#*%+}CA#gwCBE!4zN`{kJAxCt_%8S7gU6Zw8vC7QB>XL4>gJ!a2n#)$TWB>I|DiSF~kuTig3 zkK*0U=>9k%nK=xoL}O;KlJ7I~G3Z1aN)9ByP92fe7<5vS!n#*J+UB%jc4zV|`dCnn zL9RiwsV_7iHTE_P+?D(W`HZbb`=PK@o}XQZn)z)gbXCsbp6aX7`dyfcd(bBzWxLwY zXi83_e>1+oz_np>$*XGJT>t%OL+8)QZ&Kg#YSdf{OQ#P{<)dV48+r?p=i&dVF=Tm| zn)45@L&vx_jK7~epZXS8qw!LhhP)olNB5>S3|W)>7U%b@M&qp^TH-xx#BAH|DA_i9 z0q-TJF@E`wx0#n?0~%lX9fdz;XORE$)0l0PF63TbFTy}|2P&VOo5?+ma-wa$G>bgy ziZCd>12v+#i-^0yiGgj>#XOg6M%|GPly#=PLqA_~qDn7aLf+?!(3#YMw!hQfWgZ)y zsJS71k2r%jqw+up%Kk`O$~+`azkkWHiFdIG8)kQ)_=&mi)5m%z8l=xJ!=9Vb`DX`u zo70xlhfpVa=Sx?R=aC}xMt7j;PTETD{qs(Ao|5JeKVUQ3TRJfQ+q6~m{fDz?nkUuK zw|zwz9o2#M>uI^vHOlGtnDhhg$%7&cT;GA-y0q2YmkVdn`i683eX$l{%*d&w5|iQ&!w#;&+4-n5-T-uUU3n+j|h3Zx2aL{iwi4q0 z=}X`iY%LKsl3$@3#b3M7s+AXVKg!K0Ob|A49~#xD3a>?LmAuGjQ@1S`ze(84Jl3jF z<#C}gRsJ#a+G|GJXrY+6H`FKztwo1jZek7(%;?Ay%=CGs8Xad`Xq_qF!al1RRrfkE z`l5O(ed<$-vfc7+)YWE2O_Wf=d={(ye&#}NoZLd+H<_{F+fGz{sou_aPu8MytK3ST ze>9_HgiuOeDm9uaTxgG$@8JA=Gn%ey9!i=V;ggwkBQH|nLE|f{+d)c?dj1i5UC@xm- z<9&k*O{?Vl`M$!8hOWW^pY<=QvEqOWRl%bUvR0b0wWibW2K6E4@r?`ZIdVJkj+#;P zcc*2)sXj%Vlde<$_Qk>PVWSxv zZgrw@i28HBf7^wQ$0EL(XH_K*Q*tms4LKd(J7+K}d^b}dGK;PJ07D(ZE7dM#%6^<@EN~*NDor*dU+LN6XMw9Mp&S zw{kFI@NHBbiS5f=|1LvGc;9|}mz#se+l}abEw(@JZDpw29rP^E-8rc2e;YM>V*kf? zzm{Q8UQn>ltfe{VzSM{fuf&FMk1SNEb8xLj+l~8Z$W0o+d=FNkH6<*RxiuKj zEp0*Lxuh`a?|Kr0Qo;tZzGXn0qy?M4Od7=f=&VA6GHfvOxMe`yz!sF8N|Lbu&nn5k z`-X7-B?HR(w_w(Zq;TT@T7||LgND+F^9FSEZ9(tRq+#5j_9`@Fg%0QW83XE`Zb9p@ zBq@EkSB0jjVb8PQVL(l<7PRk8l2J!v6-uTK8o~1_0}8!b(7iipBzO(ocW(J zV14%%R9TW<;GFNOuqi2Q6m=aopuJm*e{D`0&Ae|`p<(hM1s*V#!iFMJa3 z4-}yBw|2CCkn$4s*E&#=6#g>v*H)S$)e&s;PT*(yT?<~NEpV~2GSxOB3 zJLACUnc-8>Qh-^v+cD(blxg(olmnHi;jz?jDL~tI?f!LU$}8+Y;XtQ0d^-23r~oCm z+R>h!5=R|J9cWjDzlx&^Fnd)y8v3Nflef}=#s%Rs*tfm_L$0=C#ln;Xo-e6Ev3yt} zzh_G!O7415STkoPzk|mBiy>!IRpc|R2F0_6rQv`=biVCH-L=%YJfB>H zP4=O0(vN2g(Kg?UrqikE^krfVdN+=o$2q%;(e}$j^iED!li%5MXuLIYK7A@J_Iv*! z8e-BlNl2j_X#8UlyQeo>dtrn_P#wpCZ@t zet0R$ssjw%&+ZE`WK$hB6i4P!?*%K$RtBuYy&0GlSBIwWBlEdep`~a%60n{;g@vdy z)M4wnaRtN+E=AR$fRE_UUl|y`rVbm{L~dZe!-|@j0Y;zp?HQn!g*tC$V9eM$zm~|Y)U(5iG17o-+!I{} zDr+ud^y$bF`uxy}_74Lr{BAuNSkbQz#pbB(+>c@_wuS~+>BHg-zb7tZ#EHmK;vCwE zA!DD|L7(y#W6-^NlsLzKLcB+Jp*Z4+Px)^3VsyIeQFdnhPWB7C&@O*s7yZatjGFWH zm_2X&Zk|8A4<*z7W24TGm-=n{8l!tm+e1FH%Fs~Ld#}&HVL9k6YDD|5Q}^NAGE~;} z-cQ{_b1<=1oZ7XK0 z+&GrI%st-N9y5@0;4r_~orAB)PHW>GY1E#qG`L zkV+kVZ{CJwC(mHriKPcP@5^S?&6ITp?cTi=%lgk?#p?8f%s9_J zmGnE}>)(p8{bw+;CjEQj`m-7Hi=;iw%iD^=1uyotWgZUNbf6VAH!FT%{kBqU`N@k( z^Pc#TxWxOhc#W)=|JzEj%I(D@ZRQd3YiY&EaM@AfJzk1UG3QaJ&pgKZ$@{T4L)J&V zdP+miK9BLWnLn}qgI08om;Fqi94bXwpBKxNnaBCRs}*xoW&On4S&B`aUUclvJi)#G z+KOX~WWTWPKq>mBok#VXng1rvp;q*{XACgUR*Ds0dNDg8^CahQYsH9jGX}|fMJZNI zIFA+MGlz(4ODpy!$ei@U7p*1TCq+c8>S8!rRcll#i~n7PvHx#7#k-W zVO>or*1YA#v82pjiKnX-dwXY`Ca-r(QFg|Q+2@v?q3#{6*m9f9P2CH^H`Z4Wth z)+qg3Wx}uv{*ZraFHyJ7c5I5Ab(!(SCKO)tW7Y54--%~kJH}e&WAwv4CLA;RG2XBJ zgZ;i}$L?$LE6kf~!lYOHSmo9JNx$xE$Ji_KtJF(t!kR)qI=i%gQK#kY82z67Kb*71 zgwZGcnD5YD5D^UNU( zOA(C^T3x3^VV{6qldb4}YzPwyMH7NHf1<>J0RgSktr(#m3Mq)fgXUE!(d!gKp0uDZ zbqF1TXd-d#R$|M5fO)+Z98e8m|C6HY$YZS%M~@1abku^@DMO*}#Hj0oswyF2LF9T9swiwSg`i;AUeMmO$l1OUWsFS1k}`8u*x%tP1i?7^SxS$ zSKk*f;cE-FogYMpDC$<;X_^|7^95`>V8Lj|5cJt7be~ynMR&prC`en116Xo(Cctv zUf36(!C8Rn>CCr3!-Lmer*bd6&W!0lLjn1=E6Exl!Ctd zAqD$37%=UvMy%QI!j}0_vx)1&6r7|rVA}f)n7`i@`kxRL%f9O#jj$z1BRGX-m2HlQ$M#e!BBrbS5pK_4$y;njBy z7&&0YNv$pv=1S%fcZLep*#;atVa3WXTo^5u#FOVsDvZuHVEAz>F5BnAv0ue^k>86d z)aebF+h@g+C>PdEm)y1&yKtdL zoDj74K^11{3|RDQJ<266jJ+(rhdL}&VPcj6`wrLRh~UDk)8c=!e!U9I(ha!m<$4^M zFpQ3~;sw<69u?}o*^D_`8!)%og#%~AiR8Ing##ZLFt4})6aUwR=Ck5^sq+gej96ZX z`L8sf^$%Cb6v=(8o2NqQ;zCT`(tuXK3&Tdl_XkbVsxarJLLBRAz%a=$=AIHSWZqmA zCa4QhC~Uyq*~3^gD1LzXOI5fms}Lg^>#^v}5XMgxKS-T3R1f}rF4i{GWB3IpN*@s~ z;yzU>bbnNc5kJ+V^@0;e7m1VDCrO2)%L}pK4%uP;<_MX6dwa_PJMsNn4DVv&n{$Z61`Kmu3WQ6KT-A*oejT zHf%ZP34O;*)9?Ae=cN5W)3Sp0OxIx9dLxFtX2WK|6Y>Y?O5*ioVD+6w zoRnq5;yoVh@=I3{$E_OFJ#IvKp$#2dJUD5;bT#!omx01;BMv-f3w>|$U{i-Qn|E+B z0|#asG5k>*MsD3&d)|hc-5wl0FI`I>ks8dMVZ_mV8%BQU!HB!3 zuOr?YHS7NFXN-N+hDFbLFt0_LLw}#jz{*>V7+qk)nhFn=oRF?3uE`pdFEL_O=a(3} z)`Lm2rvHm|$1|`e--zPbUt-&99&A1#eUf_|r@{O?j99zZhRddSQND6UF6+%p(f!4C z%6Q5@$Tc`*~t14s6?w!nqb)c(WI!>t;Mn9>%2@*RUN64zys`WFOYX$2>zl z$1lgMg=Hw!euX233pkJ-lSjPnW$5_29L0ln44dFbvs(Tvb-$>?D_HrCOVaJ?5eb}`~zA>meM~ek}OqljbJLb&vWB4=j{Gekyv?yyUM@_FC zM=$w8{~wk=$33jpqI8D|<$u{ROmY#k*2Brg+RYsbncKgR3jo7ksF zyXo(FXzs9M_yr#(|5N@_(3YiITqrT)z-c>{#b3md`Er4K+N#CTvnDL)vSZ&#AG*Wk zh3vOn8?w3_rT=Ni+&DiD+#}x{w0M&iC;er@ux2}IPWVFq|B5lt2gzD=KVObjr|lRq z&X2hYc@gh*qZZ@eE63snJDQLAaNt_Z7UEi=#fk&vSpAC~eOG+wh?Bp}x?C+vzbME4 zy>=`)?8CaNF|W`E_h~WORF2I@>?ob#$KKoJ#oYTkE$VFLSW<7t>SI0>`(n28-WF(a zq`w>|9kyfQAAXcZ%eRsDN-ZWnWWw+|JC=3%u*DN&XFb6iN z133DUqCBXqUXQxtX6%{iz@}#cAwN=>xYwWccy+=K%>BIsYZnGkzFlGFo@hR; zOm|@avjHr6SFwY7_3AP9FEfr_>_BN^0JHiOuX8^i>M`lC`SsAfJJ6aNK%r8xlXugj zN8Lp;PI}6LBboq~JgKPQJsi9O81bOu zy}$EC%}-{m4s?XZ69bsPQSm-~S)#|}UNaV)?7-R^0@$`l@d4x6dhFk0#%10P99tN` z>XnKb`l48mJw0YD=i>>l3HLs?k&=uV7G?!@l$OW1NCwwAbEPhh`vCywNGqWg_Ys5=$=G4E?! z7CMzXQCQT8ak4S&SH*q8xOo-U?cIfm|L#KFwcl|hY0jtg)#_CkePS1m{LzJZnPcd9 za!wuh_v$JfIkF22u63c~)-kNyGG}j7(*FSf0RR6i(|=rzcmKfgBhise6x!CN9mmRQ zWEIg-v3?wc+(b)D?j1R%k~Ezrgmycorrb@f4o;SqI*5hLVX?znOJWCS6FU)N$I2XY zkoNta*SY_CKCaJoU7yeU^Zp?a*cT-1uMHIlgx?mT`mzoU_n%@$hX&p?$|wtQzO7v8qT&z}O!OvBIRY>1M(Caoz{4iZ>>p zy0{R1ztf@5gQr+9#`~bvo|y?4>$U^sw{<9Vv|!q&-iO%llLU+^F2vS49R?boqU%`i zTC2M71dKgdi0b<~^l`UfaE+Y3>y*P+w1r&uw^`>0h@Y62>j z6{3Ho4lAxcMdJwXW9&OE0e!X=V#7rpN}oQ(o*CZ9`F?o<+Ak_ZX}J!o&OgQ6y0P`R zV+oqnJ5g}&CsYo9iPByECwMMN!sxMIVQ5A(O1}CBoxbw>&Z@Ix64t&f!TJr&Hkbc{ zJrn#-Qm?B^F)XhPb6Q($&+pr5ty-oAU`~=8O-ITw?Rg6-LhMel@1_8hekn(BZW$`B zwqW$kzNd+ES^yf-&sAawgo$;+MT6uCI(>ZVmVqysZeEVL4(BZ2l_}B zfQlV*)GEqQeX0ekBKqpAnr}};vGWRa?YA4X^DgOZ_w09${ZCCq-K#6m^6qYIPQQfC zpY}h`clRcueDDf%I;+OIetJ~y7XE0}ZS!PoD^Ednks39IU$DZ?p^6d_mj+?cnG~C5H8xJxV}aJ;XY!CY8C$C381+z%ngBiOwmMuO{wqP)T$h5Hduq(SrpJaw!WQ;* zos99{rC_c}jkW9a7&yY=B6;2uj79coD4+Z_&fj~&8t<5<|NUsMz3Sz-b|<$w|l9&-P*K&jw6uclwq8 zUJXIr{B#tHE3rQMS8RM|&~L)h}APz;Pow>^)l#DXRR zMs0O!V-5pDuwX+vCVN(*{Z0c`+#Ps>@5@8be(!1wtk{Q^CIhyOA9NFUhoa#@Ix0OX zZR_KIMMc}d-~Q&O#?6_t8v6#lv*$PTGgMA_FF0AK1?Q{t3p~ z;B*Y@szTGq>!=+&_?A_t>(emzQU>~ttirHW*D+_yE4MlS`1>e+oPpVozriZE>*)5u zD;@M<_f*V1mw_@(HA>YtaDJEb9b11!U`34rrQcMey6FZA-Gs0s^bh7i9FFFCF-I`OL>y>hRionwq>-tY2=b3Tv2`Q=$y=W+nm z?;EjogUet4I~VnrvaqB>gJ}bdC|~08nELLG#Q3r-)HxkMpCBW4eCcB5J_jSP`-d#d z_Beo&K}HOn_vm-ELXBG+v9KezZMl>m0{wCkwL}1aWEVS=`05d)`qCU*!De

zKI}Ph+D%8DI2&aphtTWvE!39|f5Ca4)3Ip8I_z0~2($O!MnV0s9_nE?9XmeDM$_0@ zv?w~Tu4C9s=C*Y@s&}u)M4xYMX57K#kKB66L(MESJ8nSNTZd6I;0`uVar?(=?k6*` z!gm994nKk(0e7%_nVaCS^`5(CqWP5#D7||aJ%-;wvD~c>>zOlAS+pLVrX0b>8~3om z^qQSj%b3|1_U=a8bM!F`{ox*Zz5RM$tIb}sQKH$5x;Kua>g)roYkt$-YQ>>wbh^43 zy}FOt)<-`;`&)1HvzoUl8cnmeVB(PzC_ik%*hwD!`9EMD)@|K_c`4sv;IoIQe&pf6 zeN{22X;z{-M2j97-L~iLBB9mpmKZE}qQt6dE!yk5FmH)yfK^#}47$zOirEq^N)x*< zHc#Y8zJHFv#Ne$cm~skL?{%Sno@k)eWK|4GmTX07fEMfHx@_x?qntQr>O!pgLy2{M zT5MdXva<*zLh{2wtO3eFPi@HPISdt|gVpW?TgT^`~X1}XN-OMhm%M=YI zzPuRJ9#*1h(O#d6kqh-c9)sPNx1v;k65U_z!i+GHt5xU!#Gp~Dv_1En#FFz} z=#?fKM*eDJFyo36)fZ1<_Ngv3PZbTf_5A`gRVq=QsYTpz~fO8rNtseo_}IlSHqQ-x&+BdCpeUoI8oi;x3d<6urj!ni#a- zrNpQ|Phy3C7pfCQuM^MS7;M%lQ8G`9_5HfA%~#}ZwP95Z))y;L6?___w>`40M~!}i z|DP|!?$T|jmY+sL;a^w~Jo-(}70041ZyOq?oyMN^kFf5LcqH*YS%^hLwxQvp)97>L z5jGmd9@ND*7A2Bx*zI>3qt`w{{}j)+xaY<=ENab1v*HZ;I-7BRji-q9xp8RvDj##6 zG@!)Sj8#iLN6}}Yi!ktqd`z5s2BkyI=s(U=O#WuYp~s>xu=TG7>^WgZL7eAktFCwA zFmcis=yS3GbuS-d{4btw6Yrup^#3v+>)IR8b)Oll7I=D+uk<(!JfDxU6AkD#+KlcY zUS7ntCJxoxzreP`4OsE=G3I)Cj^RA-MOd^Y9|Ny7V6=xB!@51+VSdgp!ra68DBa(H zIe$GyrMIUy^$3YWr_K4OyWD_1Eq`Od$38yf{qw~brrLqJbLX(r;ThImdG}rZ+mMK% zx*gbX{~U@X&(N~OXDstEXbCFSJ5Xpjhi)y;(0`K8IPMjfh>|lqFt77GRyn`G_=P^c zR?|`vF?ZE}QSjw?6uz{eX1vdM;xAi_xj*i}*azp(JgXNKucP%%1RY{IYsy_hR~FMv2#%dq)M zF&4aNLZyE%%E$Xppk5_1Ecmk+rRST_V{|Wug^iy`|7FWCxwRPEdYVw--iz@m;{!SW zzcO^HD#oy;Cd@Iv#BTrbllX4A3!%Bz0ib)S9&q= zz41ZRbA=2IO~sfq`vS@`1QPCb!VfLClTa|P6dSTGV98#=6#CXwADD!#J4|DWMSTMB| zyVEaVRaBp;%&VV2&hN7f%`TrrNc4(Q>97;~(kKlqig*KR*bw+i!6E+R14>m$9ICTU`r}i94*HThbySsB#fc{-%Bt%Hx=WLm80eDD`=Q4T)|qqn~J)h$}#c29<_OnaaN;_O~G7q8j4#hP!@CzoB!>&$ZGP+5OjW#hC25O zOj~>n^_v~ziBlbnot8B8`r~Vq%)e%PALsZX{l9q%=9<#b$+ZGw6R%<8ddCFnwK@b% zkJC`x@ij^oUc=a2$Hi8KgF-Q0x*EgA>_ES5dq*(gD{ZMoECN}>yB*|*kYvI^B zPl2wLHMVEdO;o==beUEA&~U8Xs=&O=8Z@7}i3Qz5vFJBJQk zZq+9u9HX)nXxLbT%95KH-#+AH?mZ+No9C{@h7kubaaKFlXS=Rot~8OTn6MT*CLF}j z_;%a-ORmY}s#KZsr_?ImR;X`d zRNoO9)L%FQ-DB2aPjxLC0`H>p&R0L-p2bn1Cfha#jLq%PNiZy%Yw`s_Rf+C?}4+Z7yi;q}) zl5F12gn-0CC7OXsK1)zZnNC}TN=XSm3sFf>(GYJ0+xNTA`s@8V=iKMq*L9uiNF2_pH~C&T{L0X%SXGzXdfTtk^WI z9c4MA-(~;)Md;m|gI#7T)+e>2+%oz-x7p)f!+5_f==G!(wUO=Ev~lzXx27)_q2<&T zluxr_eM&p#)QmRp-H(f~#%Bw953yq0q;}N4J9?vA>)u7Ey`6(GGpuM{+K!zk0^X-y z4H`5A7(L^xDm1UVjkPb0{a?2Y7c`hQz=&OMR-twKZI4$2vdQnJ2Gw3h)a0&C9S!|1x859kB? z8`ySl8-}NzM8l^0XmkX9NW9`3s9t75r{W}*EV_^Oz&NE}oi8G$@*AKDnM)0S^yD1S(FPqW-=vj0$ z_My+=$-6jr@d`AgeTsQk&!X4NN2uwUoX7XSC1YSfJ~pO1(D|7Q+j_$Cx$k}}(b}7b zB~u(&taD-9pzzN)=VCHO`RAi~wF5hhE^G>jC?Ni>WURQKhpOog6qmcuN1R+p9qN-Y zPM(kUWe#*~bz$|b$wj=+u4F82%frx#4ovzV7uNq3_BnaoO2(+`c^Es%f$?`I4^s8_VSihEx8BKZE zW%;O-J5ZnM!paqsONnb=G8TK~W9b+NRwubIWpUV7)Z^D=?0BvKbMO3s@)uob=pR(h_5~GCk3^e3o!d&9Y)=fT6kCeBT=hOL6f=wqciI~^FK%r zkoUw0ES;Q!rk@HhXm=fI?@GVHDUsN=Bn2Cn7GT$gIy4=ZmXqhq2sA#m8nfRiKx<(g z%CAZ*=)YkR=pVTnedZNl&8|9Bw@MEZUt}Z}FG#@#RRLD6tHan6(nHkGI}*+FQ_wNH z0L4{xSXeGSOx%tLjPXxFzjXzu$*aTkCTS)2C!2!Nfhm~wQUTT`)uFvc`Yq>P3dj0C zS7A^}0p@;Ehou*#N7y%D3Ra9tL9eL=*s8C?!cysf=&#sF^t-bPyZ%{#DaJa?`blb~ z-m(bndL{+6kp-Bpt;6Wu((gF``6=ktz6$eB7NB}t9h&Qwen zlNQUW_QOQPnm}d0Mpnx`XH3DMt*O}dMGxL+ARvn48~-K4%Bp zspsP}v0}no82!p#ELq)%mQMzsyzL*pRjtV~ZNmd}8o9@?J9&O(Acg*ZjR` zPj19?>);>Q7aW5f-RrSt&0chT-sqV>GT1?%|1tv`T9^ zp7)VE3)3nxu(WeO8rputzCpvz6Ssag8rHv!H4947?sFN9;lnO)Umwmw%bpChUfYi) zpEaZYr1wSg8LmPxJQM8;%FvwNjH=JQ8;JMX9P}HQiGA;uq0`)qhEv`@^NxqAJWk5Q zsM%%cT-l6T!TT5TZk~gZ$1*V^wG6$?&6rl@eTn$`tI%&;CdSS!!<6G!(D1Q$Bl~}u zgISVH%$`?`bnxneLyBU{L3&Sz8PD$c>m_My1xorw`XG9$phGQ$B7v) z_*`ax?p$n|Zosrv<=ALx!IYc6P1JwnJak$OSiQ9zGu~-I^FH5Z-p|cgj{^)Cx1t=o z_O)Q(Prg^Um$maz|Dpk#!phOOz6FDdeg8`zG{>UFw-`{}tm&-9`TMOn@`nFN$zE~_AZ9vP2 za?DC-!Q3srf4B`Ti^a;j8&Ea79MiV8V9Y_^o8)&f7K26^u=w0TOdE6!&0&7+^w*LF zm{Ib+XPke~_jD1Mn3m0RDV8mK$6{i1n8}-3sd+DRyi_!jx z5w+h|p{(yVw*C^>N4}3<$7t17jME>-`2BZL|8w9Yw>1x6$D}D+(QDapjNX42<1PgL zMO@-2HGl9=%qYuyNxl z%sSbPmEVn*x^=e1V~N~^jqjd9^`36*xIVt0TTTCEm>X-t@HM9}u&^6T4vz27`o(yR zd)0)EYfgF0@5Zbv<7KQ%mtm62gn4UDVRc?Nc3d9+m|OqZ%g{XEgsrPip?zmJMt?JY zfLlk&GPDdcVc(il=wt3iS%h++TjMevT22d?QENl}EfGsrE4|zf*`!0&1p&3UY*_Mi z50-uvJc#+tI#llz(EPm(>u-yg_J;Ctx856ds5v2E={*}ZzV{Gw$14X@*H?5X773{D zuwmb@9?!f&ImE3gPKU8a1x%9I(eh*uW;~}H%KAJV8nz1PbJK?Efjwx6RSu&M7U?kU zr5&iLwhi<2k%;=a$|tDvLLC|o30Tu?!|KO-uy(%EoBw9&F#ec;>Thl6?G({DT=^vb z&(NXKBw+X@8#X@OgP}gkr`*a{>(D1pK*?7&Z2MXC%->Ny?Y2v$L$yvo@e3PPN_wz! zs?vw^r|7V6rGRY>HnhIkgFdsAzO0AoP_8=UBH}vr_se1`gKbXdJnz%;WB z1CNO)S13pFZl2d+#=ivYtg>OrQ4ziS6wgwxS9MtP-yN8-&4x|ii=ql=el23qp9(qk9+{c4+N|@Y{Tq25ku<~&oLgR!;ZBA4*A4}(ZwQae^dn0|ATd?SuSAECL0ERCt~OY z#q-QZ=sYG1XgXB9xgT5H3~auMT7l%d?SUWbLV z1@xa`!@e>RJI*U6QSY_{Yq0O*wASaJ@YpeVdT@2 zfRdpCX2hJvrtd`5ey#}To&Prhje`V~$J?;*9TA5VDkAW49hwFT=v->U+P6h4{7eza zdl;xg=R^UuN*kKji{P*wM0~7iC@(rxD-JiD-OkCtB2Yv}X5WR9VQ2eD`}Is-ND8c?<1W z-`I;C-V>wg`_qXi3)mU`cYLVL>c!%+km=O@Od>jm?!;`R9ZkAktb7YuY)qtbK$v2f}6(moy1QO2^sT1MA>8ykk5hZ%ok(3`pF%bzd$d+Jn2m=ir)1io)z=;BcY$*p0=Qbh-f{%yjX&wQV= zX!uNq;ZGLfWK;(lRez%A(>`GqmEX!x|9BA&$~(|)qX`|Fe8Vj!d?LfvKMPUd*Ma$Y zCRCUEK2Kdb848SrD01nrt~Z-d`l-)qi^IRmFmiJdCWUmMsL_N2w|!pVdsQ+_y<3Q_ zP8}#*X2PjEK2nRLH)L2lT8JXY4)hE#p>&$xixx|sO2GQR7Gaxx2Zs8au&mT~jm7jX z87l7-qD0k!`5R3b)8G?9K4mg=aVoMZ?7*@`CiJZIi=^MxGR*z95HkfGm~S*;jLv7R z#i$|~hSnZNgG~qa{nLa2$9-QShr=@T)E&kG{|?l|nykN{@O_!S<;!sD%fs0EM?2=u zGvU4W7e!G|vkV=s9!AOU?bsJ(LYq?Wf6=#hWfeODkXK%*v4M(tcX(#H7%~pT$ zk0aL>1$tjBMmJ*@roL>qo*d6g(0ELNqS0b(Z0kb3r`-mN&L{mb{g47h!^Nn(+l8KM z>|Uc^E&dq3UxBT6i*fK=7uLRL7teloB$&Ep3r^iEM&)o920m}Mk$g}2qsOO;jn?~K zjDZ)rFn+$>CgyUj1lvw4a8g%{qk~;|{qJ@%>S~r?aM~73y-|!_qg~h-YL`I&Z~0?c z=oZYWD#rNuZWM>u$;s!W1XH(f!KSOlm~gVo`aIBXGvB!sfWuvh7{0y~9hMm|@0ef< zb)E}AeQ%<5Ejf_^+c3-m7>nyfS#>_M2m{%0Cdo8!}_O6u_?}g zksGFMWiD<;o-!?mCW*{nt=4Yle#RJa`5tS0`b5ayd5Yu3_f2 z={u>%7>FLJN$CA_1tzWR!RBOPip7Aj6=;~b19MH~s0i)B#w1}Xd36V3K+Fz||DzlQ z$vrr(5vK9pKoEvsO-8r*71+3=2la=9|K>a|2cd^48Ji}`Q6JcY>W#wJsq54-9Bfa< zxW_BdEwu-0-xH=&*EfMU+L?@j?iEHV|FflTqzjfr_dgtbbMbCVknp z4AU_5G~9kr^;m*@PZ0;!6z`TsTUQ3 z*;&l(w?XKpRAHoCi{5#?nC?4!7x!&O5SAHLSe2yR^}qLaS@XBgW`FZ?lx$O>$3`uB z9qh${Zu=bicRLt!K2V{{Yg!yo_hO*I{w?};e>nzhRbl?CS`_Z?#i-D|p`Lq4oeDAR!6fRR?)!SM$p6bQ=-|f}R)uTZuh)`i`t`;ZL`q0H^_B+&X zw*mu~s4zEMi&a;9vGynXJr+gZ2cg1!1htk$AoM=uIm?Dvt+%@vpzt-_daEjn-S#e{nMcj@EM3KU3GC|RY& zsI*?pIdA_T=HR>KSUX*XQA#a_7WHDluzemm&J4ofg(`Fo(V|OAFUH@ue~)|U7ldv$ zDpV}jqV!NN3Myvrr(c6X=xkPEW~dhHxAtOuwfzB$skfG6t*r_JmuayiqZiw>_W2f@ zuPw*?-;@{`qQ%T@y{P}d{vh+b?pYkjOu@KcD=|;hkDfBeL)3jJ7+ZBIhpgwT#5UJ{ z3|#N{KKbkk#<&wHXmhs`Q+M`bU%X=hxr{uEx{4G`GFGDgaz75lIv%!o@9ki8C`+;W zQzbS#^yBr7j)nB$p%ANODLDCKB`Rn3W9xdyBL1HhjGE#UwE3YD71R6Cu*OkC{aL{% zEl+_|r#aCJ2{t{*_fUZ)a^;XNTZY)nJxl4{h-2QX%@(=pB~S&1<}q@g~b8VBMB zFy}p|Que(Xf(c`3rPg~=jfPhSP~GixoV*PonDl)brutN4)w%&p$Z{$p4}Azu{+fpO zp02iPTbQ%(p$g_@*D6dunvT*tA7lQETR6Djp%2J2 zYZZExq~m1VNgV!Q2&K10TITys7$#iHK*5R{%sn=Q(i@@^%>Q5*=K5t|p1cMXM}{z6 zFREnzZ-rrrZw7j9uE7B9kaevWeaQbF3dfw#3~WuP!MNi?X!G>LRebNyFl>4z0|P#& z!Ls8+IM^wwwpd^a!#JM|^uAkz!$m__|IH&GS#&dnVQo|frpjv2p=b!b+eIIfr)@Z@ zy)&>msRrvm8^WZ1k&gb%499|H8R#LaLFGq7sB06Qqz|287_%?~Gt+BOaCitsZK4|9 zyAp;D0U6k~wFaY(4B_Nu(IN#WZsM^KsR+Q@u0Nl|$_8wW&nSh8jW4R5%9 zM*q)BF>f#%y=K(my%$C>F30sO>(8a=Fp`a#)9SGH`4Q_n&Gnqc(X&#Vx|wZV+ty)0 zx_z6C z%6WCDSB+q!joU@~H!lJen|5PW(;4iW97VT9Zq4*PGy*mIc4OO~GuU{26!Y&t`Z@2r zMxaQ(8~e_jLGc%Naquy>7VCUQVA9^*C@ngJsa>NO{@~F|oco~&3~tCcVf)K2$y`lwlp zaW~Z1H`Rc-tH-R*)7?8P1|C?8nO~`~{F@4chSdp)?!|#8pnTWz<@bp*5A{f=qA?}qR{K$UaV?3 zi=i+7h?Dc5_>%e~qEK{TFE)RA76mW;hy^iE7a_D1xxk2CyXJmHzb;0j&5U<(%KyCed7Kdg zPR+eeo(H2b@a8^L{Mm#;u@Tj8%!`e^I zqk66pC%4Y+W!_FiW2#{vCY-&9!+pPCz=HXG7E4yHL(e$}(B`i#Shi#Wm09Ai`QMdT z^uCafUQR7v|L;AkS>k@`tBl2xd;8Jj;TFvIn?S*C@i!KuF2`czo&6|Y--3-k6BwE; z9w5)tu{e2aKTf%};P9de6ud6J$@xoSF?H4f99-0bUh5_>@0j>o-n$%&#`y#PVL5tT9$D;1SesrGEf=15?Om7wsasLWp(c#v9 zO#kh3)I2ePHVW}=>%E9Y-P!%x~I<-K=n5*opThhI?@{W0Rfb}9Ax?hYj`hYVRPOcpp4?uMq4%Cb zG+u1Ssh_4$5#@c?VqBCAuV)ux-lcYQxjlu!$$n$JUn@uDO%3M0tw;4rGX|?9_js<8 zqwXsWDmUq|KFo}*iIN|fL!BH;dNo!b(PLBe*`dLDXFa+sHDg|ipONzlH)Giq4L1Enk2XupICw?!Gp208$jch54th*qY{se! ze!p;EOXXO0Nn>@E9&>!mI4G0+NY*mp>dWepmfnyI(Cz>Epeeh-+pLvr*wr$LXY zPV^R=F*ng~lKqP0Xmdt`;q&w;eA0~SXusd+UxOU`T92S8Qjd}aX7t?d`#X8=lVji~ z8jKq6#7Ivw##H$I!Ff;0v7}yuarZm1%-xIuF@94P3--#fq*{Z+_dBuH-Hc@lUla45 zBggm;HCBJ_L>rMA#}j=2BoY;-m&)V8k?~WyyG*5x|LW;33xf?xB+Rny3 z{uu7AK<5?3*e2^nh0fN2yf!UH(IW~}1{ULBVmCH_XzOTEcgY`HMGACTT8!E)-6*KC z{R=q`O3?Us1?m`}ux9@6Y>(heuFW zji6ED;Ze7_69w;$o8;18GanU$TTvceg9Dp8arEf8$u8|#^D(o3D_TQqFjU%!n)k;& z?y_Oqd=&h+6@_6n=uGLv;&;dSxokbR0F!>&io&OBur9R|VJF4-(|Xd zAqu0mV~pxO6nx!WD9yI zy`~d)XA~-1^04-QwC?p}3tHp6gm`cf#vAj{=av?SW#8gJoY#{s#T`+YdpZw=3yz^Q z(1MaUuNf}KiWXtg={!`&97AoE1$Aj&f#l^%6nbCC!{PtdV)bJdG%oWBq7FsT=s)LW zRQG7H=P?VGNxg!JzcmWQJ$aaLQ;Y3F3o4~vGr8{@i?H=V9@gH}V!}iVD&o9mk;iL` zP_N5F$yE;XyLmX;uf^Pn7M!=%`!AfoHyVpS$-|0nE&Bh(f?A2! zYVz37Ga?y7el+Xm^96TJ!`z4;l3Y7J@cRs@VZrt8XpTvmUzvfjs?*e-}y4? ztXd56v0%Q$E7YaR9EGWua?xo&ir$Y}uq^N4FzPaYF=n33bFcffsPVI4?qaWS{=0P% zwtkiCHtQJL9NlOhphZ>`WKEdQx+xa>z9~SBy$<6STQN6t!UE2_Bw65| z_X12EuET_9t?033!b0M>9E(Bi1(@r10(~N^Xx%s=(xu;G3Hn?uz=JTx{2Bv-+21v zO9@ttS778b^*HuQH(F|Zm(w>_B^b0!f%e_?XxPz>AxC^yxU9RnbcK6f6=?L*;qdlu z6ps3?q_0{f=ybk{_L=o)Io^$hmA(nY)gr;jRt5S5*JI&J-Kaj~yNdYgmZ5N*0!L@m zV^DTCroQQ$$UL20ip3rZ6btJy@Vu?)TAxHT)+x4z0Q!*kL(^3F2Frzfh1u zzT|PJsM~=S^C^^0yoKrW1*ycjEe>_s9XKk|W9`mf>^eMoEq!)rIocoDg}T{#3{C1q z@57VRc>n2g^m}v{#>@5SxvCcxm6M-yDK{?1j^7J0XQ>|JSM;L&?a5N=*R&kvzZaq) zP>&sPz38WzypB4)w*p1K7Gl0okIJRJsH>d(Joj!`j@3`^Lgh3)W=eWdRrL6J?saZC zs*JnQ-}Vt!Jah+h*F2HVT<=K03d3&H-~I?2Jny)lCqA)({Z|uF^5`BEN1a7Op$)Ge zpSqF0{UQ;akL*F=g0mQ(VMD!*C2gR9ZQ9AxEiq-{eq8@)wM)`RaN^doy(dRCzQUf;AKf98# zu33fR#zyz^8~x}P6p%@r&1+C!s=}O)8u9u!{iqfN$cS%SGTJ^?Vd0HN)Q!K3Au9v2 z$U}58cBoWnt#5SuT|Y{L1G4!(G8rvpD%5v1V$c8fqb@E$&iUENSgcl|>bpi1{?U)s zaRFPnXHGJDm#9#FqY-t#^rJF1;3fL(#bop^QMt7=qG+ritD^(9x}2Aty!FAkIBagj z%%Og?N&<4|uMNqlxmJWhpEsg@upgDn0=Bs<+mwtQN)_f`X~b50Kk8xvw)4NXWQ=@G zg~gW}(a_(I#^`{*(SODiv{{QVW=1nwlLygwLYPY&=TlJruOhT2G`pYI4&uPvC-YpU zewu>fZ;MbB(2N7C2C=nL_%eC)AZr>5ULOygUIIpt^tDkH}$>Kq@ zmkRUUbCQCRYem>Ky&07Y2T}Bfu)w9q2Pv3qE<(k`W{g}ih=TpXzmunsJtLEtWYE)9oYDZ#>416JG|!l3biuW|pAX*iHuf?Y-fI&Tl5 zWPIRm_x+zk%eE4XY%pNbcSG3p#|$O=lhQE#r4lrrF<|?DhOpw{z}Gonl7@Bi5^Oqc zzyIs;Z4enw|&@IIHJKT0uvsv2uowV-hK2ujWb7g4`nDOS%_qxYT`>?<6>jMKsU znXjLv7&A$Y#tki4v2z65zYH!W|Do&9=XEtUt#3h5`G|XM4ld!GeyLlr8r6v{Xg@rH z!q0-=pwIp-#j#mx)URs6vhooud}QVUmkoEM=s87w;K6+{=D-Mw&jzbqrrM=gJ4KC= zt6I={a0EkqW*uZc?np5=SdEtFS};L5f*Q%p(g)|Fe5x8V(p#|o#0XYg3VxIQx211B z_#axnZNc_8M&5MSFSv|6+>@gBlWGiF*@D{rBd9qOe2BWzja+rIMUys71QnV;8 zVos|a^|o0W?j=}{xvNUCc;`h_U$^7fomof7$L#gkx1tnV^Dd&T(T=%}Sye8Te?E`; z6{R?ucME5=*gR+eJ(`V@JQ9S=Hp<@jO~3rRew4MJ)c%jxpcO zdWZ97tw+C(GR(hn8Iva7!w&K6cd7p?8?dRS45e+CvB&!!<}R3BL!WQlfCF!rq59Hg zRE)oe!&~OmGS`PTVBfVetZTXK*7qJN=gxkQ^VV&^;=^TVJbxKAx)PO!c1-X44XY#Od`Q2p+JtrGmFQ_`$5!1KYC`9nCeD?cu=<~sn0vV$6MBBb znBX~j;$FWAy)~66IoFP5*55EBaLyUxS+)s{m6e#Z$ApR|hkHF7_7UgLl%Y|oL62sW zd;O^c(-Xr#=6Qe&?Z0ZUZl4K_jSjTf!W!r^p$v=5HK^HV!md9Z7<4!6tjk)B3^iLc zD0tn33FjQ>TpfOnJ`R*&Qndz^9VV1sabU)(@J8k$Q08`p20JQDIC{~69(Ti<=r5rR z1?3uyw3twJ-hqa@VV}6P2FNgTjRxaYCak{Vz`CUHX7V{(hQ?G4I*U!1an6AqtHVF# z+$}QnNz-8A0TYfjINa+yVFu!ymW7%`joa5vm}zie^``Li{Aa2RN7rjmb*R2_+2%I(7Hy0qeUjSzdJB;Mfhdr!B2+91PzYu zGPynDK))ZtT2U`UXTlNmIb=fZCl0(G7ycRjI$ehHWDSNKFkz71;Wj?JjXK}RMB{P| zrtUMLq{-nnDg27dff+LFSgXOFLKEhkcA%suteyUzB*U_J4fZsf+8^vgkGSxwxLJlt zaT>JkF`+8{_p9#t4*#5dKPf}ccn!`|n?8Rqzn?$&pNTpI$WWK8!PHMpm~_^G9{&#O z;2u+D*t$=HwMV}|+s956{SjfNe&TEtt*FALH_ez}aJt{y#a~e0XR|RssS2G(%qTzS zMD0k#HTo?!8@-oRVdh>ligZr24n|xjPGL5NEUCh>*Ui@-?8D*zdiG21H+>8G%&)@G zVlxU(I&o}N+{u2wY>b&(g(0t*aqP4cl_TP>nE$7;Q9Z8;jjx$eaomaCzlgi|UXYEc zVO8j(Fr%pLKj<%f_G{h;XJc1H6-I6}qvtzLtmu#UhQ9I5#zIjQ_U$rb!x1Ou-;el~ z`3lZPQA8D1B%0k;II-*}v4!}YS=bO>g~pX;^n1&R^1+B3E)7B17#UcF*5ziDA9iBX z{fK{2=keJXlU#+lE6vz-(1`;!@ptT7osHU=RoJz}jKc?+gF%z ztk{XdLGkzW`7c>mJgo}#F=kX2IngpG?&iCZEVNFp!q8YVs!uuHjz-)h&Y!YSFs%xk z7MM}2bfWxrL=SNdW?{_KDy&^%MvvW299Sg2<@_s+B_1E+9KKtyP^Zs!}BE9b?mk!HCBJJc;7+5fb?VXb@ z3)WxBz@f)KLD{5JnD);hY`r_FL(pn?3q_|Y(Q)kz2JUw06!guBLhFcZY@et@Pelus zY;)-nv`eRA*`F#bct(eLb6T8nh08Dee`FNerY*yU03CM6w%~x)<%*zr{8Y5Hs?c|w z4pU~eV7JDlTd=q*3bTJwp=6v6D_?5CGOf#1!GLch*kn_o!B2E?73v?;p?PKt_N;ZeL4Nn5(0)>d#U470oZNza>s)RM z#<@*JnOTK5M(I#LsRi9jTz;ibu2Zq~j0($qbie-f9op8p+!9O}F%=yrR5;|O!{Evm z9LRU+;rwa|YD_9rc<4~A{}GidTyFD!uc_E@RE6H7beQ&R3yN2|^zy&dY3Q4ugZ|&` zL7B;ht-<0u{Qr^ZsGpUCJ=^y<<2oB!2S)Vqomh&#g*m8f+=KO9HtZQ1@tdIK(P(Un z$-%4zpQ6-g!_p}6UCw`8iXvGK=C#~j2s}p zh-fUCzuc);6&6RGL($@qzw>?dbd;aW#qd#8SUUe4CM_CyPq2JNG$u9WVwqbNwo1;S zeC^2l^mpHMY}~X0vrq5CwEpv$;y=p4?{CCl?#30EX4!|Kx6fn2lcWA%-j>MFbHfVE zy0#Ddd@nfl8})#9C7+4K>sO%niG7&XcmV^R7&XZG3uI_4T7lM~eb|2OJm$XbF+_b| zdl9Wa=VQs3YK)7vV`!SkFzeIgXg!mUxxUpXjaqCb~G>a5Y-EL?vKHE@k&(wtr|Ti*`4c)JzNBBM`JMMWInc! ztj6weJNhPjxUxRsMeIABkCvI$XnoF(%5;wr>|Y&&=I`^-c*THVsWM#hqN`=;C9jJ120cOdr~YmWT`Q4 za}9-kw&(xyg5Q4M-F zv|;xpFF*F59E-KdYAjz~`t;>*uRccIp6j`(MJqXzwT4=grwz?y?58KODf|Cof^2%zG@~ zWzNR-%tCB>*NB=69az%uGmd$9d@fp&3Q@e(h*{rtV96by0M7H7i&bwFqI9DX<)=F^ z{*KSzIp>MFs7Wcryh0;(9_zq_dp_g;`VQ-p3sGKdMC;KGjJxSGfxbUF7elKGQNPNF z#m72OeAOqAdppNY)b&>YmyF2sgxBWgeHK>0PFVD=rHgO&0^3}0%*)`|{n?DBb< z``(*_nwf<-kYU8Qk2|oq(_Xo-zh{`UG=LlJ6zJcvz>F0{<_dyaEfDKK!x^NIZd%Dn(=J!1FxlVy~ zpA=zF%)hbyS{D{b{319%OM!7ai!k)tgBX9c3$rHsP2$`)6lngX2y?$Z=(MW~I~Vyy z(!VtdG;Aosx^E9+Lr0f0KI%7FFy-ZWs4OeOfZRivpzWUQ?9-Sj%>B8SQ6BX!c4izx z%eHRpk&b*k~M zvl6WT;V>p#xrWv|0aMB6;%nGCauZrs9>HwSTd2PhFio)3{u=fSZ^WdRkD#^UCWf~K zNXb{6fO(Od(EZ9c=&icxjEw=)1^rzUug$-jb~9!jYe4(eTXcVz`SIYp0no;iF#X`pzJQV2OJo zw$IZ#V~Gjv6}{N^N6M16GKP1RV&2sz z=lcA9ET{@eX5PD#F=^$8*q+ja1uyqw?aGivlcl%W`)?Y0}Pq!u%=k{axry;4F z+nS8IUwwq)`^V9k-H*YQA#c(jYckf_O0oR+;}{&>kF9ATY4pvOjExUUF>c^Es;Bj1 z!_ts+>h)PNMxH9g?z_iP7S)f6B_SESuQSQ0xLb`)Jrw`um?$ z?7X@i14Q3D<2VQU=7y>0>(Nv+cW+18uo+9`4$R95%jP_DD#}LeK<_~_s$(2Duqtes za~@K${oHmecbJ#`^&N_{!gAPuXDWuaY)AKTC(&Q#Kut#2+k)D|sn{2=0~_y}v1FP9 zYS&xPw_p(4%OmpW>-Xu{bH5yGBP>|IdJuhoi^yj`OFHT$ z73e$Df^};KvFEplmDKBGIwm;EQ6FW&(A|Sr`(eZ?LC4q(G`d!xtk8neRfBlr*9bLp zaUvb_hRQME1q&KJ{R6|dM*NfW|4hf?d*zrNWkL0#K`b4LSk1d_NyqHS3LFTvVEy7j zjC(&~4Ru|Zfr>vW&^_FOohgG@zBQtNeP(2!?QS_{Wm&Lf@gNpxBMPavTLzX5mt)p* z7Bnv&MD6W}wX8R#W8CjMushg-LyHEn^?F1Rb+o2q;N2aVQg1=gqCrf%9#KquE*%4& z{1`10E$IICAj)@7UdR6b%*24NDo}Cx6xtsdcE-b#-(^1cW}^L21=c@u8apG0(NZ>P zy7rBYNb28DtumUX)PGMc}Flx#sX#^$dnHcBT ziN%Yp=(+hJ+H0q5rcXU@p<-|+%9E|wqj~6z4^4iLx{q0kqJf<#-Dt(!0}oMuW6Boh z=f+zYIb|1S`Jchup;QGE`@H`2c_1P%ht;63b^Vb49f-n|ifrs|&|&B4W|W1venkKFOR!3*!r%{dPIonvT@PZpO-9mvZ*I8HJIrsIam`hglyrW9UTJ z3g?_eVe3T|$_sU<_@){AeslSRdwwHD{Wul+?$e=7+l-=4(N4jFBhygntwQTw9VTsV zMsc;MlJAaAL(vQsI`le}R5xR-O|*-5Bb|!YsVYp`twYQDW(>B7b_)h}O3^G+p}kUv zLkF5svQMNV?@TEMM5?gyjom2KH>2Y#k)Apno`#JPDy&M}jmBqfm~}+Fhy5+nv3uJx z3~kV(Mr=dv#1WrTuT#^|@xd}|Jfuher)}7iJYp|-kDiW6?=Qm}NA*~&vZ3VF5mnUX z&*@n9)iN|**Q5ORA5k)4#AnR^v1qJ%F&C|wpJ8C#SyXno?PCrei$=?oTr5xe40~$N zqU4<0=YsLk(Wpt!#gxpwXjpp|<;&a+Z&`fz%av4MfBby8rm6CLPuQl{8yD>H@ zB?T4Ri%BjDU2(+1x)v;?V_>0+D;gp<86!gnb5ty1-|lbx>-#zPoH^$?&-0wo>3WNI z?XEZJbpF#_7#S2=quF?67J62!L%nMk4wRq4x@&jUYR2@>!o1vd*tU5Wnm+Er`m1++ zq?vqi7WU6vhl+C-rtay&$jf)hnmzrqu;Q6@Xn$oF76zTcENj>v&8YuPK~ujSZE6j= zZaa&WSz&dWgHj3(%-(<=wFcvEJ&XFM!uDzwFMS-_&e}2lbPXm?Ig533!`$S_o`OSt zcI@e@!IlwcF?ep+KJK$N1qaUA@wc>L@r`awn;%xMS!7GWpp$kSI#Gk6zjkAv7`9)t zbZrV|?6PCg)f)8N=*IHdVIMPInS#0wJNBQb!J*6DSY-GzF6ZR=_ZAroW85=P9 zUo|)weinskVV{v#-Q!q)$c|};YH;H~H(Ij86xO*?ux-5^O^0hRtG^rVGs6yYPiqPm z71*)xa19D-H+IE`eXiM%nu7NC?dWQ%!PM`&u`4d@3(fWgDQGITV?;v@*7bH{(uA-^ z&4SbvEVA2ia9<7fm7hgjOjwg<;`|g;R@!mMU4x#J-B>j)>|gYgIR#sm+cC&pgC!l^ z=szzs^L>;B3m%oQ|Fn!DJ5{WU4sYSSKUi=uQNoDzGM4O6QTL1RC3QMw#{5JH{p)3{ ze_zGYGr}Rwj$15PI#WX3i!!$CR&l6TILv-0%qXTx7`Z~mh7VO7I4O9D`q5Q?dLP;fQAKf6Zu_Dq-R(8H0DI736qz|I8d&l=cw>C>z=Y; z;z$Xr*2oxDrDF9_;TztU&Vq@5m2haajCtiMHb#ZF^G-7?7&%))SH6se{VLji5suy5 z50fTIn6^yD`Z5)JZyR--??D#KnLWr2 zzZ+q}hS?JK2kpVg{VJM{2q(zzA1zpKlCW)`j6F+KOzRN-Lx28i#@vY#wl~QbT%%%n zuW*w2Q5KAuC}Hu-G8SxCvG!Y`lm7hKj6oA6v{%UJ-=?C)Bb?IA=rCi_0}={L<-qu# zDtf*YPV@bk86&+C>gr@{-=m`Iu<$MGzcyq1ObL4(GDd!=q8Jh0MSi|EW7cC5_AHmt z_NI!S)bKN!71zx;FhjziB{I6IR2=$J=;oc=V!`4+OWim3L*We-JKMw0YIcpZVEoGx zW~`C}R;gG!BD_bl@|qcc``dp6o9b46a$A$06_w5!; zN|vx_wT#uCI|dj#r#9U_w?DI8S^GcIIutt_%{`kgz!G< zk#0fzSP63%$k=dB#le2z2kLU!jQQiFfa_(9*s5Ysqi}(IT{L6iI0(WMAJ#%s+ej+3y`Dr0-G>btpaKr>{u8ACTnSdlJclvBlo zgTiI@``(N#_elZMWQ=%C#kO|gC-T#8Mq#Xku0=BT|6RqzL*ZBG8?PA?#!A>|m2u!z z6)p9GpSr1L47pFjhWRqaUstj1fN+(1oi}65pCr_m$*4Hht2gs}O|$Nj8H2`3m{lfY z^1O3ss~UA(Q`h(ewgkP5iA(pQY0fzue9bUOyh+7u+~B;yjjS7;ey4`68y? zaG>Y38*R6rN6UP}&-~slV&h&17M*ls<&YPL(hR>a?-a3Nj{`f-y3zKt7Zd(s7@`i( zi`c&3f&Itb*!8>fn2>7tmHu2NV%u&9_MLR&;B{|czH9U_<7Y%Hb~~`^KW_94dvW6& z!+-H<5uUaz z^kVQd!wAjLMIs9CJ21J~jjqdH%rF^7YDO*+vEl;GopPM8j?De||28 zzTm*}W;gbAd9iAOAy~6MUBv2D4ouqb#@;htjC{=Sd*)L_w7>2^lj26@J1@q>8Ez-O z*&^y!Ixu;U8w)zTSQ}^f198m~QOR|n?h7{-eCx%*@rDr2eMH3m=Nzc)b7Nnp7pq!E z-$7kQiI_aifx!+pn)Z5e=(_$+>N8!$v}YXX`llO1I=onakKr!Ox&Cca zUhLHyLN(*3iWr&cKykMl^WHm;m4e}q-^YoV`hl?Z!~Wi!ndx!!P^`nVvjEGr}IZ*$a8!g+; zW5qfB81gn+#1@Mq;1)Ob?DJy&DSZTS=tYcq*nvUs?!%7VUhF)fznA;mEn@HgI51?B z8$BO-Q9Q2y6ZaV-Vnm_?(_VICZmkzfbcV6i`Ed~wr#i4+a^v6!UhF%ekK{hFB8DV5 zu(r^RQUCCwKGJX>{dl{GZId0Sx4N<5eJ@6gF&K&e77?ow99aLn8}mQ#qNPQDzoy_2 zF>itc>z;CB;STTpH|rZkT+hzK>P@d=$DVq$zw-k&M2s27`&>E?UCvjr|D$>g`Sp8j z96e?{?{Voo?ArV)`uEghP|XEwyKrwbc{M(Tx<`sI{=h*jY4u^-kTHh)zmbmRE1lT& zR|RX2_%Om}j3r-X=~%kniB-i4w%<8`x{JmM)MryV)>b;PV}pW?9v^o7VEi+`n~{zQ zi=EiGP6>>U`Y`y4F^)ceVjM}DOhfch@U#);%> zMmqM6bz=W|1>+ign0v`h#wk9m|JE4KePh!xzNlc(6(2@^ zXPm@1Ivoe+I?$;4SIX@;HE9N*cX_{l@qZb-gbgEsr`e?^y+dcKXnD)Hs#(m(l}HcVc;# zf*G<8g|Cd$IPZoPBOi8RQl^4++kIHlZcNk^A4|v5$xa+tte~*dhYiif>AWky6?>*R zu_Rr=m=Aq8=rPXFEdI%g^%I@gzF0w}Z2*V9FwUeuFI%xZ)`^4j6tukU!=!`8B+mcQ zibWHh*e)tqT;>amn~V<=?nkII-$UB`|)| z7nt8~oW;F|tQb1liGzHKV$%m>cdyOR|DFD}30p*O;uCZ(4{scRMk1 zmV&(x`LOL(V~VCHIs+>%6=S1G!PI3wEUh&@&O7e3V)ZB|>K;+BV3`lwcN@*jpR}T0 zaH4L8f^EV7!~Hkpy>*FmiRDthw%yaJ#NLJJDnKykP;YY`vT(~#wRsR z?N-#^;l!cI3g#^Kp{~+6hd2&fvHW%?R!>wg^0*I^-ZzSx$*orGyUmG(F$(5Q@ZrYi zjC1L)cdQuNS&aE{3dW@Qu;3lzJmP7wqAOvG?vR zXo+vagd9Jny%hZy>h^Xfil1-B;z>(ObvuhLA+`gAiE>YC6s&L8mIXe)X6 zA`|1!ZN}2cO<0@Z$C9_A(=|hsOswkNjGhTi7_-oirqbwztZT?bOZR5Xi)ljBlm3M_ z*JY5e`bexnb>=3GnR~PS`>Jnek?DG&ZHljGBJ78R%{v5 zgt;kx?0P+VG4XH7#9sGiY>a9`+bloYUyIJtRPJAljsDFT_xI+&_=9Wc@x^9y&e&{B zoK%9P8=A9kuEU7l*d_FNSoV^@yC}iXmzvSE{ThahpYSyC-Ia|=aV03OZN`FsTtnU2 z*c{D)JF-!jP=dA%&DfGT7_ck$8TJXu#>)5-3|ZZbQKi?gsw;M>X2mVpXnCLngI6|V z`?hPC&=~uyW=BvqD#j9wT;7bqTd(2Z!B`t{{hWoif)Y$y)r_8$8-a0N+;f^e2cO0u z^-WAN9ztF64a|*xa2emnFU9KQx3J-L4+{OiplxFO^W<~QQp}n47TPy?u=Ckr)V(kz zmwxcrFfP6v^B!u&y6j=>d3efl&OL6!`jB#TO>afh)5ExN+vFA0yV-_)Ka^q1vQ`{g zI*fIbC$A*_BR2G3D8q`WtyrHij2Xp~^Z4$uq0U=|Q6a6EJ7pLWeb0 z{H7H{(uT3*p((4`=YS0>ddjeOTr2i08b(j-M6B~NQl;dDjD+bRU#{O3(h_6J^*orWGqwhOv0- zl(m}rS{pV_eHSC8qnNN$S3sOu)3D^oaxCyyVCC=IF=FA!mpFG`BI@2*j;;$87&W~e zE4PeXrsW{ZO9CN>~z=VnI*qJ$UJ@rkUh8fMvfAjwV00960EY^Kk)8+oaaR|ai zD5w*`agqR!glKp|nKF`qupphqV(RozEDs7A+VAYW-(Rom{_g(X-_O&1U2}8OjH-5YCb+o;tukRimPeUW zpC@Bn9xp)I6&2Q8{SF0L9xpr9Z-~L5eFa!!RiS)=3Bw=rC};l$F;0G7fK3-vXqjfh z;Bb!$r^d&{INVTx`U@&lUH=|~r5=_1zFCa6FA7|qQ(?fJ?=XC=M-}H=#3-C4N7;&l zsF3`CrETG4IkU}JnJB1ce`73me^iL_sY93>V#ervK@H#A7mLOP zMVNT&5EjojW8*HtPN$iBVzKi3LY%sB2)l#KIR1>F)@j=w3F^)iV$=2aFf7oFrpgQywwe%)!;i>okqq8P=?H0anrgpD2EZ}9t_I2@f< zf}YQ6Q1R*@DhIq9$?HrUHeM~p`V|_CdU_Be+r4)&53j~!qJIevZPZ|R^&pC^-n*R+ zd>x0jUyE@(N`vyWK}^{1y@z~WUWH+X5}ewo!SV7z6rA=}a&G4;%nU5S9{mTXxBZB= zh12(v$MiL**}NS~x3=Se(&AcMegDCnSXZN9avMtG+p)RYf{x?9`*?3)H9D?u!?whB z%-v$aw9kB-$ZKddhTYzVekgeuQj`-%6Zwb*;0499;yjBV~eWAV~i2bj;IwP^6H zz#}PItSPo)>o>xK%uQetikDPi;x;Yj>#SJ$jj)w-&q*=gtpZgoTFg0M#mskvhsfU} z39}xkKvSjGc39815|V&yYdY}zAypY<*2`>uXhVB+&y?0VgbiethL`2DgJ9ij^C5^GVJ zZN;fh;fLJAkCRdNdIc8eXtBP|ijkiR+sNyb6qA-zpnjYa2QjaTA%=N24`D`sl@3Nxq ztgwT=4oNZSPB}&`(BeRW72W<6e#*X1DY~62$NXR|7ROuBrV{Fz`~M_i`pt4oyHAVC z=d9S}F{hJwjZ)MNl;h}3EoQB=V%jm`F`l21qUU%y4vVyCD7Rw58R2Kl%Lh_CVlKx3 zffl3IT3zcxVVBdPPo!8pR_(J6Mg6T1HKPSHRDH#4@6-JimFzwS3wA9c2g7xAQ zoZ4E2S#RplGCYF8xBb85p1P%=Exrofa&_3&F@j}%{sztoPr=sbs<5e1hqApkR89IH zXZ}~F;Q#&xV*L&swthU~^0fa~+_Rt*3@E6=?!7uRnMN?|y8l1PZ#)^(mRDg^whl87 zjG*1<-_84?6dXQVh2eENZ0s4qf&ciQa4Hd{;OM3*JaSZr`fo-seBA$E)cC8l7_6ID1|u0xw~1d|;8MyEc*$=DN7g|&AHkrb{{N=`cc-B8LKOzQpu^m; ziztr?{1*4h&|#{^$!i@r9B>Jfo)7FLk3BMs>Z``G>m8`@zl6fVz%$&tH`ig0sv0AE zIl@fB|8rPSM&@0xw#H=FYiRj!cLT}v19mKq7l~fQnAdv7JHIA zF;{MP{oWb+mtFz~BpGSS$|x4|T4}z#(-5+U*8R z@N;0RSLmqIXlVwHcQjy<&VZFeV`y6%`YUmjWuWq414dpnV6Kk?^>>B-#=M&{Q1)U2 zdVXv`+xao9k%W#pJz~s6#aj*NH*CPNX%6hV9pYe))?}cvpaBOyG+^=I80LnD{!YJ& zGSG8x1NNRbp!hBamfj4x#+=7zp!k^vOgn7AgtKE978?3rzW;m%D)%&?so#L%x5h9y zEOeat&CkHzT@5H4FksNlG3@$1U~XLlO8N|F zkU6k%G-QIgjmkjd#s(Z{HDIN24DEA5Cpm9Z1_tbGz_4}$ipR#VZA<7)@?4UEw#OT= z^`rqCPmE!+U+68TQ%`1KZp<5~f6su$SI1Cb3;BaOglAy)x(4hiHDJ`2W0<&g!4&U( znu(L=-oUgQUtw_KHLPh_aGN*-h|y( zm8ielhyh0@Fjp0Em(w6ywoAcYEL&kj!Hx-Rd@;gY5=2Uk$8`DinjJ$CYC6Wm=ZHW-@9p9&M@{AIv#!sSr#RM96N8Cf+=dv;XuDz&O zXhgT?CeU##!kfChl8rTIm1z6zBqqjBVDqaH_d2cDXQTX@5{tu(=vFX+KA90d#9fn( zU0*BF&2bWKOD9~EOi$#r#F}3`2IW`^=!f7X?>WV=pMwrtXY4Pk8}* z8}{Rn)`V?lk6_};h`~(Z3+TCNKiX?dIDX#ae&)eLjFy=%VAr$zG5qf)O#ILzgnJSa zgN^&;SbXUqX8HG{Z{>r>Zuf!wWa;*1lMMX?MWFNQ@3GoW2P6t+Cl0lC7_qL+rul?xxl-C2q9k&t{Z_Cj!bkODGSc#t_wi^KfnBJ?X%qwq^J z7Fz{T^kZ!t4y`Lj%~mz0A2nmr&w{1I^?NL4&MiXuBWf(JF{A#l;BQV<{t{Fs6yZRQ z8cm1I82N+XA-o!k12c-yCtZz-3NzY26hw1x3gWRVw#c=9T8)z*m@#ZXu#E4E;?U?_ zgl&(iaq1;ATGWE&_?X1y@*-^9sCIeEj9K3aVmSYoSPb$iLeE8NbQGG=v|k|RJ#Psf zSyF_V2h~{9V#c1Y1uN*+5(%c=Da3&FYK(fO6uV*!LWrz=$ER-`dwzUe<6q^ zzJ(Ih{ZWYH^VQh)tQn{F2_)R_o3W@86`^>w8cp?PlqVNSsUvM;b#2u_QbFIF3*jvK?f;_w{<$4GQUUyja%cOy?+7BURMX@C(Zvy zdK5`u&ciqu-oF5H!F908vVQ>Ca#sQ);=YE#dk#QjO+8fhx0r!>e&z?g_IwTNuN;8U zeec7pokBVKw@G1;djj+dRl<0^2FlL~1IfITQt0NG0D~NrP_kG9E4K@0qW@7TbnB4- zE8Uc^BT@syw+d&GrVpghepCYVn68A9Obu_PFo+B}E`>?|C}4+334^CG42JK7Ym&`JsO{WQ>GoA49TtVRl32PQyoUnPuMu7UQ4 zguxguUkc6I6i{ofghAdKnB#0U7x~*#=psyjrjwM=W1$9?tAz7NyS-AF(IWx+^ijeN zjRtBHg`bkKH>5ClU;^wED`7~e2A1p>hM?YMDJ<-p07G^jg2D4Nu>GVk6!&be6uR|F zfE`9knC+^8rt!l0coz*)=oOs+)!s^&7o>sqxxz5?+a(R_+CLcdwg|>JYhYfCFr3V+ zkix3I2~h8i1&nf4^7?6@U5xN^^gk|z>RSqEJV?pM zK^oZdTDS=3a7YU4s};~?kP=2nG_cylDiZHhDTQTM6)@>V5p12NfjOzdD9k%S3bi*C z(BDc4?LN{#S*q|0)XSH`_;(5zJU|Jp#TuCOy>KzU+b4w)7Zi)T&KK5OXrN+-a0%*E zNul>I3dq?hVe4%TEQuFJ<9_dz!n7&{tkf03cykSGm?r!Z>+UOqm0pQ3Z+|h2zSs!c z?^!R!yeG(Dc4#8hZZGEJ%0`%PVzZ1)HI~87QHjtjvKabQG(yL#)-iB`47vp;^6|oA z*s{G5THmu?j`#U)It&?+2-7l(VP|oKC!-P8pSF(0dwMk;COITR$4`o(e|jTqD6w9J{DbMx%RUiyCKtot(ne@k zXZ;l^Z=Mcat|!Cb`Vu~WQwx1OZR5y{eF3ok$7Gl~;0TN|)yAU zkwe9s6d2^C;`2LnP;ySR0qg4#2XC>yGR z)@?fIQYuQrx}VFTsfdHdfhuSgqJtJ2MVqkC?Q*Cb$ie7P70j5cgI;>Obl56~lZJ3G z)kXzN*Xp4BsOWp_|7khYD>&F{rh=KXbuc7Zl!0-6mc!Df6sYf`;`6CG$n6(x#y%gA z!|Z+>EE}hSf6UN9P9fStc3zT0`@d44TR#>2L#BfsoM_Z9Un<&xb$&00r9C*}g2oed(0hq!C+^QiIjj|M zu+&WjV7dsSqHM$$ z^<{ zD%y>A@PiyCok)Q(+M_VXLI-2#igL)T@IV;Ulmes8RM4!y4wio++Jo_O<*-AOvZw2w z!jOqN-lulC$nTcJ|NmpL`kk1JZZe-r=0*31+6jGO=WR3S9nQDcZ?J%OG(wnhsUIxQ z;p4s)HgI^a5isEzujA)#@QIR-`&0~vEp@I2{Y}~p`)}Uu4tF*4{fCX?`xljrggY%= z4eEBg&VLwu+2I6VIP>wT9A|@Zj|B71wc*F{$>+zNe}d1?@f!@QcG<#@Wdq@eUc45o z2f+3V4QEKTz6SeQt!YABqVIsyTCL8$?{jC~#kVZs=s?~qOIx^Tj5T!WH4v`-%G%(2 z|JI(c_G$mKUFUMPYd&4y^@bA!gQ4urP?&y+k3$~Xb$#au#{@dTvdhC@V%~5Avn*X< z&UbwKF}({MC>jDc40P^V7vF9%pmFE>;O+5IwDhp~ex z%(VO$`(RCie-=52r$i+keS)U!Gfdjm$Cn7E zzTY0?_oQo{)#CTpQ={S6%eh|?^XFm0pKI$2#36ofpjxkmrVe^>*FH_{`VMuv?`3y= zCgNE4N8z_04_h<7t^Zq_}*X@2E-Fbn7 zzWZGG^NjwlYaXu*&ab;38y_}knhegdd%YH`|2C*sqSv13+E0V^MY!KJ$k%F~8^r9q z4CcYkxl3-hdd)rcHYtYZw!LI9l4(*EF4Bpk0d^dx9x07#< zgzWbYUVOp3eX3!5cfLEedol|CwcP^-t>O*1IvT!9aEHrE`MgKj7?KNI@Ce7Vz_^bmFa;_dMg=`Tp()_}>N9h!OmK_vd53 zLBkE|TJ?1@ko~S3{O-uk@V>rnZ=ifHey`NgTbFdbw|>ZXzkBw3PqFj7lq`x{t~RbA zgZd4RBs25ILc#BUEFvXlLq8`u`y=zn)Ou+eX(7(aBNyvu6_Bp!nFmSlWg`p82OmE; zdzNl*-MHVG+@LzaWu`=2Y<`{GF{ktcLO#cV<&vfzi5a81J^z#B&sX>hrRY zblUDj^W`>Qk2*)P?Wkf(KA5-rCNodCe(s;l2s5Km_h}u`S;dXapmF)>+Nt#aPnENd z8Ef^_<{`6sg{M^uGqbQ_=p$ysNbP0PapfrA$4vEgcNHlKyEgm@^&c;`BHN92U8H<$ z=bH@bA2ev+OR87m>hbIWeSatThi3YI&UGUiUy^nwy`JWi9#VOS;%~1lt0p5p-Ep4s zj}y%gkg~rfD`~&=>MgYI63r{=O)~Y_E!r=E;$}qy?N`;|#Sh3SXA2)w{)70|znMX6 zzu)qlS(s$%{*pP#C-um`%=T?pZC*30!+M5wQvK#-TmPfF&#!$hP_t{K86DPx8D7{q z!-yHR;>_5dO#R1yydt&dTYoiX%6#s6_G0F{FW*MC99nmk%z56TBbCp7Y$c6X+;1bx zm75-r)ho@m8yW->v#HGva5GU34gZiLf42&;5Xb{^^SHjBIy)k}m z`dh@31p^REX7z*$Egz>&v4tf|E%^CLJYk-R7*+?*g2rkE{9|wg47wNzYa+v7=})U+ z_O+QX+>SCPKVJ9#yjvQLp)Bn=)|2tYYnXk- z9QoG%BMs^ZGOeJ;H9J_g%Nyno41h72|AW>adpT*TLR{2HbOM!~H7 zW&AoFcw3D4{*}*?pgwvPKi@6!2KBXCDa_otke|=+dHnY;W)e)j=>ON9#l8Q^6OYLhaazGfO*QdMpru&ofvW%>{^Lo7r z?cY+*3{%P6(|UGGf2N(-SvP?8IpxeD3mUJ~ zVTC1g``Z`ZLfVH-J@sVqbK?ptrs@8lHd!;D7q1DjVP1GUeZ)YT-@eI4w$#2kqM2+h zcvodd`;uCHPDK0tv-@v@sQ>HU`v)`AGf(cZXFfH4vvmlaufRLqfq6%y*)^28_tJl} z9hsrOcGQrU^Eb|OVy>%RQ%mlPTRY#GxpL&gX3{U-G-epx=Y@yc$>l|%D_xi$SKoL{ z{xxN3%y3$lWB4=jX4;RdN6EXtFyQggvd8@v!71^c?<8YP zhB=I3emC|}0h61#^KX$Ciw8fy9zo7`Us=H920YpPlx$lVI({t6CpZmROWH56xJ3Hi zcCz|_wI4lpCY%h+J-VM%9Pw%=`=)H1GLCuLX4ALisWmn?n1V5C@gQ#&*E|{c1$o5! z(qX3H?#>@xQ9RRhi2ryNKd$o4Ae($m?vP^N--b+JPFWebgj{KH=m@!c(up@ruJ~z) zY$CI+^3qPG;E}YgiQ*-a(_<$wXAIFMli$tQa)l|V_q=2?nZ-Tiq6ns7&Tq1V6fZrQ z+d*;i;}G8u=^TC$f6L^2+uE;FZ2T@vG=;^r3;Hc)3Ty_yI7;#LXE**MuYTA(!-v^_ zPwp<#@ApZ~Ou;|dGEZNoN^0OK~|DCBGmm1ky!t%@Cc8p{SG6EjUnQG@>vSTUUT6tv$wYycj{zkFc zVVAqqUUSXs4dpe~^Xxxj`7IB}iJ1~-@AV6r>RQvv6pF(qC;rUjOoQK5P`{y`*R+(c z`1yG6k7@t!G`KR=_d`!jrrn#nmPnCTBcxPAA0= z6uk!dvG()FOC~VYF&`QQGX=BnZCpu4CimP#`L6;bxlGPw*Sn(>Ul#89oxT%0O}S0^ z97cfm+oCikfA`Y@&>&|>u{rh0G2vvFjRHqw{+ z$vbEJQ@=FxfdQ0ffB(!OuNJ-vq3>RO;kAeyb8qICl+TmzTTad#<{3x%&J`yU$k{XE zlBwQ_f}#x+pV_cCot#n-no0fTU%uT%_OSS759LSI+3%xxgw5sxinpGRP*QwNf95E8 zJZ$@MQg+w*6y{rGbe8J(d@`wm;#o~`=jpqLv!9Xb!n9k={{sL3|Nm6kdst1|*9Y)j zNl7Xd(!DskD2jBU*cGYVia1f|DCtzX>2!+9R;iFAw@`$T3Q0)9Rv{H7NeGn?B}Ir6 zz4JTP^Lw7Rzdp|xYtFgWnrrU0YD^x#xOZ~dY$1<-?{1fnDJ%-oyusv6n^0biczKEI zW!R=a`U2YhwP;2jjt5y^KE)L9cJv>C`KEXFBR{5L=PtyX45H!@o6GxbMF0NyZ2{;% zH+RJv9Dl1WzYO`$yZ727FaG1{bj0@8Pa7b1DE3x|ieb(&80YSmKL>1?+S5LEGX)w& zl`Tx+m48RnG5Ptyziz=@+Xv3W-(6}MaD>UxZD>Ef*5e<<=c4^RU`59*NA&ObDLxJH z2$Xm@`3q~TEfSjkr#rlUm1D|kPrri#f6T)V9ZDh^$ng?#vfE{L?k)1hkBe4`K3t>wcIG%g6O7L#dHL-7}e%MuKvt zVA<-G2jQ`+3j>jF>X|SXT1T6zL)QxTuU1UmBG>ycZu7`Y_;l~YP^Q3H#(OT*{^6*E ze5iL$JyS?v~IVn8Ey~MdA^B7#fztXg$%Wc{=8&MlYW!n3B9(fcROf@*=q5tEUR`Hkt?8Em)jX+)%(2 zG(SoYN8FKo+Xhyi?2&*4M{n1eV|^t>r@@v2DL1G*zf6+(F$K~&BkT~TF26ot z!c^OEP>JO$_ zUuoxf+)vaVZ}?e4?A18t=8-1LU~g&0BW>ok{gw;itvsh{EoQ@A+qv*fn!z1SW|mpg zT)0>|B~1gr2an23b*7_MO0F6+^pJS5D)Z;+bGKEPnFH!g%FH{bdF^AF@y$h@O3e1j zy^`>phl!=IEPx{_;5gYu~t$$oqO{$l-op zIflvNJ#86xVFcn9&6eSahkD6MVg34!be3dx-VaP0ig63*1OaV;NSeTrH>k{OKEx>j1>&j|N5ifndpakO$D-&FTn|@@RgEQNoro-+X*VjSa?uE&? z@1e&^j>20e(x+k2YKe1DkFQvWd1^d#wghqSOQmwerUU0InEXjQS64$B2g3)*|H}AS z!_3q%=&5CDh9nj}#Pd3`T)qzZG{;#a`=KH)j328EH8;=qLwljWdII_je?Rz!@q|9S zz$%<~PVv#Zh~+<9m*G73mMpu5eBIRRd9dPrK{$*WS9}`xHOoQ@_b)6|mcNbp=sg}* zgE&-c8Rk)QlaEFt+TFc2?ggHMa=dH{Gv$s?#%s*u#_j2Eq2;`k_fX@=$xfzGs#WPH zX7t@MgJ>~lq zs$zWwt(%aB^``kFcFPBtFm+Zt(`jx<1lFZsc)^=CX6@m!OIWYMnx2QPFyeI<)^YQ< zuzAghcMk2w`sSDKwWs$_;{kuHd(APP9(b>KSYJ6%NAHVummc7HorowntJDAPlj znv3s*x$jm7d^b|8yGkYSov53pFbv<3G3i?PzVLF#ora0uRf}Mgs}pJOvEdx7pSFTD zxj%!8%@30FY|T4ZS2WYS!09GUfo&*e|gAQR1|kp4cEG_I=2 zHB#`tkkqujOO{06B8x)4araSGNA?-NCHJmxCVLegkXaqu$ndjqBwvS9Y4i#1cvBSF z6uf=VJT?pVlWhHy!t|$PqhmWM*W62HKKeph%64(rVZzO0)4$T({WlIHU7ss*_vbg9 z?0lg?X7jlD;suN*_XctECHPN-Oj*qJ&$s8Em#SGmcb$_*4th@W_pcyluk_=_i3uR9 zB?HOG*IeGDBZ*9M*i34=?dP7K!eO$#ejh3Q#Ftc>6hijdg_1!@US!+p;6eTCm*kS^ z_jAZX|Ffi}(go7TM=YP#&16L~y`v_-|-)Joxe9xJp1oJu3f`=vQsLGZ140U zBSo&0PGwifEU{G5eAF2-DCZLC(o#d(Z?7QTm2YzDRSi0B@aiWwzQ`9+iQh*K$rrgm z>*4BmiX~tCL2-Vd4yn3Ij!a3^Bjfm!$fO80vfFALSvz+uDQpoZtIbD{*+!RX+_cK$ zWFq^J(foy9;7s7|Gtr@loL`tr$_=R)bRW7WD!F-!{zdN1r^saBAhhQ z4;>sE zrkj+W*hFT{8zAGnL@v^JY0tQMsC>!Yw`>h56o1N%_je07KdUZr*JpTv3~GKn=)C{S zcbX~CxY8OU$qMUXr1{Fxq)<|s?DjGvB^B&Q-3~66n?H@yN{`gMbAsm2vZW^Ac%f!RfWHj%?>QaM!EzcJ(eBYHj-tSD-ra5rqG%O@lZ_FptXRRj{BT`BKw<%<}RT_7mz;v?d^KMeom^;6L z&N1$MYfq8Q8kb4SbRp^U>^Aot-152hre_EFzj1{V{K&oEgSqjREGM%zWsrh(n@A^R zUouT=DQPs-pR{k;$jzf0r^_^JZagt7vfPQg-`dk$KgF#pNt1b^oGWCwb~8n|dCB-P zXdSs|UZgnb6sP5ueD3+{pW)WMS~j=NyTZBkQs+kw>EqU~;`(GR-|{cFUR%w%@0yk> z#j45Yxc8Chp=?-KoX-6|U6zoNBg)B=x+&c6SUQ=^3-sXL7dvf8fz<@=z0+Yb=)Kh@ zV!-*8YtOrBH|Th$mHVLgk(~Be?mh9N{=)ws&pw;W>)wCMz27UJlRileq{*mOvOnV^ z_a4`JO}g~IB6+*A>Aw9BbM0K_O|OK#D{5z;uF`oWtQ2~EZ~IFc^PxYMhq}vnz4x~u zKbRLKgZ1R2F%NZ_B7TfK>NKmo8^d9p>hgQ=vt^MA>Nt(>CH6se)lNgycZyWcXF|;b z=B?1OXvRd;f7%=Tw!=twm7h>PZlVY3L!bZpRse&Nr~ic6IkiTpA8p@I?+oLP$@sxS zt$`#MP^Mc1jlAc*rP%YL0_slMiyzH|jW#KsFhx%z2Kwav%7EF**NZ7X(y0ZONVLnK zZuM=qn=Oof@je+IpYXE@7XGQBf%=w|-5+yc(`u_|7~OwzD^wB{#KIEy@&wqR6dFVA zzgI>=*W9ou=oDy2wgx+s_NIT5#ZMf_G+%ErNnte^Q{_pndc2&>`{_<5Yx|J_juE6? zelY1chigAYa}y~Qzkw{!*+Ql#Mh~(;I+(6+=%rU1;qe2`6fcw7LdvCzlTsT4Nz+q0 zq`ba4c_hMuTHp1??q!T@uLYcLk)PIykwdKH--yN;eu^~_zj=sDaT zSTGj9qpj-3sBb=KJ8Xq|=XB+S6{vr1{Mr+QdZ?4dgdM1l9`P91hkEJvbJmMcKiy%{ z(*R$+%3O>3>aL$1zu=}5%Q8`aox1gbE$Xrdk}cjrwUDWCsM|`ah3cW6+YxZ26231C z@SDIK{wZW6>c5NfmRy3iX8$cgeb}noxEp$iX~&^{?4lN;pwB#CaQPU_S)*@=y7RQC zup+qszN#bY(Wd|QK7s4>mV2XK?YFk{JDinU9fx}MK=^ri)VULyq>sYt)mjRugRc}; zxuPzv{_O4%c-?to8}bT04SJ}bFS4o&LOnfl*r+1J&Nqh-AXe!bHy3sIIf6&KP=_zD zvuZ?qblF1<)awsve(**;e}n9>^Kjb1o^Qx!Pf41EdjB2YFA1pso9Kx@L@Z}{V=VRw zY*jnfK;L6tIoLmV9~u4`u~ehXbnGuIkd=zTe#5Sy71fA$e~cW1eTn+IrZv!U_<^%< zr%p^CbXIJ)#lFUe{L-CJKUnPvG~c>U-2%_^XTCR6a9G*r9O9^IiC%ciV%&7>uS}D2 zh=C)1N8iIfi<9qUdFzs@r2o~MTJ_S`J?>%D*zaCPTr2REtqjA_jJG9$+Cicw?@1MoK8t+;1nPB9< z{HouM*h5n?3&-=yEw3RzAz@J+wOe-a0~F105W)VQ$l4{N;g{1p4Y0qrJ}JWno{ata zC-TRKJ_^9T;3~s^6Je&(a_l1to>pDHhU52JRy;yH;iX6?;)~}khuUy?Eohqk%M$yP z0lt~b5$}#@+kpMc+j(PlAwDq1<1}nLy#5CAYht%PL3~~`@)Ml%P)q{*wX^OtsbD{~ zwJq8ZK3Z#Rh5gpqihJfEwlt`BMY|mV*S%on$(}&uc7uz$-N zvJh|A@GQVMX0H-&U>`R(Z+!*)mU;*K!Gf9$kLNfZY1=~k#OX&{-y&X_<s2pM zoTu`s744rj&wdF-qqLtOpXj;r0s6%&oi9UteaH7Jh>J(~=AysZjxk4(AAQ_56|T@5 z5)a>el#IYQBTc-0(N3!>W;ycyd$!x5|JJilr@;681~ueQXpF!-@xA`Z#k}zojNfA( zdGF_Z6k;B?k8L>v7xWaRV!!x-@0LwC{-o)lCt{~Ddh?;7mWB!XJB=MsM*P}XObq>& z)fRrh^Yx#x9?x5N$hG-8p1W*q)ER5x{{a91|Nku6cRbbK9|!PDlqiu@h_0DrWfy%B zWmGbfm8?j%%*wb)QW{3c7K);&WE8hVMTv&Jvy&7J8U4=d_WSGkc%O4V*X{E;pZ9sc zZxk)tz5a>XbPByWuOot}wd>M#AH;1ILiR+;uUpL~MB4ADXF3?qFH~28$)5S*m_Mc= z!-x4U5qVBre||;rBFvxSik;CS@u}bRNg_=v>*X+!F4$|(MWo2(RW~8NsePpe@%ZMr z66i%A&d0dy^^_~nR&LK3e9lVQfdItP5-Ltuw<6VcFFyCH>DX3`zv`6~N9^n|!io8a zn@wLeNxYXyzLH3J^nm{y;$J?m%;DN07GaFLr}cmNkHnmuKP!op?b;iYpnzUc05s6g zv%>s#%M05e>+W75`1G9F{5CQ#>hiM<{y3~z0=06MUMAAiqcePA4Bc`s#<_jiWDpyP zU15hooX#T}`2O?DYl)QR7dp9+$<6H~Eb6~t4}V!)(u9wU7vSD(biHajJHbgE=AnByklr9QTCE@HIa6F^W`i!&m|B7 zRW4Oq!X3Jsm7&;iK5l5p%KK#tF+3vX6%4o;l24>upQwvMJh~*n8S)wz=)kaRQ^GKQ zplm^ntlRdXqzztcZF&HGii6{bG!KgrZ^ZS62}X!>kMhVM-mP5Bj=2A#>Yys|4)x7r z$WmPvPo((CSlc7M>@p>WctR_qUxmb3&xbQ1XXa8{XpnYO06w7?wJH-MjJp$H^v)n- z_-madJ4{$DTdhPiDLZ={zWuHt504lt4J#54milE7Dev9%_aTn?^@$xZSKzs)3M7`_ z;2H!M4WE}LQrIjD`!^GZ3v!d8YTv;0xC(9D;UxY7(Tn7e^$q+BO>wJ+WQu=QngduPBUvI+S6KGO~YuT9dq=*?U zt-Mg*ec8EgSbU?|4fCJzn$HchX>`o=F0p;)86A8h0-m4!ZG)dM_4>apQiXlhGW zha=OEJ62*}U6%KQMK$>p7}Z;Po*VIV4FUL}#Nh!K-jk#OWBB-ne$5KZ-??4KiO*kY zShbuez24x)GUD9V=yM!INuvo1c6@%d)B2^@XVto&mi*iI4;K?%pY%kt634YNj$dNxpd#8hE zeiLKI{Ih=&X(yaBr-`Kx`tE)wvdv@@8&(yI^sK%E#(n zV*GGo3f5(}+6Ce|s`Aoqd=Aa`{2_cURlVRj{tnIjF?T=FN9>@`AjbWZbw`NC>sN&0 zd&;i~@4)w_uCLhj4eM=!6sPd{j?35lz$53uyQRubNi?GK+?;r+St#6tk@)yS{;4mfcmJqhohNd6rQyqEXO z+=TGn-j~o4vG_k7$|2a8A9B#}@44$B8Yme}^^ z(8eZsHS&+|f`kX;{*zKC@^4-mc`AgRmI9-0>#`w_r~@u`=J&+8 zko)56Jdrk+*RDs-4ce-$cj9nVdj=S^dBIn;JAUW{`pZ?m-- zJ9LOnmp~olEKur)x@fJiMkV4sEj&w6Uzs|1n8R;U?x@FT@49=x!p^W6 z4b*J`Tg0Q`2^WJ#=$Kx`i+V84tBp}7zMGj$N8RYQIk*$C)O_R`)SJ34vc{-47m2e* z!5ZJ*GRQ8we;o7o)A+bizji$7+=O~JzCK(Rb*z!YwF9VcGj#a;8FeoIk8@b}w`k@n z=2Oz!%Mf2kyuzrbg$49SF@8Me3=`^bqu`}$QKw%F@RfsUf;aS0uS->zI$*xYIPV1N zcJp0ZFTMDQ{g1?TK0> z&7C09YE*6{Ax^aSy^s06E6#7Q{#VVl5zGs9C@|}g`LX(U{5q(!&QX+gkjLh__9AwF zu+A0n#cd}-u&(^^mWvpl$&koGtRT4c4v{|V6I;nxS6})D@y_A7PUzeFaSY>54`+Vh zIzClpiY^(iq#a}@(oz%F@E~sBdCN!CDjgIRMtsewVFO~`f*NTeWiM-|9M+f9k~d?V z9$%<{n6o?*F`Z?OUk2;WSy(Zy^U>P19)1bExeDXYlZ2LFeXFj^Z+vedg~4Hbuj#WI zE%=`H{g<92-kZR85A#OJHR<@i>Sx)`V0>XmqYu_;UNf}D__cDH4%W%A=50d!alOMT ztW)qGpTqsGPE#JjeNJ~d*?>4s=lMg#v86B4ao;Z%#+}0RDAty6$GA;^pef?g09AFY zw+NCJLo6m4whZxn+ohk_Cx#=keb^Tv9G_n!u5I%#$G$kMEm??tG5R4f4Y6QtUJT|( zkEw>i2PzkQ8T;n#G8e?&O|Pu6jw;4sjPc7ki8~Mv&}`K)&zY_$4+Xuyi()*zBXSMm zn_4pLSTFc$a2EU9aKp+8?E64^Ko8>Z4xUEn{oSS#??IJVVj<$ZzRQV-`&hZd;qqLn z8{RJ!ArCV+zVhQ1e2)5ToiOIfanFwHTyoe3@qTJVek+D1zdcUkJzbgMY=rn~OV&EL zX6JE6|0tmA{uJ-Mzm6IDM;eEiq#KkjG1vkfos|~DJAtd-BX8_U^UZ`?4ip|if7n+X zpoG{v)bcO#4X@&}dU*7AUNZ909j$5fgEaTzdr}(z_S+Ql*4dEca^$h#QHfB*uA}V# zA+`}NT0kEB;BdNv(ZAhQ3x*lrLN~*8!4F4}FS!Jnv*3veaTDaxjmhG@R!hzyuZN13KSIA1t$WoI_J+|#F|Ibf zx&!Az+|u6}I2X$J+m66~%Qc!9SCdi|gwq`@Owh|^`V-C@MLKH@&Kai@GI=n$RxT3b zfiulcP|v$m2jkr5Pl-aso~Mi8m9B(OIJain6{~TMz1ypni+E3KSOntd_3s@J=WaWw z1rZA%nvDra%ldvz#l$c8z&Dx^}ZWLy)(v|bsYu_2|2>}gtG!rS##kX>Lc}MN6td` zO+V$J;QrDlsH1M5ytNg6p7ptlI!nB+TLeaUrzT0z8TBAL9E!ggih3>SPW>e6xPf+K z2be`U*MxfSL+a2DC@?uwhI;TQ&qF1+A-Ap+bz`P(q#m^6INpN#a;)yK1Dtrf<2~xo zNIijJ)TIZL`&K|LnZ=r@S8s*XWVF7*+q!6^IX^Fu1qa3w5oq_R`l$0`jf5%pb2K+l`7v8j>FC1t+-i!OSWy#*be|@qZ z?gQ5=A>ps+FO`og<32Si#Bkxh{eC*L3VpPtXocx4QLSD&0{!;*{LT*a-&%d+fp{K~ zhnRTKKhh+g)#7>ijL3wcf26X-3gfv>PG(l)IT!4z^~H0yzyFPj{XmvLpzCcjd0LjMG*DI{hixfVW^;5G0be>WkP)t_b`g_JF@!fjw^7& z(xV6CZc=<4mQ0oE zsH?iy-9C*vOQN@>5%HJEAp6RWd#KauH!{s5=DPD)5A_|#h9mK)?;Z>G zbwcfwof}XO4pE-^pl-CVJyQ-T=MS@>uI$nt-wiET-4aoE1}uDON6g%Ob2;kMht+l) zQNNzaE!09RlO$q+`qi3U-y7qhw@ac?*VcHm=fWe(VvM@jkHfYFar^UE->}YeU;YZz z*?MX+(x|idDNqbi=ie`LJA^nbe=801e0&4xFizYLbw9n^`@u)Xc;A;VSpQ_sh!y<= zuW^9@`izx^b_(bpt~U)BV*E?;-b1k0-a8Biw)3Z8-NT$W#fY8WyhOi3-(|)!hU-?J zwq-$Iv(NVv74~@esWbXJt15H!KYL_syfH32z#R>LF&AfJ{@inxGR)6p#x)9ep3=vnmhzHd+OnnG*UrJw9J;jC&50??E5;d{oQ|AO2)aotR*N<7x9)H}z)X(fA%Q_eoP zZ~^m*yO^VJ-M-#Kp)gxvApqBlGkNJLCMz;p`t>zd4M#{G=g za{K_KyvQ_w>@uH~aR10LD};3cOma&QUrU#p!1LPV%-0Otl}f7c+`RUb-+-e{`x5Yc z>6Sfs-q@e$Hz|4iKP@o+Z5h8V;sEtodBhI{LaF$iZ%zGNjQ!GhmxB3>h`CAZH)fsv zpRmugm-l=?e4|_szfaJ&?lY@|DUD)fm|wH(b}>BTW_TOpHj8X-z~jFavd}-CKea0k z`?mP9^eMzKbAS9WukTv#r2X%A7SsRtrJDF0W0M~;(EoV1Afuo4I>m+SL&RfQFkY|! z^_C-|#hX@ID?_ zbUTW8dPb7*|C>Te75iXR;i8>zig{cW*MIwBi}#);RP~4t>lF%v*btvNZT%VfVXH=D z4OC|H%R=5@zM>EUDJoQJj7PWpP(`dHnaYDWpQ`y4d1!&H`X%xY9}{m5JW#kT1pW2q*)*98&QB?gBdgmAYUq_EBI;ryMKET$8^5mh?u+2js@}Sq@r%*UGI$WM{wJRk~rkw zGrMOzpjVc;A)L6SFNyg>{#uI>U-)mR2YLKf#j)G)$eQ>5$mgZ8dP<1dC%Y!L{ChtO z;bopLE|6L>y$^>I6uk{+s5ELsg--Y9WndiM}Khci0|LYIDZ1RhYB&C;aDIMxR>D8V%Q1aG-ys*#u2Z<2){Ajl2%uym)AfzEokLbtU4U z^qdzs&(-tccNT z@}F!X=FD8%01dCY$803ZBpPr*fwS8$N)ew+gnpMK`W-8_g1q6cYBvx)jq^3&)g7j} z68LxgYS!`W*w zUgh2>LNq?X%LP3HwGD*vd<gV% z8m>1>{?3d0SDx~QZYK;@LfVR1WgcP#S15HQk-jI!U7bk_NAw9)AUrx^F z^5C5%(tDhFrin7o*`+6l8dow@e-TFqzlRMI#jAfOd?V(StZeKgQY(#Gn{ZvE&PWZB z;_E+^0wuio%61adwIeA}WQ17! zfpT{g*Etw6ei1X|nybf%5%!k3<3!#bH`586S7wj_dHFw$LUH@350EP=?+ml-YA;xXU!)e@ek~nXSXui zS@UndVPZYzqp9%1Bg|9U6|*SJZv8xQ)+4uAJ$h?ejXDB+<$jj&>56IL1c?hZew*1HwOqn_#=v8*F8+IRBvm5zD z?2bteG%!0QhEuTNGabvzepX| zDTfmw9w9f$fZpS4Id>3Chd&!a zh5shPpw972ABmLhZz_Z|iINHwTWB=*Ee*D|-5w#*yWR(?X^~i^Q~oj(4)v*qr#|xW zYLnx)Cr=!L2Nq2y5h?X?1%rrpm}si(Bpx*n@gY*W3irN5+%bKIlggk_C!e**!h|eu zV1y_|#>k;Yiori6p zWXUOSBGvv-RU|BzZhC<80-uaNMLbh!{|0e_CHGe%V|GLGPsCI8+HAVydQ%sUHAL!C zWj1*tg^SHzm&mYMY-Nq(@76{6!1#gjM2xqeDJVz$&zlEbi1+;~%ce)J@0iUKhY?rP zHT95hF1U&#lU5?VO8Dgjtb5kFOrM_}>xHukgoDmmZww$C)sIxQlE55DXmjhV*ukX4d#z zI37nT{IBJahNcsHSf$_pGhomw7;IjiC z#$VSQp2d3nZ>7OEtUI57pEe*4N^X1s+ug-7u}-)5%tgUDbAc-u*STEl1O?3a58}FP zk7QlMe&SSltmA3Xm;8vIeXX5DKCruZumbtPXSwBnh~F^_EfBv^<5&;9{2lv{SIE40 z1m8XK_JYA;cDm3_MPL=Y+`pzv3-3!MC>#3J=bwc(Oy6zDS5tBMf056a#ocAdZ+kB+ z@XnQd`<(A-vjpsKo7wElV7l0+r7+VVumby|ZuF~5us6X~8P>_F z{J=iSwZ0<_R$12DV80dIA}ENs$U&|S`><+K`*rNgrAr315myJ?9!EcRDJ|9!@^wzM zV_y&MVeExR|LRp@-+%i=dK)~DYn6?Nb~e5vw63@(Qazn^`y;g?euyFybZZz>E~yBqadmMqkh zg8o5+s4vZf+T`J#7b;GuJDVOYW%XqS<{1ibgCXx-)TxTAT3G!Ur_SyW)UV4`@A1QW zt)Y0-wJr;9WZ`>eVFjz+O)fdi>c@_n&!G-h_N+{R-Mv?~!i>z557CDWSESCMZdQHq zN&~uUUvNP`W^-f7P1M!RIvXFMAN%8Kl81WR$6dP+^>?#PS1S54+IztW)a9Lds_vZl z-p@5fIf(3!U8+&XXZPB9p+5^yi`j_!zQ&~I?gIJ;wZh>)#Eh)iJmwZRm5n=;=M^e^j;vq5okF-V*(RSn6>q`Xtj1=j-U7I;D5(ps&gkyvH_0 zoY9huoW}7*itRH{&%En5(b3DVVHSPf@5ZBZL|SWE5Ug>ahrmO9-n*cTYt{(Pizrxo z84hU0e8lw;Xa8=3GFy~&a9?*L6Cr$#cy!f^NqlduqK)_-w7WE8d@l{*uv7S+)Q#e4 z!|3ZmO#JXWl9)e#;CE3XlI^}CJ~_J)zniYlFH-`qWo~|q=aOs1UXOm(B}xo^8>QfU zU@y`1VXnduk*iduWR%!ES~@t6^Gve&@jmk89Q5&iG**}eqF<}2aM4A-c2w2=Io@Z) zE)E5}=Nfr$R=-w|S<;X9|B3Rz7W3l#@|t$c6Rv>76PQ1aCo6wqJ{8x=p2IvF)ehst zJiI>aZ-jZ-yqQfB^Hw=$-(t+?6s=omuD zo-iDtV11_?a(f0#nhUOC{lBX7l}0{LaViUj^+oYN;IE>Fy~rCf$Lq78EhB0f@=B*c z(pk9WrEdePZ(CKimDQgKJh%fl2r987KRHc5bcb?Z9uLCQP)RrBF$+c6UyzTo?i})4 z*;UnX*pU)_0r`*gBY&VyG22z-$M6NVrO2C|Q|ysY@6Ss?_sbcj z!&60a^2o;x4}3G>-naQ8$k#jEW&)vtnBgGYVw9$fyq@=JaTMHZe&#C-QW_LP{x3ND z>ImFw%pDD9k3V_`(+?+cV88I@bCrZCHq}(@Bi_41tzrM~kC&ijLvSpP4^@}uBQ{sl zsb^g``3rp@oqg+mZtP3dj-vm-m39rgVRv|n16=nmG7!F>y_pL=%9`s~`&v!xDBO9L z!iT=_-40_VNcIae?0+FCOFZC7mw_mZH)RABApTSk(ujC##{3i%Snv|U{(AJ=`E76} z-TW|YWr)(Szj7{*x&@cEniQ%0|9dv#_}CBYah3nqSA1ljre8AYQ^bC~`t5CFs9!nl zhVl7(FC$?1nufWJ=j7u-=-oVY4d1S3D`{>J$AkA|p2C^B|F0nj@j{x#~7pz=*Ts9S6nE?B~e*3XHM zM*Y$YZ(UfBN8K}EpLqdpm@Rw(O={jRL7jA6?$iPJEvMuz>L>G#--C$14)ds@-ZHz_ zdj%R_JYS2tYwl3R8q{Y4tyfP%r`1t;n*XnRD5&dRj_=;RDVbP`ar<8R_wclIHVKtsP&p;3Gb<3&ZIPjH@=?TtFbiF(4r zh&>;iWJllDmRPtJ{hGSRS4HUdB8}Cr)+Hq$M!)xF?_X#1Z>Jj4uCV$^np6aoS$6y$ z&Kp*We1z*Z=N^5A^AArxt7P@FrLnb$8=Uh$AbzL$>=RK@Q^7)>Zde{dcrU zEc{$P6oPSo`DIrThX{Fk!X7i()A+o6YN-`sjt7qWa3AiKTc|kS<(!=|G_T0mfb*)A zqWD<-waohkJlFhK*C9N|*ROIKplJF)5uRt;Znsz*C;i|Bs3&S^iQ{T{78-ajj7X{| z&O0r#ngg<}Q2&AV&MYZz#CyKH<3<@&EaFYW`|k6K4})*M?C{2Uix`hjvF1g#x&>la zin=c1hv&VNSbeRnnFPiuVOso%@Ao)yV!nu!kIrJg<}Xzo!F)Y4lG}~gCa0wlu_NUS z6Z7}t>xB}`|I#PR@}Tg4eE53|<7nqtJmT%)!QqG%8$z%iC@Sri=P}Ns(`XO-zaBEj z@%PgQ^jPaf+fxbS$77a>LZh!SOYk`-K2MEeo&LQj(t>r!dpNZM>+tPy3G}ISxqE%# zi0wv>c;a}Wv+gm(R~EkQ#_>Jh*_Cm9j8xrPC~F$B7~_4HT0bE_oZ$J9fPOS7yo7=QV=2f>j)UCSAZH_|GsgE1 zJDMWSm0XFxv(cBH4i!ecdP)5P^4(7hxqjrk%bFAKV7A+20mhZ;3lk8#1~dJjL(_go z_~^$EV;sMgr>+indN_+fkJ(FqkxwQ4+q#fn6S~h*r-ib2yx)W z@M-kLQG@l3P|Tpc5PArNL}Pzg+E#J~jtxHEhjAw*8fzaBn5*SRytV5X`e=&%jt(Z= zW?PvGXN1>W#lCaXUi1XCigwe(_=NM2B;r+jjw|FqD9oesY?Vf=_p92eq)To3!Oe?};% zSHS<8rSHHUnOnTz?=8IM*jI-_0+bOe8qD${mgq4X!G1gzEBFrkw5|kO7W{JLcmT$& zuQwitKbb#vU_2pxyAa|}A9qh+zaLG>t%sSs;n~nqf8TY~3r6h}JD4)OSqrxGS*?L@ z_4&q7Z$$8!zJq(}k7q#F@b&;0`%uh|RgYNj(Lp^jQT9s|I*MA%qrTZ_W!(;Uo{=p> z{o}?zk_elGJA5(zxT4Y)M*lsg3pI`AHb9S56?S+wXQ~%*wMg@)E@KohUKGpzrAZ1*gN z_ttT^L*+g_UMSvhCKmO#+INXnP(riiI_mSk-lJ@=^2UHK>UX~RmNC}Wyo!m9*F+U^YqIu^mFUm z&nZIg6|YkG82w@-NvjmnqO{;4(w+(-2`LeJJU>Y( zl?q8p$x_xzp^$zkl905JP^5*>qJ_41zH^`R9{&2AYi90!X6~7bVFtoFQY5$x({|=& z%ot+6Mr5=&u_0^R1u>#!1h-3+c zU{9|wv2vQ#3s`M`IU5Eyu8V_*>oZJS8ZHxK8{2~^tdcSOt7*{Kw zKSVTJmee^+)Nxm2Mu~PSy?7Wi@;x%I#zWcKM@BqE;i0C-P`P^1VqRk0;@pRDV8It{ zK4Q|9s5r>K*y0-;DEh~gpXj&1A_;0bWQYq8?@n9i096bh#=w$sc3Cj^TU9tzk2SV~ z%4-h@z>fLFhj4tbipL1f8y9(O1HI09pYyoB*_Z4(+}9+(FGILrqtBv}^!|ew{t-N9 zR^&ZAZ`sIhS3JMG+}ZDVFO}9SSK>WY&M~}z_h&b%obV0p^Kvrro*O+*8aCm58*5hA z;5`ML(=Wk$jm@%4#rMpf|LzGRWPjAOy+YvqWYF~ zrhxm{`Qbk7>{C8Afp~p}lg~tq-^C|PCJ{r2>qHbWkL=T{h5SPkE>0%y(Hjj`BL0)% zp{z`NBx4>1C#D=~fl4(w)>DX=1^RN}ofCs9Q*pkSubD7DFGqVCQRi;LU1;d%wp4|f z{y@3`igxF1QpG&+edjRb{Frk@jVLduIb}N0bxdR)G@6-VrB3V)5o~~0wt4x^zcO2lNm%Igs; zrpkIkg%$N@VMMQ0yB?lXBtlD{*lPbcfXGoQD8B`B4BUoMzCLQMoaGmQ_mgAu=IiU#}xRvv2%w#JQXITFfD_&u5QlBIBTYycT}4D^@Zjo~6_8_$h_NkYRz%J%!JARAPpJGEJp9f?W-h7UUMA>B?`Ah^Hc`EBSg>@WglpYd55lXg?) z@rS~8v)Z$;{zC8-A|rXrA{#0M)?GunqgNSKF030edxqZA*oUW{#?O>qQODlvr^nrV z{S9(VhlZ$^1I2S-i3tyNN{lG=w;L~2dXOJ7hnLfOreB%HoW);QxqN)o4YLGjy^5zu z&L8Jxg4OByn3ktvR9;E8Tw;R^ZI@dlN8_DCY@5G*OZH+RGqn@zeMOjFd#*N-=tgSPX#shxr z^)6Y{<2izz?0bGWS)1BtM%!^blBd#kU)t$?GoKf!QQsV6>uX$QQ6KcGQ@t)~vG-NG zA{Xt{3!EXxVvx$D&2yyjn*;~yp;Pu$tx`6Yuy&&DY}05vhC5{y^*#sq zetXe)#T`!?FK?$Y<6r4P?W*&p^}8K5(pc1X!=Ew7^2~Z#t`Oiy zzSiBO?}Pa?o~?J$rRQgYcCgo(o45MU<2jxt?DyaexkWuP^( zK0rM)*j5G)q!~4%JW{kqWC8IMkCqXU)8D*i3ykG?lZo=kys6(2U)uA_z=XuzFT_J( zL*4!tu)Zv4qABsmD(-qBN9LPG7QDfo{0UmMSB){_GGa{%;Rf2)!~^9Hs(Y# z|KrnL5oc5#3WWRJKSsj~KMXDqxu+8XxeM{W0@CUcyD6LZqW;PJ2nh>vys>o2bRu`G zq`Engb3Ff}3(7OhMFXH$^ZH2COI@l?x4`@oFIH9W3C)3st@wifMSa5>nFy3GuJnvW zIsc0O>rocsuFlh!ah&qrBFHU2Sbh<4!IcLWP`^I% zc?Oi2*?{wyS#H{vh<0MTv~V3W{bd$m^!`(C2c!JNV6!h`*A!iM#BQx079-}p_1y@P z^|%_&H$Bv79Gtw&SRucBg6|-rv(1 zJR50zx??HgW=TOkwD(wKr2r57l;y*5#kbnO;X5X`_0+-A30e>E9cLv@y^46PL}=1N z_C1Be`{xFBqJOlmbl(V*kA*tJ_lgR(u%|iM2$K0(7464+*p9{dQZ;YzqI_2H%P#aw zzp467=!XiIpS?tUK-Ty^;;D^NIf&y$*PVewAEb|>-xlgr9YkDxqi-kLjoeDui1MhB zN@v8et@?{mzwlYyJj8dzM`xg({N@x;{wSke5Vr81=)pJ?*}Se1<7(J8q#WbSugvrY z+$86dhWe6RttgB)=OcqVP~N;&+ymuG-HFyvdRwYKj+a{!uMAb4a>dc!bD_Ww%m;j` z0uM0$$33ixhZ}4;9w>i2t7RtQZ9gUqm|(t03@*VuviA%p9`fb-dB8BMoEfN}Xk|Wt z`A5v;St*o?bxFXy)L^}JHC)_LuZHq)!_6I-&*~z2={nW%Rj(iY?-WL=(Rr_AbraUb z&zzo|B64!y#5=r4Us)%cXvfdlA|AmuqU*?ll*cYU(my<>uQDj$v{lwBk zg@<6s@eoVwC(dZCWDtj`MHXS-;oE;X82gY6Arn2sFSI_iVBaFnIHW-RjC_0SUmVUo z5Qb|$EW3yOj^Xd5K-gN(HWT~AIGeZfP|;W>3j0W*T^oC`zq~LeVm+K#SNsb5&Jq=OGZ-iJ z`7-vU=H1T~;Os*A1K77p==6M3BYw4yb%D7JRpr>{7Dl?xgD0G>Wnv%9Bll|@P6A2sn-7V-e{UngcEKj5<c>}&|G~#9C?U&p9ZUtmnh(GRD#C_6@8JnxUOP$6?qJmriJg3*WiW@u0fuo zV7OZZdCZ@e=Qbh_;#VJ?hrFe_XJrQRBkJ}QXOL&~315|qyvYtpkzzrjH~*^F$QwG3 zO&5fXzNtpYvqawu-GRJ|^Olh`xTnxm07 zGzw=LkvGhm#+mq=c<9sI>TopZ^&6B ze&;i>^Vv4}M&u2bkGfQ&TxU@s7kNU>J6<`+L+!0KKz?e+4eRbCCzrIpE8OyqM8}VpHVF>?YPkB7dgy zK(>^ZXgQHX^LIMF{a=xHYgV4}1$nrkbM>u)MB(|RzeqbW_%yVlQZ5TUs!YW*AwImS9QMS;CotZ4Sz;V|CMs5 z0eR$xHAnH?r7Qxjci=k@X7?bkT;`y84|ziJ|8Yc~kco=_j69*=#RJCZf0|{90_dO4 z-NCofUn^2idZ8b8c>DiE{~p+Fza9PFn!RD=k%^O$P?-~2^wJh#3^+h z#&}ZS|7;V+S3>^8F&J;^|Mg#kHwR?xFb?n8aa$nit~6g5JO8{4#%;^ix;rrOk#-2i zbH%PsdyH?d;WT}W`z$|a8O#Gey+^v>vaW(M%nxM0aUSzUQiFOZ=8v{}DK3~#a^5Xa zMt)G^gMJlUcJyy)hq-UnDsM1D492zoVQ>pqJY@B&}3+8)S zWzjz9y;JTW{s$rtIpgr3h-fUh0)t|CZ1ErYcKg;xZTzSEKbqn{6REN%2LGQAK9Ao( z)gzgz_%Ce~(F@RJ_rXQbzipN%{&Qk4mf-)!>D2j#{2;UYYS?$g5?zw|$OFc|m`@}73WX`$N-@L%l+-!cjfMBdxrKYV{;RUDiXr&W*tbC3O` zY50GW{oWS*zuQBCZ$dKvjlzEwjjZwiC+prgc=b?n1I+*Iu7-6(ctFN>tQ(}_w2NS@ z!(t(scfaSf$)54@-6s&d(;Tl zTR~1c7hzqdp}@pqoz}DCS~X0GY@cAtelJgG5bSv#>pe-a8y|^gi8*s5us*C0(3*+$ z}0zt9N)~eHm{m&p~WulAVOuN6{f0?W}}U9>bKgvF}kXrO4ZhcFvjQVpz|n zA6le>ecZca-6nK>tghmMcu{h2AlAXJ!XHM#EwO=TQGTZ2QxVq1MQ0zqMy#dqxD)l+ ztLufaP8XZLX)4zJeb0Rsz<(#7#rmEJ=UK7?M$FcT!#e&z_{c@X4X2e$p^EyxM!2Q< z_8^XnH~%h&{fFbJQEluuY&Lq?KqqH^PwYoFXeRH3;nCJHXeXPan1TATAp4sr|5Cp3 z3CerB=f6R$qyDM|^~+by`3cp2N%LTz_FQ3wIQB;wrnARmzw{vNr83H=^@*q>)~yiH zLcQrbGwd6gmkEyzQC|6?dOkcNx6uUkS7#ZU!X+`43sAoMiUR7HZQhd&=|0URLl<5S z6xT#~cjYcs?AJVOA{0@c8nQLH)U5$r0S={wFb=P|ILplLh-7u)k#l?ti+E z=X?J9ST^e2_}o(A;Ki;el;69{>_WSIC#7|WpL!cDgSNFzMrfyW^XF95$5{G^`~=q2$T#QuHGs6TurWL^bXl`qREg2am%A zox0&@r<%})yabcD0m>*E^4J{2k$kKCSz!rEr+^~a%oNw#x8#_?Q>?T<~_|IR6BRzJD}TJLz_ z2ZC z1T8*$e!_h7?u33Z{8sIrjCp95D`zL-+kFD7XuaxoJ-8zzUkdfUnrrAhwryrnIgH6) zbqVub+iUX}WA6U|00960B-wX7)PEcY@XMYhlo7fj5s8wKjLqDtm?aeO}jJ&&T`o{oeWB_r9O^I25{lLW}2S28EthYG(;6 zcDm~kDJhCYYhc>9Ng=GOso$B=BC)M#emflTQ?As)`Dw;?5${dT2!-rz)%I|(XUldR z-~MDq4pM2M95CzJw~kHZ_>mWU&!NfZzH5*(;g2Vg9_gHG3g=m~<*_d2v49P6RWtWD zO%nIXdlth2C;u2CT{bMr6>-Q>1taJ#ZMPij9r>zb8pIfv_A00s6&w#c4>Vdq)?5WC zNaz0AqE23?wXZjpNEc-@Ge!LS<1icIT~bR+)ky4cV5c{Hs4KgcNIxZ~-?5R%%c&O+ z<$qk>4*f0~&Zv^}E$1JTIwW;l`J`@P2q@#z$PcBoOZ zqij7{kIrNBBhq#K$5jxo$WiH4A*yN1-GU|p|5>Zxcu~0+^zuE`piGR2ONb;=6qc5m zz{#i~ZYV?#3|mJ`ANoA4gzxtgixb@7u&;G3k-^I9v-aQL?N`M8xR~Mq$>$kVz`?E=#R}u^7;zglF%e{Lm z0BS&$zlak@78}EjiNh0Ae4ZZ{?!jnwV;flbWBn4S7WpD-IkD})A}+|~wkSx7Xm}=i zMv^G3QxyQi*h^Vp{-5Gd38MMi6mHmHu{LTMvHjY#7}VeqxGhfnI$o~|+YR4TiQ#j7 zX*Pz3t4!XD5`SH2-VHYgEvpv6eeAQ^21^4+E0z*#j|i&6nk)PBmJmIc@l&CI#jQ)i zc%Sfd<3hOJoD0@4;hRIfATj)SBn@^RGQYd{-{%#83=gr>0(hNtP~9S;a*uxgLgL9f ztvG(7^ZvWRe7IiShnIPYy#_(|c<{bLh1J~H_c_5`T=;x@A92AD-^dM|c;D5H4je=| zO4UPl>^ISO^K4izO)-G4$3o7t;(l;Xl(7(vS48nbiW>Fk0^;#aUL_R#o!-&Kkh0`J z*<2a<{3h2`{t|5{ndvjc_9i32X`&pjwe=KHwDf$@1kwDQ<-0Lr@rU8M5uyN<=lc+m zdjHV#-|%|(wmu@I)vCT5?>A2O{YIq8ZY*pdGJN`E%W?cv`jH$RvQDi{tbvzr8+{?R zcZx6XCPo>Y4CzO_R55OdSR7|{eU#X&{ou(2j(<2l|A#2>Vqw=T@%6JS#q-3&id*+C zppo;1qaLvkX=Q`+tVE5&-CNj+bhAVU4&r|6_;^mDgn~*Q7cqn)mc&i`RrNH3hiG)_ z_<3Gp!>FqXnSzMQq zma8Z<-&!n>>m5qZqvHAtb!GqHa}}qqc!tkOiH|#h&z;#g^BebJ_f`E6+?TH}tmJT? zXqx&SxNjGi3cBMyCfwn2$9-)+l6D;Txz;A!2=~4C&|4XN5BYawe)i%1YjTxz;rl7B zoW=KML;WROOQh&=ZzzCu-p0@IJbW%#{1J{ho8dV~yC(X!2hZ06yN^GK^m`|k4imX# zpL5x-3fKqAH-j>; zF9deJk;HzvRh$)$eUv=+ixc}xRb%lP>^IT4hCb}SSp@|b?8~KLUT)Z@#T<{;VBf~l z6S^VKP-{H)b%~0$E_2_nXX%Fm?>8qRA9&xIHbs6Ia;sg4yutBkM>~}1XD>ru5ntCD zi+nR(G=2(sh^pnb5BW*0B7HsbmbciP5b{~rt_4HT=Et4)$akJfmA8=(mtNxbLw>9& z-yn~?DPExx0~4G#Q;=s5T-@dfmn%&5z&?GE!^p?CLu^{17ng(s^7RdB!8qL3*>ef` z+^c>@3VB}S_}d5Yvg>n0S>mAhSS$SI#N~}TA-l_hAN8Zb${+&d{s66x zT|0@obM&b{1@-9BGtU%Q-t}bz>Q;2jrMIway{jYYnox=z2kM>VTv9SLnrd5(diZ-$ z>_Z~mRylA5>g3~kCwpi^<;q4qReBLP0&~V%G*D+ltos8|e+#BeDiJsP4|AhVJN**e zgF0OjqJIrBm7}B$@q293Kb*$(Q`rm2qhF!=fo+D*7gt`Z;@OJ{OROerjUXvPoDqP;03AXo$&BY=_(bx6GOCCkvr<*d8iTHp3>oDS#E?w&AALXoT&!V67vaWfF z_@VSCUTxy@*69623a_5;b;N%Ry}Dps*W{WlWZhEWjT@2vdPQe0?4TJ9z~f!zN;rfvAWX`jmV%aDmsAmi^-+VSZ5P= z4#N5fRXdS}@7MYJ1Gqso^&O5M)VBGK<7>)0DY_({^t>TKq@~s@QAa#`t7VTa_JxUn z3l!7jy+CAad{>)>cn5cRF`R4gsl)5c9{cs=`#{UTEk$)dc?!}x3?4N z!dGpr5kIKY{10(|_3UNDpStC5!^pD2QoL@CC$S0Mx3C`|QeJaqvgu=gG~0?3>Fo;} z))E=~W!JY5Y3278nc_G@dd*=Rk5aU8L|k+!<}~8Xqn<%H|FSXTGS(vuPR8PO0zW#E zpmOo|G^~f3t-h`Q?|ILJL4TX>WBq_|UKZl&`R;qr@=+sX=xn$MX(AtuA;rz^Qa09& zzm(-dbz{|hxMbR<01gLmJivMN9V;N?$jMyhdI`THr2U$FiSua`_g{H%*N-r~53Sb! z7~YqrvG^~pixS;ycMI2%q+Oc|4W74O!|}@f(~*cJERSEn`wpGpKa2AX{hxUu<{9*K zLj2R+%NC|`o0#Ez&iA?7aXdUJ&j9OtjN3He?VaqTvDYhY{!MF_9YdN4SR=hN%Z$}T*2u@f9`@!SRY#23Pus-{%f zCp~lt=Q(TZdn4ALeQ_LC&UhTab8FGszYVYdo2Il0=Y7u8QowpiTB#)D(>^KyPm~6; z;=C`WhbFOqa;8FmVc%@DT-b@YpZ!K7VlK7Zx7b&LV{4=_qR%8|59G1)azp(yDe-|hUV&R%kaLN%;d5EDV*GUT96mI zW=%4oBZKNeq=(LK(1GWo6a`?=OYbh^n~8eiC(tR-J_dQl^ZaQKIBX!W3+n|UJc@8% ze>6ANpGkIfBVP#`U3vl^AO3q0%CmBsBd>Msjavy1$^0Hb{+oLoox_~7$DVs5maG3u zgPC_D`C!QP@D}9Hkb03j$e(8p<+~$Z*UYaD=cS%aBk%4yHBy2+EL9#6u<2i(X69$R zsa^BP*NfHfmcnhXX=kD0lQ2!>_2b!Uqo@O$EF5!SiDxm7Tz#?EL{njoyo01-M746wFNrvc#w;J z;L7XME1;-lN-X*X-H{q@7vy=Bh98cJPr=u1dm zbcL7v%A3%)Y%-tMfhu{@chJ`;(}%dBFqOwu7Ii$Op$UD^AE7vH=--rf7k$#OUAh1y zknL zz;2Q4m@|dVDf`eLzow;XqhF3yJ0ODjvN<$t82xmzyjL6M$==hpZ_#JZdTp*k-yQ3F zzXo$8HF;Mn`f+-n|ND8;pZAXL;Xt20#p|sJpl7#u}DH3=0}>~#Ba=xHm5#q z9!H-aw>oMRvD6<{%#rPJGP^KGy5Eps#~iu))}_;!Bcs^Qmt$U_KIM(=z}%=vm;Zvf z;i^?bJ>oq#OI|=q1OI+9cQ772l7C4|yZUQ!1Ll(ZZ{^!Cx2$wriMi5d#VI??FN`w3 zuLC;&=Gzg>k<*EO4>2G?>i3k9jORWOW1PGisq!8|F11S=BzwaYGxFzGAMEIoSUM zb6)=7i*uO&{34F56d*p@zBL$1X=OG*dXlB=V&bMPmd?;IyzwR!c%b+iMonh*z;|a` z|G+y%4zuvA%il4`#UaoJPsY4>3^`O6hr$F^!=3QarI;D~9hRHpY0&&?oh~%$@QcND z9bOk2&AiU0F*>f>NWDT2pChF6RWm+c+8YNqeBOXicRqanUpeP;Fn=m{)N0}W7}zIP zV*aFSKGeqjqkmYGLAnNtocJy39J#+n^KZweF^AT-wNGOHywWLw?<4cFi4(pb_o-d# zgG73r)H-~ByStwXWB#-`lF{=S>s4hR-eB(JYPIr&UG4SNcuw+q8$aWBic?L|U3k7o z;p``7c19TEdCSbz|Bv|`YNSTu`D|Z%u#~M5WmCX5bTa+XAchqMKVeI#CBjGnthJHN`dEk!rDtqLG zhGKOc=GBZ0hOpm=l&F0?=U3Hih^DDyt@OIBi02=a}yfwC3yk8`1f2J%sJ&7=_W zQxfmt0jOH!+={#v&>Pf(`E%}5mn-twL38&(xWDa+JMx{N{njyfG-SvJ`H=KStjLp! zBR{V}Yt9-KcK#oj>+VQ&ZI*X<*RIc13rT^9^RGqonSnBGxNd(hVQ_kI13!u3%Z{ z0i{E>Jw`qL)s(`l)92nEWB!iaJRlVd%~oB-@7$D&Yqgb7=P$h-_Cx*eE#rKJxKh+y z2)~m%+ErM?`8PZ6!+Sw{{-AFV^%>CB`1dPh-7tu4W7RnVTbd=iuh!Z(g9!QHtEii9YBIYs@b6NBwyR6SV%#WB9)W-J75G?&^CkMe8nHbSTmJQr3g{=tz6D#u1=D9@&`0uTP+vpoV?}>4ho3MH(-nsuI znDao>NzGa2yz1$^1argPEm2CC8&uDBY(v~+B5#ZNBK>!QkKVt2I0D}Pu9=SWyx#df z!g-`mdxiCa$xh6njK}Odd$8W}`oCeUOE-4T;C=EB1hHd2TBe}Fk9o+_?v5a0{Z1(n zc+k>NoHjD`%iB2!2+V)Tk)?uy;czXY-D#==F+IZxk(8|NR2&s%`w%?VAD_`3lg z$9_YFCHp&ZJ+%eFjfgYY{$kEzm=$V1LrfEX$DFf%I4UIL`nt!)!*IPJTesr#QoOFc zw8L@BBB#ALK02SJgZ0L$W(DSaZs8<~^)!(I<{aO++i@88bG33x8@`{LgRa$xt%CM3 z@4s(ONCM&?;wR|v@;6~ec>1~OK4^FOmNs4|zd&U*bDlc6c`?4P_mY2S@Enl&4$lGQ znYY77JP+x=)|MjPlbGAhN+;CT^y$>|E^>Y}Z2Jn@s(Uc{l| z=MCVx^PK81T}EaN?caUH97SQ<6vGGCRQ;L3bFG_b_yy1V4XyGLIB~7@IyArU?Th1_ z-m?c0Q_QxhK@Ux<#aN#)`}qs|CRnKM750(Rl{YsL3y$cXMqKw+&J;eRJ(b3~sF&Up z_M@rp**Dmq%XbteBW?>%azp(5p3zps=B^Hs+W+SHQS5Wi^&YQagkE$U_W$1#N3Gz8 zPiAsh*W~*?h`dp_N%JxCh18TN9dWO4_cmBH%^`?&rHo6PGpCSeDei}>&LQ9aaEjMb`pVePMnxKdqs8ujC3 zfp7u5lMs9obtV6D`f_NuM6C(+$Mk*A75Jm=g)Wr+vv?A9D_-YYE_6#4J^?GEk|m&e zMS2$M+}=-YE8v{%&TFWH6Tabsu(PL+Id6q+-YyQu(!Fn>j`r#5u7LghSD3%+I*rZ? zLKpXyL8!mqSy{$Wm!l(F?O>7E-Os4odE5>rFu->GbJX+X^V%C>M}pm5)cZ&F@e=TX z+^;b717`JMljsjJzTZC%X+pLi(LY@JJ)jFsK50Kdf3c-nQVO0bQM|I^Ump33e#AUt zl`|yy;Q{)UFw3ON=wG7N-8_nZX45LFEc%?>)R;N+Ka6{ey3r3=*_Jc^FF4TGUy6Py zTQs*6ebmw5^B>VyeQ!^sz?DKnTIjdfoH>Khf89#^@)Uj9GtS-t^l2P&{HtK$l`J## zahpHC=R;pt?BnBx`D^z~&R_I@qH^+4=m!nFZ?D4K6_v>Qm6P#500030|18;gJXKv6 z2k@II%5X)XG>dQyahG9)BKp$HW>LsSw{gd&t7Ng*ob$`C4Up%7&ZY4FIL z;oZOcynlT^YoBwcbM{_)t#c_9aT(D}4myRRyVx#-omjeRgvLgUcTbIGB|6yCZm|#} zS+*tsZ{}`1H`nowUNCz9zIC@inxjI`$wX#%Leua zjOX4gE+bN`bJF5;h(;eaRT3SzV_ZKFX(sm09Yng(X{%nuizeO=5|umcj{btVJJ?2X z{^5$bF`};VhR>74u7r)BXNV(tLL&3TKDX%#iY|qskQ;P_g~;Z%(924U$;>>;PNar8 zS8!l_SF125Vph8|T*SA|8ZVa+(_%T_EhR<@8&q)<89*Kj>j5)}>D@ILuXgScLOy#jHIa9r=bIIbgA zJKl8;*IlSR0N0r+WxfyB-8H1!7WaW7Mm_v5?$;S=$Pe5HtJ;o!#AZ~jFF4*Nt@9o} z9_M}pBR6b&g?UhL)uaXUh%TkmO&p!yh! zGqM_(w}Wa+PhmdezG9wJ9#iKq@14~~Z(==kT{Dr!I#HPIDqBpnl@iwCB6_%Os#=2e z6R-3SH)8viHXb4)*4CbnXks_*K_#X<8(qOq6gi+;0-e`T4=p3kjIwYG5Z!kqS3IWYB~gwc8?uUM_1I~nBr(>$IUm|q_b9C<*2Ojyz$ED# zYEr~|fvP3&3ZqeL4N*Ep=q((M`fVdk6hC|TJLI`L5x5q4q<;;+46#Y^UJkTucF>n4 z%Bz3tgfFVB{p5%Nv0T)3_}ml8Ign*!ubw>d{NS!OxJdc7_j+O#XE&Du(Y3Dk4s@$Y z-?D+Y-lVtz^3XY)6^ZHR@}}U^<3<;ih;uIlmnaiIM)#N!X&(7W32?K?lCSVxRFJd^ zQ6hVvJ1po5DuDA`iW5*&`Jb(-c%KPh8j;3HiLOR$s2jd?BZ<9MUp0jbt7PNh$)HQ0 zh!pBUK4CQy|2(U+AGY+z$3s&O_7)EH5YQsA?z2`?BBi=E?g|_@q2Ge>fRm*{+en=HtnJ%Gfp}q? z|5L;QXPXAM{r5h?+PL1viiU75wel1^;5v{A%|4#^2-z$&ICL z$FCzkUqAI4@nHGlNg`b$YjBw^(b$nHPo%XCsOS@Q*Rtx`5GjsE(kEfOpmh|+slKZ+ z;S*}#OT5mu>U2B&b0T3Jo_ctVsz;7zX+2v{q*U~H84_vd`t=+z?o#%^ALBn$T&@u5 z25B>?7=QDps{nEdMU>cAdz9N+SI)CMX|*gM168})8@{lnA2$8mmt5{ozDyJeO> zI39Ceiy2Fw{q2c3HCG?!)3Rr-JK}veZIe3)#fo2<;`Q4M0}K&couq9=Z1?KU2E@_c z)vNHj>s;mdzI4%X>LSGccI6}Zz0!&9U+{Y#kKK8L-}f+9x)kH)#hvN64#DH4xK7yS zaouRjBOQm~)~lCx!xby~)Zio6trB?MWsdg!7p&%{+`mx z#`tqPrE3_s7A`r5_$7bmQN*kFX`90}$@jJ4{3Ggm9N)eoR|Il2Cv#ywlqa!{VLr9q z)c*vxi!LvNLkW=?m|wdT)u2P73oMK$t~+!J@S>`-@G^|!299=JaofvCA8AL z(}VoR8rXdgKH0V77GG)voC1p9*`d?5d25mj~MX||jZL%p%xFNhXY-{sxy!2WRBIqxy{hfhMcuQK==2<1wxxnSa#`M20l zFAnL)!~Gs_ZJ^BSTT)Cf#eB#98&vhM06q_@@PjVT^>vuz8&%k$PWO)*?AyQMc`v}8 z7#;)2yXQC?+_rY03j4f!#@29{vdMoZ^x4?K2?sW&)u0~OmnRwql`3*{;EP_tIn)iI z%d?)rYRW}F$gxaN39j?48$_MaK(Eb!3MrX~VcX9_DP~+!)Ps7YX(~Jw-VV$>0G%BF z@WV0F&owec&U()?@a9rmMHp+y{tb1`do9{6n4Vx}0maVy^S~y-MK!30wEceuLf;23 zl%P(vcNglWIr{!+cyn~M29!}>^%eD%am%(qxTuVs1r|0;`JoPbCowmG`fO)UzZvWZ zb`C`SR-5<54E5anV6qzOJ4^e~RjBvAm^TQc4veSfiJ~qvZ(&nGofw^MYKOY<)pFBB z)RBY5ZMCQ`QxuASq24UY%;1J$zvnif4xMl?_ds2G)~28c^=k8tty8F91rvIAz}da? zw^855Yfr37dXe1!<&}V?cz?57$5Ag=t=|=d`q{aoIgJy) zCuq8gSy%Iz&T!y+t7t30+Ncs=^reDhUrJGjv)%vRkG?c-SIJt~*V}H2I$iLmd>HEX zj?DB&=uf>~ww^&f-!<_jYmV4jT3z;+sQhB?De8X4?^ib_iKcoxuA?8YmOrr*eW};Q zHH{eCQy;TWG)|dieqSdUekeFq z$%o(J+*>ihg71;|@)Lfi+GFQ@{BHWyjA>kl#Ne?jv&8Jp9gA^&L;~k_;d-Un3>xA3 z#iZ73!}atMP8uFYd}%=weWT=zY$=`tIK0o^=5m_e~*(+GfV%QzcE-R1uo9YSU*yq zr|q$xYLjADV|^*VbZvwz(n(%ee+36`Qn4PNO?u_PD#}H5tW(Arr&8#*uU-@D*Hqc5 z9nwXQhGKmeU8~T;de7In$cObmV)(5a?(w1LBQLZ^%AP@*~Kf4d^Gyg?lMfeCcFswsy_2V5KNanG6S92ENIAQ z{mGv5FmiWvDDvK&JHbnk7r9gtQlJ9QtOoMu;Dvi{p+$G2s|;~iJ)0f*xcAcK3>cwm zu><*=T_Cs*_NBCjBHxdX@ylUfnB%`t2VbWgb;kbTAn|$uT5l;z#C~)5l8*}ZC8fOs zui&GIiCx&w#@F9!go(zq1K9tJ7>Byxne<^*?4N6EIsIYP0sa@*KSOHvVE?6f*Lm;6 zK0J8am$_f(pIg*|aUDtybD#IQd;18qKe|01`+v%v(n-Wcnwh$&BWjj?yo5TUsa@>@ z9M08c)*VV7?_A)SvY33-BjHk=lZbt-yR}ib%mledqK*-NE5kr+B6EBN>Ya4GC62IH z^>{Aoptoliqduawy?LUEdg-g_R2cfkr22FQ;=zeHQPf$fTP=^E9vg4j{{V66LD?C^ z$zBf)P`~|R`+FI6n^~w^GkkifS^)K4$+@fMaCkxd66(XD#vnT4k?F&;knjDVI_k)x zy6$7BBdtZGQehi=Xd|>dWH*iDsXlv{b?N-}8DrF~x9!&j!*!326=GcaG2b`De#hIz z(KmYDKd=|di+!X)@c_vusDF3Q%MK%MHPl*-`dM@4kR|GBCAxMrRE$Zhg6Uj>(>T7# zwoeiD`_BCW%zn~yOF|Or_kND;?_tfIAXfAjOOA9)pg$0N6uBAw!;U3K%rO34OWqyh zd>{6OU_A4JdJ;^Y6)MEIVW8PNnDV8%ALpMh*f)!Q<1ATz09C6(Kladd{_qe+TqYwK2=EEg;#B<*bSh|&x2A^I$n2qy$v%DYTd>Id& zV#KKrLZ9OOI6hRDA$F22dx_(_YgFinIi5|RFV%g=@)P6qO>Y@EkKW08iupR@e@lyS zJj43<1Dr4R+~6)=&ljkkjM)FftE-6Xu1JLJnxQPY7 z!h9GJSe%AfEG04ss@VTI2-!V-v~YZ)KzJoAiq7T0c&c^Q1m>G>zT6Pz-+IO9cG$Lh zz78H5z0fYl4Rc@^&lF zXFLz2aM#t%BG30wW;&7Qb6c#+;lUJ@G>kW>NCq>XCw^P7gJj>-f_&Ev#c>|>oz@)o zkKV2io!D1GN!@|i+B^3S^t3z|0tZ(7b%b>%&uxc#DG_VnuY!vdyiW7$-cIaKuSfHr zVZZWGtiFl(!bzUfh*{(e%@I$x+9|+a{?}MB-u-w<6ZXH9m$ws``=5pAe#rh+jpzUS zWF_{`=RZCLK*0mYl(CO0@E&czK6|olPzy>#=jUP{R=3tz0T-+!E@Gb^A2~9L{X2Sy z%Lb~g|6GoJeI&e28uG8Oy!ij;$3x7%&^>fFbk;I@fI1=BLX8)$Sot>qb;RYa;9eOb zYtaJ}IM8#V5_Lx>=VetW6_t7$b&1HMy__(pTGS79i;1p4H|iL&Ud^GNbL>mhIpH^a zna|H}_%0-(9$Ld^zzgY8<-DkuR4?^&pnm$Inza=5R37E41nMitL;(ZTU9adTna}ab z`pQOKX3q1s6LlIVi!&#*?)#*KI!;aA%Mo?mm#CzxsPk@E<(HuT`^J(mfV$98|Lt04 z-}ZiGFzQCR#f3wtBlDXJ9pKbdSO@A%zaAf3sFn1+4)v$Q-H`9--=sTl$U*-GAurUY zBBYK+AIH|DJd3*ZhyOJlC|ztChk7lk7Fi#s53H*ALq=>vk?RYt-?|JuD3TkLXa4^9Ow!T_jeH zf&UM`S)D9`pWHH^qAv(f=)(U>v`&uVPGZ4@%eH;^Kk)c-#t`CD>^8rNrAO_Y@V}wg z7W+lxM2$;%zUV_lc+5wp5kHDhN1wtl(UC*nQaYi%9DNL9yQdiX8nO>@vJl6F_!{Ae z&_6Ng=ak)|)X@hO0C5^`o&>tx;3CV(#n;*YH={;t==%Ykl>{|`XDohtcizUxG zaok^ArwAH|4?Ds=`HuhM{VZfQonrdrpLTp+->N5q@RXK|F208X{j?3fU$e@<0eoLh zrHUMUf036jZ{YVhuu6q7{})|y&TEQT8|q>;f$P=xQ5yYMV!CZR`meNMwGa4zbtGn8 zDz011%je5+9ch2WWN=*_{5EDV|Gyi_3@?Q5tko)TUy`(r;Qu=>1vzf~e@7`6DMQ~) z9pClqCyqPmEXDn$uMg3|{dTp>xQqKA? zF~1xnIh8U0nokG4$9#0Xcjg@Csh7r|rI^Q4EQRTq-_{=2aB_OyOMw3D_9zpY=m{4m#)(X)yDS5VBJR@HZesW$X0$LiM-J4AUXlPzO&XLUtEaV zc@z1=i>1j8`NSf_YCH1Fr*w8I^3A#7%0SpsANC1uu|Kbjyj0`#v*eRk}_n763GxD2}x;?P$3C%6^Tm9kRkJs5E2T7dXlkF zrXnP>Od&G9=Xbn+eLrjOd#`)X*?XP677B&G!&zIXj6xY~qU1w~=cS^;gbl}n!{H|i z7mEm?wBjv)c*b;$QIt^m-k}F@$gNgDjL`P;+#Bd)*=@L$Fz*3J53Kn5$3vVjuHS%N zg0Sm*Ksu}#bI{pFD6*BkAD*n=e{(xw!IUkpB;jV!>;kyG&EG_dP;Hpwxx4g7W8HLJ!*xD7YwJR+oq{uWYEFj+fYQOqUA{NcrbBmB_mU^-p zu|MZGR#_sp^HDX0w{E?SfdK<8-GmftXVz`Ih**Cz$Qe#I4i&>$f2q~GiTNAZf`)|D zuafmqFxxz`2jh{FqdVk?IQl2OCn05{`p%C~w7O%1JTX35-f<$vs)1>%hL)f5-x76I7>*qf1NJ{)(+VzHn53lN`bU)u*6j&pLW5aYr+9=dQURp%}NU{9`baBT0*?)`ub0;}27i1E+= zB=*BT8cA0|%CWE;8Ia-Snl8e!+g-02)$u!7TLlTrrngQgLk8D{BXF_M_8cLl$%4*< zP+jc<{R6~B8+;Nme~eZlAManh`QrohT*J|bd6n;q-I(XQ*E)jt&53r;U_S855@jDT zzh2=fBVn1~$BV3p1CJeNN1SD)$w^4HH#6o!{G?R_Qg+tqV7%<2RTExEF%bB@4zGJR zpU#5#WL^aWw4@!UAyn7gc5nXwziSeD8FCHddt{bB?ZWq(>>9=QEc+>VuL9$P%z}k5 zDA*?*o^Mc&#`~s9Chp>OfBG)t_fu2YPT1o2$!O0R!96T}xL#EA@kC*~?hp$tGsZ8z zI?;pc-qdgR61K(v^~QCNDfHJvEb!t758@a0eFM0E$`@bd!^l%fR9MvHd>G!yxXO?F znLmGY3hUraX22&n?UnQl?im{Jg`yQPr?Ea5AF^n|S10$1V*C-`rZsR!+u<>+vx9pg znpChZ1qF%`Pdt%|hcZpIx1pH)mW!C57_Bsf<9=0&Q18MbALd{81<^y>L8eix?<4D< ze#N@y;h!&rnokbL!o(YyRA}xaXoJ^DM$BqJV-;y3j4%4WT*f{+5upAJ&SYN9#6C-3 zljx2(MViL|ado?=u+qxDpTRyA?HwieYaAso0sFY;t=$#G+dc?uLS=v1&G22oz$ErP zec|0&8;p>TPwtCa3%ky2DnlM`6(4qnA#=GR(4fNRJMzB5f@2WOF#oa-`k8lvVj#46h}Myn(^Z z+@wTaAU(Z7n)L5i?-H0!^&oYcb0@u$b&B*8of-MM{?t!paNVj(Qk}>~(gzFgNc#i^ zNZGu)NfX}Ak?Pw%BK@yuV&!uwi&=2BzHTUd-=mQFo*9>?#xkO7Hvf*Z_K%Fu_~*QbfWx)#Z0JinjciK>Se z0x6H-?T1z-FxdA7GqhA(SA^$&esa|!p?F&je^ ztYPvU7G~HL<5`6B&bL~@E6_tPc{gMXs+ko;ej6RAgMs(2KZgf=y#wIU!ya~!VJOr9 z>h_K(LfMc0g0M>9+8Su#dZ$wW>)I$R9JbxrstawEQFK7qf z2ngMWb1%2NfHy0J9N_P7&R3wck+?Htd!<2|RB2AynW{#r7@tB)Ypp`6emm$Y`TjTe zNf**?lWvpmBi+ieG9IIQg|td(GpSQbEa~l!?AKwT+@Ke9kQ?@eu@(b?upxLN7;a{; z3WJ=pf#mOX_Rl}?`6=rK@Q`=Yw&YY zH|d~vp(~Vn$w;<@b0d!sd;YdQkhv z=OuRR=VFm8_&HhsEF2nm%?kr_epYQDq&U5Ifhq-O1)xiINcDQcaFIGcXwJf~1>NJ) zX<^ZU>4J5*&fDKygyCW-0&wFF&Qvx+>P*laE7phK@DXUTsPl9!p=8nY91Hegf9ZMH z7*Nx|Oz2tvau1YD*Gy)@eogtq2^sY_++9QXVc-5KMqKx|vIdaa6O+V%`;o)bMGrfE za>9FcXVg|>KiEVVufp|NjI*IbY<U?QG zUN38+`3vKfCw$uphD zR~f{7>S*Bw?CTPakx9wq9w9Fk-jX zMTp-8-B>C+U?u&Ra%kHmaF2{T?(TrxsRf~Ue@^D^XZT#I%TOTxUXHbi(Kx=3Vr%pW zA;sHHWeDGUO4_Oq-{Vrjo^HbU^S^c52+N+ai8SDKvUFjE(2;Wo`Ma;&J5z`2L@T-) z*QIR8)Bx8h=VIRGK|+}uuIjj+ZgjN^e+UitdCC99{c%c+!Tl)HIMTI1*eY~^3-@oz zuK3akgc$mj=HF9RYLs#s6)M~WJ;&c-j*TVXx6?#!CS z`XuT)eXQRF`yO7b?~e3KQD#Z1K z^qzOz%6xw!=_$ihQp?OV(wM0dQaGi8Yq)n>1q@4@5Nfqq;NV&A!N#CWfn9l4*+Arryy7c%WX-T}FCsh9y z>H!(*e7&Hoq7G@rp;M#@zLBIg<8h=B?0G(LXGoeq6b+LIg5fn<1(C`Hexz8{R z3wghZ;@o^FhI$UxNIg%5>=K_kAe(r!5YFFAg|@aZOyh1QtQd3n1OJ9T*@bhwqi&BA zOdS74)+K$9(pRI7Ib&9C3{@k&li{J*;bF)dP_Kx(Crh%y2d0WY{zyobIUUD{{@5#_ zol>Ziww@O^f**t@$UfS2=hsn?!^o=yisbcnVZL1HC@uPD6HP&4sJnRNPU<86kL@#A zk9GXgi$Kn|XCmzfl<}K|A5++Y84~&o$9+^@2|Y)05$2%0dMs&K-mB zQ~(1D>O!C4Kq=ITHg&NEh|50flYKdtu+ebnzk|IHuB#|&#r)oo#YuRi?e-efpA7@7 zyr@4dYU?Bro24_WBQ~lZIf1zUp12QU?vSNaxHkFjCs?iD_!sjRB?Kf;-x|*Cw}lSI zD(R?yBM&Z(BW5}suYh{ltSXrDak8HFduhRjI{UzztLCV?%RjzJM11Yf;0UBV zy(Wh`-9b^(2R^Qd`h@!Zgl!fV>V2_0MHc7>*p=o-BaX5VY=xCCrq`j5ptMJ0ANmMc z+ve?{l8Wy`_?=?^8XBx_?^Ig3zx3!&oGrgBg?@!pP0LZ}=$GRKzh%`wg)-3;^gXDe zJ-2Al59#hN-39H+1kR#g;(5|C9I^Vw+DdqTB!2)|OoT^jU{xEX0BVfYCdGx$=ynCvq> zI1-zJK2x_br53TlUe!^=mgU_H=vVnCs&m0?flnfELvg`Q^sT0E8mPkWN{U+OgXP)? zA4XqGTYA|TrF6DM_of_s3X(ubdNQviC7;lfsM<0#)?@2MfUs?NzJK0Yop7RU%{tNH7|G@9* zlzmzZ7uVm8gc;dc=x8UV$>6 z2ecuZ$d~|p6<)P~^|V$0)_1IzetR0SPiFt3?J*pfwY`pUQ;${)#6>b+)DVYGmWv@~ znhIcnitJw}us%(_ebFzYmK}2`MNGf_a0=q~hUFl{g^oH`AyLnmW1QueqdNT8>@Nxz z{HGX{R`SIF_Q&>?wvSNmdUYZ+_|@TweY8F4;W5Y){8k#{yYw7ZBTnYI`?`jX*z0d5${ua;Y zT8r2^^HMwVK|$+C2Ben~@q}8#X*$Ro_x{v!A+}&(_=SA3=;M?PQ;LW2e*|jLTDyZV z=WZe!@=k*GObhao4wEF=XY;FTCi`r|%bT}Bh0Z%e$bWzG7Lt({g{jeJ5eJ357eQPc zCfbMmT4?w$2@0?0J%zkn_)kj!@#%!-cI0zLMc*joZ<~TM#}Tjo8^Mj(;89i+o(KQf z!yd}4_)SFZ5zaGo5waBWoRcQ!fb-O*gPA{Y?$SwZ|&7^;{f{w)B!|!*Mj;Wuydm+bUi=PjJko9yHP#@mm{Kh(tdc8q~I)r-L zk>fxwlwsrPLcQH`IJ6lK*dDDx{dq3d@)cs2alHuCrGGS1-a;ZlRlvtI=j%}Sdc>-s zE~mDi_G&^sOIMxRjCyx8^G6GzwP3I=EL-L~f^q9|letDhf!8X{Uoc*#6ok(yBMQSx zd~R0U66$@*@N=IO$Ts>p9p8tCr{_JPHSqwbN1s6U=i?UC$6D2#o%r4N4lR@QarV_` z1DMw?c{GB)#G<4r`VVErVZG=_aSRr=^Boy zSg*d~C#hJ+)oHTiIw#ii9;|!8Y$vNPCU zjibkCuy2-z=OZ0>`5R~=QxzTTm~ zJ_62XJI_P8FGi=Z|EnH;u7op{eX__8c01kT;c#jw8}bKHw~={-JGZD8-lXstA-^~* z1QbC&mo;0Ff7t3aghGvvNvn{bB+LuF;r-#xMd<$D4PWFjL-}4NvYy-ak*xDdSw3=; zbxhE5BAEvz=w*->8BLbUU}AXRVdTwlGoBxiZs?OO^6J~&nzK;xrpZm@-Mwxj8<3AB zs#6knl>H9?0RR6a*>^luZyX2klWZk^*@T2_*DkwMBtnCTlF>v|wsM;!QKBd+t0WSv9n zAT?KCSBaEwR4^2dNBK6xoJXPSmC3(bOtp0ZCnm6jjne4U+&;Dr@7X5=b5YxI&E_PdgK@NlImUsp5e;`Gk22taX#`#5f(B zJ&!smvk;3B{1~ecNJ?BzGJA#k?HZ;ZsGF18#5Blyy4%`@lz1aD83|X4-+vFOtAm$d z?luL=Ch~QZ>|_U0!fB`_3N`Va?gPv-3tNW!c&@5#CRJ3}e**gPPCSA`oQYpai430+ z22HY_6}Y4U*F^1bhuY1v$&lyRsy0$$*}iMF7U`P$z53Ao$2JdA>h^$*38+gnOuwS; z&Qzt>CglurQH9e21x~P2N&7CGiD#=MCDv)B%)pOvF`_!;xPYmGF)7g~mT(U4U=DwX z@%9*&N_elUVHD%y+nqRc$vUKagaX<8PVXZncC$`eOmbj^QDCcPK86I()eT(;ZdjIkn)aER|jd3QsQcu*g%Z&R`yM}+q?;wsI z`@#m}FO~J;_wN7Zod+`_!f)btfAijMk9vb+wi2ux=_BCdQ-|wtUdQD89>H`rJs0?6 z>sd9N-;0qge{g*`)xK2W`sDu{kA%UEB1hmTf2k6VYi0^DppF`AX~%Vc9hRDd>;79p z@DAz{^&StXRkCabP2X54K<|d=RnUmLVifag#Pahe%qtHq)lAeCYPxq&J4#yk!>`BB zIAh#BQ^OSXy3O@UsC(z)1yJ93D!c+UWx`_s^ZLKJvXAhKmq|9vl9hjed3{&d^gQar z(I!VwXFkc&r@cNQU>)lBUT+t%j+AT+zhS-Hj$wNZuWm5937IV$kKwqY$rD}ZE8NZv zHyH(wU_Bb^o8&{nML!tpvf3=w0yXEn!aCTba%B|jx@^_WT-fnx?^Ue#ed=izs8!#* zSO?c@l=Y)eTwH0B1rKfC5r{sb{M_3FwUohrA=D!;#K`d`Dw zJVU4)zQh0>I1ZGcU*`Y1e+lYFebt5G z7nJ@qP_mJf5VqJ1H*$$(O8)D6QjoGH=Dq~hjn&Y!IIjOITV2>`;TW=kG{BL0QVid} zv&{t_n&DnrPx?1fCI*HluTg{hcl%e1l3uqLvV~3&w|hlMwWrVUL0!KxJ7Ln4s}XtY z@O{drcp=xOZ(c&AP1i!c2$Jew>d}BZtcKGCNF&6VH$peZSBd>Yh4XUg zjR7naHfddp`QLc(EX*3)Nx%@|Y0!V9Hb0K6fjbUHUEw4>BapDbL28~LaT*%^{P}DR z>8j3B8+OzWQWsZ|M$21AvElbmnn|;gO5G@}WhPzHYI9`z_dQz~NGJcSwxK5t)#jL| zBXy}f5xfHHEUBEGAiXulDf8zYdHoz&Ef+|og#2#Il1_GQteqhxRx*oBK`URn3CMVf z7=hoimikD|&*p9EdWU(iP~VL4^@D#tlNL`rIarLEypAC_?(W@`qenVs{IQbM-r03; z9cdSvjZq`U3;ejhk&3E)8Ek{y{(;{~3IAEcE$1H<8o*IPYU`x~*1{+7bd4xGpWG(u$0veA|+q;JS&9KI3M=xZ3)g zxUK=8jp%W`?M5E6qp^T!n*lh zntvPXseX^|F03=g9AkpE?pBJYLLTZ4Yplyd;;$L7PJbUBd;(vtJtT&8T=f0V33$V; zC>=_gmoLDL^PFZ__nnk4DUfbw%Nq2DJNr2=Kp(qz|N2H~<5BbxvAw$Oka+5Cf&P+h z5myOC$47L~f3nWMFM#XM)v2K`ITZNQ`jmv&k}Ud`*3H*xaPH|oCG@pQOV3HyFVtV%M7uZB3A3?t)_B@z`T;e%5&`$$cxP{PXzkfWR3VDnr_0Wg^ zGXD4kIfhJZ(5G2KL}-26F~>;+&?v4!a}i%($n)2bWc*vHn`_B+F(#olMw&*C5I z4nP%`ND1tVs>jYdz{LY458%nQ8^6MJ)#eP?Ps36rRk6>?y%DiR{m#JR3JkxtHyz__ z^`VVWud;m}zOmUz%gOwIj+?+aF2WnKwC5*ce?Jzpy$%*gCjEhi1Gg2C4=iI(A}|xuCe3bC2 z#trp>6g662wq(6X%TI&FXZVn(@~-jkhPHpx1L0jQl^4*u@IVW4*TT5vGW1rQU60(h z*++64a$Cr)d}q`(wF#F|Q;*Ce-w_9WKNP^*7Z&Sr+;!>t2u!=tM$3bv=BC{6fcjY} zmU#`qi}!pCl5^0Cb0ilEdS=EFmJ z_0MqIv6y7c3+q!-7g3+enX-W*_kGo&i4qexj<@GgrZE44W`!{CsQxlfUt->!AWlcY z8S^$TjHjqN;J%KUykkfYuJnG4c}(yqTQSo9-ei6V^Zv(#%SX&}>yp#Yp}bhgb$D>A z?s3>^C5-z>Vy(<3alF36Q=K05L%X;ASXU!HH8seeN1Yen!0M~jiSXQ~z8f&HuaS12 z`pQ?x2Fg*T^)Mb=q#}$u*Z$c8)-S~{ycq^R`kSx%uMZ|*oqu|+83dml+j1Q0nXTM` z<3!cNb#T{*GgHW`9Q5zs!(9KoM{v15!3%w(+xx32?Y{bSy*M-wF8PB#lf%*10Pn63 zdjap9&bbN)-CrDnANm^9(Vv22-?F0?OA+WtzSa3LSpfM%IisLTJM}cIeP?HkzNWFb zQUZ1JuDt}@5X;k!et6FBdmbF@Ieia)Ak01RTw&z-b7R!IMDoQ^FOM10p*COQD?oo` zi;+DGIaUNwXgQf>?g#qtjrOlE;2nWhcSx_btO5mi*=NwVxjYAQpm;1#0Q?X>rvo)k zUR?oO@=lbY-xpfFxB>&;${WFSho5Xvq1vSm`@)OMm!sh1{1ID7#vE}dct2|t`^dU; zEV)qMRQ@t7eo?R!I`6;225sFLKV$#VX$lR6e?>N`LWb6L)!3&>gmezUO^Un6u#eqa z*W(S#8duCoVqY1%pijD2$Z_SmCP?9}Rh?4ydVo19?g%E5N* zvp2tJ+Q55z=~}TL`*qivLhn|A57@62DYDz(p87I(S{~2rJ&b+dyvp$?a)3kb=ljS9 z)SSj8L;a@VYVUvaI&z=MyKO?qfsrlQ zMaYFt1{w!xInn;vIP&=ME<-isNIp}AYsi&Sh4h2SnNm9+o}%SWa$`XbB~CTca;d$p z^-JW`E-7D63pq~i7VG1Bq_$nhmlcK6|PXT$E}{U5VM1>*Dc_1vTI`CUTVYw>-k%KIsA@j0QK z*CTL0p;A;{iQg5=HPDFP@gU8j6S+L`+zHx!hyzE<5XL2+nf$={$>v_f`JsICamV=@ z8Z>42O*$tb7>@Hv_D>OK8o*D;8R?` zTjna;a9u+qtOk+O8zgs!;kwu5?~uhjSVbpWg?Ulqr=*Jc($#vM4)dsXUvM*I4ZQXg z^Gr^DgD2)+aj3Kr=I0xs3{lKmm%jXA+Wh6xO2zyhl45eiyeD=~h+#e4->3Q;`kk`> zh;?(T{eBYG)5Bp2FRZf^xk9METdT7QI>-6nOXECf>F^-G^_%r{4 zG}iOLNR<~nsoYxukC;01W8Ev&-#A0d=VmvXVOLy$Ci;W>E1!7ya(5IHt&dz~a)p0A z-CE&~=zIh88KLabH25sRhZ}u}3>p{V21CthxP?RX6#CUGHpW3Hc9Yc>{p_6#Z!3Ht z%w>yy7g*v(dmcf5d%F$#;g^gTov`m=`cd@Fge|P&P^@I%S@hfK(DU<9W`)v4^k-Af zu2tycM;1Taf<`=)G4!I`Ag0lIsF*k2CU+_lC2A`r9?55+2o zei&;WEQS4QE4`2#_A&XaxK}WHVdOW)|2_}X#yi>LwJC4`-A^?2y-05?%+P4!)TF z0=k}=tAkBpJ(D=@pP$c$9Ga4{Ab}iO9~`px!l|p;IIy1W`4Yj)H z)?!%tHm(NaS@lT`sKx8mTj7X}e;W*Vuv~}ZMGHRVs9l9#=D;#`$0r!i*&Y*xdiU$+ z!7!*~$(MHgg4uB#kL2Xt2a{!7bub>67bFf%O?VmMIP=qf{GRiozGe75gsO2O>i+Sw zRMd(^f2?WGb)79J7^gUS((ZHK{C(eo^C-0?@CDAB7ymNtIj+dgorW-)ON1BRo-7)~ z`6usZbK#&;^<`Wa*L6bXv^+g>OAxhAeb)f4XIhw0Hr%~+I0)A}-|?j#>W&Q$G~nj( zNFIz|k32e!d6HN)@dfkb{+57D)W00>+=4rECC)(E!jIN8Fa6z4n{Rqc6x2c^-gsV1 zM0jpug`a;9&11fHn&u8+p2i=0)r4AlB~v--w_L)Rs8dQGMWJRpG~)}`#7tR3KUa0y z|9R|*ZeA#GEqn&+X6Rd5E!K%q+z{RJ=D1jf8}pK zfN@SUFIjkw-hB~$!oBX$2gv?kLL^k!f8sFuhNc$39BN}$xjFP7Q%C;_*m!%xZQAqT zc8{ zX6!493#`V_#=*G|`_9v-trW;|{dFAnCoMB=UP#`zb7CJmn!r4deQtTgV*>kLYwuNh z$dOLnihZ$;J|r6ZYeGP`Ugi?K!Y=W|#pKZu!}XeOGFtHyDaH zdMiM$_Q{Xfmy1P*&%(J!OY*St+qrV=+XI4MOkufS;sEw_WtT`#IOBX`7W@6(;d`|F zS;+F1AF5uu`5bwm#=*e=CKz)U*3!yF?ll20KWcydLQzqece_%88$%voQ#X6Jx7d;ESNz4blLE*h7sfUc%qPJYW8GlBZqc99Q=&u z!tKIW>}k)1mvig?B5y^@e_KL+Om}RbNACLEJcj(Ff7!GHc}joKt(lfTGwv3Q;(6%$ z24|&ks zNclPPVO?a?VdO>*a$`k~q(0ZaI0|pq@%+GZUPGIRNHcWc zIdd1e{_#CAk@3BYxzapJQIkQ<55KEUtgQ^slW#o~YryYcB~;fz$}y(IiF}$VH6}KU zoVx$`<8jiI##@{4T)oaQ@)&ac&=g z=8?KU@hQwNRihHxymK(nV8eXm$QZ4HlnIY(n70EFsXCa?nnceyyr#u_7xSHU=DG>i z!&JH-f%Ouw)A2Q5@&5n-0RR7N*?BxwYt#qulex??6&Xs$Scc4mn?$7yWmY6y6d6m% zJw+~3q`4#_=|&`kOo^gYG82(XsH8$7Q+>Ux=ba*aHzQ|T7pp2@v68a z;iO&S11K>ar7A`EgC=|$ZrOcx26_ri_(&5*O;xu;U5RyOD+%A1$rr(akhzts@cqSd zXW+rAB{UhrIsO=L=xj6D1|1c|ua|I`_%q*NlJK*;kwEDhSzcF+~^+%_3`@Q+eoEhR!#qw5dh z7qbbIHMstw$p+ZquWzxIP-IVhH{ATEtFtnpO;z(-LWUyWdJPpKmi?(03Kz!}RzUMO z875W2!WBD=A?ppVI4IS0sfm!`rPCy$MtIP?*Fg>Ed!0E0JG?U+;5FuF)A)RWwoiH; z5%*t>*aYWG=6vAnvNuVv;8;ktL%oPAkB2a;6Y=ZL&vJw`t13g`XX=KbKg%sqZNgjEv`nDB zXPO^eRdV_~G+Ou+T-tKR$ z*AS~8JDG?$_OH%J#7{g;ePH9IFV+}8z_mylaqX~-7~*q9+oo~f!reM;g&*=v#LTpvAajQSD!9!cv-(mkarm{c4{;@JsOGLcbFVhwAn|J2Q@V1`t4E7=8kLG9C zm$%Zn(-1!?NR6M?=ID5p!!S z34k88tUJl^^>j_dJCZ|0;X+d659ANphp)v@$W|c~W?KYm!7wf1apalrPQhhxwe;y2 zxTS!H%tH%O$^6h*SHBhciOutPGR$!3+77pWPUnWN4w^qlK3idbDi*S)mz%=mBr{H! zvY+`S^50fllO*{5x}!O~zUw#_Jh9yT8S>@b>5@}WG2^raWS70p3yU%{8j)YOJ~KNB z6S#ZL;iBzdm%uvPrbgsrT?5Ai=waz=2BUx6Vup?kLOUI3J0I?N>lS5i~7}La*+wvsJKp}?g<28DU`Z(bD<08ylfY;3GV*!&l^F)OyAkVP*A2=5h^75wJs%OS(jxA4;UffS)uRPo-&YsGHSbfh7H(}HAC_k9s z)cBH%Ff<~(gOjlQb@{g?gyMYCJg_NiWS#@(CkdfD(?@3J1VVqPL2WwPKt zm4Ep#6P}&wk!Qkt|0X*^!@SZpf)}cY<7~RL<_NXtx?cVwyvVJ#d5Vx0fBM4&VJGXB z_#Zeff8OF7p~^nDqoagLJ(q(=2*=`>y#`^D8)Ja5+NLADm(XaR$(43OhU_(oCX647 zw5q{%on8&5Vf-IszXC(Tgtoyt!v4X><4uIFOeRVlghnEp!g}%fLazH;!lqx(Yu_PG ze7Ix~$A$T74iQSZOIeISm3FPqg#O_VZhRr+>r+26invhR>nowCn%$-`Lb=$omyqTV zyZswsweWZca%vPrU~%1;Ce}0 zMm9oM#>S=iK1LUdD88S@W9~=Z*NmMl?z4Koo-gj3@9B&-o})?g*3bZo1zeSn96;|w6^aSHq^gV9ix@X(_Dv9@(reQeWf_X_1^z0|(t2MI2JXlV51b!jx zx8b$_PMDumsy2!FFcVh6{PGD4eZzc5|FkK^IvDyn=Y)0P-n95F*2&n3tu|OcLzzEw zv7SV|4A`;GK3}`JXE9;@!uvd|KleBPaAJLC2bp+dy_$Pibz&ViKWfs&IuGlcT8{NE zp|qEo+!ql}V{m0nRVVh1tKZK8?5DI?lLYLy^Mkft*pGgS6`I(mOUz~#;G5Z)QtW5# z>*1c*=S-U}uw&nk>WW>5cOuT4A}<`%crgjxb%W!PFI?GQEJOa-9WDP4EHtz0!q>W?ny%DlplBXFC-OCj=^yY{{YmN zHH{m7Ktqk)VW>x~DdjZOt+aTtM93l;C4_qCa?d#xeRN`mjsWT-|0_8D0PhC$m5d90-erjUW@G9Q-*bA_h?u6c zry23O>xC_dQ(ewB!I%#(pJ80MW2zQ$yUkJZd}Y=1xlo1oQYt=A+`j81d3=CYD7s8etPyzXfJXU&B#@ zCskO-rt_|u(5Eal8qOr$C)fW;XDt&PH>=^W3bAs<+#L4JQu*iIuqon25%y2Bh4u;9 zozUWr@t#yE9Z287$_Xuf{mZaFA8dNI2hR5KvqBwLyW7~m^pmfwVQuL18SL-Dz^Gf$ zySC95`c1Mk!8#j{Jmi7I{dXMU)ZCSy$P?1TE%ET;b?4=<>$6!d@=4x>EHhZYs$>}X z#$lo~9-1&(6k)}@44IeOjD7?_?h{rbaMe^_8SFRbLagTRE+x^1ZQ%uazF>smDiA0H+xR3g+m?f_mOu?MVXDE-ABmIr(pH1~ugz_x0qu9z-a>sy z5PZ5428!(Y2lazRO-~QjL|QbWu4I{2y202AOB!7J=&#GDKT~Q}>hQAOua~G#j}`fR zp{E5CC;7Y2jgBnTFUy(S_0X>(s{?iItj{$+I1rpXhq_l#xFZUVwNJA{Q74XLsEf<@ z%6>+jEGTQ+0ka&^Do{UvoqM4LIaqWbp{@?-r&vO_9`0t;-9Tca!Sdnrxv0lRn~a3u z)W%d6^qu{SJno@x(~iE_h&rBDXB~~Yo_#Q8G3vbk%!eK5D`(g4KZ$;TA=Li>{eg3k zY2PBk2;K|g=pXV=f1;zGFybxxGEJDhQi$y*`jCvI%yIOI;bmp$Lz0C5Amg2eS zE8@nx`k&DkD!i#5Mx3{P-4OZ{>&RyGF)FQ>JwKq&*}9PYp3v2MnLJdH>|ldQXKM6e z+F8CF$WTmc!twpH+vGl?FM1@$f$NS*tkwC1`%yCaj=sqLY**SCu6OdDH|}dpYOFmKx30q@|chJjSfYbT$$9p>B9t&9)rAna6q2l;nNVM99B$!K`%0jwK)p9({) zE55)tyjX9=JUoMNODkt3)}xpB$OWv|1T#S&tm9eHAT6wO;_nDHtbYX&g+6j0C`K1y ze@MMtn}~hmGtssN`>CM(_9&|eAz$OGN3e}e zRsj3BA>gJv)9%_*I6Ks=Z;=pO%BE(@gl%60KFSP4`M8EwGcKkgt3PVDkOu~p(ml;@R zr#BBh`h@1-d~4`5uCrby;s@gF>|evM-T(A!jE_okHXu$^FTwZGZmCMAVw~v<57}27 zVUqKKwUQ>=$iBjjTN$y{0~c<@I)(Kkcs{OwxF5rB#y8TT^=`!@c>bUtC+!gjnaHcc zt#yw%;G~lt`U{%fxg&WntylUe-Z$r2LG%-hRg5d>a~Z@soF{*8&Y61-zeE_O!-pp- z1L4yQG4ud&joKg zlD~)3(P;XX)A6l@PzQR5@sAX{yx~;vn0d|(m&td;$d@#BX85`F7 z!aRqytDyIekeAqR84g`B@SK9xCMX})&kSinYih7hEm#5~q1)C(I<(Iv(w1)DUXUSBkvm=P+)?!=Oubk4<_j`web9hPc_iiY`OvRl-#L@ z%irX@f_FkkNaOW4caxu+)sVk;)k<`Kgx^=pj>E@q8y8@!OCBG-M@2L0VrYN1DG=_CHz%D3K=dQ?dR*Ez+E2I;5Fg`lS26>QcwGYm=H^ zTThy8N{x%tDOKvI<9p<(&yx(P<99|<*PFemN1AYjIzIRe^|}2@>U&$c)k)1N)ks;! zG)bMuHAvqFP{-Fh|GwT~>N@@IdjI)8MlN;!Mw@li{Y0sdj*qL7@-16Ky(b3&Qd-#Z z-|s<$)X12V8h_GXN%|LS6{*A&88e)}R8r?Nk>gT(L`nPm1V~*!QZb+B(*KOp`oB}> z4{(#Q3ac=6eh4pho-rqBwVyO;r`~E(jxjoQ+_DvG)aRiJ@}y}+GNcy`sq?jIioc(Oit8$skvzCW9b8uyP8BencYJztXV zGHSeqpOj(zsq){S)9S0qxO$4E>feq<3RV4{2kN+0ORN6B<7m5j$@BA5sQF?vaQbMzR>bOxJYTomgQO8v*`A^&*DfD}PQ0ss%MDq7~TuJJx zEJMXf)c#@&Nm1wj-iK0|9KXMpjrx4*y}`e&=Kopw@9+CxrJT8`^;aZF+Ijc)^#fTb z`v%DKjZU!rUYAXk)cvyl=RAhjyutqf00960Y}k8T%*+1=@a?M0R$I}`pft5C7st;$PohgK~{Nz24GFV$Q5@ z^tuf#&nd1T>Eiyztb9s^@%8^ImzYy6I}tf03X)GW>l?jKm@cia{~a&tW1>>>oz@rJ zPLz#prtQ!?p!rnKX+15iG%i+AZ!2j#HEq<&cOC7o?TB?qJF1`cCfW(973t1Iqkw+I ze2pW`XGRTea3QAd?@v@HXucS80WHt*AU-g2C+a&0iE;C2y368W#I!6L$KDu0Yc$iBBE;n%^$ogjKl#p8&OaG<%dUM!N#O>P&fLa62@tw z%V4qfn1^uXPs^UdqI3Fnj53S(UiENJr=SKn$k3u0*MAr3y@fRsm%L*X`MNo_!u01& zZOGTW+5QvatXuNWu(teEJEQXP%ke)L`QP_(b(BmmO)6LFGV*8q_FNA}kDqVAs4Qtz z88V9M2YDDViYHteWsF!j(ZK}eN?rSyLMLS^myz?wxu4A$L-v|k@fcH+T&_dahR{Gu zl#3ix2IUTc)2tXP{uNZikj*-itr>aQxeuVA>25@4+@Jg76%@6fjPHVaB*i^!aQ$W2 zC0NnrpJ}#?>fMe%U}|v5Svy9>W4#D_T)(gU0TpEnk90*j{%h}U=m)3k3u64?&E0XI zXHWX|K>I%&z6Dj&F8}0!@)x}dpgiJQ-=3&HA$=X>*+rB=VP?D`A9{c93RM=~&X70E zWC+YkpX3fx9)`L>L1LN`N4Jw1D8AJKx+0Cervoh%>RExhIhRPu;$o-UqLKi}L zqFy*uaJz>7^12QB;`3@h_X#hL{*@gC~j&X%KN;hN*jra=+`uV^nIdW zd^s`oER8D?%2~qOKeYL{!gW}KW&AqelzbOy}s)fs~_5aE0t@ztBG=b#-Q`Pd?s6^ja4{n0+JiaYeWj8nvVJ|Tb8 z{&RAQS|RT*wpaWnw-P zTpd1&%x_`qi^;tAsnioHzdK&Td?;Lw=4kP~2E zZ2>R4HelYBD@T1c!}uxO)tHY}!nLiKpE-|>^r3vEpCRUL&R&0G%;U17C0#MED}!?T zcY@NeafUGTnV8J~9}Qyl(f-`p)%Y)Po(|oD|AhFFYX<%s;`T{t9OOH2M2P>1Y{N{i zZ?LJ<`78cQm+C%g@ZVW;>&Zu$m#T!a{Ool6pG2)Y*1Sg?QIo8ON3J-&hKadeuTZ{x zfm&Alfu#?kmb9G^U`ko>3TNn>H`vScOxw?U2>74SsmynX7`T z30vwJWhK8>Ho^&JuUp{re|M>I-E_|3_lS8pr`s5n4I0TuZ~Q-10u9n*U-kR~YxcRf zBY&UAeZDiQRtt?dBF3v4T^;C?^Bs!z{L!q-$S+_2R1YS-tJG(dXQovcFe>#*ZySnG zuXk}LM)CW5RYr(=6;~PKy0L4W3Ct~MHbuEXXWwyAf3sV=8RFBk9V{3H!Jf7}+^>94 z8dMzW)!mYjH>lHTC~dyk-wM~?C@w)&Qz0QL?d!U_JDXmbn{mexN#08u!Juwakk_CM9Z}aor(4}dYelN!SS>L2knV0np z^6TPf^kxj%+FA}nx3z@#LHZn@*D$}E={iToRC5daz9{!lCm)uKF`nYYX!KeB77FI{ z-QkS>TSqv%;QpQyZ^5j(nUa3EzG|_3f4IN+22|QynKyt@b11aaK(t?DdkS*iw@e&_ z@>^#sexD(X30Di3!CAbW zw;|7IYgadn<8Qa3VSaN=0ld2_+GHroIa|$wZTlQ@V9IaPb=~3c;%P7{eE$jfAa~+t z==;JcXc%Kg&$S0(^=ZfVFv%=<>~P%op3WZFQk2sGRYLV}55`8zqZ^^%it{5FTBL9m zqMz#EUt!}PGnCM?*w1tX`f>i~EaUy***f?O$fYfdcV}RecXTPt`7)~kRuvA^AIJE-=LJ42)qENaolXVJgnO2(j)Nl$f7uQ5 zPW+Y&6)`XGLf%dD1{i*SlJ0oM3str~V8!33N5bLli$kIBfKMx++w#QSuvF!89@>2V zPzf8y+O|RElCf5Pj4re14S_L6+k>Hbi)J~L_L-OHN8iWoF!JY=eK7e(`*CO(`S>zP z-!u9l{MeBB7ABm%VB*i1w)egxyepdL1sBVeVQ_N46|u0r)jbvd*|aZHLWfw)d6B(~vA7c%jcq@9tpqweL(CgcRQLuB5JL8~a(%~Sua4&ZTTys4m z0&ZPU5eZA~8brZk*VDyt@|->4us*8IDu z38bE$<2<0(Qchnoe#3iOlkxe|mjkP1Mz1m6ZuQkqpgLwp3A}J=$VF(Ewe>hWaZk7# zo_3kN0m=*n%VC_pMtO7juu{lR`*aRQ4c&MM=3Vnof#Kn1OQA{nv~ZYVHNl6Jn{L`4njbu535yyp zeZqHWquE?TzTeKh3t`Zkl_y}er}-ABNorXPxkZ0Yf@e!N42MSB#P-l}?Dnsi7eY36 zse!W`q6?s1bGHM~zs+qG6b&*AgLw^ZBVbgKfel=^dS@HvC2m7kGEd#V@g)~(1|Lr) z^Vm6`MX)g;E(nIK`#ump8SHKbpHGc$_CY_CX}4hE)Ae#FG@BF;*VOF}hqDbdLRfIa z)(+mySV!jL2Ri~Eka;_4fCApO9CQLOZKw!SVy$QM=pZZxt1=_ zmp}U%)*U&K@6uuC3-g1av%qi|Y_qXw#`-4iX}}Q}71J0F zxtHv1VEur^3apC~{I+d^MK$MrVcwm(A6QRC^i7;#8Od;e<_j`l&o~p*_7?kwi5)MOq+j0f;y-vnD zk=H%_71ocETEl73Zd6tQ)|JvOlbvAdg?Br!?&SL)*O2vSygCwweA21FI@QkL#waNK z+?IuPYzjBq4puiGOUC+E?aOxE)=Fb$Ld=GpIog?dZz=XmeCGfm_EDl`ZhvE+C33m2j_ki; zSGZwc#yK2I_HDA}!X4kRzq=mq_Zj;?n+adB4-{FR$fEnh^l8{Pa_UBRdIs|rJ}QOM z#`)wt_mpiy6`X#>iJaGtFyUc8E6VnIME1G27cR$nET^izAI@P#`?Hg=f0liF^cnkV z`GCPe*muj?3$w|7eEW7&?AJw3OT^gE^L5kY9E0;PZUi~!NL;Z1=O1FlHVMv0WIK&R zagHLmUg?N)7V+bi56OAUUsqP)Tt?|}-IAOO%_&bO=RPNO$@yo+RGD zlbm;+9v4NboE=r#$$k5D%;)_Nkc9~;L9YW(2sX^3# zuNzG?Ay&Mjs;g7QoAl0d4e#ex{}nMcf;-w``o(e@m%B!(U|r{zx3>wH^t zRz0bGXu5D9J5K#z#;RA<)sl5zft5A2o~DQVMbl+Zty$Mo)>^X4XQlC2`IV1oEKIRr z_vp2SaI??B6*pa`xF{@nYn2vfYXdLHa!n%**tO-l)ed3b1tmiMbHf6Q9F_oq( zYD`(VH7nzG|)6IQymo!WY}?aG%Kv)ft0?w7WG+W!7;JUZ&(zv8kiiKpYNFkz3s z)SNz-lu11H`_b`UYu{Vp1$L}`@3iIr_uh28|JvuSy^nUh_*XjmIo*`i{_5REtnXBI zmp)Iqg%L~HAw$-46~ADQleWLw`)Qw>_WjqsZ<;MutoK#oY03KjwD}|%^gD7{+=caB zLpl?L=aymBkn_-OTCPxDnD>&&WG=3zto*V~r9FIiO4Gn%d* zOJkPiL|-eH{4`KCAlPJt1DX=+zOS64)N;})3ug$ z&Ua#zESIs|LCs|bSt7Dz8z)(^#GSG!&J@`)N~Wf3bZD*Z#t1tiB_aSD;yU)S{sxL$6FcH3!G|gpxFUS zgLce)p`PrvaQ&ufok`x*hE!h>%B7(~S?eN{MfYs}XZ^2bg|&!u+WY1FBca@sZeyTY zCzvNupj>4u)IVoy&=20v)}VidhlKtIrha)(8P*2x&uOG^Tyau(-W>BU z@5e__`q{$Zy|K0y|MPo%tuL-Je2-ttU;Cl_@Z~!Uvot7wegCQib5hsd+~9tyUo8yE z;tOBOXU&A?-!91A>0of&%&j9Cx>zXZg&V3XH8ZHMDG=&=ZWQjX8rsp|Jl8Df+4oEP z!@~VSM|Ci`zq-?x`kC#8@^e9Xn&J7p9$(r!3Fk#yO@;4R*p5sM5mdC9kdlK!IdGX! zj$)03@ps%<08T)$zZkdIgmP57wm6tPTCnmP!NPe$y~+qi_%0&Bz%D{NCo|!^_Nj3F zQVXF!PO}XAkrioTP@kz2lx;HX$Jg^;kALm=*XQ`E?4od7ooi}f>A>~|@8|!$rv|~$ z=C|~GI-3WiXRPquxRgEy<3>8z*>Ui|S>9%0eyOq?4dz|t0w;s^tV}42C%Fpa z##booh70Yu0O7i#R^dL93SmAvEfN{bPp;#adHrSG(7hJ=k(zB|uugofFQ04kKj*!= ztI)2=JAs}*HOEEx-lp*^eXqi)-&6a7k_hsH^=Rr>mqi1pT~TWn`VMK;P2KQ(&wFG; z&9aU2p>E`<-el;9qOKSp1Gk02oYa!4E-<$HF{sR6zle0S@PK^#_ZQso-u|tOg0c;n z7Em$6;g&0|_v!I=D6Zch4|((5!=PyR6i3LNKVR;G^K)KgL$)9 zwX6a1+k6@!dm;7%%n8q>vbf%{naT&Mh5Du+Nm)$|sdo4v96!`RvQPgd8O0k?oBEEF z924p@o`MR8GLlaz7222HC&k+ZMGb$E+`HRC`)>r5TW<>Y?R!V4_qUY#C(fx5`q?jn z)Ww96O37;B_^?<~RJ25>f9?lTGfpAYyOt=_J38OsI(+XaQfoJbRPfQH)PK5AJ~3XX z?=hO>j)s%!$K!3xLjnF=a?^cBi8`U=lg z;w|+5T}%_*&*YcKRBxp!gPz0HYcO3Wvg=hxe2=~{Lt#$(zOxRfUvsuMRJafN!ye_B zNv=?OX13A}{rl~jG1R_yTx5&mC2OAA;63eFGzLn)n}4n|?z857Z!}sixUSdM<5sv%t2bwf=QTbPXMyjZm^s!Q#+vu(2>1H-Gef&ho`XB!`t=SI+oSAs za;hoXhdr3p4&|i>6ecKV*CiU`dfDnZM)Vy*Vj0|TrRvh>%ldM8!O>4}{J5jddYRxU zIZb-`V=H$w;JEsq4fT4tD{HpY!js-V>EN%s-@kzuw|uOGk;#rP(Ow-PdJa|jPGzv( z_1j|Ta$@3DIzK#p5A0zy_k6Hk^9!DL;j^%~NARh}P79}B=wG3i%eFaM1wZd#-s$Dn zM%vWC-(3dO1*8A6;14JV`-L{5e7tJdN3?f3Ij9BgLgx%-!`02vD?E)^$zNm zX{48_@ZD#um%G1nzlmP4Yo{~qaDMTyOQw3YOIokA*UOJcx!(cx%;T!f^r}COs_%&N z&S^Sxm^}5fgmXBB)==_=8aT;UPoMcPHd~C`(&*hRVNnb#=!3UDtUlRHv3WyP%vg{1B8TdWX2; zx~6`wpr$~x%MEU@4C#XV=*I=*ytbU`isQ2;E$gN?D(|SbSg$H}n-Y2s?AZX>(dAL@ zdXrU`E<*M7OYYs_kh-5BWB2cK7+5lHhzFia;l3HNX&s)x%Ehm}dfRXbfFlt8rMyMG! z{Wnt?`Yn^HR{;PnV+-o|^?*cmN_m6drePfvH3I@7&NsV%!$4z$M<48_Pc`bCkejh z4i)uH8}VHk7r!buVH`(7<-)a(XdIY+m0cxkd4Ws#V(#w%NsCa;zHbknB=HHmyq@=i{N;HpCH%JjPwe`Xyc-z7%p(diI2xtH#f; z&Z(cR&7k$}#2+zGdtB)Z+3x?8(fauKaR%f@C9zO<@{|YE4*mBY)=~bA&s3_c4F#<$p?q(w(xV!z_M6qIBC;!UC|u%B@S z-_~M(lm3y`i2aWLdr%YhKhFC8q4)4vSz0wb@MiIA>~oHmzU8p&(7C73YJbChxF;pP z5EhZtKBT#1RYqp0vTS9gPr&FtcAcATHsy zU38&1#cI4W;ubz%))R4zc;UP*?Rks~M>oVd?DJfE#64_CQb)u=TzbMMsFr8T5ht<3 zcAY@nBu;$DAf93@r-pXYD;qI)5aKLmhjbTIY*|qT)%!f05s&d#qozP{&8&5hv3i~b zWigv>Ku-JM1=Lu_86%!kcKXH}=7cuJK}F}VqjY@9;ZIN-^Med=pgwQPf~;nR3B`vd z*(_9SmK8wVNtGw!ND0%n4YHLfrie4eSMM%{vg+s6P;L8mF5*$`=JB;qJ>6>s#lepx zCX~m#%t?omX#38{bGUO38IV8Mw>RZev0Kkm9@U&2iabkg?tKe#kK%)nk4alh_CvAN z!B0?;S~C`ToMy@Molvr&{soj3N_~;g#5^!x1nP1EOW|N2cGez{PFCHFv^qt zPbetgJiT{4{Xeh_P*Yxh1pO65UA?n7nyx)+qE_l|i-dFMjDf%4dYHZ;@q zC--fo`YS$sq`bUmXg%ezfBL+oymx3dwa=Oo;x_wjr00|r_o6&E%Qw>~zw~q1NcqXzZ}aGT9{TAyzH`ndw~qAv zpQU+WJgDykkHt7)|456+I1(j3R8n4XXcmw0sEv;?gY5DHkr>Zf`NA-acXr6%Rv7=% z8m^Y+gX`?4lt--CcN=*GCmr_)^F}InHzNOT?~8fG1*A^FJQMe?-;8<3`AcuoJoI1L z3#w1=%f|fVR%ItZb#jj&sFe)&fNa-^y`a?Tu0Q1;+h>lZ^J&qE@rlL5Jkx__y^&&@q49}0OXHI!d%DV~S*k6-uQ zN34f@vd1FiSyH>8$5+k$6s@TP91u;Zb}8pw3Jcm?tUCQ<$+4YxRleL(rR zPZ2zNp!y-yjp_Le`$?+#1MDN*qSfY=@NkcQZ*X4r*;j}CD0NRzEsn426HyP>9#3q5 zRuk4Vpx(j~{bp7xqCex%#3plp9~eKFI~WD#yO5 zHLW+szA81ga=<>zbWiV(eODhaMqpnSKiW4N`?Y#((Q3-OJZ7iUKEJPB2JQdRe;z|T zz&>=ojCetoB8f*Fp}4c`73E(Jjj@z}*-m=|mCe#{Ax^nj1l0$PA}HT_P<|JRhi@8> z_(xfB?k>egqrRVvcuDAkO6H-8>Ar!HxqEhblSMDKfBD zg7}p4DW-fwnt#n3@vE%!5Bp&0j~Nz-YvsP5gP?AND3S7x^88Gg^`BR_q4c-S%}^OX z{acEUt75`n)TT%d$|94FLeGdhe?i{Fq>0J{ds3XO@IN^i%A*@6!qWX#u~0OjcovLW zGcyhlI8XQg zSeik{Wi4x=ZpChj^P`@vizC+`35Tghe~+Vb@1zNoZxvse44dY4nFX`H=|b%#TYk-j zie$5DXjWDsrsukOI0~8>@muKmG)32`-@yr=q2|i$p~yq>M)pjhyktxFTTpXjxFhnG z%3)@5C@Wrnmh!aRq2|bQG|IeK$R25T0qVNjIw3#eF2}Bj%V8*C*R%q1jQ$wj_ieb zb@5Ir%wk<{LWTR34nAl<_~Q`B)g4NJ;>`!QL#0bu9@M2RDTb+DQPoft=F))p#W9I=9`L7R=g9H(}kHRnoT)1P^#VCc$sYoNBgEELLSW}3pND|;`a zf6A(z3aFChyF)hVKgD>Sy!dG=pvGO%1G1qL?&A3scCVA6nNr>zdaC+f!~04dX_){O z3oqNk(hKcR0OF(l2w;@9P+lq)F$!Bn&B|A9?9pBXeBV-60a@mgWiiR%01YcZY!1Nvt})_+Gb zRP~rPoaXbMcuSf`9*-Vi9pE3QsG(NcX+BIoa?B4hd;Ds#u1L7E9Mn|CSwqo}`?g~J zQTq&cgRJ$KY^+bZN4Xwre{cGqbIEx&)?LOuT8;Hs^qaAk*6V_I zu8@7+V;a_R<$%eJSl>m{f69frgOip)eopFG`tKILit<%v=Z$8{Q{9%|hFsHxJ&+lB zK9P=ZT{;|!TKhOs{;KAyv9E|{i7!*$+92KrB?VS;s5w7sFy*z$J**+S+9@CV5__7T z4!L!6+OS{o^JTjs)3UT5l}%G_V?Wcfi8G;C>Dz#Pj{C4XjrO~#8du6|>)H-eUTY%t zhm4KgW$cekm%*W=+nXZno6;8JsZecHs>OcFWhTWzeqLlH_F3_m%mgTnta?ZPJ$0pt zP`qi&8|1azhPYXzN3Untr`3+;QM6xoUt5g*n|t@yvO-%G6y z%%FY0%=s1K0A^S9ByyfdCjQUzRVP)56Qs56Rg@RMUA>*+hsdGomf-&a00960B-wpj zi|Zc;@R6v5rBYH%LMv(1NrZ-E5se(miAExMT7F4N>?DfFJS7y9D1@C(DpXdeL=RM? zqR}ITRb)v0_W7Q_-mmMv?%lf|uIqb!zxT~xFizEG{B&e6xDlC!KUB*2`V~r*j9zxt zcbI>$r5pXCwLiY86gkxlgxo#e#$RDUBD)LT%$?DR{SOyAcR=PUHwE?=&ffVM?GG;= zw4r^zC$<%B`<%f|(D7*KJLq!Gu@)wJ|5X7)>M{$U(lzHQ47BECK2RweHmC$18)NYb z)_qT@S1GEMnKYs;)ReWrxXnx3;M#z!&+yG$gASE4pFvffaDjW+SNJru_Z#|OYeam< zanwp$lq$IgG=hJkKfBSf2mKw)fxYNg{;cU!DR(aJX2=)}N$(o1{wi5TXE>45XRjz3i1vrfVH#*VU3Ak_Dabz%uZ8`q(>n*F-#c`}5S844ozI4%zxR$Y zQ)Rh{-E+tvzcXA1zuzmf8Lm<^&8-Q_OLI@?s^o;*TkEN0{;s(PIa>F5`sn}m;t>?t z)Nw|rlr3S9^}Y<3!tp@K@OA- z_q|O%oEHcAC!+(PqHM1dwcq`#55@JhmH0o#D&K=pFnhpwC>&994d*9T&ozaTC2g@d zf60T;@3=1JimFABF=N+xTrYFWX*uqLR5NijWF_2Nhx@}g9q&F2zsvmi6ZcV+V|zs# z=l!RzH}0?KUY8l}H|s#zOFRcr3;*CCxUiIs=Og$tCmYXA@KCW7&rzVz>+Fa9gAVV+ zb7o9GH;$hFqUqkhp!yUsjg!68-eCO5N&+T#p}k>ItOEUSOgZfsHyS73(|Al7{h` zcyuW5ExfT>7w0XqOT9*JZE$-B`#o@eNBd=5r|X*6;>Zu}6vPeD z`WW9vs1dEzg8ntbu6{s!Ves5`Soq}=;*adPuo&@3mK>u`acc0{&4^o!Zx@Owj=9>H zP@EIH97Nm`c`Q{!JQUdlq#-`aBC7>G*k2}{*{f0z@^%P=tGfMV`+q^k2X<#aF5<=Y zuKs8r3T;Xq)d0rJ18V_{WQCVJ5RRRU-2VIA&1`D`)=(lUS2W6>zTYdblUjH8`eD#_$0>?YEB^3&kZW9e~oDmPM zK~6=4m7z-Mx~zM!{JFi;Nc6k7ltG!tRc|Bgr{<-AGOsySZFr}$4Q-b4=U>Sk6~edV|5S6w6!`8t2dSwLnSA) z-&kxvvfly9)06i=L)~?`P^jIHVXCrKe}ogPwhcQ7d2Yv_!YECD<~W>(->l_O(WD*+ zCFeYAsa>&ev>C2*<|S{)FDktZCAEt_!l-qflgH!t)rvq^{xa__ENaW^q3zi_XHUTO z?NkecqAzxtkgs*GiP~+4btbAz(aE!i@|4RyQ0(q-5{mA=c?dm*9O{CG%d}bMIIjYi zrBJS)7YVDqgEC>%cJn$YW_kU95=$KoHty4B6Ln}9_Ut>hODDW(hUL*UB`|o7QyR5L z8lI(o9k;!(Xb)Ea?K|Sof|3p=CXOT1**pdEr<8ir|0^!WLe9Ts70~ZVgAQHCetkEX zGMaM?`em*zf~`T_>J}=^Z*{mpznMBmAak*#94aO}FtNn*D6kR2a^-#T7fKM%MM8zpe(RRIQ}#!QEajU_`HGG5!8`jtqJX zjK2fpk9sA;tR(+4Fgtk%{lD0&cOx|S=eW>uKbKCR^^JpB3wQ0KcE}bVD7oD-56UJ?9S5TtE&EaX2wP6`dS3nmns0Y6U!?ir zW-Ow4+FQB?vdX^AqIoiEBF)FB44NnWOS38S98&w%y;(_^8=_u@c`UpmR|P+I6T6$-9?8U`i4NuLq- z7+n1_n02b_Ce*lMeS|F8=?@JrZQxNm_$(U=E;6(zUQXHFhPcWt+fYKDUYiOzgVXmz z>786Ylt(Tc1(h#qTM(xiEsw9ksM%w-LZw5ksn259y1dzL-T##*Fag*KO>+t zGN&Bt1pm#rXlS0);{+w5^ggUF(yO~4(7H3CZXeY6U-)b&8lUytR{TR4GjQeYUVLetP#O;Lq8le*FH9vQ<50v!FevI|Jyy%u0C7kO0W4R;txzyHqz`$5P(S(@l$}#EgPirnnaC$N#;fN;R^j^R$T!MoRxO2s-Kl3O zAL&|p5c!G7d!P^HD@}7&A%78En=C*+Bfp@w2>A`;e32{i9q!1!(a3+~>DwBR7cs)r zuc@Ow@9hrcORVm>bC5sDVn;9TkN%|St;nxbd3rqZEm3n!ZXfcs%yw}v)ur8Yej`6y zalY>t+M5nlA#Y>!OA10B#~qzC5p}K1u=ok`JVv>|9d)cM{{9=}fwD76JCGO3obGF( zeigZk$9%zlv(ENW-8$398+EHFLhvW$n{8Lva{50-?MrxKvsN+Xhn+2#seYZUmXEx) zpJ5sDdy%`^V#=GpOk35A?GaYpRG)_ZrJ#D@+}J9rA2O^*=ON2$r8d>0nI+4i;LNm0D7r8(mFlKF+8K}$6GU~ZTz1T# z`aK?xf|5a}Zqo50zfFL$Cn+cJKa#hj8t}g?!SOMW;r?+M&P(3e@)ypNd&ATV=Pi3Z zhDY_YyuujQCHJlSitChp(2T})iyXIG{D!Y0(ovT)9(GQo`fJA6K-6E{6!#0L>qQFd z{$J3)VnIwR+8>|IdXIL?)4^1Syg#|*5!E+pI}`Domh8Gv3N5Y1)#15*IkXecm*IAE z_D7f(vk&7y^yJ7c8XvY92J{{zs7^@lNA7H`rt#&eyNK$8aCKLo+n zU=1C2Bl`ywb!42t{|n6K&ZF}UJ5fvL*%#x7`OgZt!9YCVmN8?XXrh%d>Ltngm@7~g zookA?A)0?K3vz>Od=O9M`$YPPFS11SBFJjr6p6Sas?~Ku9Fjj;`3s6H_g_bRVr&`Y zgLox)?x2tOC1bBBp*UvAn@4dikediOcds%K_r$Rto1o}y*jp$`-MR|#k-N_2HI&PC ztVbM`D)kgpUlsofMx13fJnVtu>*)t5{x18XiMTA>m2eb_E(YjO+?KeVg52SYj1brP zYqwm2tokiBi1!>P{ao_LS02^_ky~m7DeqW~^@5*&sReSAS=+Imu%tVbkRMSQhV_PN zr`AJt*3Ur!SdaLZ#f?yUTWuxPRm1)&h92&oW?0Yo@&3M4XXX4%fkoY|pP)SdZw}T& zKi$tep`v+OHq}-9`~jxu57BdmoP>lUke9RVIW#$XXhpNRk70$YEa zy9rbN9oqt{CDvBRXW}Y+H&LCDzaeGffA^`C>XiO$Hu5EI#p_L!Kl%TClj@~}igwDk zesow<9v4s`q`c0+`8wroTA~k7u;a2h@;;9TXZ@grS#$;Rd+#*TcF$Tf$}`#EM4TXj$o1uqyn-=ov>PKQT$WNbc2SrNRY{(2+>I8ZARy@kP z*A1HwqYCHGqTf0A+frW631vgZ@%cuOdnk4QRE(bdf&Rxy?|TC{+1Wy{`|Bb@<&zu z10}P@*TbU2DVjJRsa*kGpLtj-)nkSskK(Alkp6l}b=h%^Ayj|J&vKya0){)x5-$jb z_8K!1p@)_9DNGMp@{{Vdg9VmU-*Ej_!%D{}G1XiDtIUJ4M(1x-4?Q-SI927d-36;4 zcSK?|Z0CK;fmsJfeujHyd5^MDnf-^<1v+(D?1Dx6zsAEO>Id?mAk?ZA4p?rlWsCc< zqnZu1b2*D)wULe=47R(m7d|?oh=pdJkvHJie!LtwDe==YXsl^l2O|Q5Tge`qFYwvf zPn}RWpZyIgw?>hZBHwgTd#`^x%t{;l9=1-?eFfJWk9!O&uQ;c|s0n;AEV2{+52iTg z^GQ2hyNHpEX+_z{cv36EHi^ zU<2JxEw%%6ExWG+S?zi)cn?YSqRUeHn@x$TE5G;R`DKt{Q_CLFNi5Y^$* zzXMCCF6{`t4Tb7@u~fecrJ<1T@K8W?`!4MTFzKA9HEq8(T%X2C<(}U(zrO0drg=4P zLk28*yDXOGQGo3(nqLX*<&ZP2odr;$1+Ho5HXO3>5d85%g zjpq5{4cgEzV((kT14ZSyn=tP8y-+Axx84PM-2R{gvl35LBd(PDPB{yM!Qw#jK<{^^U&* zv^R>ZL0ngEUlR|@7mgJ`Ki8xEy88H_8t+d%K}+&mMY zY^a4NwL2_F(0jZLi`VoXu;q_fsvE0H{)E+|<{3i2xJ$21ab5=JW1+`g0}m+3_oF&e z=wMrkbI1VY6|$Enm_`l<%&F!R<>KCR2K(@U^U zv)1@7rgi&@RVmhSfn@3$D35JqkpAnFvEFks=kjR%7fV`^4=}wagwT7}KI3lW3sU_< zo2Z^NX|6>+A(Fmx8TsFKPvjd+^{5w=hfMo54@&v64CE=y-+uO#x1W#*8{qI7?KX2nuk63t@(|4NDMkDC^NMv6ieHR*gdL4a_x!oTA2JYCt zm%g*u*L2W#m%8i@s&D+2vG~3uN_B4{@1K26zRDGm8hxhZ_>=C~UzBd*PQUlBucPlZ z#~9n_dyU(kJM>+((pu*QG~Df32!%mOX;5q)O5bUYgmx9e+Ba%dHN%wZ>~D9rQT_e;bS!;u?iyK+x``D$K@ay^5~cl=>W9{0i|Khh zI$lWijI3x8)dlR^RrLMDV*5tq{Stp>GoG(RAY6>+E(vzLg>k_3nX8TQ!R(qb7vo0Z zIq4gHCpl)5fN{k%Oq)UDaAE5$`cATAi7|a25l<3R{{F{=uTZ?ymq*`6#upwXeS)7+ zULQ95C%s3xW;q7)fV+S3EU2hu&VwSWAO~t^zn@O+%5+Q0|MP@HY5Pe27yMq@aIg%@ ze`u#bg|ow6$of~~PnuUJ4cL$?fBBo<*W5l`PUq(?y$Z`OJdJ>gNo77{zNHIokC-r> z=G_<_8?tecJ(R5s{EO!20f$Ik?*9P*0RR7N*?U~f+5ZRdv0Wr#QW1qI=|a*fl_VpT zZhQwxR7!5;I<6ZAc=0X3PozlrL5RNGA_$+UhiZ7=<)c? zKhMWGpYu7N^ZA_n84gE0;N2}FK8K?`q%bztDCsDQhKlWivry%uP(#ka*?uM(1rLpn zL(ylaw@`V(d-?#4QBfheP^EXBGZ5jXHS?h3)FCBMkvrYS6!)u6?t|i?ySkuciQnQu z8o3X1u0j53L#M$SdFMC(0>#f2gUoQB?V&U%otD@IMUOlK&5@2%_9K)(n)?tcZ8wb= zf^e$QYA8@U6~idQ83sd9zG({s#M|w3-Q=SL zX7vug48Uw*>iS_XD9!vX8uDy{k|F17#w94c8T}Tj8si=9(9R-gwU6kY9hpB~b8Zb`CTR41EEWiKFc7 zQ4j5PE1^o#PyppOQa+OU7rjTL+@kz_P+mLgE>z52GROh%v36M`tY7PJ8cOsNpFyR| zVB0ZhzkUv@p}LPz0hAazeS)H|zw;c?enu^w0{v880FLkN_W*+1!W@z zJ;!RaFOv_2QT~NaFv&~X51Km(=E8a}@lqI+ktBq5ujXu^aL0)?FlKx1a_IQ$iN!E& zr^S32?$A05D&+eDpl!307fdjVcB6cL*g6^tA~P*1zb(8$ly1P4K2TwHX)-Z$=H z(0G{FBY?_T*_^Z%e*S2Y3ALlNEV4n8OFHkjn>xglvzdzanVTYD@6*O-h zmI=kXW?h234*^P;_VZ?47qs`~@ix%((PTfU)c$!X%&0He33J}3pMvXc>aRoYri!Of z+f!G|73D~cF@m8}ejNc7CM#TFyU5B9KH2;*6lTBpB!qEEhxb6`3ip%Hs&|$QuIT4g z4wKC-tD$7+`7&7C->;DJvp=6p`SWxRLgSB7J7L0|J(RCze3%D=IzRAXPSy@9(zUTC zEUywiM!ESucdx+wtmFIWePX1Gq3uXBcevthSsy4kv!xZ^Njv*=J}kblH3hm2bqa@} z&2oE~RA!_Dx%bMHs0Z^2xy3Md$d^o*v@Bp1>>PD;3KVMpY6`V?PJWGg4yx#o*jZ|o7#Ulqc!Tb(x1@%W! zLLubW+nu5Q<+3-6+GYOdB9F%aSscs{Zi$e?nhf!LVwiMqt#srFXl=PtSb9PY^##?^>l49}zFB>}A z#KhA$tm7B~xhcQ%$!p83V6IfD3;l$Dzrc7dXpmMz?yH~9LDlVdnUFJh#bzj9w1(yZ z(^)_G&^+L4VF%T7?fbyo2%|TcH~dcBqWL5FsOl2rzVkl@H7~H8;{RH=kmi{~k)tvH zaOy=|nEc4|E#|9SE#5t-7m|I6tT=w0=CkFAyP;#%gpDxta9Awlho(nB`Q-T7H2(!P z325GPFPjGAa#sdIMdmtxsM^}-3)^-7@}m2veD$E`^zCwiytLyEl+T3gR`i_k$7b|= z6E{OBnL0~{(sxC^$Na0;HmeP`hdrxWd!XryEp72gCY1%ha^a8J~5R);V62&O^Uh6Zb>j z%S0iqcUnAWLgDksu~5`xW(1?0v{gI*0F!+T!l1hBz9-#R zZEQ)JhW3QYo@f8YI%m_FJs?m80kU0r@|0m(%+H`s9(2t4^uLK7lvqoFDBMX5GAveS~1r>HykT z+*((K{f020XCRc053j(!L~L&}1B%{wHevt5wN6_?`=$*+}C zTo-&jI|hnB^8dtsO%!YD0J%T9O0b`ElvfUf{P3Guv=6Ly907&?3rn$26pX7`1EtH3 z4Tl_^)8+kfec$OwsF+})GUU@Zy#>=`1}Lw=cOmVPkN^>Z;%L~>< zdq4dqQw!;aeAo6Jo_l7&Bq;A{Pw#>Irdz2w2-_cA2{|5JZ@*5`#NQ3|f*jqq2fx6I z?Y*FU*`;IuYUFpyr$YJYIbT1+`Q8s9$L~`!g%_=%cv1Bu2TGq3vI=sZ*PfwplCKJi z{udI2eED3D%k-R}>yCIXza#Jhm7~Jf2IUf+c%20KJz|?-)P+T}QGTW8?5B{oq-zu2 zib4Mc_9?}*oNRcL`_)v5^^G%67YR^`bB#9Zpypn5*U>^(I4Maq?kMq-&fw8 z)C!eLtNx(xe(>53)Pv;H_{FFf{*L#v4X7S}o7d;t^HGoTPr-LluhKQ8w^7f$XKiKF z4wn8^fp+1jv%C`RMa7#~fc7LEW_J?pOrqx+i}t5@e0dzT&$xr1pd=*gGTJTQqhSl$ zvwZ7-QRo-)n2>u=DRma2{|FPjbm<(xVps+gED7k1ey2EidJE*Mt~`Z~*>Y#}PkxDV z2b}|mqvgZs(1l5xx@}M%Xr2(3r+MsQT=N`Z52SCIw zrkw79`Apr|i{?2_L30X}4d|?f+){o&nqSL%&W4=8vxn*YV9x#qnpZFR4Wjdbm)>(> z)|$bGVVtMd12W~YDdv04`fD!D`%_jPq4NUcwU1!?*69|s9;vuP>x}wU{>NaJcZrhL zBXb{E(0M`MV+&wZv&jiqpE{-$iVj^EM&|;?5d+M>Z#%Zbo;t-5SKgx3j!* z0r;td`SVD3ImT3P3k+MAj6 z{mzk!@AA8uai+T+KFqkKOzn#WEWVM2!)LOva9APfe3PlnV3xKsO_P{0{1R5qRhLQ4 zbiv-IS9cRO%1K*qW?ary7Tlx<+ORSUB0`Caah5GV;lWQZjEBQ=E65lwM``NkdsU zZUPIJA7No$HB&o+#XGNL`IX;d`DAQm@#c$J*!;&EWRl%&a(yhjUuFI6`)_CE6V0h$ z?XdI~dyXqhSGt$wFMh!CYs@TX@gvy#X!cty{woX13WBy%d)W9tl7E|-zj->DRn1hz zG7~J>bv^IyDoVbkcV(`hGK(y4n#r8XbPHzjd1INM?Pin8XTfAzesH(@bKkRYXe_(m z+>ph4ShKLUWCpX>jBe>F2eB~kF*D;Tv(Y$&!_L&=<3?7GBsZa3}SnFb@~k=(s3Y*iZ0>fz}(FNU%2 zyPoOo#Z_*(O{&*>un8wdoev2MW zBI};B`-=nEbvM_Q?7Nt4p>wC0s(rhuo=^UiO7%3}av!yCi?Sc-J&h9SoGQ4+{}-y4 z^5+*R{&dVO%KxNJBlQ!Xf=()@S)>up!Q29Gxzo9t$I_)x;PW~Y3X8wH0mF|j?0_qN z_ANAEezeB<_&|J_J+e`t@d@$TQDvKW+bbQL)$z5=ELGQyjw8tLCZrr-~01r z2aMsY?t$|_wf-Gra>useFv#oq80bA@$OI@DaoY>}{bu0<6)s=Aq25kCl3#FjA}nnz zaE6UT291KsMr$4n{@BZC9BVJSFr)R%M?7CFyZH)cbsT>T7p3MjK+Srh2D)XOD1-9B zORvzm@*Axpn6t}8M(36nj*z0^+b+|2=H!v|p7QJY_bHziy}x03O3Qb6uCafS1(g5u z^CajzH6$9=rJhKla^K(f3$&7sub^{h8K(n=JGA!3Ics=&$4Kb5e)Du_9vQz83eDqA z(7EiifGQXE-k)K+ZO<_{&;8tNxPZ=g1p_jn>ESfj{J$z6gU!EyI^Vy~JJXp!l9?0{KhcF39;ol0xCe!)Y+4 zUwk^{H~Z)w%IBi~c9?u<%SITKkrV?P3mrosZ(#OhO8+R72RjOb{zdtWwfEhJ&K>Xb zV1isLkxZRF6Ly|zv4Yxx8$RHBI4bR{pncHK$6%DnY9Zvy=S_s!`}K5Sv1q=+mDR^7 zI;Wp7b|bW(9UDmJ`C%CrR6p<2KcU`Ak4=0?|0}reJ`ZKlzG+ahYjrFPYF~zDnbsGE%#6EdT!i00960EZKcri~Iiv z@HnF(ry)!?r1NV7Ep?crRw_xQC>E(nI^#rhigJVyg^)xY zx!ED4I!r=T`t^FB-(Szib?v(ST%WtwXIfez)eTuTd@U{a_bHqMLHnrsR2Wga?N_Mcxh{pS^}q69$mHdtXn(|zm(vE6HD%{RetgV&D0#8j5K5K5 zG+Pg-NPdw8`QBM8p#8~1EZEu_b8{*TXpV)_`DJrp(*5wBDFddLsLCMw;ae%J>2Gm{ zB9W0cKf}0mCH+vVckEikGVL{QJD!PzIWYed-?ofP;u|a8Vi(f-{LsPUKq!Ryg%mj zPeS?R54`}>PiIF#u5P^}RNl+!GspcRZ7)KR+sPPMv-rC+>`tD^fWi%PtIY5m>KzHt ze&n+GFx}A9oC}^K4UIwL6+l?X9DB>*#zu#G*f?Ct-eu2_)i%lT! z%j!I1y#Ln)T|Z%4W#|GW>J2g@+^4bgmLclRIE4|^2sip0pnllh%+ts7U)Fv<0sHeA zPOvg|^&U2Sncp@Z@2lVJ2sMFz$>VU{(D^UMqFmlwae^Z4ETtYyFg1deV}&D$!}LV`SEKM8Z0A!@X8w~5iYE8@Lk-Ko2MWu>m(g)kGih7V zJbD{BZ)O%9$Mv~P$0de+fpri6u*db)aWj%2=kK-`WKO|CJddc@Xo7bM0)_zA>o@n{zDa{!|AG8PB{!i~bwDYUC$CUYJ6ai>29=?rINJZw zGYZxO@psVkKg`%kzlVh$fZbCEspvXQZug+LAmjs`SH)rDzJlURC)g@$r{@#MH|~KV zv+bo&>-M5%$QvHlPul`p6Z8j3b@yDMVxnvlly7!F0J)>bRKfE2;h$ma#$6WZXOey> zUIkg&b-SqFxpj&9BW~BXb|{^!{t5k6(gdYD6s-Lk0lU4fX8^Xgx0BU zP?fYk1~zg2cL7Rn@V-F#sN*wf9Qr$RJCrWb{R`H$kNXNmA+2^8w^%hD5l|FnUqa(q z)&IJnkMSb|jC*y#0zUMg!||u>=Dc07HU01@SQL2VArza2bVE*uo&m;N&f1WlVbrO` zYoH+9N(viB?aG7&?!hV=uOrsog9?tc1G?{8Is)Up&#$~GFl2ML0A@Nr4~FHx&DsOa z7=N6GRWI}J!WuRA1Jq#*8a-n`uT*neDCUh^4RyMErLc?Za~M|I>Rg5Za6pg0D=M9y zLwSJ5U|W=D?^jdkf6mGkx_)*Egqe??CqhZb-@ilQSkIfV$a(i0=(T&>(3yA+(RFjk zT7PXGw7Fef?VR~vc^rkM?Z>as@uO_iv_CSWpN{J(HnziaOnm4JJ1iZ1p-WQ*8S#C`0^PaHs~)}0~wFPB+zw+Mkh*g3dd)z7j@!h$flWWEbiDCQUi)dJyv`ludI#31?sBDd;*6 z8V^GMvz5s({-it_cH{*9M$h&A-9{J{T;T&-go(>xl4-#ry56Apd60WD+6iU~@*QDC z`i~@M{t?<=YpO@bwH$rF6qYJI))|kG&FBc3AbTEkHaU(a~WwcdqCy4tU0hicdZEWJMZowSGs4z)(4aSgtEH@*I`XT zVm;)pmOh8Qudly_UcH4HIJ`8 zdU1S93ilJVtv*lJl_zX@42zsfYG8!f!4k+jzbpr8c>l&g)i9nv%(2LIgLRxCR#1H= zZx}Q@ap?`-+y7YjCCF%5oDM5(>_ku|T{{h~SZ>ja@?^NURYPt9e;<@ZKli0_AJbt4 zYbsXu;5#WdKfVpS{vMPEbvCYufH^CA+@ZVI3v<}(yi^Nz7mRs|`p{KjZ~>MdntcRH zgFnSW|FL$PAlH_)8cJ%0E}(ig+0zzwFNl~3)7Nes3o{R745j)wt*e{r?GLx!ktK{* zux3JXGi39->!3#eLKT$i>^)1r2W=~)b|Rlj?YiT3b}DQw%-l)s;lUIs^h&rBLhahd zp4y8_!E=XA)x&>=a*IYTwfB)#U}I0O9$M^ir=viDg!^{;1-$*5m8IW2+QvVVQ) z_vSA`Sn!(xpU$f|#iQeQ<#S-&g44P%CpM#>`uS_~-@%CXnNQ)9)FCtuC`LD)fm%AZ z57M~MP!a`e@61|9+fPQ!hGvd-`ZS&-r+&h?W4rlj9gRzR4n>gnX2LEQ@%>*vXn0`g z9GLkaS0BpKR(--aSGsRi1JqoaTtc}yr7@GnLw@5H8V|QWTm_%R_}jtC3qEWbHxssf z!8q&sw!RUTJ7kr^Oq&zgFv+holC}eqyrJ}sa1LyByJiAaHu^)L|HC)0G2X8@&{_lI zdC@0fmvMG7obuExAC|r_h=VLyOd#yI*u4lc0uv@vz78#8z$Cls^E40H-z%nk%`hAd zh4~#9F<)W5-VzF%_N}yp%%HN@nCFOH-XDiDJBJXc+3t58^CZFgXM3Q$*JBk_v06AZ zk9yYk0rM=eH1az18m@Z?vh#Jo z`qKvr6iM@8jfIsptW5lM98?r@`e;7dUGNg}#=f`-W!dM7p;q2&%J1DvYa?m@>f386 z$BT@eD93xQ{t2q)W_-sySCLlzgyz4mEH2W#*KgEesEmCbPWfJxPV;5W`imyCf5w+? z%%|B|hwGs5w5AYBzE7gu?{#E@kmlj1#+t+OvAe%wo-SdWsD(=1_9L_&;1>`Ac@5mz zP~%)V97=PYA5wnVz2yjGo?Jk=NGLr>d5NjRX+XY^Oqi8QIcCScd5|4hr7^{IZ>D8I z#numYu=Tj*W6EzkH$_9m5b;FFH@R7hoF}{#6ahIdA0|@nJ6fhh9@KigY7CTI9laMh zQSCT=1mu^mK7br4lDW>HJlQ<@Z{$n9T96J|_CfxJ|6d~h(mS$5Ity_$bnTK-VEE3pLMo>Y_erx*78edFJR3^xQ8u(Rub8|FNNd!}+Tx9LNP*X@6pM zEtj4!bhRcVBN?i!_cpZjQyuWZkUlb zR3*j?64Rsj@j&255`-EAW=4m8CaSq$qw z{+dGTuzv~e!zAs@VHiJrdInoVouZdQ%As%i!XaDhq#V{v+j$W(1wGH@|n+L%z7du3%X(jgL2i_t1FwCgc=tM=qnBTJdquJ1Dk!ISS(`Gv(8C=$dP`408Tw zwHex4HSdLTRi6sx{MC6Ms)KwqP;b23D2(UvfsNB?9x!FWGRmWuf+SGT>9ZHIZg>>K z(r;~dA;-d910}<)MqwTiHQn2Wa%q3YN*Hpcc`MX3vkpV)>sJ+&V{gYkgYxcUTA0u1 z2N@oU1=Z^Q&d7Dk$u1Yk`J6YZ#b^Nzz&7lt0Uy=0nB5 z@<7U;8btyO$E845BQ;z+5=oJ}vWeCk%XO~Z;+;(mU<+nP?Eq|JCPCiMwG{rMQ z3A=BV*EFwwTFbzE zefIS*LkDX2J1Mtmt^ZvJ)ehcbDBK#b6IRO1Y5rf{9#RVRWD9OWX7|j;kkOaW1}g&3 zcT*1Z&SD@(RFo=pDQ9@SWK+I-zQh=I33gKcEAnud1bO!sk);L4%wR-J1sx~b{|lXG z@A`xVT-XJ$JXu z+A5ft=5P&i@>bKfct=JJRH=Ta^Wu-kzJV>`v|c)H9D{(SU~wSa=M7} zliuoWur*3bxvJGP;WX?RzJv1YK)HP&4L<&eJXZ8E)Cww?Cn(o8Jnr#T6TUV<=p)fLZRZR zNh)kwqB#Y<7Fykf_UmFh=={6l5pz)AObfZt_G8Oj=x*?%H!M)j2#2l<1u3wiC8iK| zy{df%E2n+>2-OGnGM!Ohf-mXAUUs+@tm+AKgb`vdck*{fZ)nR54}x4nm(8?o%H9r} zJU7Qd@m9fZSo3{b8WbIRyAQV5mu1m@&s7JZZ0O+wP?A)h0ZaLD$#mWNJ{h_6>=xK+ zTOSAo*8MB#J{FfH!w802HEzCEL!ilsv8VL zCP-*qggYrz54xJ#QoU*EG`>pfC-Td*u2LWz7Y%bp9bXHTi*LA)+x;!zKn|sPEUPj7 zihA7}lcR>>yWeVIO2D`C(5!I8acVD#c9~GqwJ3qsA=)y-VWucd3~kjPy{X+)+*nG# z|1+Eqlh#bLfl^~P>KAyYmW-fw_4wIm>VKl5)zmNbZ&kt-e!070ox!_J)P5bim(aS! z{%6ymBxsTz^#{Xde4_qx(u9Y!4$!+wVO@r20BGwXnob?a1*R_x>p8!^{TUJ zTze1`3E9r6-n2eoS?omP*Rk2gl>fKpQJx=YPtT#@Q|4vL>B}Q?DW`vnqWoSl_`Wwx z$(;H#OtL@1hUJ}WK2u&-Pk9J?k7k!ZX#FMS!5sAf&26^JLfN0p{tz*(@PD)D3|Yi>_O}P z=BMa?aGltR^glSy;Vk_RuBh014DxJh0-*ep9}m`4zxzi2dxv;eK`*AmUML=M&l}1v zlvvaL&+Xr*^8XJ20RR6a*?nA0O&bUB(o*PQr4*7w!xr=fj}SO=1q_hl;TGcP^{b1v~_!}bsF>U42`vMT$bv^_-+ z^5Rq9>!5uSZ2=T8$~<9A*JmSG|51J@l!+SMsEzB+T2lpnez~dJ-Cbif@COjMhcy zFU{y{0?4a!{|Ob8UavvF@*_{&V*R}zUG#r@1tSjDOG0{J%$O2aJg*}6!V;+Pzp@#4 zuH7enj>Dp?1>Lay*OJv34-psjZ@_@*SClZWy2m?gqw#h6>uqRe*CRg*<)$>QgjH*G zPe8T82@?9VaqDrbDg6MF3u zt|C*Fmq1QXtp#MdiOuME(u29s_WM5z=spx>9moxvw?S!ddNeGGw#b5JCEj%XoIQv8 zsoa^NGw43fO^n=OrJmw)8!-VEL|{c_MjExm{Xw0OFSRu+RSo;z9ofwVDPn? zGcc_CRUx!}82Anj&Np&%@I3bmSy1L$-Ac$(d=v~_Qp(RjGdb;2D7d|%4f2yqM;H&P zth!Vma{8_5J54HKZeIB(7%Xcr(gf$bYG=YQ-WEG(asGxk zESeP?3p-61m!QIOrN=OLbx;?yj`JODivM{#8bEc!(TrVT_u-%SCeS+durrLhVYCaziw90Y@hS6L(Ce7E9?JCae!v1jw7MDk z`;xgOwBeuSK$-Vn4#2XG<3ebdw7;CnJ-hS~8qa(^avu6|e3=0h2Przhm|ZG?uyx|I zB*>Oj-h%PdUFu-!ht?l3Z|m3b|KNIm9-Bb34UtYzF~Kqfa;F+6!JKVRZ$oiL%`2EY zV$%TZPO{c8AJkL$#tKHQf6jqseVw6DZ|veknDcye7F7HCvKAwKpytkjq z@mH=5hFpP)FSOm|>j}#e0$t(2x}KF(zmdBQOnhrK59ate&VpXM8nt2W;X*Z7p^~Wx zIlJ%3L7n)mzo;KfB~sX1c!(5iO6{k9xbtlY%EcGQj)qY#zqIH+OrFezRShE?q2Pt_ z4mwuxJq~M5@6Dn9up3!N?VG7AJ0IV3!8lGj2YF5x1=S;IZua zW2^@~lhmaPt23U@gF~`UErYLSH@m?;og6>N)o9p9fo-I*^RJrz~>zl{QJBW+MAoS!DA`|?NI%C=SOI4pZozf zk5Qp=ny#ms=z8b=P<;-<{-<=j`X9PpfyKXt@b~mJ*B~poJQJpc?cu|PO^t`BUC!1a zuru$i2aGuB$A*0AIaBD9Y^n)4rm_l9;=S@M`i;HF=_=IxmbM>C+9TM|CBt?ibo%!7 z6P|~0{DC~^_W9&tdR`r_>!J8`m;sdRtsMsI+l=1fIXetJR|0vvM`gm`Uk8rRc&Jtl zr12q*T~EgwI~GC1!@^mRd-l@=$p0~F7?cqo>&7_Ki+u81{007v6^=-yv17%2(q$>}x(}4G%31^KKa^WTw~O1RQ#tp$W1tf|vmf&i@8W^C&|3G(1DdCl^s->H zxltTc8@tH|x>*z~g$!=>6v*6s`ZwmmhOAHZ&}N+XH5fHHH4Zv_w%iPxMGe+a)FV=- zdDJmYmgZGK49&xX?RXCP1_lMtZ7@KA4mTR3VA16Lo1iqs!Gh*>n_^|i5tVje{^wS8 zmcWX{7b%b*`6w82?l4!u?y>O>RIh4up(&zt@;; zlwACGIc$AA(hL^-&u9w8U0)nWLV>uc8*!QDB#jqP`E1z+qTjm*uDIDHsz%)4Sm#3`N{>j53^kkM<6#; z_66m$4khZiZwGbxtxz-0_$usHN*zM^4g10x$V@lCNO|_fg9A|dD~0l$dg0j&itnp* z2cWfRl`F;hlb_##HIB7RJTHZduNOd@0~Z77`L)+%K&I=SD%c%4=?}&E=`AxcE^J1P zai(!qvMhqeU!}@LDAjyiN#o}3mamZYMxu;ys?eh`hvICX0yd3ryG>i5n$^+06oztr~9+d!KjW8=V5Ac>_up}L?;Ul&Ql`Dp6Z`T^}kILz}`}Y)37yC zatykRF^Qz}Ro6qPUY?x~WE9R_4>_;TQo9&A5-TeIJB-@fkkZ7W_p^Q@mRDGk-LoA+d66^9B3&Fr2Jy?ofx|B!FUALSjFT*C-H;| zm}e<&ft}rTQtA($KoRqV;u~iz=xG;W3OjcdvY}J{R8QC(*B1uGV~P`D#KQTPVZiliDjxVhRH%B)+t6M9XvkEL=JdP15PC;hqy zeUHCsfbko-KVaA>Jyp!3sed$#Vef`8M<|s)5db;A(vL$Y2gj?Bmu&J3CWc=6O8Jb` zKpFEmVN2_qfBjb2S$*g*t%H{4BFKGPc^~q` zrSHi&BL>#ZdWPB*T5n4?(Yopu*x(L}{wEEC3Xl9!poO|l9^|y0ucdW&Mrkkfa%yH` z{jQ11okiY_u!r%C30}1R+ue$$-#`4xgfT}$@52c8><_Sk&6cNl;>;8ltY}zdPw`0j zXo@?67wn6JjCrifkf)Si30YgCC|?l|EgXw@rd4aTDaG+_A{Us~ufCV^k7(yK$X@vI z9{t|-qlx1AjoA!}(`puKQ9QQXb0NiNftj0N_fY)^I!>ragG{&gg%syEYCnfnL%(%F zv-6)vApX}u0rJ@w?$M>#OZX{8gMxQ zIxM$4MD+@P?S-ALmv=z^0}oHCSMLH86gw^Ikk=|k(D zd8?uE-1EChYi|K8sK|Lj@%r`a1F)MDr;2z!OT*9zmMmXlM{)nZi#Jm~uw0Sy9M;wC z$Ntn8TQTfx&S-c^KMf4>q+h!`K_PqgUc-xV&5ao|t z9RXbete9{hT4O9!2+CK1heyNs`f2pP+4FA5!Sl&#{is({<46y+ zN6z&l)bLRI+m6itp20AgRi%)p$GJwohufyZ6}ocqP!yf88!DI9dO(M?(B)A4ZLt}A zWqeZ$Ug1m}3Cq((z39*VuSBn)M*V-q@aN9{3-Hjdv}17CbZ#)^m7MpKmnsGbf+cd)op%yQ1R9x%J($8!WCeQ*rXTZlC^Hd8yfHFl2RJSOHN*( z_c38e98B#?r19<)l|t`9MT?;^y)V7nRiW*Uynf6N6?6LD!m=k9D`*~3wz>n`RXfka z#6P?Qntz^&X}%E~PxpfYXE_%bb3&K$MB5*B`jjV%$B%(UJ*)o1Jm$3SHRXkBsWIni zf264)9J1_(ucLf1CZG0inzJ8{p#70_jW(KBH&&KG+nIMWX?|U)br|L<^Jw0cd@6Q; zHZLZa(tgUuP&Jx=H`MfD-Zoa8{1Up%esBkJEDoN9Wy9IWVZgzRLr~fK-99?zE(nIU z<|f-Ae{8M??Q>Nmucq}OF2jcQx4u3$CR^_5K!v(<$}n$KtpeqdqJ{xlw{~=O!?Kyo z_fS)J*GuTx&wC6d%m;U2_oB?JP&boKe{^pj|Z(!oGmZwnp(y(IKJFzPVcAjb#P@J*H zfk)*J3d13zKYIu5i#|BLfzGqSRzTavN=qo5V>pZITmNDbG(IR*q&(TJ`6uF=inr@O z!c-N9bB=npY4UK)Gy{TNtQF|zz={bY)>29Cl6ffy$w;|p# z{LU+blAwL(Ape-m0a90X6UA-LYnMRg8x1{}(-EWsWgd_Djd(9lO|FgNM!&!+DE;x} zHs#5zY3HG>Qq)P>@1EknA3F43_J*xXPOPE0QK^^WP1fcx7WDMKK=G(kqS9Byr%^uk z)fB(hT4d9{dgi~e&?|h~W{P{&T+JxI-a4A%V=uo6O^BDvPB!LHe*E&p0g9_{J2+B& z{=cylujf`Jb<=l)*o#Flrp@;RRN$Vb?+d=ymYC3as}cohcxiVt@*Xpt8wD`0*dYaa z)`abYQHklE(9PbR@?TbH$Uo3}>$d6iy<^KN`c4wC^v`I@lZ_@TK=$-(Styas|4I4r zun5xZXzl=ge|j^7&bOP)r}7q$V#dPwm69ps-2=w-y+vMr8P%Wqn%be5twZf%?+8Cd z-&KaQuhVyxsVl1C;C%WY<#9=$m2iLc_pX`JzQL;30Ha|_ zl$R-(E`+?2f*{JT++r`#zC^&MH`L!-npE&SY*$q;gItyIwEvN4KIaB35=z_YINfO? zp10Y@eYBqB}O(uHFjwYeP?O3ehA~=yBETW^V&J|Jx1nO2F!aoIg#EM?#LLrPNZxY z6#m#8NcH;Pq5Y@^Mw2JKUz~TFsU7Cywvl(1`qOpa4h-7>1!C%@cchI-{#Gr?>hJ)F#TIE2P#WCgK1yQNGldH z%~uQPe>d}QQ9fp{y%O4{WVO)zqby7FQ`iyiXqwm9D|KkU@5mGjD2Sc7dam{V0RRC1 z|5Vv)T#Z@S2Jq0Nh(gqm?1(m{ldwBcBq1b82%!=}5+xxfl_W_Bl`Y#LlY}Nwrlb-| zNh#Aoj6;&7LbRE;>+1dRzMuZT=lra_*SgnzuSZ5kIrrSU$(AxQIZ+jRp{?n|lQ8Q3 z)9c(``nedk%ui~B_WB+2qAtCsM`*(uKgF4_DO$7^s@H7|gAFoae?m*aiBfoJ^0`*% zzwpQqlP+D#o6Vqoy6p;RoSYN{YsNn~55+%vKY)&^EsZdBv-SYfE`!!in*hse%@;v) zBPTy-EZuYp1~$uP!kSfso7ANcm%7fECqw1?x1FJL=Ev>OTr2PdwA}gS zFKF;YPyyA}CAGs;QQTnjE<3808^geH7Z<@`kIHS(<#YK7nBgtR;I?NrTqK`3+R9J#R?cZWrYJDxug-r$fUP13=%Vei?>DEv+8rtq!VgsYX z3p}Xto-ioeGd>Awi4PP(c`acxRDbYBX)3mzDki}C=Hx}txW3H~iiU=sf~mC@S@wk4nhG=uQyK}2-fq!@22BR0Q2B7)3>Y4^+8(NHyRrn@E1SDP zYn7uLVS`ffb~x$qy&zuqASx85`}K=}j-fS?Q16^`6x^*|d>F>u9L4=#Cwm^`bG(o8 zy45Fl?}hb!kM4x)cT2ZHL7;Fm6xV95gMC(u*Ff9ddCOso{yt~E=e7BcFd+L0-#g;* z_qj03c!nL{-^hg9jt8#Khs{pM9iWfr5w=ghb~NuBT=Iu)FM!QuZ9=i z-&h2_50%(KCt=wPShM^46ewD2JrO#{ipIjBHdgAed65qLgUdIkp6mxoQ@^2~*i~3G z!)S-nH?ZtKpISI>Rzd~)-Qx`pq1MvYEI3f_^;I~UjI%;~S7t(V_Z#<8Y5d9W)kr$M#lbrRVAFzXofd|DL(3t!w} zJPfNCu@0vFb8ji*r1GQLFv{e(8Fbq|WIW^O1vw2Eyy+|BYmN5I9?<{y{8q%>*!fPc zVbjg+&!E5g`1_30!>^=6-^>*kpxR#lV>~YG6AVlL()We!uUEN4;p^FppmIz#<9=)p zJrR_4%+Z0tSDtI|`qxSWVT|3p-=Nn4mk!JydG)Irp{|@#HMD*wErL0&zy9X@5+0cf z>woy2g{3aN^pYMh zf_Xn@_J{S0lRt8P4{>?~1%Dm52>B8qlx4-^#m)j4wz~Bf@`)(rH`Opg zrZ(c$>&BX;UC{Q5@hV7|} zgzW=5wnAOWy=72fF~bI?1(lA2l2nHQ&{{OUgZb7hn>tvu>RUdn3jcWp=2_1^0bfs* z?1Aky(>6e3(SSwJZS`$)nB{v^08@{hkb$CvlA1~A|Jq+}!Kx9$6EN^ci4Rm08{0wa zqNY(WPNVwAL_EJ?W(o9~)n5W%2P^o&oC}Xj#HT;dx3fv!JC)5%1?;Wa$oL1f%?U zUfaD07~~q6$m3Ib{mthNiLZjrtKHlA-WRS7Mmrpzj4*}X_fNaBU48Z)Wc%;$x(Tz^ zyT5{xQ9(-ho%}OLTfmO^-#{%KkH44!^(ag^!b={9yI<(D}m3Q&8mc z=L6^&d-glDj9xMp|8Lxum(H-s%{vU%Z`DrY|G!`Gg2w|S3g};ff*tzMbGLK>G`1?= z!u)*83-(jlO||T|887{^q2j>>PkG*nVNI~5xljtt^#}Jw|MwpEyBf?GX{ZTppFA85 zFR7S~VIHroPfH~#TCn5u2@UA%GguYoiS{UQy!j1~<8f81PTXImU9;l`bp2;C>kI4J-V)Xw8*CETuII_8=)Hi`y#CbovoP-OPp}r?C}K_t45Fp5K(&6Y(hKxnLM z?$EOT>>wUbyLSTGKJZC_2HKwYV3z0MN|?IRuNg{wQ{@mJ3(tQZ0lkkdFku~ItI9YU z<*m7y+fJXup)juY0=NH|R|qqHEq}*4C?rw=@j3b4ld({!p*k1F`HtMkcwc%V5(+dQ z-eBERF8`eIK3?Y+RBJOGiTR=3ecepX8_OEKSofUQJqp$9XWis{boo;a6sGU%$$4zT z`Z2J)@z0r1km}zo3^Xe(G}-@*L9 zEJ??mbxp-p=0$2#53wFeDK21M)wCxliRX6?yUqGTamgd7QupQ`c>Lwm54=y-zdv|= zvPc2>onCO9D*Uly;b_>Wc$*RQ^uNJ8vE@$o94KCJ+nMJbwsVIKCA+=hiohoUu>DR* zF!RMS!$UA6(efD2ZwiWsyMtFrm~ZYJkOaHtmp_@$u8&WKUG*UC%F8dqj!W4WSVu?? zCNht`mdJc}b*tPdnDz5k3~bfB6v;ez*rzZkyWi>$IIk#R7d^a@bxViR`z_3K-J&VVCov9%rBm-7h133% zJprY!ncQ8trCS^O0l?|ANe%CU7418EGG=u6Ix%SXDr@;d@ zzMH!XKJzq*hI$L`BticXGqa)ErHBgH94%t~;S^sXgSw=7=`_|slT6>~z$v~~R?xS3 z`yyDn^ob|@+a@{?=DpWC3{^(WNrXdo{q`4(8eo4PZt~h*1&5CB-N3r4w&@EL?Xu`) zjrTvZSqbX43?2qA?@`u-x<1lb0_$BjyFkbN zaw}kPh7Y$Nelq6q49x12Hv8>^=Ry+^tChF=xL>{qScJwJ2YO$~hm{ZFo{hF$gN z6Id2x#X4OyT95;EmC9~HnJ*rx&~!w?MffaNm*dUyv^vLG?yV5knQo6-Ij%y&xA^e> ziibH)l+`{gWB(s@%N|DDQDwa;_hhLF*8$9J$3vg8P640WaAy$T^V%#qDA5n@KwL_$ z7B|A{+pDXgjQ)hj(9KBwE{wCQxej$lhM$MV{lbsK$F(VphY8F7_T&0V^;{2_8**_G zZ2awvHSFluUH1i!y3Kg|SnVzAI-$++Cd6X{;ZxRcuTw^gVaF2Py{x-J4LqRY+1az8 zM8#JJCfjxNgGJFYKQSM8<`sQ~E}kjhpk;h(2kS8Rq2HnNsC`uJ@BRNzZ=GP8V;@Rg zI(u?{37jKCGfcbfnDmp!YfNHjhu<#luiw0rN>T!;x?uoqH{V06qPmU!xtB^6H&f5+ z-TPavzTy4Ss`dE3U3FU%%}%f5`%RB1fq7?lXY)BbFUk6-z~^-3>m#B1qf9;KAxf5}u(Yzx3R?Di zVFTUPU1a^~rnr?_FSM8i#beEARMI{wbuqSux;N8!UC!5|GvMn_b+kQb2ajjT?c(`@ z22X08Hhd2B_Of7oD?4?I7W1a5NgA+x_`%=#{A+W^!Blfw9X?k*mFE4rPFu_~sIl)2 zn*6ohIBG;2M2X_$~Yk5r{ybv`vnjnp^q9#8zgge6%b zDF4aFg7;rJW*Y3O$JyTC>@hR>JIfqoyH)I@Y_Dkg7PdEL&cC$&fPlZNmtZ;1EB)1* z&lBWk)1t?Te1GAkOKiV$@=Gccu~x`-Y@Ep7%{xDz`KJGq#oRBMXUXfF?|-H-<02hRvv+9n{AJtKx$gcon*Bq@P+<_;x7S6E|Lf-d-_Vb&ALqV>cG}OML9J5P z`>>^t^-UNQEW8L+LJE&@eWE>dANyZ^;U?G=vT>PN_wR2DW9{!6LYHh;Ramn=UW$BN z{zmC5Xg&KzKG!9xPG90W#h$OB%lWb;KA~QauJ2z8 zV;65rVf}D)LKL)X|LzT&?pZmoJ}LD#f@=QF1GrvMpx=VJCUxSnV%AZyXIM8SuS`A6 z`sqdOcGgwel`gFFB9y0by<+z-e&127TilP|ZGumIMqR1(#l3>-4sUyALjP485}{20 zv*A!Y>9QZs`^(+~O7EyRL0N?bHe8pmGZsP5^UAu=aiSI1Eo6o%59W6!o3{%5&NRaI z7wh0#s_jt4(y$Sx&AI?2Gb`LHE;#UmacdG0CnKeW6K<|rQez~?GW?}P^5qLkULV;SRE zhkwYK#q}G%7Ov0OZEcNaJudxz8>$5Se8b=4X+IUN6Q!@=?_8uD$$H$eAe;4SgTkCV zsP^*Xd)DOvgZr`0bo!*rx_Y3_eAs?9*_Z27QEmw^Yf&Y?m-%a-`O5EVlFrfSKe}PI zOJLKSN#RgB$R&&QVy|~i>}Nas{m%8Y_s48toa8&}!_;T?r=ah_oIL1ily{1!ozTB<>Q%HRS=nOt`Hd%=i}(xWbV8i_NL`QxEP}xqRA;@v?0=k>+!oY>ji=gs!A0HmipBw{&Wb;|~yVYHO0n-wT6_|IqMNedYaw(hNHN`!$ zPO{E#eV@;~XZeN?%$p*UxZYk=;bZ{q(*CsPdc4lfTC$J^gj5V+G<9XK;0KVxNe}H zZ&JqZsLL$N`5mEC^o-wI{~K8a1)FdE1Do8dYhjkH=L_!dJ-Qy|%>L~q@4ump3L|^{ z%k_$#ZM5av!8iOak#^`E+q35Qd!DEN{R7{(&x~f?SNCHJREaL)cMvy89oI8N6-%Ye zqtlgX#CwHKC|$X&Yx{oy00960RM~kvRonXqaD?1KQc6OSBuPjzC7BW`Nl40&N|7n^ zl%%dABylo@OM@gSLXt{`QzAo2LPAKw#g(L=&*S^g@2~f3owJ9v_t|@`&w36EizbWf z)K*Ov7OR$7Jv!aV-ZJ<9*JfcqMONLJHB8TYw!L_^E!;Ni>mD~!{pGB=s z>~%2yoo%~n{DyT$myldel`r|G(F)c?T94m}o4v@b}qLHoOD zoG^6F=sYO;;_w2fXvnr0rtCW^2%R)?L|~)2`6~L{f5BR4a8+sp9K0vG2^wvBph{*a zZi5;8Df;l%`QOIWUKVZv=UIu`!pUrfMIQJ@c9SF0IA z<)U_TSg_jN8j7~J9f6?%b&jx3r`Z+8MP+!vLpEkUu-Vfk5XxrhhC)7#*a)b4YQa?) zto}F&vdE=m!iu%3xpcn4*b->jQ1S}0i4C^U_qzH0P_wvs5*AwQnXiTGD@_xIy=#)z zLw+u`t+3^GkueOoYiJ8iq(8gCkdG}PFlntv3>-cAEEQ&*;?991EK7=Dv!41hnBIG) z62|1ZR6`HXN+ulI5b_!_j;*eNRTd|yozNrl3if2$(e}T~JYxM9;ka)^7<8?W`k3c`^oBmL_*x(90FDjn}OEQz5LAH_AEs(4H z+Xze=kLA{xaXQ{{H5|9BQ-eMUuZ`i?363^ zFyiqxC&*Uw)g4ay?)8SkbMk!Q!0BLr*y*I|2bI^1dqFRm0ykJ!+jtyiy!&Mh)mMKt zg$`Q+wo^YuqE(^MGokgcW8j@Av^#ug0erpx`ZTU1>+-?xFs0(jM;H)&q#7<}KF^2x z?HOq>B;A+plTr-38{N;>n&z-|DV|d;M!wu>AQ>-`n3?nl#KETB$LG@7P+F^Rn%71S!hrR#( zeheGEgC4-*e4{Mr_vF`g7-yby74omGq4y?Taxw^dJ?n6%{rshm!2tEq{V*Z=oe|`k z*rW+tEhRTXskj3YP-~x&0AxEH$N_~~SjI6fMOgcMg_HSX@8L*|QZ;;2^sxvAR2|5I ztqC59FlFHA?6{~X6GY>3db|r13Oiy8kIK64g$f%tYC~bJYDGFu;;yp@m+^ExLhM?{t0%+nUl4W%@18|K8pscjN2u*)IR z2r^c)N>kq8Y3HXr@-~{4asgwC@ zX0LKz90Fxa8t{unY`?+rnTIhw2SJ7oM)*$0*N^8SW0+QN@vVG{ok z{Z8CDEAjg}v3Kr)Ec3>K;nbV)Y}oag{T)3groShleL061cI|&!z9B50LBNgzJ_ zcfGwtxmEM~qe;s7N~-@-{$}ayr<^_{-$DIJ{MA5t`O&>fdVk_8iz%O{Z_TFnreZvW z-lHa!7+6@=eU8qrzK;6e^~u5qN_kd$(Dhh!deZw?IqXl@lQ%@$552d)O8ZIG-lANe zSNIr4#F*E@VAbx=l*8?UMxgT!Ub>Efrpo!0PZ^~GFzCaU6)>qlPYOER@Rx@%PM&I% zceQ4w#~C&LY@z&Y^(W^5jLy?_pd8;S;{kKtx(8Ff{>Xm`78ov1fX#nx$b_RWxE@fx zO_waC?ar)tMdMk|tM`bJ)k*G!UFSUPVZr0MUQkkb>>PBhcBA|k zruFI;EMs@3d}_&=MEP&UR$n%LfC*mmpJ43i^^`NLcKy``jZQdxq#T*d+YI?mR@PIF z)XS@(^BJ{P0AWC$zflfZoBJI0bX+TeCz1;bU>>767nTls+@XG)(z^jipIT8r>wgX< zL0)OMYcN-3ZakgmWfxt~(X&Qz)W53N^totpDs8Xd3FK;=?07Fv&P<3My3my%4!Deaj(9=n?&11;#|W?}CRy_8x|@KbBEW zWm|hc90rx&OM%WuNAJT{^`@8bXhQA>XwYLZNZTFrXVb%TmYgI2bEj+9z#zVAWvFl4 zwjIV@ytEIB?$}{V+xO)=!hwGUJz=ES)c`oOKKl&JPHQ|5O~b=3LaFVn5is_9>u6Fw}0H2b?HZrQ>r8e6fKe-akyC!-cCmpz(!o>M(DM-+CzR9wrRa znR4@}eeB0LuCFnvq!Y>|zpH^=I**I#J}k1i0o~VIMnf&7XdkF5e2{XxuvwulwAy1J z4KJo8@zVW%zhM-=%R`qz%H_=MCgrd>Q7{LVmars31Cg$9$lh^12=-JlDW6-uvOfx? zZ`ALn?H!_a!su1W+n`;Lvl2AB8n_NJ7Cl@EO~*!-!ikbj9(ta5)7WYKGtBr!&#SK8 zIJ6wyHB8TC_NRV0v)=Ef=XGg5J+}c5mES^-Y?E>tH_UzMIS(yJx=HJ|?tXeN7_#MI z^u887_oe6GZ;JB&$oA+UXU5+Un6Sy`6lDK& z$POC3(x>rtNrRC#9oPMs0u(h|Ar7t7_V7df!e~}_^qTGv#_y02lMX0u{JR#)*L95+Wj1hT+%=?mtE)=&QF(rQ4TMQ`2o)_Vo;r@VjbTH7##3dEmYb#`I2&muUiStceYPxUW^N$$b#v8 z1F4XaZWRYTL^rP(7?d#$Oor?8==> zxrMpAhjM~}L=oi{wPg{I`-A2o$`?jXvQ*FWy!#tD%jceD4dwDLPg7yXy=r&L_5a-3 zPWk*fp9mEESu%ngryo@Q3J$2`X24soV?$stYv^IheNP+oDX&lF%fslwufnh~x^Oi^R2;1@?(!ADsij=+XuC(6lhDcI%?ey^ zu)s|{x*vR5uCzY+n2`cYUgy&Nij~ZqqTE`%c0JWyoqX(Qozxh}pn7Yufj(2bWtPruX5&RtLzw z{5|EV6k!f$dhWaDlefOepM(=jx6$_=sYS< z>tU}(#xBSlo=5r3;&!SIj8Tc(O8vbjM)^*at#A`uB0nHU?`yr#dV1d?Y^e?!^pvrd z>Yz*~YFqthCQHY8wujc)Ou0dI+CC~>kFLvXz6p&B#mA^$a&djfpq+%jJMDKfI{<1- z*Pn+v_7<0^AMB9{RNrj;kxuLQRUhuqePN6}r0dsXmeT$9I!X0{-uSR4*l2t1GmNb6 z9HhGHUmJc=e|k*0v}Pv-VV5A#l^3{ZdCHVwjCi|WX#KV4L}i&?Hq-+NpUr0pN7Wzha&lAk-N4*F)i z4UYIHwopBfKeUPJef#Q6JTUInySkz7WfN0mON{j1v_QN7cB<3l>`O6EN% z6A*Y8hB5fbTOoT$LEruKePq~L+V6xx9vx5ov;Ql&Yo&QJ)fsInyQ$v#{Mf(n##|0o z_LD>}<*M5EltU*B#6)0!-zp_2_om$#PRFr0LD%m(f5Su8-%_DO(91%~n}(O_ zV4F~L59QW2l_}^~rp~v0MvZ;v#G!i0S4HSPI-v`L#tQer?AtQ-P^Ngy6&C*x41g!j zo1TNt+m$atvw{UzU|!;~cv#-KIT4oXJ0!zky}l$Up{7I@>!&5q{=Dzw=<{!`vCuMQ zZWNS_P7Q<2@lGMoj#JtfmUvuof-JIChhQrsWfzpL_^C$yZMK$zjg5H=p_FCOFI=zs zH=!@kKFfv)yUwQEgKTwDS7C*Gj4v!dRd5KV^08{egx5Zl`zNafc_{x+`;Sr{F1yl7 zb?GaP6;v;`eM0LAiTMm#Uo`e-qU`buvt&tk=7acyAS?voni=Oc#kQ= zQ12oMI3=L42=cz|<%WC*{7BK8vu%c?(|lU@!a1Km~QlNUd(r!{x{pWr3fu8fk@_NeMR>Jf?bokzW zPVWUnu9*Ih5Lib4KZx4zzeVe^shij7e}}X3G_J_yXGTzdPv{Gw|0kl#Y5ZxFo^*k4 z&U91mcV4{zAl3Kh`_Q_O&qBojYPhjb{#XA`RGGFvazYjk>H14R`;4~bwEu?V{Qvu3 z;4jE2VarPEO1Xv!?b+vdi1PW@8-0}LIruwiJ>b5O*4?7R>l$hO-yuWmZG+m;3YgOE zTL!a_x6%5(f9XIT9j7dY*4ZiLUo)UXr$`Fb_Y+lVoiMP=JDSF4=08+7m3;*gp39!F^J2IQoX5v;oazSBH*KkZ%oa;ppZ}EIOY4!akR4Dk`iTY|XV-m2I_^ZM zG|eM^KUYwFAV-?k6=u4Hf6@9SF=9#!zrThVtt$-7b7@_{Z(v;qRXKh>g;R1`xv)a2 zHU*j;8lnH$>;^6Ae*y-N!b!;e%kTu?^it2vrY5=00030|18;gJeAwq25>?}l1il#Qb&^HNRpHx zNfPo(k~$4inNkNwk`SdyG)R(!M43a1q@9o^IZ{cIkRwebd~83c8O$=OQydSSeKR1l8XrS;2BU zH(hvq_01{p=j)Nf;r=`5~08LXTEJsg{_aX$^e66kaP>A$dK()Jdps8RC+ z*4%ZIz;S46&zI$SI(I3<%4=eCVfES!-O#xJDt$Mz<9%B)=x=!BpCw_?d`3tzw~rZl z2dWB{zJmD+47*{;>X9RiaNj>3SB5q>3iM#H(k*KkBjvaS#%Cz*hRK^<4#U>CWzkSR z?ne>~N@&V}dRM3B!|V*bVmLLerxZ3_)w>Th9-BRaQbA#rFvoo#jXw3^F)ZqSz|RZi z%^yHzt)=Bq$*KDeG}0XySFdA80rb1JD;KI;zRQG{C-1ld19F`&@;FQu#KGPLSv=nT zUrkOyQF+agOI);!o!B5w@ibK@@LXB&?x5MZ=xxTPeW7>Xbe!wCEy3RWt1D$K{ zCUe{u^K<$Ahe`yna#BepG!wsF58LElv_pT*(jV|p>KqB0#=~&amntw@Ttf%; z{?WJuCZ+q?!i|4rZ-(l&)t*peZ%8my%r-p%otI6Dht|!zv*G%0lWxPGom!Q!=D^o_ zsG|7c1FYTV@{`*gF_m15&qEaCVC|iCYOplFQ4b#1d$t@lI8Iy#$39hZhvo7Y{9!=q zr7&3ipFu3tGfqf@@`3tAaH#8}$I#<%)z?sSlI|xMcirMU3@WY=HtE+k`s83(J?*+U z>`3kz2CZ8QC1J^wFI0PWFaLjB#GBi-iJj+u^3E>@!AG(!ef-`xPkP~CgSxL!rb58) zHJG8%2J2UjXo9YXHD5ucEgPP}yegL`(DvW26^jR+r@K7vvJL_4HI6NYMUHQ8!Q_c5 z{D1M?L!}%iLF57SJCXD+ucvEj9dy2x`wq4bYwd&*#+E$Z{W2n>pmDdM5>(w8stHFG z50#UK&4kB~4w(cy`t+rs#h|mlQ1{nsuKWm1JRfsj(2h9s5L)M%7IA)Y zOG$&7UnS2$_o%I5u;H0$0PIz~?+Hbl^R~ez)v+6(t-kguC_Q$}au_?wV-b`*zL4|X z!pj?GLC2pzrt*8@LODNLSsjvs2Ic}0xN~-0ml2M${%sSCo4t)WVrrFk9+dnwn)AM$ zTOad_Y^u&$Zg1_k5I)bbR)WEsT_yRs{kbmWqShLhI_PjrP-ZxATv^ap>*-lIcC~W3)XEIm7yb>_q>NUrgi}*l)U*>ZwCpt+S&#`ps z<SJK6ME(faXELApNqvH*D35FQk3Jlyyo*UMOiw%C z4WIA+(#c$xJGKk@=*|2J*X5n-fpPI|%wy5VT!b->PVEk!r)Y4^$p4)W^I8A%&*SMm z>aE7}*&fC7>wkZYc-+@7EQhN9_h1$4MN-~I=$V}4%DP}?cxUmz^{!(5{t?D{e?#hN2Xq=XlzFa4Mrb4y8v9)V=4<)Sf`dj#8o;0X4_cTE zjJpoXc(u4Q@BKH;pYvEo^HDhAQ&P%{Zv2EdB zm=Euzd^Z_*Kl-4Jv9jX`?Gk5j2R=l14646tkQGOJwa9!!VJIbg`=HH1mxMRCPJ)z~h_p)g1aK zOj-cD^3JHi+LtpY!tgID;vDbp-EX)KNs(!9nX`A#d<6UFx$97ASxX|kyx8~{bM(}Y z|3J~SVqR|vbz5UzU*}*|=JRJx%&pRMo_xps>fQ6Z39j?M#M~NuLhCk^n65u?pF5M{ z`5egEMKZr`@jVDX@7b{j`cw&a@OjFUa)M)>F06r7Mb}rr_JH@yw@qi=44|Cy1RWT& zrF|9@biA7ex4y|%gxV!O<6*w%gOPmy%%(_izc)F9n5(;f^s-*88r;eC;5!SxciAID zo0)IxC)9Htb>sXqSfN?+gn4%F2)-x%`Q|R);~8;9%+2v@u0i)i*9_RbL+cXE%XE*0 z%7G7=tJPol9D!kBSN1VCFO~FTJsEB6#rM1UD(hCT(yJ{TZ%oO0=IY&>>{+KwU)n(X z{8ZLE18GI(ZMDoYBPi9Tw1DUFtY9wJw~9tw|8@NHNsaYuulY2dZ+MI%kF)){EWg*N zRho6e{^?L?x^x8VuGy8zTvvb0>f(C$r(g!xohHX#bDe8!`igbCT44j%tA{3-U*~#v zQR8Li=<%&%-$mA?>B>UnA2@SQ`pzYFFyyn>Wm^_ z^6QX&>~l=_W*?*>{|Ngc#kcF(Cy}oBVFF8+9G=Vh+(&sT)YMgEZg4!D$oW3@kMc&U zV8VV)z3iYk=7F2N%-J2nf$Rh2*c~!~D!Jokuut@PDW5Mn$FxAQ#<}M%sDoO{kFvIRiZfm{q>FPw@ELU zJ`wtzww?x0T1?e~m)9&XTI|vKk%AA6a3bJ@V zd~ZET=Xg1dx0q+Os;c-s4|g_0hyIlrl*tNZZhQ2`o_R4wb1v6mLP?Sa>~rnVS;4$` zNS?V&t8Fr$9~}wl5ZE{;Ba->jeh+h4xy|i-_Svcjp3fsro1gJHa{JBvRr^Y$8`{hr zHw4dl*M^&1Z+fhJF$D@j_b_+Kx)(2kzOwc!nU9{#-v*6Nl=#59&YuVVx1K!(3w6G5 zJ?!9WpTK@V8_w~=rc=pYN#>cU5ckBIGSUK#UDCV*84JX;Ri@3`5w5U+o z5w53S+zW+T&$e-WU9LYnfbZ{>vfUiFJkuMhnu+h=`Hb4cTo^gzzs*qSa{dOcuib0e z2Q>MwiuqABA>uFAllz~zKKGpWhbwfnUgX7fcZD14hl*6(LDre}Stpnu<=t3k_9tB7 z`AN0+WU!C+u#xphZkHnaYMD0U*oXW0K$QKo=X=W7PqQ5n#k#gX#Gd`M{&l<%>R;2^ zuj~^>_qDTM(S7+8>u0M>(`@FYRZ|S1|4Mb%V`Z1>HO!f{LhP?;R2^pDBz5#@)_dje zBO}=V5Z}sq!B%P}bEuN5&kb1mWzjv(8|~7ZcO=JJFo$NVMRh^F=r-obeBtw>VcwJ& zCH8*~rLga#`YYHF2EB3MyjidNdp&cgM>zX)&dx6aVD-K6;n42RV)p6GE$z}dPF#E; zl-jtZoc+3cJFB7Ta5v_&$X_>_IloR$dk?*DH++VDe|dGmMq9%k&fiO#dtted)h~|s zX`T@BLV3zLVfMS?imAD_Jo|sHSugo_&+-kw`Mo=ff3lD0rp<9YvWGJl?mRE|1rD`r z<@cuse{5lHl)l#hv!6DzzbH|lQp3DGx2KZ%)ZXL)bB69Jp4a~6j_gOOzC1urR<5P% zPR8AX6KX{u)VEKCf{oR);n4Br z%&mgazN?wPh97W)RpX3;U}O5a)6BQ`ex7g)pN-U-{7U(F8&K<}3!QShhx4dzW9bFETt|K92)G`;xz6O{SSU(^iu zbH4R>sQMynCX7;cHH1ckJFH=P%*{X(&Z+2hfcsZ%GblF_mwdq6-^j>bt?FCPTxqp&w6UXac2c3uh z-@+o{PPb%!fB3U~fzYFTuqRZ$(6yP{g*;fr&%3rQ;d$llox{&Bc`HG?AM;1RxZ%aU zxE@LgA}z4$aP4E}`eA=vhkZFKn9pV2+Z=#3FP+?B&^B2c*s-!>9?UcRpuqiaS`3Dw ze|LSv{fkvP@Els?1@itzj@QnH74_EfT&En(VBcDIjX@~X9>3BLW*bF#z<}1Jn_)|M zHT&S&mR?rui?7l*fn)tW^!U82FV*CGCVzo_^g4q;1t@#vA)n8!4NHczAARqT2<)G~ zncrh2@;@-g_pdkEhdz4pDf4o8@O|cL#YpD)==WOr(9!O08guzF?L^j_6sKsYmAR62 zMZKggg!z8a#oc`GrgXCY$m}}q2t6}S*zx^ocQj|+NYv1WlCK4-bF^yOV#7k>_wVEv4>yTtXb_5B+Do-y>ozC`BUqigs( zN6}N=!?3V*2J^S^7gZP5b;p#|Fw?cggyU3fW1SD1=+C}GV!?X}=HkiW{2fU3U^{<@ zdfv9P98O(*APWZjCq=V=Vl1%WZ$ zu4lWk!T$pQ0RR6?*mpeD-~Rw`;$AbWQj}!XCuO8$BtDI)V;Gu!vP-k)EOpTC}u_dVx*_IaK2zHDr=38hVXn2k*@*zFBy zHB$5p{LN#O3ksbWxdTpcnp_791B=~sJtRD8ocATFCLt^*hSU1q0#+5I2Lo{In_>u>RKv& zv)?b!(=ulQtT|jRxRp3{s9hGENn}$8{W^XbgT2j?j^Lf%VSjL8uEYf}m(hC%Ov=wL z1zEbc8$p3nCkDW@`Y66_#OvPDa$r_Wwl>I{RAvbpS`Qorqx649gAS)SZh`#w{E9%m z;v2Q#r_h!*(6ja97}#XKoll?WCh8^$e)=w=0`|wW>VOS0^G!fHkLfWh$m0+0to{{1rDyt{q{>~t^Ay+`)<`{{3vCSqpDjK>1} z17_U(%Dx@yUlqm&nnivS1-YB$q(D29J8Qt)@B%gP@v0DAQ2Z&!F3@)%$Qrb@vv8sE zT`2MbBSs$ufol_tV?e{+rbIAF?|B;N_EX{^c-r#q6R^V5ryRV)^Yt}Y6)Rl}rp3xM zfLT)>jiB=OiO(RfkyaD9v9t9H)!y%uRQf^3UMjz6^65INUjfn8U_z--71*+59#xNL zd`Ag*eV$z*)z8V-xl}!|-FK<>d;4X8ii+kpz=g*&lR<26k^tsw3C4r6Tb<5Rc0YZYqL@BYYA6mgDU@e=2O4350!%as=RMO@882zzaHwUc7mY6OF?hR(~6+Ql|5TPvlt0W&}!F%L*U9a5n*8JN?dH2;kP)IHF9awp~ z_ZL-OcGwKKQ6)~)ka%R!MiI@HJBEYQMMPXp&+Q8G`a7k_; z=yf>Dn{rzMRsKqk21n}sk?niIio+X>!OsHQw5j(t*eQdYWqvED_N0~yfZtA?pN9S^ z*PrbMR*sP!v8&I0uo z{L@YCe--tg;Qd#psC}3u+)@LUWo1-Q=|QH&;O_lpIaHj`^`!PyAr4If>CWP@;LV7m zA>jE-<=)_LJ}Gywlv{j1wO=eXO~Gf@{d!cKFL>HFvy6l9OMl+noq^gEY(aZzV2v90!0`OXF=&_n}evh>~qft z)YGjz4qjmHJ_P!4w^8SY*9Lv+dH7!yN|P5)D3b;XDf!LUQRkNh)05I{WRS8xHkXR? zZW884srrmfsq?6Er{6KE-b_jAoGN$i@dY<(c2ehF?)L@MIVV1(d78>UpAiD)-<1mk zNn8u3`b&2>LzN#TA3=?Skp^{+D7Fhnf&0W6l(wOJqN(;CsHWtcVNrgX)u75}I}@KCmN)l%75=%Z@TXmgSe>c%Pfmkpe{P7}j)+$OM z1kz9Tya*s3W1B7whJ1V4g^m%MtM^EFLHYsO*b(BtFJr`wiMhw7OSFk5?FRL#LLT?gXdEF_LRTgt~v{NR!INMw#TE1!?gC)!tNvqL`D z>-+YsAfCTJrLqL%$VuEp^xB>DN1eDhbXkHjF(IAJl(MX2nHI5{rWgn95zd;?k%fHD z8>>L`@RW1%#FlwHF_J_>y|KkQ(9VoI`=LM5p0e-lh@oU#`w%m35Bi3~c;+NHM-ihG zvyLVcFTI@BzXRjCWB!I4L=`X5(R?B;Q~Sa*;wqKnA#aJlm4>70h(nbI_ANw%=b2tj zMCY>^&A;KfDOS6KI35<#3F%1-@?Zaea$C+SK|V9HX~Rxpql(yhupqNN_48aS-ng|B zJ+^;y>>|GX7`I~(>MipM=Wi$NZ~v%4CwkmC{|cV>rschpCKii?bW0NRy_A&K5H|~i zjf3gS)9NIMJNayf7ZF3MHT+f*%X+VCttI}n?z2}SdM3vIk_G+mi-{4pd+=*Y5jpRh zmq7j@%c^~1bJFYHUGm^1s&HH$V3PI~hsVrbuMNK3Eo{ z*8CXOb-M%qeWJ^R+|LJ4p1HDoHt}xJH@hq_bu=NBC>pt*adpnVQ5SK`g?!8GO@%Y( zZ~C16{B4i* zwbWZriLqPa_dX};R;HVkLwmlu$XCEVeo*2Malzy2iPSV$-)`Pq@LpvG<4XCQ_WfPo z9#8hWJ%sphF|fE8o(ER5RT70btKP$Vjbp~6wZyW{Na6B1^HlloZO589<^GLJfA`Bf z`#%yeUs6`)N{l(b=Tui3!uv3+kbZY4YYftPoqR=~&za9i@|jsRXB{*LK5d77U-#GO zEuHiHw_M(keLo?88RwB^7-#hew${&c_8Uw)2U)MYBg4XDG50*!2aoGB782K< zUd_QpJRm1o!UyZxTHkyDk?ca<#YE?2GGAn1zcG@N6k#86(S@|(eV#Mi>cl|9n&{22 zF9OC?Od;R6v+_3LBF&sfM#Mg{tV!s_YG)Vo=@K6@U+8Qh#{2neS`ycB-(O}8`_@@? z|1P3n!|J#r;MM(qEFfJj{Qc>aUphQrMDfNlV9y+ zTN;%6k}Z0r3H;vk(qt#pYjf!cv}-IXNyLDdy~`_d$DDqg3-MWoAZ`SY%4{VjO}77o zVf-SF&tFf>sc-h#2>mD5N9fN=GfzJq;vOx=tKHGvB6xvI)68Wb5!{$g0^k)9eCSe4WmByP ze)D3>19#goMq%l8x3~U(7}fM-r}jgmjP@_TY$Ov$7(Y&STiqTWX7DvQu#^>s8ESi^ zmPcC-F*q-7z3TUBkg+p4<*441L58Gr1?^_tAVYfU?9Fu_1{vhG?4-dn#4r^tE&X(R zh|yOfJ@)<0Fyp9mbd8G9D1%M>w$W_-AI37fj!k0*V~k)Do)^@PF+K*$XKsEef@k;N z(CA4Q!InAF=^UXVSjb8vzsf=cD{W|W&rlV?O9yNDe=ZQguO<1l{SLC)icr`VsDk$9M+>6MW# zgipAU@ApJ9@2@X7_C%9-|M=st1Wyv*s{Cgq)r2s|`+xRNGzwyRFe6DpOb~wycGC3L z6u=(#qD>ly=i_6(9?ATf{8*srUR-1gANFP$yTz;X;X>nxw( zP>SNgd-j=+?jPXBExxykb~@h*RFnY9P$SgPg)kFhHq zqnY|NZFf3e8(gYjMSi!3gNZzAIFg$I(f*KBl@3utyGt*WC|u#M9zsMN9P_RbZ;whh zoriqqmouIa&7<^x{vwufaBxeK@>WF^3u0nrmPg+yVqN0#)enhkKWvkq5XCcESGN;+ ze$-V8d(g2~#H%1tqN7~LUISw3i2ZX@VsEn~)0~*dnU(EKw2~A&b%I#rHCp3FJR75a z%?YgFR6Pmrxli<-CZ=Qy#Z?fG{7b%XAbsXNxf#&$(~k2qSBMu%xc4Lwr*~cwJ36Pl zjVFc~`-uA9wZ+?r{fquMh za~}^O28Y|1#lw5YB-&z#wF^lAhjhz%tHGx$Y!Y*bZk$US8FPMb;M1;tJ!d?ERmjZ+ z%8?AcTSpZ0-tzk$G?TT9DoO&HU7)o7$dfx0rS;Wk) zJdTINR-+#}@ILnm*S^-M<{coac23|2bBb(pN9uOdaQhv+yY zf0q3dSr3neqZ&s@dfbmkH(q*?^o8Dm24Qr3a{E}z_nUM~zBXi13+Z_A+K;qn@920! z@4D>%4|FW!YQJmKGqMiJZrPGc#@~iS8nQ3+Ion$6FVgXwX@RXFWPdzvEI}=#{1xw$ z^Run#ST*qGq9waY|0Pddx}!tK`zPlG{MbqQV{E+G!H16J0>oZ=ou%V1wtN9c&yjiG z#jbokgpLyql8Y{BH~(gb;cr{$|J^TT$U3!6iM_mpj*X{G8I^Gx0;j8+E zhTrMlIm!KohVi$L_o}LBIL_R#cK9(37iEbGzpSABx1YOcIQD&QL(eD;e;8-2)uEH| zI&kF&nxi-y(OHs~#Cp-zL1az(01Y3zWa_-+ z4-FR_dY~jSLBmE>T$@uyX!yjCS>!j8&mSFOoE#+iycoKsq@4C!%p=aPX*e~;Y>5r& zPnUf2e%BW?49mpmDGdwe&(pPdLc>BjAAf%=qv4-Y=WbL!r(yl$PQR}FOT#3pz8WIq z(pY-h_URA}Yt)M^@gJvQ+ta7KySr&Pnxzz4`HqZJ#oG@>X*4X>_M+E0kkq%ZV{?r+ z4O?a3OzXZv!vbzyyoHZwm^ZDT<3ceF-)|ecRZrTJ)yfKuY9Qm@AnT{wM8j9iKl6M3 zpy8Z%Ha-%heA&VhuHQ2>ToI6Nk+hub8}fO@Ax*~z$3yOENzw74027lKQ953ewsPVm z89z>`y=9y=WZWJcG|>O@|K+93OTM<1NyC?7xompLyoIfkHgzNY$P0-4dW)ToBP>?A z{?kvxUaF7RD74Y=+t2T-XUO>JW$n)6BJJ|6kXpLEk%rr5&u5u5lW}b_Sy%I&jKf;~ ziyz4E;uT!JQ^X3J&hLs}Y51aJk63vf$)EL2PvHR#?~l3nrt}^SKQ0Y<9ZSZ^r1jd# zfI~FQQ9r|FEhi!9$!lsuah!Pg;OTmkFixxy=$dct&WXpj8wM=VcxhCIPgLn zvhsR3u&lrrT>O*+*Wc-0{^cYGE+21rWa!R;x%gJO&!}_Yqb2Y6W!BBZ$*UhQ_cJ?AKOx_GU7sBvvi-PM;XNA`7fpXyV9AD`)O+MTs-Hyy!fKiEIV@+rg;-EJ~vHHB_9-l*slm_quR95PBhlPJ1iY$03vB=R*=)oFM>i3B|4 z&z3)&M0rV{Pwq>ZM5>N;-o7eRNJqdh$vtoiWq;v#Q1*TbC5spgtME>vM~gNnJQ|!r zD(#;GB66pY-o^`x8xK#Rmzw6KuCh}o=oRa8?axV+b$sh;sia9{xo_F!6t_v_;bdvO zO@0!w%_hj37EU1f<3q8(Z6^?qnwWXSx(U>FJEdX;YaFS)D%$b%$~cNGAOTBr99hLp zTJ&&^qq`1pf{mdMrA3T@ePd|n$|H*^*v3$ir~>|a_YYbOA85P&pvtd?Io0$(XjKdQ z^?cSSqW&LBA4O)b*-T!}A4T(?^mk;}j3C$3e2<-rM$jko5Nm$h5j3IyJ;PmS1htdn z@7}XvG~K-EpmEeNg5&(H@i5ZW)CwQ?FoX)-*qbbl4Vhw1_n^7vi*iNDFX;TpBjt@kk`T$ye|9$NF#6m zEx|+q?k~&LkP#EnLb%kCym6 zcrM67r&joPn$TIuui#rU4|!knGC!MnDoKw~Q;B=VLZRy9;@-?c$;E3*>{u)$`DtlE zc|Hp@1bM773}vB;ux`k4=z=lK39o_r2I|>Hm+cy zCAsbLq6{XY?s;#RXz;)a?h8^ZMEy-5!$QY}zen#S`6U%1*MduWEt%*=@j!o-6%)ZVowkmNL|cAImo6arTGz_G zh4%H?RcNy_5p|B2_9HGk4(W=^{bqOIhxYX&chei~0!#bR zJ}b2riR3=isUiLSwpkytQa2cSwV@9!6)@sJ@_p#c7S3f`F886p;fTqq2YsldUS&5k zyAOp$qZrNOeF#49hP!(a)eOmA)GV$1NiDYr6`9>uczCP_mDTJ>IVRqN7JRhfu#xLV zAw1uTQ!=}dYM;Z^F552TS7&*_<^FGUaL3U3J>I|3&xE4!ZNr@?_9@#2!^NFwzDD77 zsniZ6!f=?sSfc|u$7pbCHvK{-<;GtbD!OV|Nl(c zc|26#|2S}r8QIDVrD#Q#P+1}+b0j27N+Gl$lw?VkA|VPTM4Ko|lB7k5a7dzL%{F7- zk|ojDmwaE>`}cc%`s?{P_ue_@+;h+NI-|CyC2k+33D3>jWSuI_G0k(Erzp;Dem$mJ9 zY`^Q9$CP%Q7n6H(wRk(`5g;oipJ>Mo3u@o)3b*5}f8I*2m}Hp-Ai3%>eh*0c@IQUvODpB2HSJP z)m`|U0;R#tw+m|rU8XAk=)y;nj8_yCfT~aPOm}x-Z!MAK+mCc%qSd-DbYaaV8B_j` zUHB7)SL(E1H;%98@G(g0#tRkK1&{yg#yM)Y`PdHk;L&B47nSRK@YTb4Q5R13VwcT- zv!u#;u}E@Oon~7vKGG}{aebf{b7`~KR!sNeUH31K8OHv=aVbx8mhbMvHR-#*?oaK* zL+#`DGcq7jt7X)^1j+zz@tZzb;yQqfv$XH?D-PmFgKI`r z9|mz;%Wq?$Q$yHVS+@CF-Y?88{AY=?#BUrP7rg7&))9Q(Dtu^P`3TMsulMphFp3{} zgx?|MkK&J~OtY3vkK#9Hd_HWv@CVnFOW&~+Vc`Q~g{3EgS=f}%j0>$E!;0UynLV$^ zaJaQmwWRJij;-k4dhhZ$zUt1eq}(=+Wf^a%A!ZZU_>fB4^Rx+^vqBykfqtsKRrtqjA@kUcPi&=b3I$;XyHBSlN=AXtlavR#7 z<js6d zHqg+qlN^5GLXeM8*^nF$4c)z|R@KBsL$TkyE&Itdq^!?TSI0p^4^J$3IKzF8JTgrP ze*aCgx+YbJhSo&=J~$9aLnfq(zLu9XWDqKGaa9Qoxq3A?f2gLR9WjZUl51(mhkCZO zZp}2_cfx(?!!J|#Q3RdUaKl z1IMstUi$IZqGNc))w2G<92VXj#ar3o!or4*r%10gS-9rsQX7YTEX<)TXVYZO!l8pJ z&8*^B7}rjZ$Q7}$arj+lS}_X;Ux-jLyvM?+mv*dGie%yARgH3Y!&!K6HR)}m4-2nS z-B#^;lZ8vzLM4rZSa{{TNdFo;7LL*(8)ZQ`3z`yIH|1IQwzQAF+By~v=zr&Y1^Q{V zOj(uAW)^PzDEH3Yf`zm4&gGv?X5j~B9;UoQESw%M%^j*dhSzTjzsGPG!&&;GOZAJ# zFi%VFgJ&~iIAP@x#ZqXGQkfmM%Ar38vaQEL=;>#=aqkMZOvHZ_`1x_@DCwM(!h)!WX_dpdj z^(nmAjGj|?o;lM`e=&uPi?d%l=S|_qRl2L(*r&0JoHXCpPc(F?vNio~77dvOmUMo5 zMMDWi$(2tY(~!fZuL?(Q(9qg#lAo-gf0fN z2c|R>u`1=p<^41iBlv4mk~)lsXHj>)%F>XMV%gCk8R(yPZ`ewR(oo_0{_mThAJ0gO zZ)W4Cp<0t30XISD&oJCaxM|2~_~+#u3JpCk{G#GINkwYIF-sfTsmL=WSz@r7iX>Ay zEzPs3=uvc=YC$p;t(YFya*Cv)N>Qoc3ocZ2`;P^8>tQOQm$-G*@1~;s!;Oitid3{s zD^>c~HY$=Td_6ajmKl5TkZXO{^L5ySB45gNi-elt~YJ!?yX@UQ{QC-eSX6a?e^ z-nfl4w1W?6G0aM%O%g{kz-`$>V zOHs1#l2o1jOVNIM%5|Ysex&;Gv6xXGADSeOeTupx6J^|qeu zpPbz2=*-?zQHt`D~LO`UQBOIfRo zT|lR!jzNClKn4I^K%&1XT^4i?;_G2ReQ8$;zb1mt?N9z*1P$i%p6>-aPAhhwCEoYz z)or)Iv*AlV7lF!;+_MKkimXxQ3do1O@Qp(iq$7*MOkNTSO5U&szp#IZRR=SUd*!mA zT~#bEd|3buibtpla9sxlixcJOTs-jMIG8`%o$m;`3!HzK`cL~ZDkn|4L2ZG)PEIIq zpJw)5Wum>=NepCO|*~h&GQuSwmoY* zADC=gsWbuko|{S%8zHA0jV z&oWsJ`A7HU6f6VpHRrcTfvR)PxptrrttsvbSkmiFehlsv)lDk_n+-<{zk?>+`+tsu zDz`X0d6saa#dR0buqvm`f?xk$5ZMaXpK*SYumUI7bN1+i89WczH-lUC?84N*qYC1A zyTEk@VG;Ym;@`=Zo*>6EzV*J~%WcquK{Kn>w;zCYCq%ABfP;soA4Y+_HQ}#Q2zf2` z7J?TzRS#x?iCgmLb3oKm|Dp`sCLPQ5n#kXle*GyJ(>4o}OKCh^R-$2^Sk8e{?$K0I2h(rPdM5 zDTNI<_(NQ#-7-+Lu9h-G%Z@;=QWhefkRKcYKe_14r=fp(d~_W|?L^ zxZ{Xpemn7A8l-^=usvk>NF&HTseYLW9x&8v=maNxE6y>%kNU0yByPA~)Jdj-vwf!v z*MrJLU;w@-mtj``dmO|Y4Z(A*F|gurBR@0F1xq3=Y#nwEbZE?99tyVITK)P3nD$(b z=L6&)6a4Cx2c*Sj*Ovzp&zF=O$N}wx#agStXi@D35gu;T)!T1%06f$5JJbVoq~&c0 z2LmV%c0_>DU!KQX6VI*78aoBPqDb>^15@=NpaDP6P$X5s5B_&osel{I295}T#CBQk zpLFzLsa(~X z16yqToQZls5J)HP?`>0yA)Ys?-}N>J6iMok=^^qXJ}~H#Ex|Pe9`nC+egLfYOA6uR z>h;$5N zeKaWS=c?fW&cbI81A88(51WH4_ar4B1vhWMf{%lhsa5r+V0)+MDdK*+s1};d~LpxOzu=x1QRmT+A*_$YNZ=?%DAoFQHZmR^zfoCWs}l-C;ZbEC!;5ATM7 zxsOaDAAyBd*HLkhK!FS8^$}nagwesEqI*EOEtsl9^ki;C zUBjWv0X}V}<#a$fuDJa8W&(ob&fV2Ar-PqXR5L_VQj{!-v)gt{AXfpfvYAQBTG?>1^;xFItvK)a$-)Mg?(yU-ZFhP&Dz;^G0yl zFIzJHr~V}-5z55x?seXy^dF+%Zq3b8vx0tHBwCwN2=moTMH7q5kiOQO zXsrO_O6ShEH+hhrw%e*B!Slay1EWRu%0J_MF<$>CO$_H3;JX)*f1-)`E9K0uOQ0gh zrq!AtkG^_>6L@X^j;Iqn|I6?H&oi#vh4iOj`6CzJJKzcEX7c~cOAv*T=pd{fr+z@a zZw{PaKM2YnEmG+M!zDD|bHM#>w*&HG;P9KVL|(A*sm@Pgev2&7`{kT&4~_`cEbq@!=SXP&%!S^I%_PM3SLX2JArca`Kc!CXA)$JoP0x0f zkkH8ESL-X@lMs}u&HI{!av#SCq@|M30uK3d{)^%`veJ@iGQe7JV!#Oi36)B z5~|DPcf^?_v>uk1)IJh&+NHJKeibK5nBj`zQ{zMm-zQ$B9pXgv8v<+3`f{ST`iETj z(>ReznS{7QCnvh|TII9RN-|oEkL}6m#ujFG@H;a4-gJ!jVig&^?|E;sqY18`+L=5& zKt{Cj!2Rxj$mk2%VPtZU{9oJw*Xt#XhP{50(aLYfH@Nqb(Fg11$KQTH`w<5hVAI1R zv;=U*A34;5wGmfMet=y&AfV_YqtBtQJcYo<8L>opaAC0J-74@o&CW#z%>0}nxEs`3 zJUApHIpRZtxs$G6+(1=Vu7Mb^#SRaj2VMAJM-F!0iAYKUns0Bd#dz2S_QvjrC%&m2R&V1t15sZLKP%)kW_i_Z5;UI8|D5s7$`W`5J2_(XmU~n-`0gL6{ zxyOR1thNi>0*Nq|0q%87Jb8}zew%x!E%2Sj^RITiA0i{~5kao%-()n$4ja)HGMavp zqBQxMjI2nO8_naOT{f?@a=%7KL>QOsNk(Q85ZU{XQQi`h82u~oJ$+&0pFl?B<%e-? z4t$q@n5N8DG8zoGu%2ln|F_?S^0YW~?y5rjJ7r$WH|`*#@Yq+kBH%eTmG!%=7-V#O z@SynEclho{SlwGH$Vj77*?RU1^b;6{*>HXD$Ab7h&<-0dj~a19epWZl)?b8v7@u=3 z==VGst@2zM{r4{!9Vysce0c`?{r^WARbYT-i&#Y%&D}nw7`jXQQCU59R~T zL3t_~(etb^GTQJZt*vtc#?=JZ*Ryav6t+P(xGAXkgViT5F$(g$A-nnJCJL(PYx#9i zhJt#B;%iJdQV^fj+A}&ZpKc~L`0FUh@_Syl&>9NbI&sXmW-SG&R3?l2i&7A;&PERo zs85BMkfo*|{I0U&w=g(uX#F&hhk{tU#Hk|el>f#TCj|{`{H!=nqo9NLCbxf=pdhnh zvVAbTr>8M-(n$I5yu^iq{M0gzCW8FJInQ4BKs}Bu@05H(L3af+nv7iAQ`R9$H0`?6THYR-TLZhcV0B%V-vsW zGB0xaHW;Gi$%|-hYlHl)cu~qi+VrR@FKT#E_S2t}7fF^aNpbzegQRme&vjVwpdINt zo=d1 zfB7=25>B+QGIZBF7f#gUc+$*5k`oya8=Ec?(#unimxc8yWUHUZq&*3R4qcJsrI64b zqvKVLH#pGUsEhl1g*cGrgVh@SN$kiZx`Y3;GCSIwK6-x$vmt@6v)f~}*#4VmuPxAT zURdK+rt_DcF0a02dGj27bkms!U2e1VYwd>FLjp7O#&(+j<*!rpN;hZ0;oFn+_PMK} zl+zRRI~#6#xLJ7CoF>;qIZAf9StmcPh($9;I7)AKRqzV}x#e z?wa9A$q_mcmP^+S)4i*Qa8D4=$!oo*DbTe7gGnQmkMs8qVDkuEu(FSJ&W%RNvzU}&73hC6YuZ*2f-q45d^!Oh&bjHMXLh4Ee9xRKhEG#R+x{Cv)4Bxr% zB3)}+HO`zR{*bE2wl(KH6}LCz#r6GF2Y$1kt)%Q$HlyVU+v0} zKm+*58R<;n1B2ML=F7psOGDTwD`2Ow)G)rD5~{Jz?l*?JHJ*GUc+AQ4Qo70r{=}2* zD`7W+OCO~;nMaRcdAjRusmKwmDk`f`6*huL_ucB7@f*Rx+)s`$G)6F4p*nL*!f#A$ zFY054apYv`ZEpH6ykWyv;dhaPxMfrlcD4g}pLJWeLG(}T99F8G8S(=k+F4w8C$|T$ zINi0TL$3=H|Du?Vv}5A<|F>`p)}GM3Ll$J<^1x7f*p5bA@l&^0#=RadTl|Bt4jUQ< zswN$%$4M{Fd&ToN;3LZM@q9NM@Q`xt!3#SZG4JSJ=#hBU=JL8#Lj&U8!$>hc#h;>uJ{6q9*(yTTDTdpMg1Sh?S0k zWlxu=3TZI#)!wRXvOWWkCNMl)v>CWJu1RawoPhHz~LZd-35%UsRGq@gD!W*SU27NT%L(b)CPXO7h&QjVn$Mo0S0a_-dGx6%fO54ge?QlqCb_1d<+ax zZ`k!GP598_KyJbxw|T*o-h>~7-@fOtu?atdXyPne6J9(&>}kY?_IWSIn2q?oyLFOq zW+T3@`}aggP9y$r-E73VYeVE}KQ&_SJ;4J%x}Y72{Q$WMeIeyUA)F-~=A!t02? zUC%V(UfsE{ZBSmh-0nBam78#Dt>fMn+eYjr%HJU$*?{d^>JUq<0Uz37zRRVFyt6m;_gDE-z+HYcO&OaGyeTK@MD5O3%>PjV2$&& z7R=s$wr#si3l?eB95P63#%E%^;vS1PW6R-hoW(gztZ-XP3W+T^(b^PW9L_wm}&j~hT{zIQ})q5tcj$L>8^Z_P5MxArn zxRZ&;R8)2zyu`$up4%>bb!6ho=O@`xpq~iuHJ)4P&cLsuB$k*V2JXxx{y<`2zm*%* zncErI^DJ?4!oXYe=W|Y#HDNvvbC@EVumtbD!j~T!vC8YifhC;{c)K1Ec{kvg&GY&P z@7LppKFjW|_NvGCLdBAt9qRGf#SKI~c8hqr?5J@)wmcCL8e?CNCrf?mzXsLgAidF1 zZbm(JJnbC(TBHFFP%AOEehdTU!00030|3sO2Je1%2{~7MVNGK$!kVMg< zMQOQDTC|X~iOLccEm~!15mKlug*HlvcvDD3xD-iQvd_#tW8e3YeeHWjpWoy6*LmFM zKI?UzbDh`ooUE*>w>#U);c@)(XyM!nNMBj@fSRlVG^S?g5zc}#1&@8A^C{?D_inOk z9|x@Lhp)U=K_~&={N4>topo*T>_u51Mts-qxIt!gISpWUKyvW@X*5DEwK5U`r3IUU%&yS<(w+ zeOHzCTpnn?DBefc=fQ#Q^1f$oJV3HK_N!cZ@btfhFPm`w=G2lPQ5hZ#w>uT0=3cnJ zPGFvtaxdr|D}MWVX%CDg`%IM>bi=9q#K9R>U2rX_!Uc>w;mIXszq*|rVC(de-n$Hs z(=pAfH@6jBYr*;Q$rcbhU;K5oax=VPFCN!qo0S1MG2*zuWV;4rp%0k%pDk zaOrrSp~M;v{C-tXq3XnfQq$AYKJk@Md42ZH@_{lqvfXfCRJ{a-9aHo#e*OvCZFfty zKK%wy8)dy-1*XC4Ybsw4t^N;kPRXtlI&MkIn}vqF`TQRlP3v)CA0*BJ#nA(RZoH1A4UmTES^?t41EfVtXv)sqLGpU-s!c=vL*%zPY6po$Bjiku+^KcDMoF8E zwMLIj#>k(A#Bx7}ank;Q_B@-%6C`i8NJ;PbB-wT@xM1g!zvK@0nA26W1kj%66(#gA z0rW97u>bo4LF6&i(fGzs5d9HjJI@;zMB7Y9#>^aPD9=a1Acsdo=3$Z9w4*}kk9rXA zZjBJ4VpWqQuLz@`S7z<8XcI=?W2(Ms9wLydw^QfDIDy*a(r3B-qN7WC%CwnoB53x& z9G6^mQN-1^H%yNgMOlMZna1K`NS!H@-*sLL$*yP9d$PsQvyq5*tB1wVh1T(yK5YiF z^z#lpeU*VInqFu9e+<;QQ!KPfwbrAZtkUvBcnxHL8(IG zXuMNaj@!#XI#EkB`?48`?z#2(&L<3Hy!Yy|yABM*v3I}tVhaPgJUS8X(kX_*Q=OcC zyNMx>aY4x$0%AzM=eT_PDN&?#{D{@+Y!S3*VD(`7Vi6>d%^s0NM?W-g%wip zQS%e0qDAj-EPG5KS%Jp6YXS*msC`9lD49SLlP6PbDhb3rdE4H$gFwU@>2;eX33UD8 zvgN)EI=Y-sFZ)iXBkuAwOgmvZ3VHW7O_oMSMW(N>7~pY;EG|r*>?BZtdUD)&D}i2p zB<@x<5@`Kv-6I;+1R7T=aQChyko}uw((h^rWW7To%8G^a9dEV7{U*@u{A2HL7ZPYw zMr-z!Tmtc@V~ywI{=L5NLmq)*Z3Nym;IuvUgHS6jxA#i+do^6|-o`mQT}lZQw$J(6 zBAj1glgHVE^97@3D3+8FsB__V?Izrh?2)DK-cba4^a(z0#_4yOMQJ>fK-X^jG-ekN zsQ7#Bknm3e$s~GN-N)@+IC{`jriwtPt4X=G#j#yNL{W6rCV^L0^8(F8*&Q}mfZOv{?4cxEs zQ1F#3Jgz$$LL$jHUs+e!R~V10TdVnIBL2VXw!&}=P8-J?4g}$GydbFg2XMQwJ3r9X zal0w6lodbXZ%MaBZuBn%S}BpEpNsuiVeuiME(_c5V1AGbt`~Rsi&`Z1tAjx9iOgRF znvP4jKOee=6N62lUfp?re&coySnCxo#^r`Yeq9*H{?W5+E>XermD$W&brjnp;h{uz z7oPWNewf4ao?Z{wAE)xyh}KK*@zF zGRNw1xy17={w;3DDV8wSkXCjG%UF5LW3$DIhb7kTBkrq`Rczj6y@mXxZk%y z^-Xlt9J+08tUDbI_T#|XLPz?o6EZ)nM9{ABg_iMSBB;eKF^82VT| zlJz-I3~g~f`fhEv7}6|XA$@T(1NCq5ZOK2&KqteuGG2uMukR^8EzRW#Jf^jS2#2-%^EhuF-$V zHKCz1e9NZDheJ-v^IuJpBMlFRoUA5D6NcOIhF#<2#&xv5^etngvFyS2C5oeDiT>Qn zf^Ea((U$o1nL$IOB{5>(PahbuOR5j_;btX~fCyQig@^@GzDUU|>hc7NAhXX_KPW?%y*c`t5 z^5Hkqd&!sQrG6>#V#;;5*-(Ht{Z-wNpgL4uLq{>`nVUYtxbx=}eF0SWWfn78mwU^~_(ZMgh|xi`|mP1QUxBvhTkC|FmY~Sp%;$ zCM@IJ&uH#oLifoR?dD5ZaAZ1wvmhi_DdCDO8}iFr+H(F6$sjK5 z{uh{G#bJ%S&-Cc`Jj3W3tXp# z3k&ACIh_DYHhj8d>RBW}LHC}5U767oICYoZ%PFIPb3nv-^D_!gO>ac}{nhIhO`QXM zHae@vN-5~~J$Oy^DFq8XWTVZ*DR9hOv*S)V3+7n)T(O&|f?(VIEh5dq9Iak4h^Zb=n1@m0PldKGxutCDulgwel$EO#f z!hZR#BeUfgZg195x2nnn1u4TZOV>zoAe}Q=eN9E~rGyxkL+`8I?LeIZ&($qTrU z(Q-JnlEwx38!NJG{W!p~G8ns|!GT95zbiWBI54y|n3(NKflCXa(`LP;5bt$M?_q{RPj0?v1VxR3HYarHwowp96XcT`+CVM$DVXO$tSOdmyUk*K&D99vu0T_yu|M;C0|` zi3{00=n!!T(3{%_^LEX7d1Ox?Jh0D<64}uQ3%s93U&Sc{p3sf@9%+E^cj!0#COAIVy}bXhfWaVgP3$XRFqy`o3yM2rgh2M zM!1?mD}AC}2Y!DfzchX-h(5CHXupyE*YRn+!i00%D$A($n&A=ES}_($LdM)%;ZhIa^Zws9YGC@P*t_tpDv_b@*eQl&OeGHU#TH zt*hypY9fd)WBubrkYr_`&HR0$h;4D*Xu*&u>Mty?8onil#>zOaAGC;}Mdu{m4yiEE zX33sn>cao@+It34T?RAq@)<~DtLq#6E(S`J#mZ}zIGWx^(&A`({f;rvqU`n)8MO=) zSs$1-n#Vvjv7P%3V{m)v(sHtw8A$!poYL!>47Ahfh7>JH46TtWI6YHC3?1Ka<4kgp zD8i%EDi{_)^IO-|o12QDE`vAy3LH90c;6kANei!Cm3MSAka;0SFvqPI_ATgfJABn^R4RBzy7yzy*6r2i8$sr37-~0O>Bp!2Wcl~VNR^MYPmrV z&nJt!L|^b5=3w&O1X#E$HnI3aPAZkz8E zh?b=>#XxMa6<=dMFwoNV8A>Wa3^dIX4h*Dey-jC)8w1UZd|zD|tGBF{}2GCK?m*csP z*j|4V-s&HmPoUnT=b!jQ2_yBi95wCL!l=sT4$eeGAi^%fyBMBfA^C!N69GcrVfW;GJS7D zoR`@UX?&hA+fajqKVUL!`2ltDA`pL;9sk9-6b_%WlA|_M!q2#x`s-Nl zGQA7>7~5-Mx*bLXqzr92?0K&Vn6b{snbpJ2;6pMqj?z3EJ!Tn1?oY!Na|W zsRo4}7#zG=bcNjmSS+ZDGXEb3@&HFax&D40DD`w4wpoMq(B!G%CaXReKStvj+4aHl z=9`JbDt&;X)AFVO9_TqGU(Tg^fq$*^Qnv>-PKgT(YIi}Z#TL_5+ztrMTusHQc7XNL z$-5spZSY#CKw8_s71DITD*S5;Xeb{&yaJj*Y~Cw#je;hKYc4iesn`SuQa^s!w5t*J z*M;76Io|;Mu=uC59(Vc9^ASubGNwF!Edc=i)od$Fq|-l!J1hM_|z|C?5KgQ z>b;G&zSWR3sE$3#g$i}m=an0|;BnqGYk3X_j)a`mD%8U~@S*iwZ~+Cf^ZIog{3&SA z&6Ay@PeGkKzaRxuyQJqH>0`s&d;Et6%oF$&*8Rzb?mzL8osZZM#QKz3{g@3Bhw|X} zXExNz@^2#9u;||Wyhva}$sL!~XS3K~*59~7tAh>41wCEHM6tfNoI5X_%?90I$4a3V zT+isyQ+v$03=i!`YI7*4R;9ZIZKGg19`2$*YSCT&d3ap(X+cQA#)rFIS9nrjzUPFt zFXkP7*z@(HV0ENV!{I6lJbzbx{aSf3wd5M|?coK`baf+^-nW%L1RHxd}PX*bpH+>A7GP1rdQ#aj}?RmAYj9 zqhp@ZGS{3DP|kszj33X{&T~Pn$>UW~EEkr@jriDSa$#EUMRVbq=k6ZpMm{wZys;d>Mk2Xmp||>`oRL)?MJFx zKeNE_Rnm+1OIX0CYMTu#@HBUw^?D-)-5$WW>iL-ZaM`515^ZIf<+Qk9n{X5k1F9j0~2ZB;QQ(#*>7HFM> z*Zs;;CBle;jsSYs!vl}-#@`45Rw+=5qG{uC#2m#}j)=b!V(fZ?}$|~?M;6Dgd z0kYkE^SL?`POfzIEDT~o!llP8es(Ny>V3CLxrGH0Pu^CI&h=;`j)zB-LzT!*@3r6pDWjrdXfZ^6~g-g=z`AI)CO|9ahOrl?j|x-B0|Y&qM2;`@$5^m zR2%uC>vgoCM+fQX_LwGK*F|bLJNOE+d&qSQ&L?ut@W_-A8G%OAK2q$P?EZI4{*bG- zO4NQE`$M`P@|pigXn-tdnTxxu7$m8KSN3&T4Uyk!a{WUd4wHvkTIQ8zj*!#)IeV1! z)(F_XqH&CzTH-qFt1v-M`?-69ynTdkp-FQ39Vl~(OqlGg^a>;lMQJ7<-{ zumIxm@zYrl4T)dRNg-&6xEE(Xc$0==?%Q4y>7ya9w8*nx?1WI`#T)LqRYIuQqF@>G znDD=Mmrh|cYH0P={Ve7e{sYe>fesJnx5TDlo#SzunR!?QZ9X}`)nkgF7W@g&l_hQI?WrdaJxEM+f=!^=~Vf=d!xxqmD z`aZvtOT^sQZe{CG#z1S_ROD7+{`2xQE6>0>?wbJzk}wBOzq81QBYOj*qYZ-M=$`Py zu0l*f4VV{ve`09aR~$c9{>OV|NksmcOX{p7q{-q`$~~W6D^cT zN@?9ES%qj=A*H2~rVtIQK|%^4DYGa$Ssfa-WWLMZdykCtdtTq4e~x?Kd!Of=&vTx0 zKA-3A*QiOj^_7a`&m7n>vzCekZf&^o!Bzl?+fHd8%H&6Si*<_YW%$uXV~0SmFBH^2 zKHxKXh=LAjoarCzBhbvp*Rs?i0xhjs^DZcxKs*N->He_ zrszujogoBDTGr%h^NK)7$2gI5e|x#eltL7NviGMNrDhOlBp^;Qde9kYh)C;><4s85}FAo&H9kYy3Sgw9*OGUg4b>i~ZLBWl%R9 zO(0gMQn7LZfg~IT_L?UX=!W=2>USVei0ZmDgGvIGal5MCsUy%QZC!)!c>ZQ94WZ~} z0-c|5d^&=0S^Um3IIwZC2;s6c8xWjqyqiTZuI>37t4j zja~uQeWTwTj;>K|Igs-nAmjaU3rfa2eL&`|C{~MZ{rTIpJGY5y&e1vLz}fklild z@#}RNWcGspZ0@1!+obGEPP^afnwZt9*)mShIw_XBq*U6uh$9Q^gSbFAE zJ%OGlv1S4PE`CJx?mle&M(4=G*iVrde;YfDgJu=8s0oi(yLv*68;|dF=+~3I*nfk# zu0>@yz8CeSU0SUKDonQ*njRt0LOo_T|2ToZK9N>^^@l+D5y!uYP7}zNt@tJ$Uz^0; z*3-s*tm8O}?S@??@@g2zv#Y1vTsjH#;MHK0434YL>YlAN#$!R3$L^*11bUp^-cx|> z9@b8)&0q2Rf&YB(WfAD`tB|YeINyX+>{g56eCp*M^_9amPKuH_@e|{{X4WelL-%1J+J9_VE|1kbOzjsR5s5i)S+2s-OGOv1g#LgK%M$m>$;1cP!1Ni`har|N#v zV7`F%k<9@2q~(`PlkaG9mf1-0Hw)@^$SMgPF}u zWLWAoQ;)KG@@!e5l)VU>6p)s(R3qqQ|3W#6_O?oLr{ZDfw1{Hzy;$_%cD_6^XSJ@U zkA5O~`BWUA*Y_uoHW$D(d+alm?ejSj=9mYkr%xWZW?l&Fqx_D0gDRl-$46I*u39)V z9P;fDQ3qjt=QYXTCU6+(PTK6&3XgLPa&K?x0BwU=iJQh|9ImKvo;LD;WJK~yK)A>c4qZBJ#GM=DqLMi z@975@^Oizhk$$Mw#Ffde7iNmx#+GDs!+c#(?ScocUSiuNI-q#E?8mLQt#IqWvD?#m z&7hS)krhg7f`;cS6XS{+!R0xR;Hlzz$liCeHfCi#lxMHJ-KbOt;vg4)+<*;>myr2& zX-p8lmHJ`*Dh9-@)!N0omJZJ68b0(I)B?Mn_m<_a8VH?6Bfs9(Kr%gxY>2CY^X!Y4 z)wk5bn613*g5p}J&J?-?X>?FZKKrcQf&omK2Ucf`7%(Zt*QOK81hcfuYA4RH!0qkA zO?4wISn9g+#g-~IH0-{l`#7Txng#veyB?{B_YePunZ(qC_!H`-KjQTuDD)%w)qy%# z-^V_v{)Y`-1~!DA4jaDeyw}NBVgX-5z;5L{CTtemFelr?go*nLN81S&=#*&Z#N1%Q z{XAR7XIUm_EY5jqmBEAui%w>xHZ$Rb9NYgy3s*g5cMAPefWnQJcYV1v?U;kIyh zHXKX6p}1ue8_cS*TbHb21KacOxyd#bTwfv7wAq&hrjtG%UBWEbe2OQ1po0m!$e-7n zYM5ZEa#Q=#TPCo#&|C}BnIQVbZil`d6OJhTYIIj)f?vNgx&0&)xNZe0D&{f)C+8B$ zH%zE=6ZTca?;SU)8ds+?q4#}_u`!N=Si0%b79kd_GSm~clVrh{&Z#O*I~I5(F4r+x z!Gf}c4z9eFEO>2gEZr`{f^@+$yX6;IK=nS=I&IH_AHSCDN=RaX+!AKUxt z{um1s_6GM9&9cDQKPEo9mj&wL7h6^}vB1;Vl)c1<1v|r|HZe3=AY9~orgs?&YW5~) zTnb}CYpZDTs0zmOyuvldcm^1W*lzu>fB_e|uDbC3q{Bej)gWtMI;=h9PTjWf5q#1#OQRGg;s?MxKr_*)EVWPRd-69dM|cApcSNYYM(k zlE?F*{L9cEQbV}2nQy~1>HWLBy4Pri+{&|Y<^GMcB(LM`soH{Ba=V58EsHOI$<^C8 z{4lSaBWvT8zbX#=BYh)OlSjO`&=NjQC*(%WNLzf%TW)mc=!Wg7(mY5?Hof2J1rJK- z?+<8`;zeiY9pXhQ@$cnnW_(Cg&{-qBfe%$aTXAoP1?GR?q~(qIa3D|R9KQnvUE#G4 zKRiW2PXhLY1>EOH=7tj%A}jyTm%;?l;7$##8_THZA-B#aD?ch)B1Jo|+e}67o5BtB zC25G$?jM|{q0GzFsqh#Y(hGmAv4BlOjD?zgqFjP#&A(EqeV8}xds!9sTvQOrYTMW^ z!q?==b?Q?*f=En-*W9WxS7+U+ zNL_;Tb{Z8xK?Zrv#1R2>;eL4CXCHp_eBZ}+WHkj1MS7HM)TJQl;-#s+ToiPjv!Iwa zyN~R9)=`N0eM0-o-j4*@`RCi&58(uI4w>uI@+6R)!0N^ZI|5DKvMaDMBalrJ`@&0A z0^P*Ba#of=J9b3N$SeK-Jwzbm{$Sr)6RbaQJC(jopv{&XazdadA;*fi5((sz@abK9}9zj9T+FuuI^q_ z?~szobsWzt;hP6*R0vdlQQX?Tiw{jWm)&5-@}c=Y5W zm;4LKmY9E+Nmj9z;Cauem99^tpeR?*50+GZbbvR>rbCz?$ZH_raxC6WBit_o-vij`ry*n zL;G%H{Sb(|__a?2N__59Pkg{Sgwv=i-RRIM0rllUY9ou_9mn+=BI(c2y+p1CQ&%VS~K={7%u!d7Mwmyc3 z%Ez#NcHyT8?@J}nR-f6t+!XA8tJvc(e0?^-{(d%&hri-PMaLHcp(Uk3u4!0LYgq0N zPQv~&DFY}6=V!|P4a+jHo^HRpvJBsMB;LuK!{bJnFNY!QmzW9HF$xEd-Sv(w__=wW zkMYWjQFZhy07XE$zruMZAFyT$>oe8V!rNc5-kLvlz|XVmg2ECb3B-{d{WyPp<^nHQ zydw~Gr~Ah3Aq3Llsjg0bNuXcXZ862gx-k2u>;Y`EDhiwt-alzun**mY-bN1wRjy*( zLO#i4Dqx%Mxm@=<#(DRRNaZaU=Ms^vz83-sq!B*N?}yjn!Ul<7+p%?aqK7Nuc|AUd z>RiWhud67L4Zu1vRrS}EZ#eGD=Qk6P*gpTL5X1Ka@3R4N>#9rw(e>mKUSfO~Gx<%$ z<8j_BS-mX_$0N@vOE?b}IlX<*kNpeA@^m4#zK_0Uy^JDI<&KNXm*D;H!Eh4{r4K|NB)nFRu-;J)o3&x3IIfX0l^q?}&$Z)W#d27m%4B@saD#&4eXs-L6jUx2<$fxS zA0^!7&bjtT0NwSE-e0kYif)}e6BzrIifWDe6tiS#XjQ?Ymzp*-^g!sbu<8p`oRf~KWgiV?mk(F8U@P-vefz*D4H?Aj$rPEOA@N7b5Zp>b=IvDX z*WYL;WcRe?rzkwm5}YUxY3Q@)dTBo+8tQw*IMvKYL!9HKKp!fq5K#Gae^LOM{dPJd zfCP~HS#HrUFZof;%kq&u3<|>P^R~Mvt~WwnN9cF(`q#apJ{-mML>?1cTRy~_qUJZi z&xgXyk4dHY^CI;v3l&z0@}dF%2(Ba7cn~{E=uuQNH;P-AyeL_h8%eJX|0WX2g{BsD zrzh}op|dY5m2-Z~k%PWg57evvlJ7z}M0J*2?|*Ff_ZKr{^@8{B91N$)m!m%$ysl1> zM9ez+xnGiK+)?BEGfLn!+6pTco+PII^IpZYOUMf#&s z7vC5;kB7!6Ny(fb##~28+~u$f!z8C{9JL-MCsIs2+v0}EcSFowI~jvyz}mA?<(~$~ zU1rF7uX8_nHDfyI;9M^`PqQENkToaO*-GPGdfE=O=TJUQ7NK;vC3SkWnJaGkY}i z$SAQ!gFiOj@br?%5#5GdpekSaSA3`h=$zN}D&X^3L-&xURj_88t9Nf>4UDO%>^^#z z2^)5J#&3U752unIdev1m!Oca~#+i^-`0+BuUel}tIMu~^S2yIAELd^wZZDJu#Cu-z z?}uGoix=i-48o`C6sZ?jch1YUXG1VgqlSkdN22)2ZLwjnD=fRlJ2wPN#}5u9Qis86 z^FAW?&kz`?>y1st4gn>@Ym0{C5G?wAS2e`~>)SH{d#Un6@H)#vQO|D>Hk%urRz?Hx z%e$MZv!@TH7v5{(y3-9fTW*Fab-)|L^M`t`Vx8JA*yWMc45bI6odrHLf%&eEJ!dQ% zfwq{VH0waBg3r_B2Mg{$dWYT=GJ&3#*YLxa0f8UKHPp-)uy#y&JX3=Kin;rC*|pPw z{iEpbLVSH$Hf?FeZ3c8}^xqR}VnDH%Zf=4f69#XHG(IuKdUNBy6DKoR;B;xc#?XZg zn7r<=#X5Meki@#XC+cA9d_kxKv(L3lsaG06d+K1CzE%@x8QojPaM0wAZS|nQznN99 zSuonFxVgul37RKsfACl`p?EgpYUMU2a8yBD83T?{7Fu`H81NyZ?o{k|Iyel*DoJD0+$eEko%GoDmBMCQ8( z>3pDr?l$ebV}*1mJiX<y6lv-z5?pkQCwagD1sRK z;d^!WzQdwmi%Fw(Um>E)#V5}*1?Kzak2o-PVh9p8F;Hoknf2>oB#>TFn32W8d_AyB z01MkK)u%mDKrCO}b>)jMaQb`IrgO`_La66)2{VCju>F+p*hR6Qpvg(YtO7_(uzN2u zT?Bp_!4CWmrI1lj`A8wQ9Lzgznd;h902c9QWU?z^Sr=>RZ^3H#?|{Aru;@H@IItFu zjO7-b!n(R&=L4$Fd~mvy4KMV4t}MI8hWWm|o(k6 zJRaj5lrf=cONA7n&xAMK>+`q%Wk7%><&63}yzl3UJOh-R)peh&W5Djh-n_^^7#G=J zN3;s)a5T8AbxRP=$N2_EhmD2hxH8iLvrLVVmpE@EWppLV=x{8B|AdP)1NMGCmuq^6 z0e_X<{^UMmfJuDwn#o%XIQ!f$B{7Bp-n38~UV8>?V|~D#jREmZ>C*X^>5zYE^xucI zbT}6yS*<~%!~A)6VJ*BK>C!YgUi<&^zFM&E+$Na18$TCUBFC-7fHKoJH+03B!1G2@ zQ^1D>c1D7IN`7o8t>ge+2PeKSWPzkL@i5+&1vgz)RGlkX@TOCLMNKyg773yWfQpoG4!G@Jpq5%$w4V=?0dm%Oq+8wnFxLpU|$7RiZzSV)W` z-?T<};64+o{4RCJ2s}tft}Ty7frEzj(=pKUJ%pLT_3+O2*-zU-$2B$8lKMV}JUx$~bUj z`=jwOFx2mmyz4&(inC45JrZLO_)HZu%27DEFl$g^^(aiPVLf~AGy?O-cD}=~%5>`7 zmi!?wY@E`d?ivD@iuST*)&OkVoV0cMR3G%%dF7f|_Cn&vH*+Z+-QcHnZS6V1F36-G zylZ-*19&v#tr*R1@K!gX=%++0Y+T0m;mdFnNTm8csA#W;XgQwHhMz1rD!k`w4$i+l zx-%VfJymebze(ug@d|j;(WbGXsSLha`z)<&E&!!Fwr@9ye1jYM#`f}`Ga!haQzxVK z9`-Lh6m)UMp42;cgrQLpM-JCcrI*~xAbG}S=E}VCNV~GOkSn%7$o{ZB^3}nGWFt6U zZ;2}-v#c~7oP;Y#L5<8e$9${E!>Mt;BmT9d^WfFrC+{-Jsl%mrlwQ=4oY@X)G?Iyi zu0NYgn@F>imw~hTEo8%|z-WP?Rx;4|Q+nC)cJk)fpB%mW9b~ye<8)#}Cpo`=wYtgI zV_%2UF7%M%k;}ZIm3ztR(Ck7!=RWe_!Wb}AZ zVW0e+m=<0XrB|~z*^v)voHhBmVu}x?8gU3E)~$*EcI^OwFL6-Pc);WDG4M>bLxHq%t3>U1I1@Cg-#=H5Dy z&P_#8^<8K7JrF?ieQ1^+sgcJL%+B(oi`&-?Bvn%ovrl{cwIu}&3~*;E@>7r^XZZ^W zwBh(Qhy7Tu&VOgay3!*R7cy4@oxHg0{p1S*)y6)uzJ>L=OF~!eWvmmu`_sZF^9dvs z?07@3nLs@5i`JhQAyCRaWhDy%3i=-a00960Oqq8)*YEfLk>?99$|@<*5|U7&l02`X zLWBklkyP)}K-yVJDV4Sq?IuzyaG-|^Gu&U#7_cgc`ukp~o6%}TnY z8$ppZ(JYPe2^5JoR{7nYNDAP-)kHIgBe44Gfad9a{^5zOJkU(bDJlSemM3LIT$GF3-=!<)%pnY|d#gAU>U$cHjg{idebs9T$^Mk(vXBA|J5aK;8`@{XUB5uktHQ!TGP3G5VO+LXint zYqAOUuQwvsRf6T@y^V7&;QFrd+*Nl6>xV3tIPe{*eO>Z2;x4ewz3<5jEtMcN@!tk@>NyuT+q|3ep`*kp~=$x6DWG;qTjT`X5s363;9{ zj^ZaRq zQn=4rXI;qb}Scd`slY9+Mz*L zPAVh+-g|8;ja0JC=#*vp-&|YD*o->~BZr>8&>O&dPjhtJS!hRb$G!Q4cA4q?{5Q<} zH(5qJM1Bz@1b8v?HLNSRf^7U4&V9?+M`HIyAhn9A)I8*kEom8T%=ZJrkNc39WmFDM z`%k|!OukNF<~L|Net0>ut@M7o5%PxEtV@fK?~c01EJix*)GB1=|98TwGsZ~WoezbA zkWb>At#%{%6R%!!MXq!@HSCETm**u$GbEE1ANo(bIZu_GZIJ@r=brV*_3Y%dXUL}~ zZYNkFkDd^(d5-)jTNeM8=|9@Y%o@4IIQm30GtN4S?W9Pu z=b!)V=k^0z=ZfO@eTNsYO3;=Vu}ovek#ouNQ#8_Yxc)EG-npjJkKYZ*FhV1X~7(%YWH@F?Z~t$LcbMA z6@9f#2d2FX;}zB+?Y9TIS|E9wFP>z|d-@wJ^+K+-kGXOJDW_xI5QMZ{_wLm- zi=QJML^`dbkhe8$`$Ld>SKiFLfxP;>PV6o7-6*x;6VuLhuQ~s%7l+r(8D!A0N$Y)( zimm4lUSi7Snx!${<@)@sJ(1%NPj+Vd^-L8hxQVn&vKcBx`nVe(ef^()PSS^f8L!;a z28Cqgqw>r5qM3D&Zk~0HX_uO`36R`(>&0u4!j+u(1|+LgP%w&=y`*?dv5+Dfl1@%7 zXm4wt5iN!`OEzlXWTf5vCJn|G3SNF%8yVvpF7ZQ!7#lU>v;%`eDp>8@H0K#ZnVAg#6%6z=C-Rm8fNUx zZbj_E|NZ{;;fn*Cnevx+U9~|b_U?VDj=Xh#>N!!4?d`8?^MDG*DjdNg; zqGIJs2M@EzXtPI!>wOj(9L_rMEr&(+y;SeHYAi;ycD?Md~;lNb?8VR!g!O5kq#%!`S_Nm7UUpA38d395-h)wLph@g0$BK$5?7rkZJ~yeBuf6LDMwe5yt-4dZ{ci7k~LNPu=N0& z2)nv+w*s4lTPwf1<-;c0ixrz=R5D_6SrrpdMc`i&k{+@{5dQzBVEp2Z6FjbgD4Z>{AcR~b%*ujeq zLgevzH|Mg!QQBwfK>cE=QMx|_1M2VyElBlPA3E@dzA5}DNNHf0?kk-YI`K=~LYxZOR;|Zv(VNhmzCjJ^l2PcZ&x-N%%D=xHevG1Yh z@uoExICs;FN4Qrf+IG>$3~C=vG3})9Y!KNgr`=As^2!gH2e;793cRKHB2Dy)@Id*{ z@AY(KxK6+0pIVx5Z_P_xTSJe{=WZ3PjMH1AR!JW?aVkQ~q>R4T`tZ5%SuUO7V~we1 zG2MDjB=M|lA>FB`jVZ`?TC&S5)#!c}-5``cZMjbh9hauiTdw$$-miJ-vv!aVm_^<>%Z+y&{1c+lr7T&30eBaH@#b6 z@;q1F@g}YCHD$I-!pSxm`uJgE#Qb*f-olGY610QAQHobfMh9g04+~3Mc7itxZ=Co} zXt@-S7{0a>0_GnZejV2V-`z0*lIj5Fc*rQV!;uxH@tMa8XYceQw+Y zi~5pR?RZ@e&n`&4I`Om?g6y~OCra0V*?uX*nZ1?Z-w4;96 zU@5TnZp$~UDFM?dFL!E=6vITZpB=-Ci@`d-j%A`;40zdJ>(VHOjkPi!o|?trwe!Aa zg1@a6o`xk?AWzvBAw_>QAP&D`Ip%NH7SMN*V>Pxi?$r_Ksc@QS7ogGrggOu^EkRZ>8Ior0cleoZ#vA8f%04;xGWt2q(fLTKBa_@`s7i+Nq59hRXP2z_aJ`2~fO+szi=CoziU(Rfc9;S1U|z-tCDZ*} z(9YVlyJ8Z~yMD=gi2)8UVd$d^7doGRS-bcm7wX3+|KX&jI_W$?<_o&&!kn^m|D9LSjK*>k0l1FsE6qYV#p;ccPW+PXF_c&(nb z$o~ot^c|DUr9}8(qHOn}ZZ;n##wcIrsH0yjoo#XYEFZ?U(~u87V;2h#N+)KwYT-H` zDclo&{sj*bURWOvwBi9@aaq-zB|I>f3z+xFh6kxlAROM;IlM-`(yN5 z?{PPkR+VtTM`>qj{U$C1&0>@Z4~$Q4exaYw14(E7kQf8>qmyqtGFI@x;f?&Ann`?M zC$0bCZ^MTZ6L!A{isFN&+nOcwPw*jc``T==<$Q=MO`*$Q@jzJj!3vX6F1%8WlaABk zL5WG6$~_F1TzLtUg-@;xXCL z(|19!YU04qL#~w7eU^{lv7QxDQcJG#c{|TrvWNj^TAmT}E|MA3hNb$Qf#ULjR zdV`*;>~lX&&p-8Cr2S+ZeE`F;&8Lra>$8tqZAD+`*s|qhpzb@}9_MsCx#t%>nd34m zf?Gnb-2Ti);Uka!dX@>O<#d7qRuix&XZ@kfdE^69M zhw8_EvR~9guT`R2Z0kcfuguH{rcW#;hTFoZ}vj zM#~WG@iIYI^38AhgUY!U+YiIEIe$?8_V^K6;^5Ld)tZ0lPd`3jrL#B)!|%IOD0h(n`==*tQbBCFV<6zVXJ z45b_|3jH~bJQVKRQ)DDcr01c6ekV$v$KOo1U5|NskA1eo5JmJ}7%Y*+d~1{5{<$-( z#7Kqpl{<&J#YoCMquu)6;^YA9!;EeH;$$q2?v@~Vj*0gZzetea#s^2QD6k2)U`bKO zPBvNO_n!DaVH1nCRqvDw*~GEW?__o_n|OJxJXX${*DQw{9AW?#+u9`%-flC3G3Z1d~n0_GuC4+wq&$>b>A5# zQDo}yjVod)6tP*7l3@7-b#UW-_J^+&8GBxPPm#|T8%s-~QRk=ZaL-Sp$f5`0)kdk* z|IPO!MWlp3#s2eyBE(f*eSl99mrmWbFyz^NipI0*De|+}u2l!^w$v;6!8o41%f0Su z;5f7DPEb!!A1I3530~Sk5sR@vLy`OAhyG!8q5eLgJgv12=eKf2N4hHPJ#L2OH{`#L@asig?9>pMkH7QJ+sYXIrAYj3CNaWxAAhK^ zLT=nRV$m>;MVM^m+8>I%cb+JE75g2Fd#(Sz>vU4Y(a-xxGwPNvdV3omR-!-t_5N}$ zgCa7_L&i&r_;nb#h2Nq`ee|`Yg%@x1e z!{wG3i?GZe+7+N}p)O~s--G)yS#1MVgY%PQlrKfH+wNG~pinzCOJ@2AlKbn#$ zc1%E#;heL*6S=5gf7wph!|2p+f1bKwdlDIbbC~xq4GiPXh5vh}=su-8*SMS_k$2mV zu19~q9&RbnY(!l=?RMA;^ap2~$bwq*qxmNa?62W^DWLq4LH)^i&lx-q&6^{7Epgm4 z$DKSjgy$r;cWvf2^f%#W1|Em8y_)hr=P#naXBrDnoQ?CI5;d@K-7rOVFO`VUQDqV4 z_8ahHk#(mnzF$-pBP(~*{hXB|Mi%Xn>+^RLC*MbkYd%hrAVcf&PA#}4K@LYs@U2;F z68Y|Lh>#JR++$uM?AWBQ>*w+JH`pXCTlCM=CN{Zxxww9`k4=Jv<*XhxvdPF$;*O{Z zlH_l@vc8(CB#GB(ebOi_NshU#+Ud_j9rtHS`RjBx848@g{9X{7Fz&v9u*p%CNu$SW zC5Y`m?K7)ROAyCW9nSb+aWXIRm-Uiu;$%<2d$F01#K>FO^d%pPSj6(8>ZvJnSVS!D z!B+31=(qHmqyUN}WAx?WkV5Hqc`B9)lj5dB(r9teakwdq%}o zsf%Xyhnnq6?4Td5pOaI*zKu?~?_IazcQYNh5EcKaMp|!uM^yN+dOE0HSgU(~E&VVi zb6k#EHSM@d#OI1?B@KR#A3U7}blJ~a_kCgtHarF|%ogy5gm*T{^8`R`&g4_oFs=9mNQN4k$dJ5}5AQ2}(L;s;m`V zU_2I}y20daQT&Ws-LNC}{3XH7?tk?~H{{oQDCRkJLs^{3pNx_&Fx|f@tj3`W&NbIp zyQOr(*ufm^fMz4jza1CaA@)$}vV|qB5L};~qjRQ>=-3 zR>_o#$#*m>A%T$@CIYaNY+Z2u7w2DHRRSH?cKVsh7lRaedZfvz5UQDH&x5}}d%C%~ zv`HbXR1cVt98d&8bsgolF2x|)a9N{md+yvH{#jLd(e)f?{Ve_cc`yg0W~aRaX$Pp$UKq%iVrWxa~X|4Qsy{q8Iq=n2ut&W#sc_uta3%WeP z4A)ih$D_x-{(RVFWHHC+u>fv_ zxO#p=eG{y1Z)y(CYK8y~Zb(84$mA8&3?#OK-~{c zoNrea^ns|Bx3kQ=KFC}fZsA0pGw$@w5_96hjX!-w4qtj9szkJMM7sxGMe^Q%qtgw! z%%c3s)J|~G6xV#ervp~{pVn+FY6H84iJQM@w7`b$vJ;mT8bPb+p3=y8Exhi%eC}ZZ z3pT&1dHnoCDeQ_Z`y}a?57a0t>zZB$e4gu=TkiE8tb;qA2GvJ^wA=EGHxP)tRL}Ca zpZlZ8LTm>@pjeH-`$wK=M z$zERcyBdv4&*Bd_QIGn*>09M>Hlo}OF>b%VH=}F$O+l9~x1xig17az=+tD|}80`_6 zPW13g0hkPRp$;|w(qNxn)bWWwcAab=@-L&Gms;PC?(Qs!G}t_V%nx*0)A1l;w`2^u z$oxT`*FOd=o%n+?Q>4!%jt-$qIg4tV8-@`MKj8Phc?5M{skMALGK#zm4ipY97)N?e z5rIpD|02noz7ac%|DqA4Z^!O`nLxP}V^X0plgLUvcJ`vMDb%aFN7MEg5B6+TdR5cK zgZF&Re!Izv7x#S1(Y{d4i+dZ-d%i!xhjX4tU7X#_hwYd*Gr8CK@i7s5-9a7!EF$1# z-RmTP&zNd1`?!+AUUhqOMB6Fs7~|68^Nfa*#CKoZV=Ra}FB8X$3t`iNr~=EMLU??o zijnFXI<~J>+%e=!$M3W<6n!S>n0eQ3ub&D7Q#IL=r2bm2Xm!7UFwRl25$q^q z;J6+8biBhDc%W^sk-iH9d;QKWP0}FtelGEr8>HjO?vE!OoalH-!qYp&%|ci~JA$!y zj}Vr>_O$Z;J3*|!G^1KlOb~Bx9B(+{Ps1X`A7Vn(Y52G7CcC@BG+emxK+(xI3eSG` z`nrE2h1YGKmuv1xVK;H^=qVQp?{I&)=ISj9fB$V1aq=F8uL{O1xsvxOW;XfDUsBj$ z;qGd|R}>C7=5l)7TM9pvleNB+L}9ZX_uVG5DXf+}UvyD1h5hgHA5U(e@W+?Ekr|y7 zM$5gHzU`v0a^d_@`DO~Qx=Rb%)=S|Gh1KVM8!4Q&|2c{%r|?Q6gN;y1;ay%!)V>r^ zcyq;M!B7^3bHc<==@Pri!EMQ0^8LT~rtqe%iAvht6!zl`sdW&0t{=I75_>4jyjLT> ztB%6+m5W=$@+e&SYUB3_GERdF9v7V>D4cK0YI_kv;c>q+AHR}v8|~}|2U6NvsqIoF z@0U5B+GG$%{aeQv3UfrysbsyOunl9~BK-skw-4yMP0y>u?+40+)$`v``0kBhbcwV}4KR%TLdKz8!=qFi zN@0%%g9;VWe_%t@$6nI!j}Wnq)x=M4^bFN=eJMPsV-x?{jlwc9BW}MQP*^8!YTK44 z#Q){TpScE5_?}_z%m2tc@>i6yH-9Gn+AFpBUOt6opA>J4VpCWz@bQ^d;}mWaX|j-B zO!m!6@qLTMX*gI|`up4EG+frtZ|EpR!@RG}GDK$4@X-zJa)JXCt~+3FB|zf6xJC5~ zy^_KQ-5N({5&v5_pF9y&LgC-Wt+n#R?i-JT>s%#iIB2DT$Ol^*{;VZFN2`&Br#eVt zG!ev5Rv7fCOc00g=g!}xAcWJS-(PwZDTJ#whP+=QPsh@huM0K*qvOqU&Ad<6((zjx zfp;R}3>@^t|Cz-(23}a|YBUkgzz-(r@<&NN=@mbD!@Qk=lZU9mUlR;$70vX3O%3iMG&6-3cOUhi+m_+q~V~%>>6X?#_ZC9OY{-PVM)G)sUIe$*y zclEtGj*e(%mS^>hp**<&(_XoYkJW}_k9Obp7o%cKHIIN zl)6y|uF#AA(249-lMgr;cA&iC#$lC-HnhFr>FhTit;jSbp+0VN3%YU0sdj|jgoqcv z1nh4_VvAH+w9EA<;tN_lduc8D5Evn3Aj69#-O@*T&(J{=ES+KPt{nF+;g^=a%B|$Oczwxc;84)?gryH z{l(l(Js^4ef^JAt4>0fV@9U#;!Oqno$^8Qtez-8^Y!vE)*ge8UpT+uMW!6r*(uO{G zOABS+z89!MML<^>fu_RW5$oO zH4vJzs^HOE4m`fEmHEPg1@QUSSmARfOdm4}YnhNVm36gkuo7av>llRIWkQOkiebJT z3!c;6>}D&m!2DaxAlr(RgJJc4Ni1k>+9O+6$%4Oi&K*YKEZ`d)pUn4QL+k;mamidZ ztbM#eV5=Ml%&U>;>s?h~zL9gtSh^Z+<_QXH^R0%pJQ+&o+p6KNAZ?zyUk#|vpJ0!* z*Ffxmb>KvDH6&X1e2^Hff~hXeM_F+k(C~k*R>UCoLnc49WLAPRmmNO)K?U^4jzqM7 zDu)@JF6I}MjU71K>fpJfsKw1(T)KZ)~)0{Y%#e82eRqZ52d!rAUp`a^U6KTBQY{9GKCA6Kv4sxarQ@!G`9qdL&|4up~ccXr(m^ zI*!fD8CPY&!&46w+k2Vt^v#;O?t;~b3keF*Bup)Iq;O(Bk^jS4GYf4y&HJThHbHX?ZeNp!Mgm~+lW={ z|J!3j-YoHR6Xt9<9JzxiD>it>SO{gVXG7wW9opk9EI5=9{j}eg1)Rl2!VdB*xX`e? zZoe=KmVN5lZ${!LMP{p+A$jktVPBJB&Vt+vI@w#}Sx}NO|6<=7Hr%i4>o&R1h8+rb zxS_i_;4NFj8=Sy_7io#?G}9{hJZH|3tXmbVJ_~POepvjY(H|52}aEt%_no2U_FaBHJGO3-&4N^cI)K4aZ{-QPcKo6 zS#~w>kW&9dT_M+dh`af0l29=zaIEBLGt%E zipMouAlYS?bsx7C3`n*~%V>vJ57;V??{z}tcAXs-!rid9n1986{~mZZ)P6lLwHI2B z?O*rf6c=Wep@0iP-aC7w^0*+XyYQxZ4i^ptMcp_%z=dIZE!)%{F09e$upcVtLc+GK zyRJOo!ew3a``RCS;atPfowEkJ!E}HBiP{HUFyShp=+x5z=L}qe9!Ir-{u9&Lhs9dp zQtb0qcjrdIt^Xh%6FimaeRpUW&X5#l?v)k64LCa#1n46dT8t+szv;0C?Nc!FtoAzf#$ltk3 z{_v4<6k^eY(|RaCYg`OZa(r#7$SJm^CbRWB1c z^8Ki4{vl!0!G4q`|43qlIe-!$O%~;q4x++~L~(Qepi2{jA<9!jh%aQtUZJ@oDC+du z373Hp0#*PIWbtX_JInCzZo<#Zfo{R z$NL!g;=ojtw4gA4-?CMzmJ-H;OAlM`CEVFROKfcQ2m{|+=BH3v!N4!Zqcd;jGVm5p zBM+UQ46Lz|Z%*hV243~d(tN`n1~zo$I~6%X$1~~Ki~f(}=F|Uimp2(_8cBo#LYOC7 zT65bOLA*LO?(b*?4PVKkm86@KavJ0o(y)g|nC(KsaXRg06Cs3K_&f67jy@tBlRRsx zo#=AQA-qn3aAtjhtGB5ig@c+j|3303+_~v!&{QDdrb`b`*bojdGNddOzfxE%a%B{k z@Qhz-%d#DWp9B-GQXImsCLW@%F8v|?O}A#OBW3nfQ*TWlg?)^DFKabX*dfLAxfJ0q z6-lzQ36DKfq%OW7IzOe{u4Fue!shO0OsYs3>MHP9zL0#!>(*RIbo-tCYxVN#i5-4> zWycN*Z*aaDqeb|#DLA&ri16#oz9IZ-x6Y;9i0J*K+EBToRtm3i2x$x>&jt4k@QAVq zFP$|!zBh-$?%xlm+7phI@VIoOm`UN%#c|WiC|2+cfCoA8E zU%i&X%O!q|T&N=J9Cl4#nfU#db!o^1Szk%B81{6XB&BngN&DY%Y0m~pKgA{sEcTR9 zxK+&j{ElJ@ufMZ~Uy#&QricHN_$90*x@mfR9G0O38MhVVti9-W3QwO7FQ&);Ztkky zZxn8PC|Qt}P3&7WC9fgtp;1&E6+n2iDmf@}8) zwpDAEzbE59x7;(fgv{fX*I4HwGOyLzL}8F}vxvjDY!Xjq(E=W6Bo2bM9AXTR@v9$y zp_tcBVYIz2`7~KScFeg=%X&$>>VPbY#1He1(3NHqUvm2^wSSC~`3o1Xv=N};^ec7c zwq*TgIGC*KG*)ot(Xi@|p*$bLk-@V(eGD~e__}6>7si$x z1;)MA!g$Zn&HzeD7@I15ZShnW##yGllh<{GvBkbc>CxK4ct*ac3gdvCi9a983FFjm z`T`E&%-GX?LBDbsSh;Tw_l+w9e{(2%Hg6#VpY^jaofAaIA1w;cSuUXC7J*B)BWH!M zdR!ymI6*w7k>xlwMZ-e{=c9e(XxKO7{Bna!6z-uFA1`hZzVC|5q0}&njzyf5su>$Wi>3pZ zJ&Y_Dmue3u523JQEcK?CKWKEpTGel_2GNl@<_pc94WLhJ46g@z^rO=U&*?H<`_PUM z-aqDkT=eYVol~QBz39%%AeF|1ZZu^QvbD3c69s5U2CDYAqnUdhstt`O`v}xCS`beb zec@iECiH36mG>UT4d{8?#M#GQb%==Ju%pka(Q5bPx!978`0j0W`dd?hPA!RRS}R(L z0@HuDG_nhjYr*uvn2j`?%`$J_{f%b)C6SDhCi=4<)xSnF_hOIT;op5*9GtS6CZnG) zV7E)pek>DggabPGOpD<3V3mfUR5_$?5m7f5WPxyJMv4GbK&!v>nQGWSE$~e0p~rDD zLHA`N48A+#U-GFLavs_*Ix^V`Tb^_$z8Y?ak;b9i)zO_m)69;xd)y6X*JZNpCVHSH zS2)hApcgg-J}DTzzy-A+144>iP#APCw#(%Ldy3~`InhOlzXrd%)p6lSC3{@op9`^f zV-~DG#D(tUFH(xUTu|&xKYVC&FZ8#^Z{R=F1BF9vvxnz*|Ie~Ko-0=^e*Pz&jQjr?XEuy+P-DT>wag$-@n6kiCP?JmlOO%SKz=IJ|;`3IAafeEnG!G(O3bzO7INHl{B|EHyb$s-v2c zsLci*v2d*^9~LAW`;)|e#DrCA^|vg(T?x-i#*F#670{F#-CUqu0lU*qmn9BWfH_mH zbIU^Fr-;vGJ5AYOlHRbz)xQdq+~;8gkQoGKA%Btci+YKy;UviBgH4E0heLLn~ zz=T~s$G)d^Ga*6ZhqlN{7F;6f-4|Fe*8B5fpb8rXJ~aDxUSfmU)oBu7!`bUy7V#o% zF#mBsMD-2}4ir38OYmaBw7f}kX2G1QyW5&cTx6YCsxSV61@w%c;b#h1uxT1kx3Ixa zR6aUxDI5OjI5u$JypA7oV1r{zbKJNm8@%^%Mi%PAtdoe$p#LwZT{Uyr2Y&h?*PZ5)L`F<6( z3+@n(WPX;A3`nA3-FSbd74S(coyf_=#|NdWLHmncYx+;;x zLE>0P6yCsw>E9({gDiNxTT4PGmj(F2Xg^;U3tHmM&psu5-Xis5;U`n#hc&kDU$?R# zZ><&Wt0WV|_wMA53{^t#>2k?D;^%&RmLMeyI&H4{_r!953iH{f7(NUBlMTUo;e-3!0-)aUj=+POt4{LA_va%b_5J5(P` zJQ(Cu{^Y{?S>C0Uc3kiaT^mtS*bAe>OBc@(=z+$^rw$d#c7X#qE|+w)L%g!FWA;=F zcx)0s>odOz>U-W-+lSV}j2@U%2T8xZ1*JTyU@9(LQ%{WvY=I>KsJ0Yt>8IV&d0z-L zc`s$@`#CVZ%Cj&2hA@Y9uYFH&06;C+3Ri!6dq=t&Or zp`6jvz3G+xX!^R+(sKa)+qZ-0hE8)rJ--&#sIx{Sh=6 zA+;#u=qQRi+Wq|LQNmdcUq0@(7)M_XTVj$A{Y8(fO3RmPO`z%DHJ2_-BDURs&jqZf z(9D0CtvvW!+_a;4Fi|~35cA?Q!aL_2VDjPyb=!+22l=q`fViw!6CVyZ-n)f;g&#XL zzES8c=ErmPZ}8JTB!I66NJ_tI5Wu$ec%P^Zg?}mL1`CMNu<6S)c!*8IGkJ^Xi<$ob zM}_dgL*29VQiQPi2I|d3uMp1oTUF$zM#mlK;;p~obZnw1{Y_1Xf&13*WGL-p;O+W) zKG&`j9n+d>>++s~PkB_UM-#oY&D$*MKV@O;{~t+or-iZfpWvJeL?10aW41hVqcHw0 z-PeD0jxatL{PB5gD+8XF;uf89$Vy0#?JU@(&CPdwb57eHaR;C-r zNuBV=C6MypexvZw zS%!j`=w%(jkHN=@F1FXpxhO+)d1QwK>jdEzj%&-dC!{`e9uXdD5?P+zO!($r{fV?$ zgv(}tnS7^}ZM)zA=||wbL5eJ~zw^}Lh~lRIb2RBE)n4Ir2;sVs%L5tv$$Uj58Rpug zTrzV(LUev8NmxXGkEoWqbQ5m;VR`P?Mq>AW00030|3sO0Jl5a)$F29xeN!qSN=sWP zN%axun3c??BC@keOFl(esc5LAMM+6RMv|4TY|38uvR5*1A{6=^KHtaV_t$xx^FHtE zeVyx!>-9YEi7m>;-nA4yo|C0=f|R_F-TOH?6h67{cyxFHg$MS1(I^KB-!*esa4wg^ zm1jIvwtl5BGxz?r<#`ld*0H))GmFBGfvLjFzEJq;uC&k{6%?+P2=~Hl3iE^hou%~@ z9$OH%wU$HSP$?&|)2$SqY*2SG?4q!0X8*gLy%aV-@F>i`pTYv{o`xj@6b}CG#{X=D z!Uw8HbeR+l8!1}!gb2}auwd8dJ{}-~qF4#6u z_>q?P(ZVM3ebf9K7Q{Zz&JUI)rPQ%=J2y6y=N8N23aTjlia+3m$u|oB6g>E^KsJR9 zYD6_liz%#?dS6waw8!`dzp*CucY*zPwvze>^%o14R#JF$sZjgwA_~vlT>1TZ357-W zyZplBx#`x-6hjiX*I$a&JPOIU3WARRB4vc^G0pE~6y6>XG({)n7U@e|2@*eV{pG6u zrNqu#l(T{O#XZrdyNkr-y)xS?v4i+^J8XEvFoplp`f3XWX}BU{WNjgdgIR;+gu6Hm zZwQPS{X3V2EsNySZqK9PLdDMSL91xErLthID`}TC<1F;%r{TS{*~fk`X!u+D{Db!< zDXddCd)-MAr;Ydbxo>Hqu$8jW+~yhzPslXJWpgR4FaPx5c1arka_6o2gd+_LC>4cw z^w995?&68(w}f%9fX{Lh6%pKUe-l?SLj)@*k3XHzpyQ0o@w!ou=(shZSayU*$04rX ztN!d@;PcyhKifTE;3P>^#iaKP+|=TE%)Eqwtv-*~WDPQK-GN@^Okq*H!s=&br@APs}2?CtP33`|LV3G=gK;It0;wLkb7 zcrsvT(4q@;Y-6H6v6(G`mo4AiXDcg$rK=4`|8W+^Nevo!G@pjuN_wv9NYU`3ft%NB zgD9L^t>7TDoWfh9FVt<$5W-2(wCW9(Lim-;9=$<^5N0X4Z(aXR5VHoYmx^o<#4)@7 z-r4t3081G;tqzbEz`uIa4UMAtanw~kF?BJ1ylD01e{Y@U!zRmfK!o!b6?ugjc;!r? z%SYyG@RBA`_ib8gO8x{w{PX2^zx;z*+b>>;_Wg|{b}YWSe$P0n-jtPRzG@5=Dw$<% z=KVs(YjnRXs~JHiD;~Hwz8gliK?M?85kHZY-ThaMkA_f++Ks-Hs6li$WMksZ=RD+? zwczWuU;XIe(6U#uS-t4AW2W|!xNh`D@oXqFpbH&0%22!=(urQ=%j8BxwIj#uyd`>( zt?28-^AlAcnvuD=2Ws|fKw~c?=r13!k+M`!(T|>5G`V}vL)+O^Xwb)AE|7Cj*49+PqX>05SHG#p5i`jjke5K)>*sXpzoZ;`DcXt2`Z&Z}m z^bEi;i_(AE{tSTkgDf|7MIOw1s-8XN$^#Dz3oolTJXmr6Z|KEL9-MQK7K=~kfoA+H z$u@5uq-ki`W?mQor=#r-M(g|F(TCR=J3e+pj7t6@p~x;+CHtazt$in;MJsg21==B7 zW@6G-traW}MJJa;H-prI_ZhXP8zJ%JWTxindRQJ@yzpoz2inZmwa~NJu*PoMBQ`i* zwL4O;&xQ?;`ErN8v*Eh)%L|b;9EfWhdscOo3yJy1pYC_8hZ|P2Ol4gf!14L%i@|LT zkYk+WGN-c<%2aLs6fbCk9hwPV-M5?I;E^jX2Jf3d=+=n=+2JNg)^&QQx26f$-KPw& zVIwGWjV}fNmmbYTb*>B zPjI2IZd0ILI2$x)2FQduxe)g~m9>yNXPb|Pbq(mK#~zAms0R68^r!`gYG4=B@H4x! z7J`jRK1ig%>dqbbHVEgzmE1aJVY`SvxYjHN1jVMHlm$TrWo{hAg zI14&OWQvl%F@a<;4|xYBIC)!JzNxB%q&-@CwFz}_N2`Cip;;ZgOqa}YSziaZNosv9 zRR`sYXI2W-)ekXf58@_Q~ zdRgvc!<9UZaLqGpD0t=C=ktaQV=88WHGOO_bggDtiE@DdYUX)K84gUh_9}4T-C!% z2pe>tt6z;=%YmB$y4lxB`Se@O3NIZF%#!`RI?bE|@BPjsImZyYXp5>tEC-exqk`g& z6TA1_wzF(GkVj<33sM)_?%eX8!GWm!Ju9r~9AE|P8XP1geLTu3xtk4(Dyk&i_s za(`0}?BD&**KD#M9deXMe!gUZva79MLKhPx963|>?lGZ@>mQTh%Y=4i#qPWHWSw;0 zoVxGI0&)Fb3A~XF0n$E{a{(KiCvp^aJ>h_DUC6VDV`Lo<2d-RfS`UGbudmBZtA~-S zpysse_0Uk|va{Z<9zwQ8+Q0qAh07Nl8sGGAfNx8Pv?z&_%%YVEWyG$1lF>R@@}0g^ z&*&8^Sb)@uZ;eT^;P8;w;fu{IxU4y?G}s_|e?LpigS;mf8t9{554RR*q*mN(1U~gG z?gc-ZVMdn-w}E#?hFy|T2h1;L3uwE3hsSR_w=K8+0hfhK<1Z-mK%U67g6M5b5tYw+b%X~qGIKKzw3wfLts=-0Lzl zzaPm;J&#Wr9YCXR`I_7td1(EtiC00BgJ^|KlksxxpD1mqMR>yQVRYCa{I2OgBM5oi zTRlhZ7s_!H5c{@d6tSrQ*Z!_i6f%8Ge;Y&D)6>~Kjw}YYa83&TLC$SgQ^w{`pbdT& z=YH;+L{j4;I&O(mNa_0?%l#k!qCDjGqjDb~Ufw+CO-(N!KEUJ7X* zF!5(}?D|lw@aH%kpW9e^CSflF@3GS^S$U6v-zEj7Z2ZW;vU$Ru6HErazCkZtb&7!} z_+F@;oF|H_ZZ5pIMNSk)uXfm@vrrUETzvg>i=-&t-!!gACpz(&pSjxUA_o31?=oq`7@M>zF++%abo-)e_THQTO@+$>YFV|Pf5KlG_9~Imck1Sb9r-ZwcX>s&-qkIKpvRO~(pn5w4q- zr?SZu7T0-uchd*LH~cJL5#pC=!Ptfi=@cf5#iWz;(-w2U4lq?ul9^aCE>DZbvoKf{TIhJ3NxUl z{BbvhOVy1lZxcTB9XdDgir5uqe7b8=PGJk5v-_in{dvkJ--8LKjV?Qp{+m3Pjb>a5 zBIA;}`Xp=@;ikRIuUYAnc9#Bjb}8X7#e1pp5#&9laaf=(;Z4o==`K&m_kI?BAPSkn z&2uH+Jno_JkY&@AfOf*GY1{6J5$>8aATvPf#(L|nE0WSz@8aYf63?}V)1@Dfcy?>Y zO^FaYyKlWbuR_L~Je>|%6uz=&dcYJG>(I?)5Kf%YeT1LYJg;@XBk@jMK{h_|-@xY( z=QZJBE2c7Q7O`8_DC54Lw9k4S?RAgX7qIgYyi3{_dl02W;<2{0^W*};tMBdP=Ohq+ zFG(=wdJrxQXRLd3k#M1`OuJGJ;kA0de>y5j9ICU7yT1{8&qfR8@R9emer`LL*+}6( z@?wJFr2cgK`kF^1{=Vr_iulj}=3Rn@6^i*vOVX}I;&CxOaMG;A8XJ!9?x8rGI)rA=kgFjI0<4p)cl8-1?} zbEfxuI(MWhOawnYG%xC<8XYg_w_NZehK^^pXAd3Ilx}U7*I{56V=H@sCk*UeW1W!L z%)mgh!s%tAcz&{#ScknRmYyAG&wpAJx7g~;@QXx!c zF}*%Y5KrUOdU-+Y^KSQzidzD>C}~8jWsDzBtElt0`0@I*CA=?7`SD*NX$6-=J{)7{ za!k;a4;xrT+F^1I>mP9)*n4jZy&TvqROm2?)XpR$)8iAUTS#@T+NVD##!>u(06EVq ze6}SYS@s+0EY7|WrZ|p9b_Q@c+GEIcT2L8|BDemoOX&xGA=wiOS!xy|h~DftXuE6} znZAm>^`&VDh0e?Tn93dej}tjOG}{GIBvuX}|HUrc4Z*!=@Mlv1Q>hze3p`Nq`0^de zbUeJDd%Ob~tcvvvdfkTdR!8pKP}_puMB2FQmTN+*UbR@5Z{Z-3nxgazHaLquVNYE>!4I;jrIh?B12_Y{Uy6iN& zpx^{UL9*t@|8!OlTz9IdK-s;pNc-L+jfy_lQ6KFYX=7+S7ywUF|ECky$?&~N8|;7!P)RaV2f!MwOV0}1A%+v% zwlSa$!i>^$GA&!-nAVzswqq?|eMItA{?TTTomt>b;PJ59VPjGQ%-uh>>C>TlnC-eQ zBu9x0l6!xwj%Z+mr}Ub&iF||)nbFiS3l`Ylxt*LC%LF4sY1@$nxol~CZW>YIwI0CWEGxz<*Jz}(ia zZ1rlm@XPY$s_bfLsIDc1Rs)9FvQE`=YyZbxwJ;=qF<(}x4&sQ+Y>KIa5|I<)+L#Hu zUj#!xo|M?hS&SYT<}VhBT|bCv$;|ZYDHX_$!jOM;G{G4P|KSO zV)D}pkqgCdPm2{nZt;(}FiTGT zRo+=HY^%_5U#QQ8(13Y_3^?Fm>h7`pHwRQs`+c)3<-iV&Y4YK~v9qUwT5l5Ws5(Bp zaS7*t`kDh0{`*IU)H$Hdc%mI&!v^i-p2pxjHXI=8UF##^(~8n5oX&=fVdY&8!E8|P zsJxN*iVZBiO2H)oY&d9<1iep4f1mh|wwKsYA=WCWKE(ogLo=lt)+}i8?lzAZX2Rp8 z-I{!_nJ^y})Tab8!D|L|nBY$6Dz%&m<7li}vzmwTea%6Xrum&5p4>!D9U-|!>n)CdId|fNyxJr#4 zSw#-$Y;|Pc{lbCgW%W8aqZ}|PGp!$7#f7f=zVpt(97y&`+MsL9fm_?kS@+#I@LBR2 z-DQjov{Avu3or*tR!s{sHW-2Kr?XRRIO#d9G}*9>GFf(z@S<(z1>gQ}Z0LWGp^$l$ z?5p9cm8S{+{yl7!-l)cbgCf%klmqpVDO@F0E~Lb^N3e9bU|C=^OZ6!i-d%mv_0x_`m8F|$Q|MpC99iSgL2a?OiJ`ccux}FC^rsw9?YKawfboz4@wU+ zcK%s1_}~4F!XUW6J>=v~>dvzBO9ffH|IVM2JYcF0Y}G3qfXU}4s#IU~!(Pk%zmDAQ z`;U{i^n&!ruKvVp-O$SS+vl%i7wjwMGtIxz0roQ!+Xh*;o^N}9su`q$&!E_)Trkn7 zYX11K7POqIUUo08gr!v{tcA;pVf{>k`~rKsJ{2gLCBb@ImW|=>5csFeogiW?GXH1E zla)oE&`*B9vKL1AD3m!3{H5r>eOQfJ2K$Z#e6B+VYrB5kDPW_ZGhQNXu?=WbuKppA zX+eF89o|W!ttdEN6m4D7fs_Qx_Pk&89r=f@KPr&gg$j3sYzj*6MnBRo$LlWbL+_@q zscZ*Oim~O*gHb%x@}XJJ+HVlac!b~SupdH^=~n^=e14)tp*^-t&tas0H15RFQzOXO z?t)^M&o4w&|IO2nNB_G|Z5~7K{hNXo42&bstCv_+ZNHH{ZCzW__djU*7G34j1UgG` zuddFVM8285%*g&JRJX)tL81^J{u1UVc=$XYcAeAdsXWSuU82S#GJW{5Ues^l+hPLP zv`HoQTeJX{&Y0)dy+jbtERO&|JmXHAAigwuQ&vJ-2+Nt@4E6gYgqPjD9&z~yg-^Yt zb4`f;yJ;R`!tX)DmIrJ$eW8SL$nO>BSb4&Dberbkh?64t?rVRuT@505TYA&8HKugD zkzm)wY&!0VlVaHkFtDJ-O7lfZ41C@!)0*;P;9D``M@)f%U%hs4^%-Q~{&Q;>!*o&n z!IOKrQ&tr3h=07tN`dIJ!Tut1MWWXv%_MvX#}Vk>-1UutD?a3XJ@$fu9~atexa7dV zT4@4|k@*aKc8PDzs(3n{xqnrs<0V-wny221V6n62E#U)1XZ8l(Z{8=2yMkW!4(Afx zwp_A6N}GnKv$9P;;hB%DzGT8Zx$8fiew0t);xk>tpE4;-UG+LEUf%Q;g>u1YCI&|lcYv61JU(Ot|B+T5xpD z!k!b-A_9cB7hxD^nxOE3%vCQollhH!6_YMWxO9Pq$SG4&idKAlbe6Q=7_|BIp7^ai zrn*{rh;YRmIe{JI`L!~YkZC{6jCR$v6j7K!f?O;q=U3>mc!US#PHn39O(0w%UAsJ* z#E14d+9H9(qhZbaI#Uwg2h-Pc#LqwHd^+REIQmyCp9mp5r8m8y3BSCXP+1^PzUO&D z&({Apg)?=6`R5UiEuTBC6hrv-*!>ee=HfKW5zy{w5vAb{y;aRj5gLwbPF+?&>RJZ9 zoJP`bwe!@2IvNdUsp|Pw6Miw6zL+F-FJ1E@Cn4eL0v27F#MNo~$4?4{r)B#S;`eXs zcs)@v-$zf+enNjo;;^P~)@M?m`JF-d);)BWei`Alnd{~X3L803D)N(fudP@;w1RN8 zN(r6Q&LccLeNjx}E`G_V?$vh+^Nck$J`xTK9es0;PI$0+p6?|C!f|dI)0vCHXA|!J zeoy%9;DgW1IfTE;q~;tJC;ev9FsZ8vT81hTt~${s7G<^15mdXBQG+blL+t8;@xb088$kcrro;hdvgt3cqbl-#X!Z@== zWYSPh1Xl`tc;}cUg2f+PF&roRm@n?;q8}x6%zXCfPMkagmu;P8cG;SN35-fPgfs9p zAAvRc9~n3~HSA|T;isAZ1~m*kWkZOUaFtQ!1IG+$Q9OOC{d$flURs;jB+*0oO=9(^ zI_anHz1lG=je!#`5CMILfva7UljcbUI-@;Hj&W$pBUQE&Pq3jbn*YAtq+aDJC zln9Gp;hBpsVeA^2wkQG9uu^E$*hWVRZ{L*d5uYuDV|%WV6I=-2J$c>!R)rw$7Cw7h z`;Z_u5s^DXFBJHX)6@iTSyQ04&?kO8ef@HC6F>eGI$PW(f)B^ZfDR12bk~z(sH>C9kEfuX?=3)OE*(z#MU%bZA{g5%^ zlJjFo^;p-_=IBw>6B76_;@dBDU?#95$ozFwbhq>fdQ@gi+p%jH&G1dYPh{T8@31$1 z2q`;XuQRJ1M4e@Z8zOpmXyweG>;Y6M{Ebyn+K0r>DP13q?m=3*E}Z-iKhWk>ZSxx| zyU^FBtmg%Ro#^Odl@6VXb~NYAhc_$b+R#i|*wup8u6S6hUf+m3$Lp?)=yMUCxrk?? znfzc|g9_lB2s@jI~Pd29`AE7DU&!*?d>Q|5PxhGNZe*gdg|Nlf; zc|4R|*tR`0V~|Q&QtGuNB}KdFIYL6Ew8>JGR7#|zXi*}iC@E5@L}hP5NN!t5LWo)H z`#v+a?7lPJ_xry2=lb1e&NV}jhAvGojSJUY=PjYX z_Mx(odVxQ=KJ);xcHmNLG z+Smr}n!he2K5B-fjmJWzk{Te#QQgkzUM&dB{Mf*|=~tQL&w#OKyZyZM86ds$gsS%& z2K)&Ma9#b30g|Hiqh{T4Rrkk@N8}yfiZ0tvDa9~Y6 ze!P?o)phS;%CP;#Hd>?MI2**tjW4wiu)!rIO;gv74bLnZR-_NH;A*>!O2;ZTEOmD4+r-LJ!rZFi;=L6b0Y%j?b;at#J{bno zeQ?_2;LU(f1MAmsHfO+Wx5ZwSOBtZb&RX<-F9WKzOQt<2hrQ91;uN;yVVW~QFFt~x;vn)^}~38T^Fnikr#Kf=z(*wODO3V`yhe8-7C1TdU>=| z8TOAS)J`>58V|A;>Rxk};(@ZEy~THV9?b68!P>Wo2VowyimR)*;Hz^}UQM10y8Tq) z(r>+>*|U1-q;3~f?UVMg3C8|m>YA0Xv>8kcMr8Dk)x$wO@e93TOxR>l^W20|0okn| z9qb?cfFq^V>LK^jfw!W{<)LR7WF#E*$IS(*I2R zcr>q=)S8)aA*s@yr@$)6BC7&-_A6bBC&@Npp%=#fWd8WM@zzI=A@uLYid(&j@avLQ zXEHMt+zyEKXgIeQiF9NzXF&iynpFV8Ikm5-4%R|Cr6sn-!D6ndi4z}_W>qAn6SusTwiI zp)4t{=wu5MjMdfLUpD{09XS!ndWUUi<5`S9*!J_WtjNH2pH;k62*!>q*IVMa{6^Pe z11*eg4=T6*z*x!2sXBxERZ2f$^9G|z7xA(Umpi}Q?_ko+gkiM;`*YJw2#v5_0C+qW zIz!vN*?8QBs;2ROneaGmblZheCL~Kcyna!^1hLAa+||8I*ey4`r8$QQ-!}681T-SZ~PN$#ey~FoapDnEa2{}I6<{$!&_0dS^fx) zTN(S#6nEEv$OiM2?W|gu;`q`3{Hg=}wxU<8hI$CmF6_=$Zh&39)c4YJ8ep^YvCm5T z8(@r+eL5ti0rF)n3V682gS9W~Uywwb=e5k(?JX>J={OHIogf)z z^Y?&q7hL`^-NLEs0_%PLen(xqL0tHW_4lJaFzS7yy-vRuPD?}$E3$e)F~IGd{QW){ zeA5`5HrfZfC%y3v%mH6P(}bhvI3S!9@9=`hf#?xXT0V~piVHvY7%$<1Pia+lwgMMS zp2c|D4{*RC>yXKlM;rjPxP80#aA4upVycKX2gE#Cjfp?{;PlGkt(#T*z#}$6e_d2B z?p!{!c9+LLG?}1>OM*V)JQ}mNBqi$ zl^+TWOg^W9i(41LWrn0=y^+*Xnke(_Q}DJ8k=nJdvnM$K6>u9M$G z8n4KF&1G`Pg-T4N${jq?y0}zg=hJ=?AL^%`egotUy3qp@%|X&B;QTWe&LFwZT=mr* z?hqNyd6#ecWteo#TGCnJ_?Hy3xr2txM#!jYhhr*BN6EFU80Al;qhy7T#pE2{G4gbO z@Sh7;$H^H#jhrC&Gu;ijFiDEUcD1^*rpVY(6S7fU09}t7Xgm}lfDZPCJ*biuL>>pq z?>hSlqRT~&>ESdXbVy3eACwvy>A?O?>(gBa9xawJqt`E`lbU%pNdGFisv# zvENT1-u4Wg7h)9ja&z`ncLoKi1a%yrcbbacrpEMqRiyn_pN2+FmZ)6ZDT+*k+Q+s$ z7e(R;X>X=mMbYr5-lTPkbhL`S%S!1e9X&2z^DQrwj-&=ggz;&|S^#2OT+^w%lBU+s`$-xaQ3fI@0dm z8}I}7Zy_A)yWl(i{-Ty4TXRwLufNk!ex`kM_AnK#9#}Myr-zYSnI=tsA31lId$O zr(e3X_hD2$v8?YB#_3K9Jp<#W$0`D0MhT1ikjwXe_f5K~`m+$7l`0DESQj zkcTjuJE{?-fzQoEjP?78SRs_-gNcN(5L&h8+qw@!f~fb!?*l5o1(9@SW>r+1AnHC> z@AyJi2+@8r%6=UdLK^#~k~2ODA)OuLZBxsI(V91lCEmpeqv`h5M-C$qv~Ib}Cy5#n zMBxh#y#7}^ZjL>Xqacc8MP}Md3d$p1?MYutMSNPXRzgK5sn!RJx6@FpTa#->4h>}o zObh7=h$7wchLn`qqUh_hciJsWMUjxidN+mnqKGoI@_c#^4XL;Zh0)kFbfK&0#N|2~ zx}v6Y@?tFwc{0R^GX*sCZ``4wz^Rbazawa9jtgzS<3$?6r`*YT1ODD)QK*!pA=w^Z zC;xsb`uW;0WuTUdR`LhRq#`u_P*JOxiXz815u<5Tbg?eq!6=4`y7${(KtWU#fS38^ zc`8aDCI)kCsHp29mc zngbM+=D*r7ZIFT-zR4Ed8K$5Coz%^z@&9vLUfp_%ZS3{Su3(&@O&DuG=}+WhymG`k zrX1t(`uW+@7*(@AOpIcbz9Z^5g7Ngx8;Knlv)sPl<6^wM)4ojz_j~*H>T3%yo_ndz0shB#f6Yj#k~qD01OQ$r;=}wNTfl zmWSieqrIDR@%(4}t)GGf0(3n!@VX?m6&$g|<@<84nZ;pync<4RLKsi;)CBS|&iD_m zKcoM!-5nb%lsrN~*;qX&OyY8fn~m1ORAimMQ)2Bj1%>AJZT4-aAb$6ID=7c%Ck5^D zvKt+Ur=Szhrci1&(VmPm||8ctW6P?+k?Q3AIBB1agaQkNg`? zAiMl|ap&-Nw*?PVj-=vv;gvKki0$_c+?#$$1k%~*kP(lu$h>=U+gAb&>pdZ)fIwBT zg&kgb1oENJTIE-W|DU?NU^T`~VM;5Ym_S)70@J}o1e#KRqBx3iXyC2l{CooWt&%d_ z{*6G9e&Vs0atXBLS&PvG{=b)VCa|symp7=jnA8&JTv5#xr7;5WRYAD~1qEwvDLyPs zL1*zb)Tcl}6)z{Z&%yCR=xdnH@%a?=*l0se1YT!8JF#!Y@%?Y0PY3QVk0PdeDw9CJ z^+H@a@O)Ez+M|xXA<$O+X%U%N0?o*GydFM18TWr-RQa{If`#XMTW*1w$ZrDeIEQcG z*8j%Yh2yeF%=Ou#6yz)X&!H>>3cB^|-tyc~d~TZ?$~9G~C}ySGgX(4~df%)m{P-aa zHI{3(%Z<~}V#%xSD@;X^%(DaZ8~EN7cp$a(UYjW5tNkmR=qNW;-r%$k9Zf_TUJd$6 zM~%s*^0V-LDf|24j@tQR|DM0~Vknz0Q+JA?$Bg7}wdP_dP*(R#**Y=gln~bLw@?g4 zooqd9J4{C}j-g?XFLX4p@FBn(Ebz2SqcNf zNNclyU9_z*T0L8&u#6{!#w|k@yuL1k9!f;|?-Ub4Gc^CIAX+>ic%!66098tMDf*ZT zpegP^y?4koS$@y3g85^LB>Zm5?fo!GR!wgz4mmhMu4YKErB%ksAKD9TqQ*x_^>B~K z?A{SF)VC4SixE<M{GqHo5Nr&8NBX3~0sETPJB_-`9*7h}#AEF1|k3a*Ns;hVOt7i@AP)kZj=rc(D zy%)#yY${0+tX7}Jl#)u05v4|Q1?1-Z`7%bWnWX=M9l6{&(WKfFD@%zx{(wb}pZ@wJ za1$o#e!RwE4K9@aW2lEeXK)*HhrFvj&V2D+a~)K#^I@Rc(bn znAW}2Tkgw&vzc>hKcD5oU>!an&0M(cK%!5>Ifu@ARy#MkrJgBnBVaaahfj(vr zxdJ@UHF&ex?*$hu4ib)+1~tmy_`wf%h$S{IZz{&VkT zemkTy7ccwb)C$*xmTh}d+yr4Nf{u>N2Jnv_lqxw}4>R|+dJW9B@>u)l5%b@CMlA#Q zy^G(khDOip-oss0kTQ5OMs=VHpu#?%ZBhl3CpR8HoB8M8yy0ji{ECahk*oqJnGsfr zo#oJ{xMPpT{c@;tTi^0ht^$g3s;kp0D`5Mmak5!KC1}hDia(H4AlAv9T@AT*ry7jb zF#rrQ+@^XNfJriTbtWw357&|fYro}LygkB#`rF>OmSH@v@qPdCdKM_=F0U)p!8&N> zLS;kccGK2g8XGwIH*;R?U_;hF`=Xh`Z18fJy_msc!QCOJ?`L!}#hURx}I3K5uCaRmb&J2LdyVS>V@CtW>sT!m0Dm z*|$6ypjm2S$&+A!fUusI_#y__>=N}ePG!LF$FzOZOPFx-bJzLg`7Ef&9wTp$;(1@` z(b#Ry24@~OT=*v&zNB!m;%CG1*5tYArYz`Jy7qm61`|$5CJE^uV1mNg+rHo5GvILM zklnXE3}}{HJ80&@fKKD5m1PtL@UPRg71eMgS*tN*tor}*w!()U7|XixI&6@hM>$># zV_OR^PcLqOU1Em^=SMceh+pVj;|tB8e1q~#Te1y=zVx+42VgxM5t; zfWaL!Ipo^~8=BV|%%5rpr@%Uw#c3^|BeTt8&(}tv|1HYcUtI^PGYJ_MJXxajDrZg= z^bW|jJ`MQ|53=v>jraKpnHss*({JR#j2`@w2|4`b@Baiugz9l~{S{5)(6p`gF{EN7Z#4K7q{BQ-Cs`Oksqoa!4JYM8IIFC)% zoOt}Se5{U~ZQUw*Yf&Saa9nF)X?qhn98&w}HqlDXqn2^TH?)&{`k7+eNj^O4Wgzvw zn>3ms>V2g0Q4{6grd)F3z3*grD34rGzh>_1-~HtG%~_A6`v%CC<2%*4^M^>ElG8nN z=MR%B#uI2$e}_pfKOIDjkTZTdG(rwvpEb}*jFHXnYYbLOjFaDD6;?|!$H{wN^^y)G zO^~X8H_s!|C&~4}EdP_^Q{-09Azqn`0P1qLJDn0FfSMA2EEt+Ch-UJ_F9ngfn?>W3 zRYIt!4qpUcg;4wbM>!cr!YD!Gok(7uFq)B{IwD9jWS`T9Y!T!)>xR;eZN$GklY#k` zQKQE^%nwC$D^u*|QPGPbwF3K(RJ8u*@i*tU(9o3RhXcLoG-Uaz_Mh)dM3IkTZK;}{ zD9X=kYi4mpk?)Uv+3yYL=(2F}73y`&2a*~LkG!U%HYK%AJFKTgcklgKHAY9!ccJ}` zsu<#@x9A(ikV|lecEJ)cw2aeyGC*7mRo_a=e>FfyRw@E<|4)>?^A)xv8 zays&U)ADE2TT!IIPtz-6-K3s&_j@1>MY>8QudSvc7b~kvhnG{4{-Oh^t#2rZhrM-< z7Uo%rmQT6e1QL36SN;p0?|@Lxo4sEM^x3v4Faqg&+rXqrQTZ<$m+!NbN>(87&mX60^sD6}@O`z-o+waj;1iHAl=(Gyv*C+Wz z5c5*oIA>c|%r{RaRBSiJeEYq^DHkiuXA8p~>h(>PGRnYV} zi|28AcH6~OxL+9wxj^$y+>i3*1Wq#^_g;ls8eaE*b=iOG!ohmq{pMsflR%EEB6>qv z1PXt$IJKw(w^#o|WMDqdisw5ffsQTRvuXs7%PzNK#c^E!=?ZU0Z(Q%t+aro~xLsng zmD?iB$MZft)i?i1pqV`RF9N+b-8d+X+aJ*j`*;%9dlJ;D9E^1g&F$gVLwLTzwmROv z*yg7ZPc`EGn|Y_gx+OmA!Jl3N&1o3asKeuwOp`mCMWvuK*3${43n?gWF(%g56!gYz z-#WcY3NlGae?E6N6$M><6FAyHMPF4V#gct#h|l_8$%~?OVb=FB!7xRK2vBj`-7F+fGN)J~s1o zxpWk-wb$}G=GTMH{0D*m<;8ULR^oQl4eTFJK8c@;Go_0v)fzm|PAltAOb$3CS_i=de_ z?IRIn91*fdT}A{IesPx=3lc^@aTML8ER0+iM9{Cl6+*UdE!$5B2qAttYQrf(WFP;! z@-XJjL~fd|oTUJo;aAV6Nxqy^jhrGQW%!DGk}STQpJ{(=f^5$pyrrTrPCoaCUeUQ@ zAy+~QTFy8k8b20hr$P8}v^(zC1~awb15F+`q!-JjUHe~{Fb z>?>h84UikvC2(l&Cuj27O+35C0y)!x{|1bPj*E$kBYQh7B=Es@*9 zlCLCXOJBXdezT0^)7riJ3rTX_;dEp1Oj1cxPoh32hBTTXo=&jX*jQ3O_A_XHvJYsr z`3|(^cjuh1l>+H{y4>kbB^41f_A3{sHT|nFKIE-R@V0qJppm>cw&^So0{}IRmZTIbnXxe|4Q&$^$_&%hb57JP29Tv^eDg4|ZzgXK4rUfEKtu zz`~RVS{=8_^s2eQ3Ap#CjpRbr1>N6nc6}fb5OlCTv>V)9eVYQlbO2lKZAxW!D{Kre z_3~KL3|d%?P=g!)7K))t`lmY(( z00960ESY&cmCqN)ZO?V@RV0^dn~Jnjh)SiTC`m<1SqhOPEn1O8yOO0k zk)pD%cX93OwcTqE@f*Iszs_ssndh11IWy<|ITMm1vTXC63b>>*dx`S1a?p}+3!EoY z4zmoF7hcFO16`LG(a%&lSRG_IA8aoNC#z(c^M5M9?)#(=jVmn3h>x|vavU%-+}HkP zkPD3KeUr^ys^I6W?+>1Asev2EU*B)0*FqR4>({@~S}neCl;#-Rpw8FpwHYE(n4L8Yn779L2I<^8Dc=YnePmIKupTNN>Ipio#;cl`ht8awFEDP1nCJ(V3bGJ^{y>1%^Tr*fe}?{&(G1zd>w z*>6+m#etE8z40T?9Qf*7c&BQV4eiT{cbs3vfvon!TqjcBzc)@jLxBS?`Yy&O8F0Ys z%W(adV;peRY7YJ)&w)Ub{f&jH97symQkE}cgZ`^&VyRhd(B3+yeOe+LxYcasFSTr# z8HuWAEaZUye#D{cvM{-*?^XegYGb#+s{)Q33QMQ&tbl{++jR$* zv7odov;24?8PCe*=PRVSpl^KZU(YfgNb)004c64a=iRT&2i5ApGpi-lU#9_%M(F%A z+tCD!s;~`|MGIV7EU5Ha!3PD_f{Z#r8}#*E$aAyq0Og;ta3`}9l;(<`_xRfdy5BFQ zUA`iK4u|`#_RRv&YBP{4p@bkNGilBRO(D3lk~Nb|gfMCvxAwV)5QcxvRB`MQz@_8i zD#Ano$op()Ek**EqGr>5&ZY}?DY-4J6zPN)!y>Wzr`llyV@PUs9Uo|m=I?j^+X6SL zxxGhF6ZmM})uWv2;U*bv^5q&Ji+)p5l?!6pS7)$^pMTdn-4oJM1k8$&~E@7cR>{T(ZHdmr#^MLxllWLG6^YJTR@j7Ix`2MoH zUIVIA9dJKm+Jwa4ipth)ZbA1pl}Z_J;iI-X{n_7a+mY^K?P;wSJCV=BDE<0n0>nEY zcP~{$h&t!1js({Tk=^)@8|+53!?U;O(0b8VvlnJRg}vz8{M%YhHGRl$k;m}M?tY}9 zM}Miv89-{Q^u>f}gQ%;~*pONH7fsK;y!#Jt2x)xfY=1Cs1esq;jXmb|4^4T~Cf^<~ zin=2cRia|Y(C%EitBivPp1y0>zs=bqc;`F4H}fn+u|lfL=JOq*c;@@GveRy2IMbX9 z@4LnDy77Soh~v|b6{%~g5_tCbvG7^~dz(lxX0E1iqbJwgpGDydT1H1b>}c4X|NF@K zDjGiW@td-olO&c}+tAxLB8le|=u{7d(Q%$whqM-rfw!2;JMTm?S@W?(3hO5t@3tlN zZw>V3Ya~(lQKymc!7B=HIlP^zjzf*N82Z;j8+Se)^eGoswjpUk411zNw<{ z@LBJsmt=gVw}SQF=2N)E;_cWQ+-lC?U=qsg{;d(ksVPhQYp;1 zT2)v3g~E#peAAPXDZH+l_j@WS=QO#32?!MRl__-(p zJ70+(7CFSg1<_|0)O;m&`ZK@%)0wzn@yBPdg9FG*Onl6RK4z;jM8ksoi&*XrWxlBA)NjY=y z7Za}=cLP}oRV8qKcG*?Zqw#4 z9nB?idDEDssRa#-^6o6fkyd@?th~w=yYk(slI<`V9!t?^>GAQ#@+RO5;Kf^y7XNil#+AJd}iM7 z{=euyKN>{OBPuqxbPgbUN0w&WKtGb!Q9AwTT_2kHaoEzwwHLMPrfbNU^&s25^-I~P z8x8)PBBHoTh#ng)EWNKTKnI+YyTivi&{=IW_egdd+B15=_HAh^TKjuzf_GXoGO76L zW1rH9#HMa}a_vVw8m6fm1ih?9+Ru)72EMC8;p5wCHwXQWUvfR&q#UW&RBW8;SBxg_ zwB^rvlZT48OFPQ#&q8Ai9jns)$;d3cdB|8X79~ZB6^}|@gB=qAEeZPDEY3bU_YHp6 zjm|51nho}c#4d)+&x8NYsUm1RRA*%}sT{m|1BP>6ap2kX>TQF^t6(78tL(R5EhNr= zFY|t30|cz@5L7fYfxa6rqT8kw-gt|CIeDZF!rk*4qB`1Pu18$q`H)UXRKJ!cBO-u{ zLG|Af4+|ivttu!hO8}lDRdHyQ5F&4F8(MQs2wh5{H$z$exPv#s zkPkjm99IX*JbG|YN)7xO9GE39T@4fGZb>Cvd#L4Ze~=3+$?}Nm57rA8I7ijxL0Lgm(5{&Ua9wU+hh}~O?C3PkHVrNWr{_&>zE2Cm^@{6#<5flA zbtTJVK%^KH`DclX6vNGAp~eD*Qjq4g%S3R?028V!qblH=muU!taBH*_-?qt}4fK^Z zW#OS52>X0mbFC#8tPU*wMzOgt`Gko6oHdo8?-9s6MTl z6d!1;!h@)mp6wg<@?f1mzp2iZ2aVd7BUm4Kuq)@b=L|m{{P?jwHPD6!uSS;4oHvyR zJM-nebiYOH-mj% zA*u{&Ha^LSBYyLrzpz05(Vd`>^K95hH|!d#=YYzSVK>KgF4P=+Ter)(5F9)5%SEl4k^&&7?87Jz0sKvyG}ii409ldBTlyLVz|WT}V2cT1 zD#uOd$8;gsId|=}Y!SeY$-}GP-d@)4n?B5{=x6xzx#GkQ{vtR7*OmK6uxbCA9gYE^~Q zgNJXJOV*;B>+heF9IQiYS2(h7eQQA9H{C~Z%bO6tb)Mkr<7QN4DRcL#c`FL_s1&3- zwW0m*0)i_`I?!Lerq^oo1?bzY89IrJg=q9)N0EX~H=1P`aLQm~4^p3HDCK3-i{Rk7 z_9J?Is2BDI&zRGX7`w*igwGv7vNPKh?kWzVN!C2Rq0?V9uXkx*+K(Y*9i5b`S~`r> z2+q%G89`6}ZIqogV-#6#|NNVyK8DH&#obdD!OFoWb`+(M_&7f~U2>x+R+WE{QC%R4 zL))tR?wuCHLuz%edUVC{>M7Q-fuF>2V9BQBG$RSTs(!d`$43bqa>r$=?;Hx7kX4x+ zO}NR&r1<%A8kVt7|4>^cXHJ#Tj4GyMp{$-- z_(sNmJo%Y{Mcgv|iY75}1bfb{>qbm`Oz+&?{u4~RaMPo<;kQh@{DUaVCx?m8tPJZb z{Y|WjPpNt*6Wfq!z`F|!U>QBDy%N6q6z7ZXR`R)6*+or$NZ)=Wu= zVB(>I`zn_Y_dE+-uSPM3X7K)Am-gJ(TVVY}+9zJ7EX_K1(0-!_GYk5yOhTP;n)#QC>ciqi0> zsG6ua!jWmtjK5EsDLnGeA^A`lg;#wqja->S;o_X;>01eZ5@^^nN;vpxTzjuC(G{`{ zPyFr?KD}4As#2Paql9HIT zB%Y$e67G9K$0dF1D*RO#c)^&BeX2bJk7Inr8wS38S==U# z@UZq5eFbejCSG+~hEZ+H#C75I7Og(SuM02a^FoP#+R0x$`G|>Sr2EwavX~g_R;Dg4 zW@6qXgPNZ2Ol;zi?&U-D=|o#2M~3pG?R;8S2V#zN62?2Z>zU+{nO+ zTDJ2$92r<|uad~A3OfFJE%_i{hmH+S{B*i@OcL*@KfY2dg@(0kQswVXr(qYk@ZN#= z=~Hdl_|aMkOitNdGuBIB=S8_|Ry`NT3Tajfl0o!@79w-0a|WS>Mc^- zh3prnG=*O5Kq;%7KiReL(F0)k(^s@0r(g9>e?^;+>y%g1PlPt0C1Wj7%O=+&Q9Xuy zH@z0AwR1PE8|0xG<2bCuLHWaDD-L9qqh0YXI-|)YDCW#A(nSGMoWJhxl^H+LgJ*{f z8P7hUnRZo*uggMF)v9CTDH6Cfa&6zcfKTur?`Ocal{fb%-1`OB%7gT?Q;UIB)}WQx z%7)+D39!GbfuIOS60sU!^@V$yYmPPjKfl@n_pxm7OpjJ5EJ}!UpVkJ9Z9D&zd$xnL ze?fVMNhdrX-_C@W?H?Y*{b>TwJiKGAf{zeVS`NMFGwy~5F`=P}Mcts`C!OXe-UB(3 ztD`KdyW#G*%y91p>#eW8rtyU!WfzG1whG~y|DOfNNqqk|Xcjy)UjX!`7NM6y7c83q z!46no_Qu`VsQtfuY6c&k4G#LX8@2vlFEqn;kg`p>-2kno-?dJku7m!&8=drT)WEM> zvCit%RiN%NJquSuw1yJnDM>)69Sa+--XK)qZR!IDBmC=ecaqQKbJ8Q)k2E z5REG#`(a5*sG+ z4AyK|cC_VjjRPA_e-~RTg`q~E};6%%V7&E;f$f$9Q9f*WaS#) z*#3wML^Lc7Fyw+)#&g5-r2R7A!Ed2sY%tvL-ZXv|2Smim6YS(TV5^~%txdikfo7gG;vim2yBe=$FF&CJwy5RBOr&!! zwt-3V!hLrRbb!Uaf{KNAx?q%Gj@2mv{IDwgki`^2cw1aVMUW8Uv{@UB*g^;xa~G$o zgy7-Axn2?`gpLy7-OHq1`A-%@_p$&!s}5Fg_UQV*PV0cfwQbIJ{5HtiyW=BIf)85@ z(%(IK+YFyg#)-QTS}Hp{or3D%`k+Owr(QMOagXq2OK{*`$zi>Bf6L&dN>qdCNHN6z z^t)@8kPj2bhvH9|i2IJ8!Dt*y55$3yUfYjt77?gHhW5xyCJB|_*wQ`kVg_ocRIk+T z$wB!;5eMI=6d;og*ni%}64dWGuE@*Luh0+rsq+yv`#9fdK|2bYab(izE1if?&4mMQ0<`G%r+E(| zh3LledA^lDy3y^fS%HQ0UL>;n{lR%t`p|e3u&(Jt2^R`B`u*%j_{6T~;_LxLC%ZN? ze-Irf-o38=FKXE=k#K3sFxvb{%`Icr2#TE*9G4{b4_zekK1*d3MXxhc-YPYQZl+`x zU)32y)=oQ^X5KRF>HK(PyF%|VtDDO_fP+NF)Wo- znD1mIjt@~VS?{Yj_Kj&MGgOzryNgurpAVP7CFo=(3_NmTYZxn(fkP&_$sgb|@OTLIpY^P zN>W(A;qk02!l%Z$_Q?;+nb_r7h2z0zOgs^1NZi)v&z;Si%f$CRd8&((893m@qBCLg z4E!O-^~&=s!bYp4us^bs-d9(^mUu-AxL2Jbo_f8%tsD@s4sStZ(J;=yoaL z!apUc(ZnY4Pk)@wCEwBTKYycy@ReGF@1r~lPabQfF)JzTlajdmW)b1Aoyt5q;k%C^ zXgj-*@Sv&T-7PhQKSdP1`boQ!_74V+5pEry=3HX)6AH?#+9^y#omx%{g^8#+YS~7{ zb#~K(=|T!KSoXPRbMa zhS`KmRiD3UCgT`xyfyth;bTJQ_r(bx`r8_ZhkvDTG9<0`B>Z`4Aau4I;aKLC>`!OO ze6);>=dLQCFs#=wdsRWe8Bdf@Ga@8!k9TXnzc)#!L5SjOQevWYXkrdI#Doqp) z@#;}fC-pWx^}34|&@dj{7Omz=!xCqH$0*d&@WY;+ijo&4@x=A081cti`+J{)=s24G zg3BiUuxTRk$-o-X`)m=9fsc9yzB5-LoOn!5V}ST&qMSnfPbMvxE6bOxzy$ zS_++G;^BPV&4q~YXK$?eF**~^8$Tv<891FpQ=InADyCq78W=*Ov=vK@5HyYFtR zdPfo~QP-}_Dxu+?9F<8%@-%EZew}7Z;XqFk&{8F^zDh+vke&pduO44(n<9?4HV5rk zvrQZim25b(QXqyawvJi%_=@4f$zDS}0Ch`vSCOD>J zFq2Q>-1zP8XPZ{QRf$&WBYgND00030|1FqzJk{SH$F0xhUL#2%p(3&?8Bxv=kx`PA zq(wy`k(QJwDMiC9^o@p+QbMJ8(@-HJ>n?lmdu<}W5B>f+kI%a2+;iUV*X#Lyt9-ti zvdgL$j9QPp=T+zf&gUA>wiW%L<+p;b8V$fU!#f93WjL@Uc^~I!1P3-cxt3F#IMBUY zyy%Ys7lNqloOm}bgsVEXcp7q{s(%-69*YAW;_auk^*Nw==D(Iln+D)c+{3Hh2m2va z{lB(zoLj4QH-M2A(T@W}~c3&Z|9putxPR41sf?ij)nU+B_Y`?g@uaesU zBh?N;P9k-nw%8-k?K~SgzREMd)7VfPB!7&xiVc}*f4*<@V?#~&8H>VWY)DKLiMYFq z4F)!AHy7BmL0vk!it5gW^4R*n&THB5k}X_9+r$P&Po2Vm0~;)OlMfV1vO!6NKgRhR z3-+sw96p-Dg21te#S2_mAh$H`(f0u+`1>@!ko(4jg}zT75J^lZwmCYj$;*Uzr|cRj zDieZbRre_MF`(mQ|LNSd4Cp>DTHqtY0PiYV<=A2dY{Yq2XkrY=wt8)lFhK_=HE#<8 zO$Nxle(}?OCj+u})JL3fV!$Fv%HhRZ7yv6x0+TElaC~C3mA^CtZijS=8%QwV?%ty^ z&&TLcyg4_;mq~}hM>{?*@TbG0J?UL0CUodzN|g(rp+jm=JGl}%@EGZP6&|I7l)1m% z$Nh8=HW9OmBd;qpjlLpJI=udouHbT+4#7>%Uqr&`@Obg)d6z^wBp!NEtjf!P^&!sB z-Aovu{^(Ab`U3{&-wbZ#lK)fRJ3+F20~3DT<SA?R3ny7n zk+gLEW`}(>pa6Ew;gLqjmbH*&Bn|xn=g1-0R<9gse;4hw^(FoD^ zeoyYX{zW28Vf`H5Y1jz^nHLYWfwO(5QL);rQxq*f*3~dMv01 zqONhYgA04Xy4|tfVO~E-)97O6o&zwjGp1AH?ErifJqB5k1F+`qhK;|(IUv}3Y%r>t z13PPz?%&nm!uPKxZ5*IJy}#R< zcL22bOSfkv^g>uMmu6<$1-4G_(>@<*hoE2U&ML2M1=ZL>?N4``;fbW*dCQhYxNyqh z;iAiRu=asa^ZEn^ST9|1+RM8Ji1Fh?g_f1j-pM^5|F;~@@f}QY)GdYlk~5qIf<-X) zCb;3M^mkZ1HSLmp=nE)nM!!=`$N`y?wGx9S=};dT8sb!W6Wn{P_2fO1kiD^h!=qhq zk=O1#tuKLj$iDMap_bh@G^h-lRIH0pU(UPbt4%6U%DL~VhIgyb+sAK8346}{-#C{|x}s2>IOgvm7Z4WOZu zruL_EIOwcP&5fi4F3Pg~?n*f}h(5Gzxp<>=5G6>dg3O-> zCy-e~U6DlH1RCsmqsd=7i5OYAb$1i~puL_>ssg@KsPjnRL-yztvU+=N3FYK8Qr$Zl z``Gs{(u}g%+GjI^wyxmE3#E9l4d0Ir!?R}xz* zfc2a9-Fufx;6-76DCH6b>z&;nEqqE4y9>zHf`ojFoR5Is8Xl81qUhTDOnWux4lOYJo-?-s8WvI`RVzi+a~I zUN}X=mHD@h(dW@{uT9d>;`3BI)Ow%qUak;Mk1^6I;0WSvUMH4M>I!1E_J3*85fnU^ zwiF7U^Ow&AHb4LAwpcoWm!%a-)I23H&kmoKMUe#lXd1>V5l&#v4QmHxGJ*Yf{tokg zM&P42YwW5Y6WGChY0R$#0+)+!VRWSs_`>P@Q{U1Etf8qm@_^j8ws}DpL$hR~ z5&1mL`+)Bw@_X~%1$cD^fw%1x*(I1yV1tiYHdnt8xLQ&4xJNO8UrL#-t0*P#a_dKQOPvor5kzQV6^vxO&@_vXJw*` zz(=%MTlcgOSTtNE*r1HS1bb-eD7ij+{$CyJUj%*=I!Y=4fgf%?=ch={E4(S^KYI>= z-TJbHe~l2BKJQJzXDS8TpE)cgB1XY%dhg~DISP)C;5oiXn}Ye3PxKr&rr_Ykc_F7< zDLC^^&(o+_3J&R0aSfnT@RE(u_cyE(#Nr)I0#73aaVw*3kHV-Ro)F&=zHf^V{_^Sj zJ>{E1IPY4vYj>#-ekS+#e%fj(9tdB?V-Q2d?nPVCvmPq;3&=EZb)?~jhKIS6?`ha$ zz}~@~jGwN+4~sO(as8OQ*1CQgzB=Q_Psj`7kMSvnt;)hU=JYWweQ9C5=GIg}J{gB8 z#V#>pBh$=lD$bCGB4xIFNDtsof!Qgo-WXuW9_gLd6>IG8aqK3gN}x>bZKdLO5lw zjZU41AXZ)47kDX)f;YGfvo}gn@J0Q)4ATGtYd4keS0$ts7pn;Hq=k&xR%e}NyD zrj}LjwBg5Ze?OM=`^blR-J`Uot@-e^+7aQ?Exfp`Pbh`(=EW;5Yi;r-c(Bw;)z>^% zdGMIusqZebJeYkL`u*HyP#g71qD%B&^wJ}9NoUeD%I_R(KjAfnwg!$WZc_S#SdWw6 zjE+qp(Xe)2jlpqLrx^dDePRsxRaN-t4vwM?mDV>8PmZ8{vp69+f-d?zx7xF07_BsQ zuz8{|geEk~E`QV+L=WD*Vcb#UqVCM&mze_tXt|!Ff#u0QbhPDK*0^L3x|gH=@c^e2 z%`;ncv{|kLnWM#9@5#0yJDYkQorY$_De#EZThfFc8Or_eKh}U4r2FRcvC!1h*V|1t z)gU`kCalnJw4)Hp-k&HzZdC!%0llA5c-48elnq(v;8$Z(BH~eZ`YzJSAHtd<9qrJ% zcaWFsK_cB}a7*M~@Ol0N7EK4~{hMMCa%binNq1f%5JX@{T1>;U9PF4B6jiUYG0E1J!LlHMWdHW@CI2b9*m+Qo%sQDZ)9Ex3@Vb>sRk za%{8|j&+dcLXySJ2Ya4zAoOYP@MV7vEMIr;y#vVw5zhKgKGpPtc!oyYxMCk{eA`nW zM$UiLsq#~cWEYsn>W6yhwnJvi)rKwaT0pkC3)fUOLCL=C#BB3MaOK8-wj%0b&Ij(Z zpx{Pc@LE?UJR#*lIiCSP6yM*;*u;P+uST&dRmMNQD5ArWqbcpaB==?Vc)i%|Mu!&Z zpYlmZ=#WObC$A+Pey$%B ztDTr&x6r;zC4mXyCMs9Na+q-UwYSRrCMMjp>K0f#p9SJ8oCeQ2vA~dWDE&+z3)ZP8 zD^CWHT;8EaIv5Ln8ilUeL2|p$9MG^}_5J8R(|Yp#IU!@grom`z)yo8L>(*c$k|$4{ z6>3TGVS&a#s$hvJ8_w~U1PG!!7*S80S0+&p|9q(t_8%;mz9iTT`rlfToy=Mx?n}SX zRf~35b26ydbxY^}dA%Dhagxle<$EEyoCMGteW285t}sOM8kueDmMd_;Rv`#Y1(4@{ zouYcShyz{k()l|?xL_)`^L?8l7nXaT^?yS0V1d!ZFntjh@m|aX{Us!9z%F0D7NB)mnA-!NEn$b-#jp!T$VwukSm$fhnKcWbE4kmy^%&+z4m| z(Ug*3`pHdjZJ1RXbg~`}o!hnHfIJf%73N(yqh13fw7=ArsD`LD&yz&+E5P-B*FKez zVmQ?OsyDdc8yvKopAzYr3r+D)%f#Miz?Dz(Het8^gPgp1f>gT*B-#{r*p}}tD#>!^ zW$yffPEpMF)qE{M-)<+^u+@H}9@#kd%8Xi6Y`OBnver73-w`_hGs$(c)rDF^3$j~q z!MI4M9sM-^k#WGK69qz?=I(_(=pSeHp`IoD8MQ_ODEyvTZet_|<>a@$Ir5l``W4?P z*VPQ7Y%#G>Wy&x*;as>ybnOVb4EsxBG)B=(w@<^dx=}RWK*Ig?^D*SKnN-H7d0ET+KPYxOr!ukQ58D3jZTk8jQz+tO{E76EX_TSOIQyEIK{-}uY8k6| za8&M-1nn9g+`l5c!tfX`zS}Wryrh*ETb+A(rGGmgPTyE$n_9<*S7`+1X*%-b?G=uH zj9C1bqyypeP6GIl()la*n*?ySTa3W7>jb_YZ~v2L8wK;urri=jEEL(?vf#HM=4pPl zZ_^PW%%A!4NMeN$CO1h(Vi^@z>^?F-%!~Sue?C%i5}kHGW}J%W!rGAZyGu&Ftm`zq zAyM6mT0p~xmOo*vCw;HU^m@#C()R{4loyR#3FCkDurMBZP;}JRQWytHWgk)37RD`M zHy-(tK6oo^#wfX&hDBa(E!{?P+yzq3V$EsTDfdfXIfwd>FT$u;#L;)*jTs^ABS(Je zDukUhUw=1C6~z6qwmU_}Nbb_M?FjRw;L3%biVs96Smt(a{q!3G8xj+YAJGKPr;At{drQikk zm13e~DcI7QbXGwMw$phW)=YAYZ)3Hu8_7>4f&zw-H3VLlrDNko@|fk&_e?!q>o4f+k7soa03c z3jWr1mPihzV2fAr+xPWQaI3avcVvJdPF`8AGAJPQk6TX(VPUn@i%*7xaIwb5Hw*o! zSS5M?9#lugbt^M!wyDwZT>HU`hBfB>wr_n+!y$W&@7}Ga;rKMWc@;v!*d8-yc+`cl zw(dq`PoC$T{VWp3u7i}g2{I0rb-FuPGii9&-q2%KzsY#1RGTz?OT!CqG)V3Yqv2KN zN;FMt8b+;}yHGY2|MPJwK8G1m>H$Ky;#8Ah$6G;MvFwCWc_Rhq**YWz8Bp-7tWCud z|LT%y0j#iU-o3#f0X*-(o&88j088aa1a*_VQ}nsEHfIMv_Apx|rbXt7T~f}6@jZN4 zgN)WxCNDM!iKeMp@nU`ZW%AeG@n9EFsd>JJ2YdZY71G~5gT&msXxVmu(Je2T6EWM# z{B$=ol5w6wS~rK2PY3=%U6%K%%CAl$6{f@HiR%-n>43M(=7@2$a<+jJIfkq$m(-3Y zj3WE8;BEDxBWN_XE;4k}Fxq|msIF4~AUdno_@Lt!7x79RDjqz=LFr}>Ck5vZpo#G- zy`RGSkYmxBuWz(^(an%$zLS&P$gFYm!-A(>$acf;#%#S#RD8(bLD{8tWXk`>v;B4} z+HH6FsB~U4Vl4Z6(0X1I`tR17X1?+|B&_^*Wp@c3T_EX3Yg;AqP_f#$+^ZOA9^iY| z-(G;`_%1#ZecKRY>}L{=lnrMi;t9-@EH!@J@(z+})(#kK`T~@Pb~(e^#bCVg*KM`1 z3V7~jvT~rM8rBcjz0{~+0z>7J%OT4~xLhx5%0qI_oSf^n!3&c(R<3gg>@ky!)W==G zA1S-3=6*MXlzQ|^RQLYto0Rv%t=2(>-va|6@LbYpaVQ50^`5(@O>>}E@&)Cf78i>C z7~EI%;KE#+>J=9#mp%GBfeR~MxjOs2;euyOv3bWQE`-Ecr)I}<;lpe>Zo-8-0V{4x zeB{99CV$CS-v=OgwtYwI2kzye=dRJc@b^Mt2!B#HXmBrOsP5{7fAv!vJil(NaM-K` z=HlJG3I6pL8bIsxpR_ghY&dvbFlx&O7MN5@s6V>H1n#EUf{y`8YCH6$0&C%~>11C| zel-|ur47luRly<0Z?g9+D#0l+A?ba~Z;1Y_ll#@N5(GMKuIv-7f;%d+;9Uhn;hhgo zg;&Ey%3$x{%Ni)sJ0aK|RSQw$Z0hKKI(*$9soTAb0i@Xnl|E*GPCmiN2w+0RnRgjx zZY+2=U>BJCnFRu!W7F|cY}hHzzxNLx8wO)uD8#q2KSg6VBbCj_clK0_Tg# z#wcwjOnf|36(`Pw>`UeT<7=33KcjM9_i`o}cyRL6q?nL35ma&gC(iwp>rPCw`1#sJ%wc{ys^7~ombbInwbT(9zKp|m9o2w#yF z{$>H=|MN4zn7{kivk5vxlqd$S;?QC0v%2Mj9y)~G&Plw`MhAQ~LT*Ph9en>POD=Du z19SKAR)S53m}uoE4_V}Ut?EHhbUNr(tyH>KO^27(;pJsjbeN?5zPYKA{{Ot9gHwFr zs8cx|0_(a;7nISV#@9_*x|9x4_4;|EC3LXxE6Xu2rvJ;opL7soEjq0CgAR*H+7%+l zzLlkR7T@XcKOtVN$qxVk08@|v0C=1bdAr3R%k(?QDE1O_&`v3ga{Z`M+KoOf{F+f z%W&0J#8F_1dJ)CrOIeIde6`vLF5 zgjXtPu?T%5xCC8GiI>821$;gf{@tK%rR3GFME_sm5k(9t8tQ3?*GQjFz~gJl{{+6# z@Z1Q`P3YQ09D}~iSn?x6CK(3pUr;cz&i&YbK#c@pIo^QJjVP^GPjfXc#1inLeFXPK*MRy^N7!) zC!ad`@G4-x3&{Tk{$TeAov^x|y&gT6;d7by75Gv?{|eq$qN|el2JsF0gPJPhD#;74W?nV;RKxpP=2gr5 z>d+0k*Av&X&v)4GM$Q|l+eFz@-WAE-!?>_bK)7Jnm1NUn}!% zLw6fG+t{1O%<(aEY=>7n=TGVPj2H~>WFDQ=ea^msx-Re)=daMw13ysv8a}V-(+lrj z=03pt0r>vO-2WsV1 zMV=M$xI*!NoYZ$$$-6ui@p#D(x0SjVY&oAOczmL~_p{@j9d+#sP5P4T>E}qE6Yrel z+`<`t&Z5WBMKIfidsp7MQy=v8AodVmfm5gpx_eRw)c6QC`AEMAU#VZ|OWqRtFQv{> z;$`Sri4M>r0(}wii6o8`zTJ_`>m&MoELi(7`K!^rnt83}y@vX0=(h%a>(ILnUhBzU z&-?Yv`)|_MFoGNCy9pjK_yB6Oyw?hE-Dm9AXT+P)v7L9@=@Tpc^|8!Hhi^Lk+QIuB z=-7=fyQvokFEC;c`?Uvs@w@}W6VRW){g>Q-DLj;Y^xH?>eZ2b$+|RuC<7YB^pUl3b zP%j0ZDfsg>d=H@i0DRMk)99OykLkn*;dO{P9N}FC{4%JY39n3i%wiw2*n{t=lY{R$ zlAZ2jqcOz;ThhYq5qH4FZ5^T`!n^=5}$>4K0NZ_Q9zvn z^cInK4xi59<9Yl&kDg*;P*=iUUqp8)aVd35;Zuf=GUiuKT+SZ;jvhUGqbI%$Z!o-q z7!1F{oGO_U7;%I626}@}D?dRP9ehrbY6dAFuZ&`n$XD4OwKFKBv#DjKFnOs^US4Q6S0Mbc&g{R%_~5lV?qyjl7RH;kJ%)aL|T6wsP-iC;1U}!Y|cM z`04GaXGgxhoJZSB{$YFJnd|^h2Xr{dxz{9gOp-cTlkjO0JSO3nv%C*uQ~WJhy9!*bvr=c0CWG z<`cx+gYbJE`hxjhg7G65|2c0BrtSiCEI{7~hM+Tq`e5)v?iaHE;NU|14yEr0F)+NPL{V7~YHN0}d``55t)&coS4D;r%k+FO#?!>{$lC2QQD12DO`&E1&tJwPyT+N(TQ%^%Z4d06f zT^e+(#izB@Ux&_h>?ha&7Do%O?r3ywfX4>>*nrLr%J|*L4GIf%vlgxLVLZ1}seM3Fa zB9;9G6HTi7KCcNrVMBMWm z?=QfwRPwKuqO%NN%j7(z3?It4FGokY)Q$X);1RG6w7rC%m$)a^gUav2xY4#>Pru6& z?*%VjW?w3V$D#`Of|V7L*L+p#d0gZB1b?{3cXv(ns;~2XUYEGwI(%-x0}QHS->SF= zm1=ZX<4ZMtZV9%4uD8*BTk7T9#^2lQ+imf~zeetz>hQ6Sx^?VD9rNPezaD+{>}NfD z)F83_9rgpvy2C!)!JkHWfhQW_)y#g~We>sByXe15-4^t;NZimOK6c)N-+lbOkH7cf z56(8Qk6^KZIX@)tA$1;+_XvKE@V^!R!K7CFe~kZ+@u3~Q?cBGsm+ko7A^cW!(B}z! zz@8`U%TvK^U;)_ql<(^q_#9uK(+_On+@lLVUHICCuU+VS!T!BK-%EJCr0+{Pf55r@ zEBKG#YwCiPujPDvuhd=B%Rcl{rfZb8-RrD% zXb(YcU2XP0@x-~nU8utFBRgLqK0}eN?>-H@qB3(^bhAc%+(83&s&Z3hh1Lxc88}1^ z#Ea^g5FczNqM?OV*|}=j>Z`QmFVF&6>I@$}hl#{8JvlWb6Ge)q#K~XW7{AS990yi! zt(frMny8zn#M}`~yKQ1i0u+|Tf&-ltszniV(||#$hr&Z;Nekg*nbU6NlVi4oCZ%2J z9`um(bMdd&q^CGw_qEmFAhiQ&Jy^Cc|HcL3X<_VX4K|b?qvJnAtYt+WjW4PE;TPCR7ZG>L57ECbm zeRabRB-#n9Gh#^rc(Vk=A^(S+TqFam`4_=3uy_ywh-ygD6n0U}duAjQqB_;Bn@e1& z+aD6csPvBF)ek|il0HXEZ-Da8m^2&mkHj%tBSMlg!Ag@QG1spuifQ_zC5899ELn-{ z7*;QM&@wkc5IEDsoj;(!osm&(FdgV8^tYFF%r*;6l~MxzvxLwyL+ zrnqsvJgrmXo(Qb)Q~o+o*5>=gM>!T>+fD*_lDWsz9FAq=`t4{8L-Qasp?R!&?7vC|k{Mcqg}e~n(Co{eoKVhDPqQM= zx+gLEkZ_8k@eJV`T(Dq)KNq3gkQVIBlIll3$#vLS$zFF+-6iknCEp7QK|U_2H`;ak zBQv_&HBn3QwR)$x@#S6xKDZ1MUAx4AHEXi^UF9L2`qOBcAcaH!%c>B(ERug!3$fuh ze8}Pm~tuIganSb*`j48sXtQ3h*A5R@({cub}nf%sYc#w|Gu79AWKmfq41Lf#9kOdFhKF z&Lb?WlMU+00P2;K26SKt?Cxk?4h1J41nyx4T|Vh#?Ai?8a3)L7yvIk&gbcDC00!m@ zkA*szHep~Pv|bQ)fN$f3>vneg894$nG32{$L=80ETUWFg$C${zkd(=vfy0g(BY}vu zUdGjJ#3-3b*8@DeF%z*E3B8@HAcMIxoubW_&Y+gw&^}@VlUG^Kq#w%Y^_3Rn+`3nWSy_=fzlGSj4 zJ?GwWNx%x!umfhiQl4lK#J(#hXi1L(mB3{;TMG*Bwg@(Cv*lN@$0T=UcYtKTRU=pf zB7GMV^(fU|Jibjn<&km%T24`TVFE#eAh~zuP0&fw08OO=hduFl_%cGv z20Syxo^*qG!#ETqoaKi5C>|*;p(N!$HZ4gr`b{P8!)ewSr2A+wrg6-U%+m`d8X4dj zp6pqsbYi-(+Y@`I4pobMx}l(lFNd!%4=Cg{CiDruCR?W+p)Wcm?sqFXvSIZ6x_Ghh zC&+3rD2O@&hVFY%fVu}^XM`ps?m@raT3%zWZerd;o`ORL!jJ5Q+CrQ9k=8hU*mv$Idg zjXnq@H7INma?a0oDkq7@_S&L&V>J3m{26M#82sFmvk3eg^j0y`d!rTS*H5K_Pxtww zAl(I>nA;}z>xHjiu~Q&chweUJo9>zI3kbHx3^G3gD&7+)+#$Z%Jhp6K=!q-StssaL zI9(wus6KMyy>%m3b+IYP&C8W-Zj59&g@vCKf;j?g8!|OFgx51w3RW%`$L_X{wvK+Q z`OkHp!eSE}7XQfYEDxGrcZc3dN}fL9ll(i}4Y>1Wa?yujvckuQR?ka)X|i(41Eq}} zbvw1mJ$EnU&b@1}1JAQJ1>tbPKqUP`;gu)Elb@#)#1aTd5J=dxuOt5j>~4RZO6HSg zFkc?#|JF~O{ir+)2`>D|4dE)|moSb=u;{taSY0$4^^EDz`zxyg{c?$uw~gErk(1E^ z;Yb-33h#Lso;|ZaBe2JNtWqt;$$j%B#z`j|V?d7um!fao-phwy_^I7rV*L;w7CcD; zYpfC}1wECou;vEUZ=otUk#~i5CMt zyM5A$|Jx{>$$Vk7+EtlF$j<=e^UO6+fnbKU0gW_OtC2AlYr-0p_E zb|t>NHt}0=2m2a}xX<$HS@1^CeY*YW{0;uDHn=}NZ@_nw*iOsnepLPd=U{bbpa@F4 zLA$P68z?DEVf5#wYBA;z6Bz0ReMIh9+9w^P;Srg2SCUgG!k*rSgf7E~!qGCbI$3IF zb*X_cK(SuS?F5-U#NCUmTmZ4jN`deyg19Aos(Eu8+Rdc5YvW~6ECte-6`+)9Pm>Wu zlAp^jarX7&TlD={y|lfwPz9fgB4#p6CcbPl#MxR@wOI5ARqagxlQ3YkNK(*+{TU)I z(!S&JPl8bgJ0s|9wAJLw@TZ~a=a)e8ikzr~=p!qVGp95+)86~#d5#Jl@N=1YA+*#+ zSGRZ22h%hMp7XM^gi&prc&0|m-;Bro#pATy^Gg^z%07xueaeV|d<4g*;G zOk;d%m;TIP&l3a4{~Dok@A>RucJE3j2u!e=IeGZ}VeRO{A78<8s)E_G@q;}gT#Esw z%(ENYe%Wo%PZEF`OASWeiyt$EkZ18hZpu*Ae(&IGjsvm%qrh~8PrBbJj>K=;PH>M? z$Nb@`PZHb`PI?8!OK>q*EjILWupx8Vn~Q+8!nar9R5!4$KLltufAQl>yvBc1H_}00 z$j~dB3?A3}^5vuu-*?c^mdBX>1nQ#;O@-&3ZqZ*p?d&e(A2&l55kX~&;N*UC@6oI} zXIMyWad;ga)N4~|yd=M9S9p8EYl`eAjz#ZagL0v>R|WLR3}m)_Kr0d(j!}$$DcMW#;Ys zufpCa&q^!E&3cvNel||7BWKTPM4&AKR0#Lp=^RHKwoSNFLf6H^m{y(&%#e)jZykA) zGjxaKjOetKwXv@$x%aq0$kx#q|G^RKrw6|Ki=gaxD5jzultDgew}Gz@$t_wd6-!N(=efRAEGdX5_G7@_Xy2mCsc|V!lT3 z#JrSS@}7vyP6LlG!#kmO5(v||;eANOma|G-DynuixS%Z%eTwPSLA+~TSkQ>Gyd^(V zYJxWh@N#)-LPue-T-efvyIu9rJh|VoI<}h*-NC#O7$NnvYAL%F zH|eLI<*p7(4|d6E&07t?LP%;sRIRftE=82E~3K-nIDn9aFd->%*?{&f8&sebp`Z zwfx$m(HZWl)Sf=i=F5T}nkfs23|H(PmXPqe+V-By_RH86@63C|5ST0|ocYrM4Dbc@$uZWG9sN_=@*idF(n=ggq{-++2M#cHE!*#1 z(mw27-kHMsr5N<&@cwPme}+wH4F007n+o=kg~p+67qhXhfUQ_ssZw}6iSx{z<)Pb_ z^UVF(AgyIfs}!tbUnyh%LxtX_R!2`~SA@bq5qs^1nKlWn9gzg7k=#%hnk)GW_iddg z8eOKL=LR%;utKR5)*sS}@Nm{k^Wi`Q{&{-}m?G$_ni@C6E$sliZP+uT$w8v$1ovkZ?OMmkj9OD1@U}z~UU)!?dth)uswqGz8pU&mg=(r((1WcO?Q~ zzkXNTc)e2{g+Y`=yv$5gjy7PX_0N7l?Kf?7M~;0|IR?fl(-SvKttWTc?7zO|*md*z ztT_7-DRNr6J_R{%(mx7^)_Sh-h6S-)l8@voPU&!=B8%}R;fO7gNa{K^`iI^rE$p`F zuW0=HXUi(3laetH#d`q4mGf1GaM#_2iPrOpI`?L(>j*QqVCZLLyee#}(*AIerr*22 z%jV}n+L(>S#gJ2(8?XOv;~-9qj=4NN4gDZwV~;aI685RUZQ8fv=-h7y8})oo9OHrf zG!zuut-SHvmPtz=;1YeA+1DA|#CESfdSSm~{?=mcd)Xe72!}AIamFYl(-Znb))n*6hiadeo%qY?(tx)*mrR* z+>^>ws}5GR64iP9hKPUa)}eZMb&cXjplh6KozFk@>NOqsSO-D}WjpW+B#+o5L0^V0 zsCh8 z&+=8ZWh;y;!j>h>lk%@pbVFGGZqID4uY^2QPL0Btj$Va8#*J0Ub!K< zUP{E9T){XYIg%@s3KrYJx0FoJ9VXzzT9rX{B zWlA>tq70l3jVSqxGJ*96OLu**Ju`AIpxmlpCiA)Q*wA)|KB_Vh_;rZ^l>mjubVwxU zt)x0Cb#IsLw#M4R0NMSW=j6oV)FQs7@-e(1-CCDkc$u?;4M@&lMYZs(O^QH?@O+*6 zNWCKrD46f8JQ@(6uTw(p-bL&6B?6c?6-euIgV;jlw=|w&{~NE=KKy`0V&vbQ(cg?e z^G!gBCzS_FksO8k>an5fr3g*6<75Tr8`(W4_x>0S9mzAZEtvli$RKNKUoc&-x_Z~!@i$**JV-g1rM8e=YGd?jdJ zD?jjW>)@kWIV18U7;rSlcnvOS-&4u#TxRt#67V1!#>$WjYmOX6y}4+W`z}y-D&&!v zeMf)_>DO797rw;2ma%c0m|F7eX9A9Q0_>U4WoQeAc?OBe8qT_8UwGzes4eL)G^2Gh z39~D+$D>(5_lExSi_#85yni>0rM@}B{<&9q9;Y5-lEx1`-CImN;GTE4^p%KvtC%Y9 zLX=yJpr3?y#3o*z#WPiiB9wK{CJf?))2VuJcbR;!%jGlw=DsFCyoDjNX5|xgJGWar z9V+g7!PEhO`sa&kIM0fxPGUO*LB}fX6bGqdEJ2oAt~qV_$4jvK$6dOGmDe9M(;s1u z<&SQw=fft+7G&~e{Za=%`fGG9q7VBz$M5Bi{zP^ne-v;`uJo;H^=UD?VtR8%q4kAj zLRai=^WH$o7c&KJ&sD@BF%!Ai@YIEiPkwk8990FPdOw75fZA3CdW)O-*AkQ~nzo5E z3o~8^V`*kWsUZ7?f+q(!r@*hbzS;eVU`6!esAvwzu5owq8|$kmQ0Riq(?EQ?6U$rD zXB^>$n@{fxeYx%dTzN4JDY2*bU> zVPvrz_QsR-IGrE=PJI20j2mDY16j8m(p)oOxd~lT$7)+sLRk&rSM^7mBpWb!3&WkJ zp4fERGuQk_09TtCv$N^f2WlQSHe>w9_r&8!I6?N+Mgmn4RON59J?w0cCm&^b$N985 z>?WhD_qiWd-t%>qV}Z^Ix`w%ewS<9%;hHyJYHa zUHmMHWNP*moum-yH63Gx9_&))!$5=$t_SU9wt7J}w1fN({sf^*8|M1>6a??X-J4lP zx4SMAI9c`tDIS#0r0cfEaZgG~z1HPkt?vcj{lFu6hP)F>ky+MY*gFUNrmWWU#>jNE zk8YE`x_uy9R%7(lb0`A48~!@2ojPS20}kxnk)HH+0mD3~`|EE{zP$3@T`wqy>pt?; zy=CO}9hWt}gImkB_4uG>1mL}l%}Ec`#RcJ8AAj7hdMx|W1N%J?u?vGQF9~;n13j=k1WAp2WH>Ta~YQODXvmNc!^eE2|f`2*ZF9-45 z=q;-8JcyhK#kWrD&)eY0TyDO-tWSXphndm#*%wFpE(B6tpm59^TdSOJ$5bO1kF4T1 z{>>!`L_$0#T}b^sTR87`5W@w3WOt^SK7Y`FIc1YA*)Vukr!t^1WP;=YhuLHzyS-q! z0Io@2PNFE@!bFl$f{c)Ax&<4So0uWI3~C{8^1+=;DXDRNvJ~A^KkP3&ZY*YES+jF& zdCKk*iX-c~&fn~=1KzD^)^(%1YMPo5>-2RiS@k&y#Pg7zT-5ek9%eWWiG04QK|$Rf z*$H1azjhZ0j9!Xma$eSW(A~H$ng=ekUvoS6g6{7YH$mq|k!XRvLyc<`JBsnE8lC6j zWPLpFbQPJtxCRI^- zL}6%u_8SU~JmSibQl6^#r1N=C_xs+PjN+7ag~+C~6t9I-L1G3;(_ZQjw*Z!w=-zl! zuGb>vlD+J|U+xoojvc?D<+$qUU;ge^0P2FdK z%M-lg0|J+B!L8jNiIxSpTn~UZv%N)kG4s$U5X}QG(7)>jYrB!Z0_LxAiLrE(6hyX2 z^f|CkmOh9LYOsflmy=;xCBLuJD;Sx$(nn>7J^Z=Au~?XyLXwZ)u^$1nS0j6RfJW$ z?B7Q1&cjg`23djVi^GrIB{I5>pI+e>o8W76~Y+;5FIBnhIzh>6{%mUsx1xKQY6rfHQm8eA?|E zr@19p0+S94Ts=j_&HDSlx`<^re|0tZ9-O->+AowTam|6q9B zSbc<*k26pSqA_pzp^6_?m&YWi0%e3YP|8@VgYk-{2cmc=;MGaJumC3+WjBTzk%9U{27e^$|D^d zsd^*cAGOar4FZhx`xy|o$)&E`wV=?AaPevCg_$=N zFV615B+aIQ=j_+5(a5nj!0ITYSYu=^ndwe}c?SOy~&-4P*s9KIgwQ;4hjszd3W#hdIqp-p~S1x@tou81AvgH_euN6{s)J^ggc# zwRcu4S{TRmYCXx+)_1(`+a{;9WLNGjjvl|=5J(S%VbwBUJPkJ8+Y#6TFLD#S*VvYB z>@~msp4o~>+2y!eRmSrQ8Urlwuav5%a%g=MahU$U#umC4{NHZFQNIGglPCC3>SOKD z`XPK_$Bj~{E=x`SXM*l9|I?HB|2%8Fh~x?LQ|xX5Oa<{tuxOfm$fhV}PcH56VU?d( z%<3s@|1*cHUJZX6rE@U?H-V4gU=;R$Z}GRDmXOi z@NmJvv)xz6F~*Vf_ON_^>HJ;){M|si!#@`?6Bj`s^z~gW+Gx!F@Xy3{H*_AI9Vm}Q zbuazM2e*NL2l&Y_)*hhE$-vF_fHNde&IE#xIrXyze}o`9&g$>Ez}`%YMlMXppw)|a zh;}s5)x)W0KB9Z`OzHvWzYfj(Ux$)iQc&eq*vi>l49wON;;^mKW(u`jJrhm)TA*w7 z#A~*R|2T5LBKOhazpmX>{nuKNo9wq0-&-mIQX=~d`_UCpysM|zO&|c4I(Aw7Fq&3102%d+vnX`TtNrjQ2*~h3v@y* zh00Xjgm}uSj(MXgZH&jfI*y3QBUNyg3~7Zub|VJICq=PMjd)~b47Hgf$8F~?;_7Fw z1lm7Hazsh=2o8HuD=qErOe#1szW1E1A5GV6$!Vd=JF+XzXm_XseeHriDoSx5W79Wc z@vi<9#!;I%+X><%|J-ak@rIb%CYep5QAC?KUj5wKiJ#nOxG~Wy;Pq6FI}dY1g8a;} ztuEgL!KYmTafw`O;{CYD!S9`-1NbxB+i#+2){C$6#MJuyo*&KFZg+*vl1Ex7fHXUD zU8Ppfv$}u=*%zy#*t%}t^YO3D;=IQVpUw4tAClQC*KIY6W8c`hJ9e=C1S)7fnw8{u zcrVv-Ae&gZomefEb7XjQJO}miJ|GuC*nx?#cSHX;FR|gPiq>K z;=(+QrZ2n0+?Sg887d3Xd=IAN7%=nk?mQd55O}@#N%yK*a9}h1LFv~%2U4QS-h4n^ zXq<;)S+ivB7y?JBUVZ%PQ?dgMj@IluB{L7ai;tYeqn5qY~pD`;g3mRj;b>r`R0s>6!r z{INTIP-e}}dRedf$1aYRS@QSELofkB!}p5Me8)+JVz<{xnW!&u`&SLiL)%FI4-)@s zH{xFGaRsEEogI5Uh&B4&{lHIwCwnkQ) zVCs4DkgiYD-}#qQOE!CW01oerNw77&#I@;IpKQFnNmgDi_bFpzEr?FvQ<0e4HZW8EM1$;plI*C6{v~5uvRn_Lem*m1O(FC78_b$5!pp(5 zCxlvtD`4SV4|Mj_Z>W6hwRiq?KjqUC&+K;xu_i&TsaS-fn6Wcs^iyr%UvEFE#!WfN zg-hk}zj;Ulp4SU7wUK?cz%oDcP+76mhx{R(>Umg7jLfjIzW3VoRpMOE_%&cEvmaKb zmwzNvd>nFGvT{`I$iJ}ZrLv}VQz1LS7YPtPkB zbTi1O6SF8WNGrf~L2YFXm)qB&digZ5ZMPtXiiO8__`~t5XGd;$`~msuYFe`;YZI(q zM+>4=HX>n>Jk?3u@y-58Ouq!%^f|+f2iWRFP4NG*esry%@^E_0}<5At@HthEE`F^vhRQUo5Xy;iM#Z+@`_+m}r`V_$1pm`6_XFTXDs=e&GFp z{ql#s8lQJH$PW6$k?$G2dWa9}oHu|&G*xfU$71lrAIy0ZYBrYzD~#qX>5sFH{eCw* zp$khq5#tdyB;jsP_}IL~0)?JA(bYBPorg|*jhLOw-5 zPU4<-vf&h0Ku;BOta>bErIDR0by}15>bD|Cvx}`}J^L5h{pK38XT{2!8&d}Cip1mE z*HbgpYx0?$Zpzid`HfUOw4)R@9o#`(TRB9pUZ?kho3dF(04^;Y5eZe48ZSC`8z$#6 z1@^N?d$!BkH42)D>N1)HMLiXtz#1fWlG^bPx8c*7UPNa_HdwnzLr)r^CJSR9{yl!K^iV{DclRP29GF4>tb$u?88@4<=tva+7fll7;nU4sXhE{=74| zS}V%gdCfH_N1>@#ANsE^Enb>wVY8I3y(^U^Eco0Et^vTdq?}*5NGbXvejfl@&}S@u zvr>^-Al+lk0X>?~*`bzYcv}fmx zyM>FsOG%_AcEklgWh4&lbdmCHjd)k!0rS@w%cA8&>(E$)jn7GM0H*WKxKt?L=l5(m^H);6(#&4Q|a}PxWvwpQYvO=~;F>=$tJtH)T__#%e`$Kl(z`v*^+YFAOR0F{v zHX(&6jNJ-cQns)=)HXk7@+7~6fmdh9ba}Og{Zr@1l#gRtN^U96!29-;Eotv~&3@65 zP&`VX_xq$fc$#J6jm2{SpBLvgL*W;+CaUo|NGwA|_Mb%LNT_yN%+0QV z*!YmnG()@Un#^58NGDG4kJ;_Fw1;ENz1&9aL#0;2aNxdVi1Jy#-bLhms)Y2RzxUx2 zI*!;BCA%2Oy_vQ6adc0pvD*~t%oF?JS4{wjbDCl=i=ug-fy6)5BvO<3P0M-nEBD1W z#V%lHe9w^hOws1_TzUzvfIzMHu^Y2zqrr4FnwTCR05WMbc3frfM4fvTkI-5;65{pz zTV<;SVwt)AledO)kO&=cfNsCUj(*g{g8HB_UfwV2Un2B^!1-9*=%c}#(0QREpCA#2 zo@1CHiA$lMI>bi-_X-7ppGRZ{*_Ev8PPDZIh&e8Odk|UH{Q41_I}Lmy)H@^U%#GgPej%=lvavb%)I7G^CB4Uzf6U_E z?s9^(i^-YbR9pNOnA5FwMHd;kO7S8tF0qJ$(-!r9(z!0>eCqm}k*&9LhlvM3^Z}a= zyyHXrQIqAJk6PPiEH%qzBiLla!F1+HR{d1HKamEL&ecZ-`=EY<-wq_6o=X=QF zq~D))$LDlHd^I~H+1TbIXFhj&%fF3Qt@NehNax0_cg)py|3$?0ZlcHQcWTD+5^uGcMM$ba80-y2qt(-^EQ2TaXVNIj^CzlzlK==(4-y^yDD zoOf3FtP*_qEmO;Em44Yb-a-y6hPMK=Qlpl7O7k9&;(d-qCVe4ilsx<0{a>ffrymM~ z*I)@crNno;-Bk9#5fX_sd2&^4DU`IgauO<*| ze!CR#kN<@i&(3G4{p9*9#J`TY)V^%g#02$=R6##(e^1-zcp$TrORO|-#xT3H$M8$b z%z26Z9Rf_1oXTmt@xtqs@(!oL7TSEA`5pd`O2ri>z6dSx=Lz;pv)AokPOl7(zR$f8 zQ&ykLf6GhYe2!erQlD+mYp2Kv%r2@eHM)@e{ZLGA@ByyE*2Ej0;jGKd;?2dhgs89Q z>*o@FpB;*^DWIy2O*U}|3HrD>5~}VAuqP}CX5U1mxbL$g#Y^o)pxPn9i2@YDZtCtq zH|1?aa`bz7#sZSC?g3=?jy@QVf2Wmetkb+#Wh(T#R?`I+bK`Bm+=I2H`~-v@osSLv zp&xH(uU-iBXD0k3F;v?j@>1!hWjj7*bjFY0QDf-)eh@#$5?Oxd(+T+x>82w*WVk-; z1?vcVjkm0Be*rInh06W`x^ z%l$)bKW`adgqc|LE8q^hTzt}CmX+`>>mbL2!S~8!OFWXkaQYzwndz!%WQonBh}bJ@ zUQ2mapA|NME_hk`kBMyyv^9iAoFfdRLi&c@8O~1r+E7>@o^01B_kSaG>6U9rMc%e4 zaC}072ZFTQ=}K7ubyeZ2R{Y|{`@6@{B;BaT!qmm1gvgwN6iC&ouYJY_&$h1%*Kft9PuQY z$KS=k95d~b;pURq(7imKXb$;dJz)Ic%ao&-tATngNW42lHgM%*?+cbkdgWEOY@U$6 zVm=Hv+EI~X34hvMlqIY^49!}z5}bX%_fShp<=3ifCbjp68!Vdjvo`vFhGj8)Z!yMi z4m}seDi1qt69pXG#}hf)y8PXA>3jEjH0PqTn`V_N*!*6IRa1~@S>v>9HE#)VP%~L_ z{)p>twJ*hI9HX5hmwEPWRQl7zuh{oC<_zy2-o?3nNv2jF4=}FlF>YlBve>Nv*+3n` zw1>|_fE}gSG(+>>ri@=s2xj%ES?jU7B`H zD-1Pq@?9}LVEsDxS+$ohq{F3 zB?DhsV-4TT>YFC~0C1K|$~$+G_MY;bvcN|eJA}}wgBb{RsR1Myd_x&P5M#|@ye{aV~bH*<`zehAx;^2d7l8@qU zePGgVCVKDmOKr-j2;Vb5clA#83&GqEQQ}!MlMojN481D}MN{I&sY|YKY-47^?t*|CCjmA z0LlIv4sBIjNc*?#B}4c(O4dC%K>(U{0t6=wqgxn=; zY%i5xybXQFL&8VGuJVE8_3P=E+~Gs;8XgKTE{BuH_qEhcq zD&eq+34=f}ZsqBjbB12smp_T_Qzb>!l~VbnXNJ0JS_$W&65!Wq-A)&Z|YdOP!i|7dmBsw}5#$41a^HoRI(7QCha*DMhT~*YVF_ zJ?8o~YU=}gO_rLZxZdnM4tw1F`0oRL{N${{`?IysjQ}a}2RyPW3&sSE96M|E34J_@5IKid|z2H@B+HTT2r7|w0?oHzu@qi0l-1*qPp3NEDCat zEfS(0z0P9bHTA=%W&%uJ#o%$;mF)l>WKDIADoyPQBl|_QDDAa93U}U_GEdltnhFbC zg<;~^&ZM!`eB=FPe?~^6`Ivj)iy!J#gdxv1B!cPNgODcaH@Z^Q zfVYxSw?_uQHc6?gS}Sqzs6B;z!g>nE8~TdK2SvZ+{G3en2W{jMGNj8|jJhqCzuXVL z;)7Z9m+sW8G&+-$jU9H>^073!-(j?$-U^cQS?LKaRXrvok;|Cxm8|1AKW`0~6(aUU z%M*{whq4YEoO$k;$qH@&gyJ903mK^D^ghHy?^H7c8ai89_tUtklFj2tNi(U4TX?FT z90F`PZfpD+8{M_dNZeZlqI^!d$=XB(3dZ-hS&~=^$1t<|O>fyTQbH@&KZK3N2w>Ug4tw+9Hxvu%6$LyC z7@w4E=X!bnV2GRv#G_oD8M94R()W99%Rove*!^P}B0ZlRozQ(B(^PF2^_I{r$jT;S zWW#))j!Y%XjT4YK&)2hdj}Hh}Ce-h_9_OVju?BT})W*G_B7AUgxz4oQJTC4p$K$I0pqo1sr7>rcw-T< zb7vMr&8Rw>xIvmjhTN-nxw=>25pW;c1<;v(f>M58zm@V(|4W1+mLQsiv zBsGU=di=lj6jrV*gN!I~gjYCw9WS_&PFp?4w(=OpYYY+Ni#CY@O(f*}o2DHtg5E%t zr)1|YM^Mf*TAB;O=by=@-cM6x<^?H8{h#qHvGA)ouQsM$ z3N=QHPMNlZa8B0-$3aZvJv5cCt0NO#x&o_!r_93I5$tnCZtozaPIA*AHWPLFczTI8 znFeJpA+g@2``nK4^)M&BDU`+w5fT-;Qu#o~)bD;OF8teNn~3!J6<&NAK6;(Rgbgmq z-q$oQr1mD*1WCE9&2#fTVObhvqNv6w5<#sMb@Q|YX6hQuiPv56tVG~^@$)~P_2yB- zuqohhlPWZ5;OqmaILY+-H4BX5lp zqQZdncWy`@rCiBO&Y{m!O3T&LI3FAQn0>u7AkJ&WkmI~FZhsEfitC-Aw>H*~q0PPa z=aYnxqoS|O7!NZ+njUVViicCQ4((2HfV(UX=5lU?^k`(5aD}pQ>gT^DHe4~; zspvLm+!k+pSJGDEG_BtP7F+9>gYDTL?Z&<+co+U#Hv{`yF6TXkJMVT!32%B%1oE7K z|3TN-GI9A-KpzjW2-~o@#Cn1Vk35%cY$J}=I=X;%*J*qkuy5g~r8sqD)JvOp;bf6U zI@;erg_aJcR)q`Hgo-m|)_e^P%p@IB!y*XdU!%!U3nqMT77_WQy8j-~^$xtY^ zJ3FcJB%a#wY_#iDeD*q_m5j#-fBgjR%gg=@nXwLYvv_i(J4*aQ-AbvsfqVj;1a=hTtuRk(94}#^&IrYr0H0gPA z>t^MK`}&JFQWK3w#7vx zNaLq*P$_v!rJvE=5=BzJp7o^z`5Hu96V*)cl$TGo$_EE8wpRa(UXWxK(x-kFkdE=q zGb?=7gag;!La55`;OmpCclCxOYH6|6=xTcVc3jN_jv0ZQ<9|C>5i0ol;>Og?k9EJZUaL_LGz)5woYHQd?#HSOF*z5* zu$BV*jZadqkqY>SV&w&2z?hiOZk$+mwQu%MScuM?V3!~K30UN$vz$b$h5CBOcYHm^ zX}fz1ZRAHn68G-aV2aHbXTa~j^g1N596THDa+Qf&_y}P0?Fm0-)`sI}OM;MT|5k$n zL6XQKZzKE84-q!eSSVXWYa!Xs3t7hQ@XvuA5t7-_nHz10KE~HYdnSUOC|gD7MJQ`f zyZ;;SrFWDxP9d~8x%wQ3qe+}idV^oG!XbTc?{1(US|sL$ld1-lXQ22~2}EH4(@w=j z)xSDl8h`ml5>d;!nXe=~I7T1GUu}3&zN)Wu*cfBQ<1j(151IhJmsIn-i9Z<#(KuOB zoU)=Co!~T!;#B$dFpG!Gl{2C@x z-dJwur=v^W;VVLp-kGxiWDdfs4|?Wyx~hXWxaT~`$IY80;4*wI?S^a4_1iRlO*k|X zs|4dPT!PDd>8H$ojO;pHYW@j}%}%H6F9%$re`QCNvC`T2X8ZOXRVx&}_rHHy+s1jw zB7ka6U!THt62L^d&tGm6B2s?z;#7{pf>k5Fs`Z9cZbmNBNIv)L2JzDYOjlA~B)r&+ zs-5WK29o2$$~pi1F91(Ku)og}VE@cZTFE#0@Y|_4|JGF}nNI0!Mr|9f!62yyz&MXoSmL}Ir6DGMZ*XkUpyGe%q z`PQ7Oqh#D{eynWxii%ptnWsM{QgMgn^1(2`9$F`QH%w*QL9z9&q94JpOQ$Y_OTT&{( z>3>EyGzmZJt~goYIfIVo^v9ibmuS%BZYmh036Q)yI`hMT04uD%{C$4Z1P9igmAhPI z28pxB92hY?+`p-2IxgfPD|&O^n=^D=B`SlEV^WG5y*v^m{bq{;-PqrE2e2Ln%j{QG*> zi>ROYiO9m61kal;T=U{O3zfEwNs+5;(78xrYPXFoSTnC1nWxgxXS+qEK!pzJy5pVs zGnsgv^E7G?p}(rNKNT8-nV5O4>8@`&6WNa(59Ob9z;%V8ElxG|m@Q}g-FZF@S-)qj zH>{%~E4TPsx`2sQlV!nK`jTylD9A2jgm5VMXvs}z=w;&02I=BMS6SF~)NpH2Ckc|3DaFk5RL~n-XZOZau{ZSG z>qYKl2#mSc_nac*=LKeg>`rGimV1-F8arbF%X1S*BMX@(@|0SYyn5nH&dJE7KF|T`#dA~pd>&3 zGVduL*(Wq=B8mBt2Nt(-Ok7c#9^G!~&BX98U$g5QnGosgr|j@HL+q$1;#!0Sj&*3< zb@miMF4NT9@T>p}-9>-SiMzs|^JFAv9blXx*XKgyn}&c2oy9L%Sh;dRnOlhoLY{5j zWDvX@4V8-V+KB?hX`0yVCJEuNS%;#M=Yl?^NhvQqKvUl7Eiaf2)`@Wqh~BIKoahs#Dh58FlME zn=bHW!Ysm9alVj=eub4|)BCItv%u`$O@e#6zh)G^l;go7X^ygXI2Zl@6f4qHT=B+B zQ?KL`Q8yFJT@5SfI5x{gy!syV(}qourH^X%2M%`8^%1Wn)m4 zS7ByAhOMsots-YKXiK}Ud~Ky*fyFV&{|KKx<{9%K+}IK7d#fXchMZtzJ2v$`hR9u| z?fySoSWuW75vcKug3RytUo4uS;_7;@OVQhaAjzG!r}nxaX~`nj8j$hLzlwV(gp98* zJf4-$VM4I=#EGhX4D_l|B@}-#aBuO-s-K$~_-l~p?JeU7l~cBbi0v!=g$zjp{d>wRd@*v|ye^rA zcO}euad~une^_`(e-j;gnx>;%g6FTUJS?+wIR_H+6D_D8Na#$NxBQN{HP*Y(vibLz z*uKDEc9VdG(>+tw|EX|brz5j8KAMA^IP-UFh;^zrH`}R{TH*4WpMNRDI#wf|`Ky+( zaIVqpNrE9Ais@Ygo_pz_oKQ_Q=wjo=&9S}31i$`jDsXO+BcVV;D6TV?gpo~0crBY* za4ia0f9Wj?BN_e^+licZ*4DyJhuH6>+_hgri2K^)SEel)#zFIadzs!p8b~)ech@7W{f`syT1Jz%-4mw1h9OxYQNaVv?l*e7KXumdLTN?Aq!% zTpK$0s<)C_UFfhpwO?ub1};|G?P8*w<;8`r&K z^diAIVZWkokm=}MWAt%7@tt?ErExd%_=Jxh=M;Yzz%qJha^~md5IbF$tr%#GNr$*~ z1HX9)2y57GJHf-l6WgxLF8DvceetOw@`(7ss_)jN?066? znjL8b*&&0}Uqs$$3@5BVOFN z@$(8HNPYVv6AMc0v z%I0zSI8ig<=%Yo0f1OE()MFatVnTvgUwL?TZpqie5FVoWiy}f)Epg;VX1Y_B1#WBR zEmm2_Ma!Su%mqX~;*IJhSRbar{qwZdnlTzeB<~f^qjBN;TRJ=7DhIN)xO24A63LOP zmSqQ%FkG+q(>R??=y>=em_jGZAgxggAia-}=i)8n-{71nzWoArZJ{iwGeo#7M$b{G5O8YGx3=Gam z`Q4>S#m4|?GkGorVuhbXiVdz93zk>9ypoLghG5-Z!dHF;p4Uk~=7NU-zi*E5S;*Y> zAl+~_8)F$cB;5)!q}3-2A3SnJ{R{G@Wp}CgBBw8P<0ut7(p78jP#tjZg3j-)m+bIX z+Gp#lI1Z$~2hKZ~#KFy~*ne+N181eCy;dYUqv5H&9EaG~z1vk3$4~~A{ER@sbnK2 zO8F7hir_vE4Ij-XW(d5pd0;Zn3`bS8|D{iJp{?rtb511}OK$P|*Qna#X!E@1^aOi& zd&nMHDaS!~UR}8EH5M8z4_|ODwu0PqXLXr25?ZybE0pRu7*T1dPA2LpZ~BQ7dy6Ap zEm5wuF>-=pL+gm(9|MPVj@MQY{quX@@Sh!1B&_gL^~sb;Z+j95i~xBEe^m{0rZC;#0QiSwGjzssT{CdPbY2B9ah znd0W_MZ`HJdW>~Z9kGbEHAk|D2C<#fI|W;5nC<3$+^n00SnhtY@*Fk_ADj};_+X9v z)gP?u>};`ovhGL!9Tqmsm^fG;!a`i?;+iZf6@gbjU$oyrMcvM`3jSOkDCPZ1q=h`x zx3jl=Fel+wj%Y?Q-x6J6o8G2=;38yyj6V4R7ZM@$bFIEoacHU6w^1Um#XRQ*SJn$K zYfpSLrCNZ#sBUaqV1|X8>mr%brU>5Vl~P9Vv3$lrea;U7%&XeYmh{rVn(HE2M$A9< zPQJ3SRfscPrQ6o03$gq4*vejc!tc`ET&@0DfO~aFU6yzsuOP3!W1SGmMtPHQObS|O z7_ONn`pjmlZPvEC0<4?&Np)m4!81!%u6or&LMl(~?bACX%&GD%YI-TaOR16r64pXA zZ~i#;p9}?2eM+5kPEwGTkQFpHg^$F-V)}<5KD6T!q;!%=Xxp?gX!IWm$`U;>rPh3C z=Dj$acZClvWA2^-ArPm9(sz-!-!6#l~)oMX;Cw`b(WG4c1==ZY_UTe=*wP_RM+J|@7<+PuhrIA z?$>ZCZreWYb6ds2YP+>x6Y^Pz zuD=o;u55?R8WVXfWdvUv6wo4CnaELRzG&Rb1S490Sy2QHiHfSSAu===m1^21jxex> zHaxFBmVwu?!i=Olj!3=T_;!ti6E15O{LSUk(dtP*9~dMZd2eOQdoEP3k|&8 zo)Yno=#ZbPVdqlGX!=T)7LO;R&E?f4#X<@!PB%Rm_NCzUT7|RAS+1~Hx=SzNzAM`8 zXwmf?25b*}CB3X;LhOXb$kZ`sj4^Z83`IM`KEZ=u^plQX+jaKml+f`%00030{}h*J zAeDauhACN_=ROncS9${jpeqB**`-BZk6*uyF zaKL;VeRimUjYkjejy_(>hOn%%`p8utuI%rkUajF_Uy*H!b08fxBN6tlo9U2iWJ+?4 z1-MwZKl5y<04DBkd!Nr{L1DN%+f$zftNm#$oeP8rE%wtk+9^c$9naO7Pbhe^xz9Cn zn1YwqPeuD>Y% zqSXxVFF7U4pCG}dU*AJn)f%2R)xD3KSwq8j zZ?@1*f|;EsA`3hvkgL-DU3T0I{T<)b8sp3$eb#r@j(iE~mB%?Ii4rXAJaoc*1rv-3 z^*NMYCekk~=s%<_fzM*w{y(M?lo-1W-TP|}6+_2|Z(S)kT&vv_{Yrw9Z*MQDi<4l6 zHtUjVJWxtEm}#W}1WlgTQ_Qu7!@}K%d|-_ z>`$|@ft*>c95tK?@&}gxZ3iYASLR|W-IFF(xQ2djwWUmKjy`SGRsa-eoE>GRQjy6o92hC5BI)8azm#kdT>KTJ z=8{E-UG^w8>jn=mbG+vM_mYdWIX?#r(t*8+-TfR_z;LWh`GW!<4Y$p_Sj7E_xqiOX zmdk>cTFL!^au%j^#l_8<%0hcF>C27nOnmw)?cbVjfvq~y)21j<(JQSl%k1UD_NB(M z#56t*y$=7GBuhtL3~6I%4h;=yt@H$SAsqTy-?#4+VKk<7o5a}yRsk`cSydFc<(w*R zFBBkW$3XOSJs}n}OL>{wlJOyGNPqD-3BIrW$3J9>u)x@K_+gOpaWiCNucF9t*ij^w;7|jFrXbgxK!$Y;?SY2Cr>GQAH39e@$mN zWykO#*?RHNCO;mgG*X|h-bzJhcVAxVFAM0}na$w*$4AP~kD2WpJ}mEj!psH+l=c>1 z<5&PzF1pg}d@c?Zta1Ifp9``m>DF2Yp!(@x>i%0yM1FXs@wkhPBf8aH?on*?yZxf@ zirJ_bOKM07<=|3rPR=nO;86MDL_HlqiIK*=&@I5H;+)powE{3#TNrmMG68$DZ8ltB z%&;-j*-nJL;eW;ce?@rpV<+!E(bu`9o2M*!O2sm|`OSn-D-?>?nrYfuq3mqX3A0s9 zXlD1t=+9t6?&nDVm!Fn+<$dYZhp(0x-|@1p_mw%MeOKfJCzGL)o0s!ahJ_}_k43vq zGO^_8(lVKSHW&$zI&_Z6w*!|qG|V=~{08HM{MF`oxZiN~z;y}c=q4@n{wRSC^X6SC zPoQWGXbvy2M4cYkt+2PK&Nwe!== zJ_$M&wG5u{r^9%>{9cna4XZ4SZFS16@V&+6+nEnmAa~60c=&+^*IPTBm5t~aAaThY zJqdIT?51xd&UeO=Ex-Q_17hnH)xB@%82q7Uu6@c9f`|OP;Ydq-yxUM&JfDiqVd7Gc zS}Jyhc{zDKvBJ&a7^jaR*0{qK?U+^0KDYq>+LC+3p3M9>NR{FvCQxJ$6$+?yvDdQd zfIF#ry?>4g&~%tqP9<_#bXoCHF_{VdX%5F&%}lIcyeQXSi`bVTqxbbYSny9i+Mg)m z!8vg()bceKdk3nrA_G`RHko>7x*Hp+)%PZLY-iz9_Rf25)+`vT)QT1pJ5;e*dE#Or z8ys0T51D)p3bKc9_@Cln>g}2qo);TCS4VFBb(oE*W2CM0c}%F>e5f&FH50mKyGtoX zTvUi})Oft&pxVyjN`n&{$#3gpXM3}-;c{tR!vF=-a&J4D=+V&axa91I1$?Ask!#D3 z@u9bP3U6x~AS`lRY_tXNm^icfmnzXaV`GPdV);;hvdp7Bk%G#ol%s9Lew|+Wr*#HR zfYiC!?90V`bW2X|d2)%0>agiwVh>T_)wOBL**XE%*mP=M@)jbYup#%;7BWJ8o@-3L zC*dqje9b3Whz-&b^4&Zk0_IKqI9WhJ!Rx*GizhAcH0{z-d7c1g65Z6-D3^p^=s0djZQ{<&&fh6bV?CBJ1d`j+l`)89ijHof1 z<;R%FDo-$?q-cP(7_ahe3iHQTp%&y=7wMf`(C?2qx-$j8bj<`C?3Q#Dt!#f?vk3c{KtFu(0v zKJv#J&gbn{T`#qU#Y5W4tS&mn_Hi$NxJrZBhg0K`ZW2^3+xFBXR)XcNn`#z#(P5zb zZgez?hOZTR+U_Y<82|8P)whe5C=B=`x!X>~^{tB5mzL6Sg&QNIRbYd{8XM`0!`9$z z;9+9)ipy$1Uz53`Pb(h=8NSwvZG6ms7wRA3%D}o0ZKYQvK;zDN z6SCz(R5WBL+SdzF_GQ6~h_y_tyR0u-@fDb>G^RAGnTrSeifZ!G#5UmwEG;rr_INvE=HKECllEr_g^ODGC>Vo6}!ZMgUAiKyF6<-2)Pxm zS)sy0gW)^-@f9r0@Cwnd-p0eZ?!(8gm+`PJ=wd;t6${Vn=C`dnMdZ)@&9$Dl1UHdO zBCIo5Fzai2>N<^$9CmDW@?JJZZ4>3!^m7n}c^uirT&TXC-{;}SMoY4`XX9Nq(pXpH zB8*w+PJ37B*TRI!%7AS;Bo2%YJTd!P&%vLTSZ*AV$Mh6<>l68}5%i63IL^V@U0>&z z{36aBd19*mT{_;JJtgfti;jMmq|;Tmcu<_FJu%tL!-TQjvE|uJyl+~$`UUa7*{PCU zT6Xh5{jQ>rcZCNBk5?J*dnoXEM*3c9ZGj^`!FQ@|@-Z1~CVPC45BJ_(jkOCI_@t!p zrY)L|OsUn+ddvh6|Dt_SV+)WQX_GWtXpWY6S<=aJb1YCCPz`PrV8z{?eqa6xuq?-H zcC(WOsGrvBeJA$YOy+fC=~n^lUTU;z1PHOSFrsSy5fXyRN}e_4lEBTS70&Mz;oxtr zDd|iRvW1%UH@8_Jy7Yq8RjviNH!62fjtX$OMj5X50yu8FZFECoilgz)T4M&LU@l0w z^@<^aT&2oqdxArvUi6YI{xM+2wK+dl%z(LJQ9Vn@gXn=nSj}H9djBh|_1;B-`P5~5 z9ScdQZ7L=8n+fssUsO??gAmChS$>VDfL%_v^XbXJreRyb?Dt$09?UkCO5mdIPHX%^ zP~qfo=6p1birT@biG9&LY@G9^xh;#21vvJIbczX1cy&#FDigc^-cdV8^mF{aEx9pE zI5_Z_vP~hEj>rJRZ?m=}b00U;D2i@C_5cmwWooVzA-jZf-l_%tkmxFemsA7lOic(W?_Y zSQy#~T8R9KoubM+beK@6U$uGNX)eP1k3RlOIcf zd`wFXDjgEyf!(%0ImCU-7thT5yO@DX&lr;%bwzMGtfALO_{!YpUskLgr(+}a$03_^ z2Ck?{#p|?LV%ZX-LSG9j(5UfldY@^iWOkYiU!%cg+NQS0fnwNIw6iy?w?ta|!5dEr z4|DZyp5uL+PH@niD|TJhh@Oo5HP&X0F@cPVL(PwDTQek3Dv%l3lIz5Hr#+zScfx^9q~vLrB}XwIV2XfRehvpYwY zfjK{~S}k+7!G^NoK;IA>7_uJxB%1ZN^knMjzL*WnQ$fx|xf;7%99 zt1`~dKP{%BD#y&ep4~wo%*ctEDa{3-$GWEi;<}^J@4rPG1@Db_v0fN2;{9<(iOsh z)&Mze)*dUE&A+f#?ur#0BCU=E2h(s=kh61s8x6YygV%kP6G7?r?7DSG%+*g}7^hkss8Y^c0Yo^1zEbD%hJmKw50iOD| zd1z@~=@7k_hYiNhcPJ5_?i}It)0D`^6?cOJXLW>V&wSNuP7`7auh8*AH1K(vpQeit z$T)v5G<`Y;-g*iZ&I4?SZMV#(i`ZE5Y3|mQ1h*SyFSH1<c(Z2i2mT$uyKNilK9(X&?s$vtA_dkwYgRF}LHRPI^>qO(Nd& z`o#jZXG{dW?OUvy$A!Mpz4Lo+aWVT@akqX91?<`Gi%wjzK&p~b?Z#OGggq#6>t7^5 zsCCSl{X}o&`IMYWjs?iP)t^_i@Q^rqx>IT<(eGzunliM_At$iE^Oi}%p3wPozpDr_ z?REGEvos;(r|Ql(d`H7Z@1c1a1gC4aey;uUo(EwrH&{oGk3=U;=aYL);WK^bQ0h8U z*d~VcWDuUhEBaU_zd?+H45hB=L>}zqw?0X_#6agHg z{ob39EHZ=pJITnaI5L>yNASYPnRjaz3n7(8*&pk{!k+#k$~SJakiPkO-hDm? zo4$XEuYbx$k!UDGJ=_9z?+4-npHo4mt#@eJ$p<})ly9pn!0Pl!>j`-_$omfScdcWi zwsfFF(#^t>A2S9X6tj@qddEdRn2u86pfkk{7{53^Zr{j-T*iT225c@KlKk5Z_&g+c z_4vlG<6-&1WePuh8Q6Q{YSivl1_tt{bSFd-{7%33gHC);FG1zzP$mm5t8-?CJz^nE zZ)C7F`z%(Xh_|R=-u+t;&+`Tz|o zPhbB#Pw;E2?;icpN^6W(o!iuPhmM7vxf9v*8F+PZWSN7sE$W^eW7!kFd9By}&R;_d z9DFT1;^l1tMzSs6q{AAg&Kdq(IB1Qys^h5{noP{4I*pGx61+2O%Zkk=wz!)A;a;`C z79n!;Jx-O7anEv**+3Z?*Wa4>Rg36yI-iK}YO0l90F>b_*u(I=>B%9i-hYH3I>6=T<--|;7W3BH`!pX8>- z#8APsV;WvI_?`N<#y->rn|7(b4=nK5eLIJ+rOImjI z4Ie+_LIxYeEEJ_Z6h(6cJhO>2_~q#2{aS=&WmdpI;c-9Sgtm3EgcQ|PdN65MQl zfP%s;eg)}ee5xvgM)Sc0#Y{{?~Jm^(`yA#uRE6Nb3uUmKBtKNv*}PfbFJUX zla5yBRd*AaL>{k_mj5Pr=7++9S_NC;KFhhRnpEW=VP|^M3^yUtD*Z8KSb(WcVfu1E zi2mNWqGDSf9h!zywbf3uK{qhn^WPda?1jsGY=_vG?4}3KA-L1{jx#;Zot_@EIWM?n;Ow6_A{` zsB*M%`blt7?5bB+{5BBYu4a~}SHu9fdhS=BK?eTrsH86-{NVffty)?KiF_+w+SgP@ z* z1I0pD?amP{496EYkK}XVALijDW8|pQwSedm-@r;A-v`-$uHOWGz;4@ohqM4aZsvOzUtOJVy_%2TBhqL z__iR);GDh%EF!o+LwyCPWIeS!!WCe-jGkrDekMXrKq;maFbwYO*Cu*UUTjh0dXS6X zS*bPmyGhV+I%J;uiiBl??~lr=iJqojAYUPT{#Eqwi8f~@4t#tZsbk25)ph%sc3B*> z&PxCNS&0jUjg*Q{gol?W8r6=un<3`dVz~=#BCK$xcojB@uy?|CKz|(zj{B#7*K}iH zy1b`0t(}G0P1U0r1P|x+=ndcbPD1;-S>b=8$nXl%`4W9bgePf@8Ci=&$d&5Nkap*w zY;V7d+$s(RGlLIz5%=r&u1$B8Auw%{u8h`-%G_ zu%KBzsO2GH=`XLH)jYJO=a3%sa?!YYO^G_eEA`gq@%4x4xO#H?l2h$8bf_+0JNpL< z-$*3+x7utZ_r^RabLYY~wqDUzii>CELkHF@6ky&A7wP=H0&H_Up(%TliusdiF0^H1j#zkO?gf`T`WtK&Hk&h2}taFYYAqx+if25>MdeD>w; zDh{GAhHxT33-P+(C2dQE5Q&SH7M%G-!IHmOmif~ykZCyh?|~K%ni1K4%4>=571{T- zB#8K+i=r!k-eiNCuuG?Nh8TIx&P#Uh7emF-I74@#m`{exE4#KGIov zqRt!weC)7&F2?uj`~BkyR*1WFFumm)11D?b!$?FQ-dO6|9!_}1&9SsL+f)g5j7O;4 zmZc!7;?_y^y%elTF?|%e+Zt1)yvit7tr1&bWu!lii9Z`pob>2tV#U*ob>~^O$U71J z;GUB$T9!XFc6v*~CgqH~2e~9{{pUNr)zTUTwC}&X9$VpqmK>$_5({hIWM+P|WP_LH zaH~<<7K6%VrpJigwkZ`#zHBo^9?4kx)QAaw-dxIwX%eHj@d1DOGcla=m9>{Dv7vi8 z#kg9Fjkdp!W4|d%Fmj4amhq5am+u9~J`ED~W%Z;x^pN1Desa~k|L46(FC*JQgci97 z=g=w^noB%e-OjV%bL&Lr%RSaGn71h*BZc6JS=TH~`$_Py&%K#wLx$qjrC&nk3J|Au zU};ad0LiC=Iai1rIZw^HG0T<>|1s~Y<%ExoY^YVt%(q0YLCVe(D=FBM*V$H=WsXgx z$Mz+Mxp*B|UX}6~h`Lk&P4N5G7g1hxJP}4UX-IEp|`?Y%T!gT@+>?_=1 z+t0?{r+=LrvIyT1+IDz!un}K`?D|SJ`ifn<kr8#CsQ>oY$Ajg51k939`h~XWkr#(KjSy%5Ej)zEjX~;qKC5 zA<+wgSH!QSMc^t1XgwwJenGYQi^PD3{99dJ2U@vE(J;JT5eRg}yDcvh0L}@bT~d6) zV_p{)g;mhOF#KI3Gr`CHG`Y|xb^n3qg+pn z9oOD_o3A1x==t$$dt=Q|nC`E;gYX#tabhTk009604VQO3)?XaO6BR;=kWu!Q zz1QK{)ANuKX&Na>L`XDMC`3{bl_H7;iHs0GNh(xS6jHW|B!%De*XOVM`hM@d=braD zDT5zHb=%o^vM2X)%K*yU5_+h4!X(nW;{=@g`X+;eiD<^T#o4lr6BVv~JzY3?_zTCZ_*8 z%tEWy^}lOn98u_zY2{h&2x$w|uXnmRP%JAQyFAIkY}?jfg_&ju6#QZq=3@q}JN`?( z-m-9#MICs&n}vlCLC@rQ0_50I+7ens)NQ($EuX@L=$dP}wdq`_6!ZrMOd6uu-{A9( z(?$@fCH(hPgb5SNA$y@EOk5eWxOh&81hf8&FPa|{(d$I-d)vo>^X16{MFSjkk=IN5 zpEN;VU+FxTYl_E%H*Mq|(6D9OgC!^aqd~l3ba2d=2rZ+*9SR0S(5qrX7f-U`J$9>W6)U0(-qb(kI-%&Q+3&>Z$ zZ5|c@TKjLPHEy9|N%H;kZAnyQobb@~(4wGOXI6B1I~hNUXX0Y^0MEW&PfH938lSiM zyC>Kpe529*)jc-Q{_&weCxD7gTg?{)%c#hamNl#RPD0q0J7>4`5YfD77V@1AusPbY z{-J;)&d51bz0b8m))kF! zdw-rJ!lwSp&UYDr=i*Rrg1Q6vifZV^##RsuJk?{tv_f@KGvc!u`0ID#rpa{%R-at5 zb^RwY_&5zWP3H0OcD+5qW+j55EB;Liz?WkAJ-R&f3-14>FN?>9%9Av}cd>d>4i^u9Lsv|S;i{c4@}2@NXF z^m!{?D<@$>f5{THVV>R(x?HU}!A9A$6vM~OY%CJrb~}HOF$~6s1Sj>35o!N({#_>x zI*4vik)xw7qVdb8WFl60H2sl0Kt!nX$=dKiCrBR&6^OFpKvkmOIqb11Qlj|@70o74 zI27wdabV)4cI3ZaX(nz*KdB_Q5z)FkoSU3UMBMGf@=jG221N#izNNA7OnEM&{FXT~ zRm%-RhfP6>E#gzyNP=Qk%UK_P5{#Jp;^@Cgcpe;6=dMhK!aL1%&+QoSWL=B6{E3b& z7RsarNo(|349bxXMZ@VVO5$~>DyU=e*LA^(QNaZvc7ot=WkbcU@r2ZcTfF;{ zJStvHqJZuec7<+8!Ht*$IrNXftVBk7!nxC~3U(9{O01{T@0B}1FZRFm`w@=Fl^1KM+Qrl9r_!>YTub!m z{EPN#r6DKNig8Vhj^>xQhgds_@SUsd{NO-D_iz8_gKHcyUU%Si%|8d|XJr=cHMfA@ zNcEg%g#`jrlJ3xdGqAUqMOYKWK+D6-&-a>1Fns&x%!+9e2&8(iRU3iCf4hThHvp;0 zo73)ESfN{H`aPx63jc1KQ2SOfkh@Vcv1^`zs`9^Hxf^)`=evP5aDO8<+)=2s*UrzS4hFPTLjbNq&MuoqAaz5h#3qtq4tsE*!UbU(+O{i$fpY5>Fq~Vfr z;vGdA4g8K@RXfYfVX1BVoY`Uyc|(lw=7IIJ<9_~wf-h+8Vn5BeK}nKyg;v;`H*M%4C+Xwe|o@T+j23eUIC zTWhO*Cc<_7(-(uMosfDkqNC&#j~5dI|K2+o!^p+?snB6#?2LIgdP9+bOOocN+D0Am zgrHj+b)SO(O3PP`WnA2uj_{)jn;>t~`@=WqP2lmNiEA`V#QS9X{cFugcxuA7f6&Z@ z>^fbRMimzqtoEidFBl-xCnWU*T^|(V$^^z^CbGPWMMp!K_?Q3W_=*TJbPHA$3>A_Q zdd+xn?hY3xf5$dQL~;@1V_l)EX8;TSlI(p-2B^p3qrG6@$Fb_DIbk~X`a5J=tS7RK zDc(!7CSxKYhv4tb0^fpQeY`vi*9fZjB4$lc6Y`L=lx%|3b2XL+G)S;cQ|O3RC1H)E z=`BqjuN)W77uJoDu{{0khs&Fo;Ia}f?-63+*yW_)OO zMwHM6A_}=7-gzMuEH!jL;a^ID>V-yn*Ht>sJe$tScteLpP+h3*1xpxQyW@28yfuav zIqx|2n~K)Ks^bFgG{l!nw2Hl;KxX4Kn?R=ER*$8He!D%asBv!ZQ-Sx%;Nyp&b$4JSc^L=sQr%_Ene);%u*z8nyAwdDDS(nZsq zD|TDLKFq}H&}B=Ib6i$Sdor;!a>4(r5ffpa#l2Rl6s!*qJFQEg!0o8uoBk0Syi|0_ zB%QEDh{J6~aSa=sD}2CWoVP)yU|}5pX9g&lr)b)-44lxA?`z&m1zqev{h%Q#gq8b! z`pj&glKQgx)gfyfvP!o0l?Ajko^MF52Znc)%cK?3(EqA`I{ga`YM~1wVi7bbY&)K>1poOC1@D8EG{A z%VcQoih6zMr4z~FP8FGSsApEFNb&MOk)Nk&~9^t6bRCyxz0CfeYg#f>I0&urleGWs{#it|y2;JE+fsUh%dznH4Mq1rxUH z-$p?}pT0<93mK`2qi0CNT+B)hJ~j|?#^<<8G2OiyF!b{+_S&t5xM#xdQGXfOu#&!^ zHHv{L(SJ6L*C{A6R!P=%qu^BFjhb{2f9ZXl_T0~7gm z6rLX&PIC6o%TO>Yv?cA=K_^&0H|yQ0;)K5fuP;(R>4Wg*t~~d!0V4CO&6}1}AlOZj zG~(sQRD1T1;Ytd~O5*$$yg9O7dStwdg}2^&Bp6C;gc=!U6tRurxBS|zy7$ItmF`xL zpC%$J;YphBBO=!J?z(jO1r>7f-9shksR(mR&+yh@Li_wJn>H>JKNs!auwBm_pEciJ zB}JHH-%zjz_l*PUwld>~n;jrk&}8+ENypdqwCH8sG%)HdG(!4l(C82eU@p)QvF`op z-=S6@=!q-J%UVGrYkvG04UnXYIrp{Np?_CW(})iZ4Rd{`N|)1d^4+u3v>jBu^DmxX zyOfIk-1$p#nue0(o0u>r&9(~iXxbR?=ao;4R|z^HVU z$;wtTI##5+nI%(@n-=2dzSbT-5ha1P6ZY6Y6)GGwW`&PyAAjQ8Y>mB^DIMA8Sy*R~ zo7(Ki!oKF>Q0os=_?C|he7;3PQR}^YCnsxUhxwNkJh4WyWnlH)v-ap|+tXy{o z*M^!NFcH+*6MsC02|~e(&-YI7IR7ViWT!VB`&twYLO)qxx+;8m(NPOrY4Q8Hb_}>1 z)yYlMae#(kX|h{C9jmrftM*){6jI(h=q9DmnkiL?oUNJNQeN2EvaUl~0msnA;UeX^Uc_%~d$ZHkO5@ly7|OQw9hb z4_@r;VSw!^_iMHJ$;hpKz-bsEp{3_a&x&{|R=ukb{F_ciZ*|il5uWbGyKdmVpA!m3 z>Z8^=XyYtro7TH2JqRy#YO~<^PrsKSS=o~YQb<=me<}r4Telu^+d)Cski@@7mpGV< z-ObjZap1YDir9T_~>}8k4Mj6mB>3KC+R-BjfrH^+X4WdG^x1Sgr&Vi2isaumy99TVTmYR*z z!jB%Yv=>ZihK{RQi1iB!yOJ*zY(;e@I)-_KNN zI^ld2K_|XiAJH6{+L_3fNB8$xb%oI#%7-VzMUP3kd3zM0>guPhM~c9wRpcM+j?4asG=|qZEM!-CZlE?e$n7(;P}XBze5;3LM`qM#DlH;VmR> zA-#Se_Bqi8BWHW4D*^u`*p54KF zS6^BQVxCtR$XU5OFWTH3qAAJhA20HHn*PCwC~F7wx&NBZ{|(5m_Tz-pnGiozYk4@C ziND!uQF9a~BF?UvQypYLQKd2$~Naj)L6+@EWRR;w#wY1@fdX8c55 zwU30zWz&i@1v(6z;l`V%KQl3hb$lm$a~N%ce(z zJpXalZ{B3e>lFt|wTC|H(2$@NlPb!)H`<@E@64ARBxfIRUXsc|dv5^K)mRHnZvg@Z z{rOMlJ=mj#%fIyuso8XN$NI|c<$ZTi%}OJw{Zwe1YW^`(rXs2!G(4?^1D~~@bYfpGWW+#OzgC;>JE#gL8N^mp>Hz{ z{BP{;d+|AIT`@@ioCmHf)%NvI*87|0!O+jx;ZbRpQ|3RA=EKLk?70YpTXxXyNd9+TA0C zI#6hIKfUc22{Vs^-;94J;qS(BrF}g9eNl@)xNjF7*R($?onG#QXkWD=xg0h)4i}nQ zVTdQ)r}rFjFv1U$ZpGhLM0}dba$rsn;Jo@3M_-4D(WN^L0(trC^%+)SfF_3 ztu_OaVplsj6+B-N&^c?$XNjueOHH&cb9l>lv4(i{$9q?jUYP{2d122DiC!k^?~7zR zC$q54|NK7dcXWhB4tAdSNyq8D&noAx@_KyGXofT_Ad+}tt)D9}ua?uLOak82o|=B_ z&W7x9olmtfY;>OdBRO-72?;gxariMYH!kfir)!2IQ=Z91Q>O5WDpSha&HMlH_}|ZL z9U*4WB659*h1D}VJH1}8pue=GCu9*D^Ls@nUJ0_{wl|(?DrAiJVdt`hRE^-es5QWC zB>~eJr&ed2BY^yrxIQ48iFQ6E{qPk`h*XU7Ywlsgt~IeUQ;&^J$*pp^HS1x%S!So- zc0EMT+z81oBVm$O9Xa!lh$=bGV@^2(?Yr$|smTn;jemJBy~7E&9_FVvg*ai=rm)zF z94$m@2XYH#G_d1o@4ZW_czMBhqhCHK_%_f5(eqRn#qbhx7f zI3TUUZw-Df(l2iN*=?!}i7V&aCd`#!hc|n(gLr)5F39)Q^K{qmx=qZBhD8p>N=@Uu zzB2EB+Up$`k7e5Aw!Y@VRaIz{(oty?_`H{2vP};0`mgSzti6~t@haF45!I)Aw73zs8{GDG`^O^Q1p|6|JFrWX2Y^hl=7@N8vJtiLMCs@vBNP>Fq9jm_z&8~%Lr^DRcA!n*vnBzm-@4NioLOje`DNVo zoC(2(FoAm`Z2S*RZJzWG0001S0001Zoa19)V3+{JY(UHbr9prd%4Y#$W*}x{U}6aI zVPN0{vJ)84!3TQ?E#Uy6MI0CoY*#$y?|y)R!S_a;keUNS!`3@9dCh?GRk>!X41wYr jheUXR;tU5SZn`QB0O#LI4$kNKcR^T_U}gpb{XV zcP=0hYCw9;>+`PXA9&`|tg~j$nGa{p>~r=WLk%;qhUNn~N#FxR4KoQBH&18r2QNG! z{w_Xmy_Ejiw4Te$ia*eL>kRRCe*M75Tj_xrEZ~8DfcFDw-~*tv5)h;$E&X>6l6mm| zI{tU-xgq`k{`bH0N4NeLoGU&~9n9?9(sj^H6+8I!F5N>m_TJ33zObeV;cqn3?qcu{ z-{e}vwHav4>fZA*%Z7o2zQHC+beB`)rrTYGvO|X+O|b^znY~DG_BjFUe$^iADn=6BG?s{TENa5ZV^JMU0Wn$VT{CKcUO-`Ul{mrU zKZw|@q&<9-WCMJ?^Yk#x*~j;$K#ag<6MbW84QzKyW8)JJ%V{cSGW{T6HG54JA0Jfs zUO23D>T5(sc0?w6&5GLkm}lB_CW!z1Fazn(`A?izjpK`*u06_#CFkMK`kzL`HCB<| zVO-Owsx;Ci@9C&XQfj(E?P3$#v4S%&z4DRf8o$1z+R$c+PHZ z8-q3M!Z||&YxL&Q3W`WMxA^Rd>;WH~IcC4}4lPBcniP36FA>N_8Us0lFB+k$7v2jA zgnI$IN6eqH{=+s_mr7w5EhN*=> zh0-bocurEQvwx<7qrcNXUa8!70sRuWhbf3#bsEVMjFpWWFG#HF=nkLPpQOB=ZpbkX zh51=^zMR)zY(ropXivdJN9pW z9plkbzE-pSRjlGp7D%@6Rz38Q@L$Vdj8itLNK1FXSds>jT4?$c^+L#d<8qcCYP@t8 zXAdCcTdn~+&8|MR1pXu{uk~O+=>9Q3nDyhm2V_@imys5roOJXFr{a+WL(oe-YuzOf z``vgw%-IDuU?aJ;Da%Vb+qkv%OPZsjJDtp7-$C3}u0)mq%B6Av>IzS_1(q zoycBW&LM}^+HoH2??mo(p(KZwQ>xN{G07utDk$s)UCe5K4Y9&v64!zc1tKz0iY$VO zqNmb&y661tcROjJ&$6^G%~z(z74)!O-t5+NaRjAD2?F&P zeRqyjO?9u?*sbYf3Bv0@MI&+Gk|<}4Piw6xJNDv6kp|iKXv6X+NBC0Qg;Y=W9Y3p! zjNtbXGOxj&Z%`7 zhvbnAJP2#D*A1&M@U!7yR`+)b{4{NNqt7|!VaKrm&>dSglHe7IG+0W1y_4F4Z&E}w ztmYBQ7Ib;%)2*ODTil+e1ZHFM#KE$fNmAUm^vR-i1N5uJtEfO4G zcUfVC^JGaIB?WWl(FfyKQ&0zTtm$*b(4&K*=ygTj@frj~v;@6h=bw8m#9G-o7h@4b zbL?S0?v<{86lJE-Iux@Y=EM>FYGQJ(m>G8(8;$zRi;+r0k#tzs3`b8@q(p_y!tme3 zNX@cSwbW~$dPw-=XyBSuSG2czKr4gYNGQ|yp=(Hz_Ty#^QLjFj%DeKuz4bq zOKXE!bPGLdJl<+R*!g?;wu4wsDmawHu5q?EAlmxIP#{^CX06m5QN*m>{$d_9KH%-y`BlEC)?%pdcQERT^ zn_PB_7sJgU;KO*jRybwB7pUsj!u@ityeTX`vJsv+@Z}Z`k{8{hrchD?hrk-(*o@Jq zTcPF}WHyDZArNlZl0bMsi|&-80yMUQ_H#HgUA_`+AJPhXo8X&&rm*?Z95$B2Lams7 zp0-85Yg+srT^*S0WVkAO)8b3|%Xb9W$IB zFEb^?0{-3%YHej@&Jb1FFd+Bem{Y~eH-X4*V!A>VuogW)_vv|4^yKOMbbUMP5F2a6 z_mA&7!l?wcyulIk@R?0fYmYArJu3}syD*UnX=kCmKpj80c^Tsl<~elQU-{?m7F<}}qbWMLB--2| zlrSmuZU*~^%9yMAcUV{{z`)M_C^xw%%7n2ZU)r|+(1t~P_tfb>Fn4-#GVF+}+J!F3 zeMcl1w7@)ozj~CNO*8d|?^|>^g8f<@Thk0=_m>A$7Z*H}6Fdnc97J$?t?3}tJZkqB zj7)&-3&}H3Uz${5r!Ef;@SW^73}FtSQ8FY?VLH_ zhmguD>~A%x_0|<@aW>GIUhm@*8x|J%Fpxhm_0Ri97nT6Q`kS|M)hM+fT2ksHoKbH-?@jh^JH|EY$ zXO-RH^!~DBz%Rm*uk4Ach3c-Ry}xHl(MIcSmp$npzZqG_JGc6;)}PFFioq7$ki%-mawUuV zPS>eVvgufX!L7@J>k|$ddidl&lTYG@S@0HKNR9Tv3IaKs-85%)`Y_;@Y9oMUxb>OF zh@ZX0BFofD4HdHG=Np-WZ|=C7W3(jaR6aWuGS|B)?pQ{qc6>)?W6l?oMTN|FZ^{Vv zmAmWk2Q9)o(3M32UWApQ7x`QZcTSz8+4Lf+|Bb9bW&5#N6kWBk2UPiDLaB)+dh^&I zlj6d2Dk&w`{<@p(+wp=NE-#lz6?HcvQq~U1P?xYJ`h+M=tA zek}+;Q1;3y%9Ou^cQFyWE-9WTT+px9EADUP)3+1B1)7+T!!{0*em6td;!9-F`*>ad z>MhNMoHhA9t?amWTmZt8AbuC}cwG6jbGxJBf;hr2U2%!|L<O^ERQxfPPIlJ7bmBy>F3LN9!^K+&xvChUH_;Rh&^J$E{7$aE) zO%+CZF=wlJYuQaPVrb+iq=PJJOQH>l#^2q15AF-zL+-iQi@Dcc_6y41)Eg$#b9Y}v z3MxmaTg7B}oE&^p9W75IA9nN)!S7sEqO2SDRgk7_Cca~uicG85G+q>X`Y?@jeIiy^N`6FcgSa482-Hf&XIaM8?%9B(a2)zd4>>X`o;3=RE0@&NVhv~ z#9Oa@BbJT6#;PY=sva7-=svzMk;*nj`KcIQjN5Fn{T>Jw=HCDQM<$DpMYW~-k-H8=z8k1}##xtFihVDR;Sum-8@h0sj}#A@!o4Z*V>W8Z zIrlZv^1n*-;P7kWqzm*NNbQ;T=4^HH9oT!TTq;hxZ58?Y`Gz$>;^SqQeO70F+UZ71 z^~mMGh94)*=hlh-1@D;d#@FPm_P-zdV{ z8^2l^yN8AoKjHs9;f$m?Lx;{+qfrLE7lk5Iv>c!J23F2ZSZ2*D)v6&kg&e#u^0x-| zn@we?ku{pQk8=rca|YLwR&IcAl^vwU;hO|{apg0p;;cp#fOVH zMee>vO6D?~8c>NVpk`vXKcW;&c3( zavy6rIVN_EU;_ zvy)txY6Nh!aHr{N^qbW9{`Y79+n#$2z7~bfe|6e^1z4|Ph3?D=p+fvw)}Uq)3q`0J z^YHh_RZN0WAM1kJ;Qh^jk{Twy9to!PcpVeo8m9p_K!g25Y?68=u+~_2`-A9((F7hZ zu7(R&%dB-uM4#Vh4RiG%w%hLfjtX%Yy*9yqdftB_PCKS?!1#x3quKkP@TA^XjwjEx z4vSZc#_KG4f;$mO{ARKRWf1pwXF-1|n5-i|f)w<19Ae@n4*Lhn#Q0I|#@Ju?S>rYV z07(|Ujq@BPz%S{{gbI%Q64bE@sQZTe32*ZWq^8}!F9B!}>=z<#1JxVkb?ep`SXam7 z!1)4dKh-J(Dm^m^2L^1rW3v9k%mt6^B_PcYpy>SmA9a9++=qb&i^)t%>K{SP3du=O zS^r!?HA8i&XI5k@>{dr5Z`#<=G{0JJ)Yv1`p%!OyYdun3Un{{TJoB{X6Fw)a?leKX z1P8F*NPK=XVDQ*;=;!n|{^aFl0KkYfL;a*T^Ypbp>4(!gkoK^?Z-eOZE|$$4yLD2@ z%O!^?5LO$xC}s+s`h{Hjdm0qr*I0kld-Vq>XbPgexRRF-jdEnRe3|wbauvWS;qV&d zTg&HX+Q;4`btrID;#?V?-G5PY4a*bn_z^ym4!r(`=&yRUQ*{b;|A<_L0Oo(Jn@;aPT8so+_hlh3H<>~${{}}+th%cMu!$8!kJQ-njn}e1 zKb*dF^2rqSPv8h5n`&Z3%Q50Dog}^FSK*&;Tn(%?KZ4$1;Hk}k7It{e`wcZpp0L-L z-`|A8=h8YLD;48Y!l*+Kr}Cr=;afZ3f>yt*Z%piR=U|JEb6t>)ddc178j~qsrpZ-l zDj#Rit1Z3Dhb!toq3J;0bizT6_+7Pay(Ln*gAm!5$z?B#a1m;eroOAU-1R%k*Z6OS zzUCaNaRL2#uHLX$aCP^Xhach_hd8nP7CQeoyoZ;^k5*9PawttY^VH@++ut;1GG_q-YaCl^sHHLX#K9& zi34Nb{@(Q5g{pNz>X?VHt;^u(h@A#_2M!r+Gja%;1lISJjFSF5SP$%b!BIyiks^n? z^ztZQZFoRMPK3ChDdBLHkcfA?Jj0ur57-J)AfZGh)qIm)+>IM)v{NpT$8`X|?@q^@ zbLte_B%#+qseuV~YKaekeYVi*E%4kXcB&?x2ssfA)?S>!q%u#zVQHb*yGvsme7)l} zisIHDFvYPGwE#&vr?onclf4m$<4Z#aa{ca7Tc>d1yHY5zVyzZxYv@qmVPni=Nl_Q< zK%*RqL#Z^xSC!7G6{d;B2x~*FCf{1Ae~lj&oJ%+gF=wbc9jI**N*LyMCkD>`xf3cy z@1*xAK9l5k(NZ3t`l^BahCW6EQ<;bgaiv>hltbjcp6j}N_WX63*qQn%K8rzfHh5@hQj4AMGz(x%k^JB(?ig4_w77SpWc`Kh^6wX~mR42fsr- zXY2-6d}QQJNIFBv7PQ|O-!a7bFM^t^{e1XV7CM-hH+?Z3y08{+{Djm^%i(}WbZ{vX zE+#`4XakNqCSTx5S~7sWo$&}yRkol>6Ez@|`q*w7F}ZF8j%wvy=!x{t$M0|Qg@D36 zgaCBjPb-2Mh8D3^IJcjgl|sA&`%+xB6QKf2)SCVxRnEI;iK3p+9?ocO5eOme+atp6oi1O^AYl$)2JGytY$sw) z3}ZSTlSYJ!UfITeE2TE|IVmi1eepT`dpbec`vdRDZqLOp-bznyOy0TuTF-COhq$(q z!iX)lqx^^A#Y+b44QdRdt68ixHjRbd0^vg)mQDEUH~0A~Sa-gAce9o5({A`RQ`_uO zLH_7aEby_{su`SRMoI>tNGJwD`xp2bo31Tx$h~9Rot~$9&(aD^Yn`FD(p7tc!bw4p zwQ7cz0(1OFDdGVbrP;2=zCNdA6|UdC)p8rl6_!_*Lu>9H+%=V;gH$2V2#+KwN{TPBX&RVmgc#mBWJ7&j zQedBDj|092lDYu*(6QtZI+FZ=w5YBO=e6`G;*C`U>2uFMZT z_8kSgJ&W5~R_%s_UCBZf+cFa}r6lGbEo8Gnck1g~cXXG9*59^K(^@6~|8BAtaSSNi zmx(Y8f<#2#PakC2i9r7=5>uOY>?T=xp#^Jx)!mg&!9oYv9#`m(>rs5@zx2g%?Za(s zl-yn^>8Iq;g%qsgQQ^M! zEq=MxTU+0oYTsJlKcr^GshD-;x?H7PV4G@J=NVeaUy1oI@lypr-q*Y{g1GSZ--T*X z6hlGmwSU?Vg8t;#!PLcK_Xb()n*Xh8O^MICyAB+U+x+~{-~Ov3X_vykMxIyNF&IfL zw#P6lWdU3=>H6b=)u`mMgT0BZZPD!3|MD+e|C8XZE(Z2>V>(noM|8OjwbiCHuacwh zdurN~_q+u)g>Rs@#13O0-oZxs^z>CSD3QMqB_)X4l&decl<~12pjx5f4bkxe6qSL1 zlp|9g&28U@;Ol~D9s??2_17%Zr=^1aM)y%OMUMYv-@b6d_LenH#)^d9U-e`4w6pEn zx`Ty`*OyY>S=9_x(d)jL9D-%0^v;xaQdXI25j|ekc9i{_5r*LZajC_uq!))*wdsBX zkx|-{P2~n!y7gT3F_gH9SY3O{Sf9`<=7uY0<9&ng-=U*u=kvjCrD=h4$1Dwz4Y5E= zo21WY7Bn@SF6;SKxyfs^3XUx;qm?6G6*pJMkfJj3c{6ge`PSgI80hNQ0!P`a=a+ii zjQkwTpQ$S4c-F{dQG!f!Tq3wSU9H>~%&~+F-Z0Gy<)ppNKU_!6adwBlnfP#_qR)}< zs0Kf)41uW$MDwuM^n_Q%{ybO*<<8BAOk3N+KP=g6Zj%K3ZE(POZwTy>f zy(2cYI0DAwrk33T*g*NY|6@bi(H;D#hC=|29U})udcSt^91gY+!psVIJKeK?+}Nlh zhoy8#zr8Dw7q!mc-Ixv+e`}m}$kTv#bO#tCtoG!2dat(+3ZbhnWz$Hy8;NSTO6gad zm;CgCCk>EDu)=Jdnz*`8Hn<~&*HaN6-}7NXSRvymp#L#b)PLQ5)$*P^6Djs6dWjKa z2}38T`^ShEOudaOS>`VUk>)XICxzlK?6@rGwXTf3Py z@A4&4tt6IlX1wdro1Q9X?x-nKvp1G$(h`{}6xDc--vNX2F{Y}38X!9t{BIwtkTiOu zW`XG9+T$jsY#*7tAE)qpt2VQ>H(FE`MFv(K6Tknf^cDjN`MMqV|jKC0OpPHvBdO*CSJ@0LrO>{AK@sN>Igmx{`0!IdW3 z(E^^c0U%M$|3S1q;JiC~9SXLCT-I|h=Qj}D41nY8_I?QPOUrB>#BnCkdo|4xA~~Aa z;nPD5+|#;5fBW#e-JB>QkCy!{hv4umNkYg`-r3jAKhsH)sE{ica0k3G{)>%;=J zwx%l{&Wash4n&-aaV>bw+Qemgr4Y{_A%-31KmwmqHZ81dJ$Qpb*i$_(sMAY@DA7)OjAR}o)L$GsC0%f&_E z;>we=L8=YrLEh}~SF8$$H;nA@QZQ^^nFVGlX!E=dE`kg~6-CKh>{KB?w$|3RIf;%O zN`jAkurTL}e2-RO=Qk(7P;Y#58!nWr2=64Q`dALzIbp{2i%#(x#Nm=%(t>!jX ziPcu1zi~hKW`tzRq1Mbccn^a%n~2L-WDVNCQIK3<_5ejd{*nNJo6QX?M#J4E3F|En zLi3-YuW4zE`TAOe$=OPX1)e_Q*5gTSSsD_P-MGRxI_l~NqJ!zM1vH9ZU>NN~woEv0 zjpq0+NLU-Mb*X!jbL09NcXA*7O+0CM2r#+BLRu#`OhBAM8FteigIb>V`d3&Dl0#o$ z&&CV$RiD$emqCJCh0~)x)Va7bP}4s?zKV{=j`X#7)2a`0w1_0$=sd@$)If$xSGciJ z86Xvr#NqzuvejciGKwe|^oy9y&=((;PUM4@xvG?Jk5tMa-sw&6bKetGR1&M_(qVRJ)WgS%dN(hzL{<%1@N@K=Y6#=$+xA4l zh%<{My;Ha~Q}LyozpB*YNc)+YZm+Wj#t7`xprN(l=fr=y%>OFr*^5(pR_YB8Vw0{d znC$YCID>NBxp;hc-3>{fXgJ@CMD!Fs$QBYHNE?qGj-eB-8W79LG033D1Vz1GqUgb` ztw>XBkAMaZ!T`PMO}i`BFYr4N;cLoJRrHbLtsBznVW{Fpm2@ar1CeTk9w~+_oA`>H z%85Xq-A5m6J$C7wI@)38`*LIX8gWeR6r-AS0-%jc=u3E#mGv5NO69c2_Z+iW0&z-e zLIf!MDm$XudIfemuL9`v67&ibe!ym`3zz>qW)t*4wmXC)Tk^9&*BQ}CVjnq>Ur?^7 zv-<%x=_VIe8Uybi&-&o;wNJx8wd7}jE%J~m5XPN$`dNYDpJvrWM4?LkA zI$og~j`)tiBBM1!n3(BkGn5WM7j62wYqS*9>yIzk3J#x;PT2_7BG8>c3N2sOU3FFy zqQFJ7tK~1@c{K4xE(yyBSSK-9zE#g0ghgq+3UN_WB}t*z#1ANkp-2SwCzbW(V*=1t z%QdA5PO|)gjMULE=zL7ItAk_rGX8T@EWIuyOjHv}T4M$1oA#9wd*8k~6<8~m*>)nn zrRB<9ali2GL=3aDEbu-TZ-l|xO~SMNY#%|bO>c76@()TnVIf>6prbEVhc z_NuoBR`?T53uLWsUi~3wQd&N0fJEQYWMRmzvA>OfP+?P$Jy5zSM)OzOr z)BsV-3Q8BtrLihhC6O;prmG>r$g|sr!=FH{R^5HKSnb+nWo`P75lg~F^(Ni5Xs0V~ z+H0*o+RCVUM4c|hovCu+Hv2xj(Oh!w_6KYKztB3W3a*(Hzx-~6Y&!LrbJvd*QDX}7 zZAlz`0qScrmkyn$63l-|c-xkk+P$KS&65Ufu_Dxq(C5#5S3d_RfFe^6gc*1~pC!S! zsVuDSjOjQfi=b%JeI?3T)yaB1?-2f(?2SO2a8gX3tU{8>F~Og9)f#}tG)++UhJVpXm$^KeDEuLx)c}V6#6^m28{gBF+1zHRiak=v_E@idYu@ zHmI{L`*r|xIpJh`376BV-Yy!}p#oM=Xx9nblEZ@{pHI;TpGEJgNjjB{oyecIWFcU+R21nOhVn5GaxbYm69*mMn=lH7%U*&OCsg zNmJyRn#;D?X-Cbn@q2t1rZK^*Xy|M%J_1D5wj1*qPoS4yQj9U1gK-k*u&muXlOp42 zpMRtCeZS@}=*WKY6qC;@nuQ ztmykQwGF~}sK(pO;ai$ETz8-j0+aVo3n9PnA{xJMo_FLI`0+(nYDd-a7I%7eJ&oX6 zmp_^wK2*&RZnH_FRi1*Dp=kY#v%4aDkPpsFR-Q$_U+wAaR;!jtID(B~7OmFI6& zFVx($PH#Tea4b0_Ei)g7cD%XMLh{ragnzWi*Q?efmxOwrd8-0kzeBE;KmK!RZJo5| zx=lD;4*kpC^=2pN2jT~^YI@pUrX5U&9?dVtM>oC}I`7s;T-&D6_T2qc(tskpW6C&e zd-GUyL$WKrLIJg0VMn~GlKpw{*+dwDOiLP+-#kCGn`Thn@YquFd8`{I*>#qYgXdm~ z8@6@hIsqh2{yOL2ZKBjVutO5XuS@1U3qA;QvKLA_GS5~76@hHB9~G!Fr9>5^(VA*< zaMat3>=rM*l@#Cy%|mYigc9)Tp$a8)2AyN1h5JXed1;een#fjP1;ELty_E>Be=dxd zlGQ}Mq@_)#U>Ay){HlfY3O(@Qo@I2XHzY~fD4Uj?hyspxqo_Ed$O2+nY)n}8^yXct z6BPd~3Y8z`tsC_-jTl;T%DWX3M3XH;O&EpBSSOU2SdA$g7Ayf`&QIbvmM*D8vr6mM ze=dgoB!DL@+f8VbqHh?^_pWxaJS+Z4re$~%WPwc%cOsfFSKC#7nz{sGMEBsaq0 z7-!`s(}}OcT{9@Ag_7FO2DtBkH%>j4<{Ds?Qdeh)%o&SbHs{3fv7Y$xvYSBz{h9Ua zZSWf-jyLc3jn@^-p|ID?B`%GQ;W~E*qu9Ug*py*&+bI`VLKB4>4?%gONz*~ zOKFA+`hz{XV}*(~5c@vs3Kq~%E9MKKM&kJm&Fm@Vz3Bvbx_Ye~JgA&v_tY6!z!q6T zKl=o1Hyewhlz_cLcJJ^$90)4KLLhILl>{-4q4swrT4Noa45$x4937e0E3ARb!;UD! zvy70m6s^q_K}4#TMvQXIE%UP!@*(kwEHVeL*h0bcc3t7RBb)A9B)F$bO{yi-vo{`< zCtL-(9#&iW0PLJfjz`%Xt9)T*t^g+lONm0x?n$k;JRXYx5lfi()^T#w^CtJ;`(W4*ej&gmZJvXZlA5s=)wGl7mqnEXK zgmZmFH{~x1V~11h#km)v->EC%Z`e)g*WEtWhR3i|JLm!fFgfN&0f&YE z|H^2q1qSwvA3D$skXUPWfJADBzHmifm_?OP`2zyn%h>3R8Jf|#ipBrEHuWOfMGN>g z*I6g#fwqWJwBtVyvnJ&k?223og^`|_2Op1hjb!Ki&QhWx)JMWTpN8b0^2Bs6=e(Z( z56A&-%@gL`>i;GRqL=IJW!qaQ zd--^^FYD4%ov+x00;_iVuNn-ASC<;9-pHeEe*Fa_jLLlSWJ*r$MtclQ9t<$ZUohIC zJaKA{V$MG0(H?>Om!+d+$}6w4l-UKsB`Vv*rheL>r14WwcgSBFxGcxumSb`5p=09@(9eQvC*b06A@NQJ4F5j0#)-(xbeeU z>JGGr=O#)jewO9p)7~BG;uRZxRRVTAwKiP;zR$Y@SL2L0oOfcINt2D`R6M|e=Vx}&~Y(~->*jW`!o{koVC-WJXKiPF{moxqUII~=5$@){A@7b zIG_QgDp7PX!6s|S(f#WP`;+LUCBhF?D|gzAp!HIxynXq%qVG@85^k?_^6ZTN1zGlA zJpLUhTXi3`>&$wGel4eH=wK23OWQvsg{lJ)0iiX2pAo&&W#igmZ`f2%*X zDiynALjDp6mY{<;r@+@6Wie5bxj#FYXF=hX_f1V$tLEe?Gh^$YM0qL;-hPPDHLGkx zLC*elEJ_9KS~W|>jxvi{H@L$tpPi{jD3|aIQEL*v`3&UOIXG?3kBtcK!SsCf?u&_; zV+7@Jol;ltLiHA`KJ#gg@QcpMyAeh2Z`6{Oyek)(HBFyQtR4e06XFE_Tz99e?=b+P zMNitwP%6S;XS<1%721cgDuw9n5ZXh_Iy9T8NybiwnXy=Uz=92)6p*6!uq&S! zT=rgqI46J&c1T?Zy?LZ`Jl;0}-cTxs>3E1?h}zMeVCfm(6&36Our*S#zh5f#76)j; zvdnfu!DFiuJ^m|bu0z^~;umJ(HRE`^)O7Oz{Q|Ov0z{}nFGFc126EM6PD2Bg0qe1~ zJ~{B>JK1WBZ$iaF=4R{W*?P8ASPci|jvmK;9#{U29Szb@?Reg=_NsSUX*q3v>|ZWb zEW_RPuc2+)TE10p9$t?$)t#BYnCjpWyOhOnvq?TutKyN#ip9Up`#L~LJLD1j>UZl@ z${+QZmZ@^2)fdPaXSc7m>#vk*cLuMivT1hwQEq zv(l%;yfG0B+Ee1J#mM+fwPmV~&Yvj}B#JtZ68M@CEe}1V<+rF9F4glw?+W;E2*84m zCHF{iS@-xUL;9GR_(CD%?AEgJ(K3a??A;hxUb)jm5yZXx4Qohc092H@Z^fTAV+L>{ z&Q>i*-=C7&t|4n%hz`w*&*WVO+$76+i?hbSl#O+ct!aBt?|c1b4}uztCbF664A|0& z1yN3YToP6IsvOO6vlD=6k`s@RUsFe_2TI20SfY2&d64>+_>ed7Xvta|NL;)YTn#YO8og+9)%i{7Bpv(3__CWlGZ;C^>EcwuvZ| zMq>Y@$<@|FLTwD}%{ljIxyyRIFP-e$ao0TE{rf+T=H~{Ax<8Re6ZH z%o+wh0K0-IJji>?Hg`59bB57h6{%Zn);sEJsyhB*uM4S+9!MUAMeGReTuzL0{UEn_ zA2snKI~7t+(%fNcp<5~AbrpB2EOmga&!Ej#TIGx58aEsMMd!whpUAnogO_rj+zl0c z9p;q$YZ4s~8e|1eCxCuUZoK5>Pu>VSuI^vavPuc=WjE9QG9d!WFWMhP3pfA_wdBlh zCdQvH8Si07of-WXv$5_C@u@!9Ex`^+bmD)17wm$eZ+&Q6J3P16l~-E{k-q;pi=<>M z$bos?FN`OvcAst^-9HH^CDiQ;nRUSaygZ%u#>nf{`a}W@l|3%bHVn!A7jisEMTO|M zdVmU_@uLId?C|+*q&H4M2k-9>;K`Hwq-A*6JfeTk`j0U*ODv`T2C%N~-V)cr(L(TZ z`KM~CxbDcEc92j0`Mk%MJ9)0!_+@aBvmb3mMUId2(tG+l4t+1wAo~{A5h>`^&+Bu+ z3O*MvR5^NoBQ-FKAoy@;j!&rr=?s7KoCaE=;V;RdGhjMI{e%?2r$pCRI}1$wOnFy5 zKz$KWZKw809ggzHJqR4))441f3VO3Argjw0ptZSiOFT@E(1t!Y+Vd)26l5~Bt@i130C;fyzpo0ZPFCLb&kCl_fhr8W zTf2&wFkM13=G^;_{za`Ad+)!Wv<~M@{Ey|AdPCs!c41KBOs3X`LD96#d|P5$lpLQ- zX*G5_M-em3*T3a>Sda!gn@s3Ww=7y)=hl}Yr{uS0lh&>~h`rOp9PpP$3RZfSh0O`4 zfCI=>14rh@dMyT%nn^KqYBFWbchbh#yI;c1mK=cDakmGn532bi>{3cjxUIvsgsWJ? z%Aw!sWoodsD#{64ssR`^F-b)y=Qw(q9O!g_A>A(ZHqq*@aBBp_C+Luhy58c>-YY9& zVkDLB-BAT60I-)~W%OlB|4aK96>*A#D>S zg@o$uZ4Udt`lPdKHOv|s8RhlAj1whnXrJ1!-Kx&Wo^Yl;&(oNS)RjlR6syVMutgr7 zfy`T#wsr%*HGKtq$CH+GSF z=&A)O{6X@`;Fj>Bpqeh9Wk_9<9Ng~SH<;hJNsCT+?iKF=dO1UQot&>Tr4#U}eT5mJ z*KRe#-M^pkN_MCcT5dq&M^7J8*9L-bb%?LKPJ-l(!#^JO+WUJW(9Th8ci6{GHW><> z$kI}5Q#v5^_d3qjJYgy;W0f|`{nIVNC$z6YB9q7GicYbI!=%2CO#QzXEB8J_Z#3i zOI*SjnUR_L|1^l}yN-i=OrxJmI}r4x0( z8CHMS{YX|#(=nON*0~f35O;X2HrR5gT=(q}ym;sp&iE^|&fHcjzcB<n zpf@9Vqp*>?l$5$=!ZPJb*uOz;?B8bODbN?@Nrk@s1+pljxK4j>sr2G zWCG#9vG;I(Fq;j$^AT^K3SBzrZ86}QtRsJB!;vyyRAC8z^FZvLPw=~rYWMDNea%5v zU$aQn$}p4OQX&6;=ITny+>_>S26Axz2gh!kwLtZ0m#1}sF$#cwCuSG^Yy=$ja8kDPq}FI z)Y!0~?7#MNb7fFa_b~;!>7a$ooqqqtp)hSc>z;1{xAp* z$hGOKo?;w>Q(`m0++Gf}kUBpc+ZMBR?Mh~Cupaj%FHg_!%%Y2*y`#~S$zLL`$%rBq zrPwu%Rf|79-a4gIX_*Num7cNfq`MI9m(p^@>D>pURvXY& z8=r)a2=S`z-waA<;M>T;fYKYj%j4kI=!m-8*7hpZe@*c^ZJ^j3cW zb^*sX1s5cw#c#8MPuPHmZ3jHVpav(aqau_|_jo%6M%8s*tAm8=`ZE(L-pqoL6m=B! zo;PrKDN`F62Whqcjo#FkHvA>JoPt6% zm81S@V2cKmzo(aMsxjb20gg*iTyGqHdOYr07n&6POM+r2bpA=#%?;pN9Rfd4-f_J}?BK-|5 zYqv{opQymNvBxra;BZ>%A!|hV^IH?|LB{RdE{Z0iA(N-Od8Fr7K^s^q{?Eeru zSv|H2W^C=?Z7paM!u7l%X^N{g(#eFu$t3cv|5FRISO(b|E%8m^A8Dhs(Fcaf`dWXC z+}uc*$AC{S(2toOqFMC6JVrlra~F2j=2Tr>+z8pC6wuLy%l473Zj@@mNQ$R^!yA5! zt1@1IjYArjy7Ix&+b%eNYTFm#qoUn)@kF3rsBa!E9d*4?IInG5XH?_0JcEpexpYz2 z&v^^_Fzsr3(F|=y70}ps~ z$tfSxV06D_U+>^`l4_{@Zd0Ro4bKkyIgW|o8=n*CcleWq9l^zkJm#xeR z9R-BpGvCbAR`k|D25;a8vA4QbMIWjqgF_~k9aP3BHlz*g?{2p|BzpXt=9EAkZAd%3 zRAl$U`}LxDw?B4w=h29PU!JddUdxzo51^pnj3jp9{_ab`IimIB35-=l>AGc@%}`zT z3!f)wAdB#gvi%LUaFo??pXo1}ndF^DJAuoTjM3*AlYZI(vjO}Qlm;w6Xr2`$eb+i+iLzWDHPS$9X`jhY2!obrU73sVv~t@YaWzqw4XN2Mx%;gzF1|7;{nPM+Mi zf!Nh=v2|mq|4j^N^LG4Bv|;wC5m$4fbX)y;gpJGm{{THe!oSeC_E#?OkR8@+ZiUFC zJ%%BhSLH;m4JMLuivo4ik*+s<3p|SVv*?rkAd~@ z+kZi@Z^c?zJq^CMKTaR*GRu6I8QH*o_(4bFa|?u5TG@u*H^w#Xk-2dp>yWx0l~sSN zao&x$K=FhlOjFwC-)V8jf$a-cChKf~$$BBrh0*31c(Ci^yJTl@r3*AGtG$u8N=j$X zL?AYGwPnldd1C>)-NGQ=9X?VlsYRljQDFG63KjwAjPfg!Ebv1|#Zb7^dOy7Q8-IOc zu^-O)g|Gat(+5pWF%^~feK4P2mHN)c4^p{jnno3UaBPo}rbd-FiY&v{#vJ!W)0=Js zofbdnWltGZl=z^?X3}_hi60KP^oCnD`{9{{s`1S>Pt;g5q=%2WB1$ZCpPr!y5*;6Q zkG|T3tyg)w^8fQjjO5U&&zWA>q7!t(L*E52a=(SD8oMK&5mA{cu?eTmRUcPrd%`7E zAjqKH4FQ3r78*4UXevrESmol1({EmwOnCug-5Ffm|HTMyiKmDKmt8BqJ*T$^vBTrC#A$pqr%vMw_ zoR%{4(Q_okJ`aphYJ++QuU6_&J2rH;%xk~*3cPidn&lO*QPuCwd13kn71J7iR-Ji+ zWkUPLg%)?n~m zFegu^?d}x@tbQsVdRomu{V8qNOSufV&f7JkWrP8-7vGv1C&+l_-jIp|174N?Hu)Z7 zV5$49geCb5Og37+a`9rIFEsa-{2B&Iw`vV6h-V;JWk#-*DgzNMmJ&BUbf7oWd1m84 z2NwIO^A9g$AVr{kk*g#FLbu1gI=nm3?cdTjK=$`BXinna0}RygV+!euZxGx2M5eK- z17ft^TMriov@@sad&@G=_D8e9dItlQUzgb%1vB7yI5smwjEU73-ic5CW#XW8#pcS- z4CDo68!WlV#5bKY&Lu4@NKDsoUh#?vrxfKKc1kRG?yz)xY0Sp+@e-O6W4O7jv9Wxhk@KN~42kkC0zamCtmpzS& z_)ESg(l}5VU)|b2Nh8B@Mx=HsjUb!d!_Imfl>HJiP;TX5d->%>UVCX=`o$bL_LoK$ zYX_76g9HEVTb;AjIM}axFS&($pYr%!9N@!2(@C`{z90vqjkv!~hek?!Pht-F|LXoP zT#*JEF=O((x`t?Ig~?3pJw`)_mK46*LnHC=+18t?9K>y(FX0kPqbw@<&5v_5is?7y zY;77AKmX25CEslevOl!krV#o$MD>qzb z7t{FOx>G)h#GNO%G}teuLsG7vr91}?ITStRuU&a$MppklAOIS*sgA-b#iO*zdC`E>^lp3Z01wD42FbC@y zUPI+?$bY_f82>S*F-Npe`#Z^t?6UY^qs1JUuibAV&ZFV!6>TWKje~2~r!Bv6gU0!| znVrdfG*&uU&ysQ^`5n!;Fjz}tM$%z*4>pb2ulzL4UvS|1RbgR`CKsa$vnC zp+8QKi|b#W8L-?r$P>QlUhl_2(G86%XE82zk1oh^IK#oMdpCC-bmc%k$obtIGcG)F z^r#yd4eFFLB~NqES<_^8Op1#m|D74SGQz>4Yb&$PpXA_6#d$OFog7HI4Cr2Y!@5Je((@2_)objpM%&H_x~l3ytr7O+WNhP#)bBCQP)0@JQh?eF(Y-Iebj1) zy8w;FlAk`Wl%Y`+vNX^C2?g;r8@nS;PB6m$>eS!R-ZU?*(&B)f^iHD>749u*4AsH9rpC_}AjgVA<*EX#b7XDh>o@YxzTGr=Yo;w@dx&oVQeF{Y%H8yq+uo0Ew9x;14 z8*?8ya}-apks7k~T7M)98QVj$BGTZeCNtD zCPWJ#MO?ob#k<+QWf~L7#zcoKnGoV$N-RIi#GHABJ&&`P zaOr)P_?N?kxOJb8%6S$%nAY;X5lkrW&0V3jhzVMk&lvY);lBv!c&}O}wng5({6d$B z2W>Sy@o6j^RCybH#E^x|T88Q@HzqWDokOh_vvBNPU}nco7GyRh?!V#7BDimhkZ53G z=zX*`kHbRyB_(f(Pb@51UVYJsoVRT?L)12h4fSVvsnZ#3oc=FCOTwJO5fu(M=^%x5 z8TCpwg%rZ8t{m+*rSY7t*=M0naI*T#+BK(Wa1w(~Y?;M@;rNh?1i{})^$#<`TsV++ zbgs8;Bk$`LTD&G>gLvX(|qh2Bd4L{2pqQcpF%CAM*K@rb@;i3$(f7uJ_vZR6o~+@wO`IUZCW3g$cx;i0+z zSDD4kPDsqyw5Owyha)cGrS?`lA`Phk| z6-9$mPCWEpqt97&@GvVaW2=}|CuFz2OcFNX;@j^%&%7J&=#m8-vdKVdK~6Le*QkWss=8k z?GkSb*OI&{#RAU-DpJ{nKSRpNC8PbRWe3;z2g_UykH+9*!^W$$t>RgTBqwZHm-ku7%{I7d1Qx zt}Mzq^j{~g_DRO>f7Xd}F&#Bi-d*TRj2yU|*ag9v-RbptU6}7bH$JRuR`Z~KT>INUV8)Y4~&EaF-z?AwrK|TcZ;zaVT`0&wGjg;8H z$Id7dkL3sWI5OPrd)t?fS(68kJ$%kbVdui!Dd}#URt}SLljMUD)8TkhhmX^)VH1A zoA~%;HlSeR#D_#d=za@LK6>XsKSie-s{GGO>ll1oajuO%AkD|m-dzPo^SW{DCO^}V z%g4ccb`zH~x^Vo%92u+ceB7H1-<@-v50Cb^q)|o}E(li{%p(7h<-QyG;M@&2C#~H% za(s9m=Vkvp(~U(TWpa;$x}j0)A@|;vk57-5yg2okoG)-h)n{8b*~S|_dS&*U7g4eHFWpf*M)O&m--G|=t57#xn!rm1dnmX zKc{(iLRx?q`fy(-e(e=V2_twuu)!hs{azkkYx-VuNaG<<+Eggx0|&~dY7Qn#a`9xx zn;2i3gAeLWa%10V{0g1#`{^--?H6py&e9aR7ls>cGNF+7xO?r4ST?5LJ(RP06&r=4 zQm@s-SU71o=BUxi#6yFLnyN-7X6(M^lJ|#!2`QVeJmS_PJ z7ab!t@(Hi|*c~}{nfS_uuBys?Mr_!s4Zd}BW#P%%ue1EDn9wPbdocN)1@FACwRZk& zY&n}H#68YJNzOWh;50Vo>$Ym!?xkRL{F+|Cdo~2yMSMIJDRA|VKQ3=1x>Y52AZ>uc zpX|GHhKL_h@jhiK{E~*84DfZk<_zxFNm-1P!2`}!x{amE+4i_}<{vy%u z9Pr1!s8yA4as0=z+|$GdqjKkpHAKIZH`jJWDsmuxqS&Khkb<12-5EC?g(YPTHKH^P zufe-c8Qm1D%eS`gBYwC3q^NQ2MJ^PMw{L$;=07{4Dk7LkL8nK;veu6Hp0)R`T6`jY z_mAoMTH-sK0<~`4CH{NH$OBPzQb*4D4evyKXw;YeGTTk!Ep8bn{yF5xz-k|&|7OYGR>(Xfe(c8E=r6lztZhr`KG;R$ zZHJ7G*fQcj)e15yq&PUdWv0R>Ne~; z&*`=;dUJ|{S9=4U!lg-lrZw+O7GUG1UTgjwCWRQs+rv2vXejl?##xzvOJ9dE*sLv!_&|2VMFN6t~DOT#NSB~<>+R^ui`}IXL$<$O&qy4-Gz;n zQJDLZ)Nvx1@z!L5jihF7>%9^-K4jJueb!}TMgQU_MMZ2}6W<%WbCQMTJ?GTJtXK#h z=@u$|!NSDazx=TuEYyY?DYr~9vHL*hmzF~;D2Y~F9{tI}$QQxoN8?z~ez^A0gcBQL zULnoJYuVV>xpnRdPd4^0%XxWY7KIz5Am=<;xbB%f>FZ+NDR_`R)FsCVBle$S>JSq1Zo=v3WOzy5EM@2{+m3zuw?gw~(y! zSMC3tO?>*biu&0BY$UqAFVrFH6dl@x=0#FaD~b_klX*YC{iL3Uu#wX*tEFwH~8 zn?aEwM);QJlhNZmqj-+d;PM!}?i(U(rb!`~B5QL9rZm@eykyg!}r>eK(Sg=i668}27)W8Cmz8Sz778cRZ#W)FV&hnz z7SpPb4R2g~o=p11J4zptL=8FUZSj;Vdc=mp#egj*H&aM_68T7BibBLO=GHt0@hK0- zs-Nwn@MJvwW_|<7>wV$MG14!6aNXn(L2%@>KqtoV4tX9`DBpRXg5eg~$Y8?5+NWn) zi+f4#N{v>^ICIHc~w(jH@DT*{bS?3M(x}reWC;AUxQl$ zh`$h(+mJoXhGbRIX0Ztt?u6}S{3QEqS8FPrOK{xc&N#GuiUnnRQ7Z#u4#Kqb#JA|t zFlc)juxcB@ho!(A?M^o6m-Zhx2|=NG*K3qk-Ue zdJV@wJB!q7o=~yjJR19FK9jfoNx?|1R3x47Z0x$HSHt@#oL4jFHIsSQJ`Kd)=aPD# zn!mB?52>s5)<%7zmt9bd5|AW%I+Pf7PnGQFqqNo!4WbW^TZh6f5dNr-K4)S@<3!iR z^H$4g{HwV!BeI>u|NY0AA3!5KEY2j`hDK}C)*V}jKF^!xof{HFW6Zw%jKXE|AMW*E zebzK)8f4w_)uu7%Sav0I8x4W)GW++E@p<^g#Y08$ z|7a)~DF19BdH*Q0O0)bk1>HB()`xnLd+zOVDQTr=+kTrz8U>$ zt;vS`+D%hWU$HR5Mx%LT1sk7E+lO8qWg$)foV~9J;eD~9n{7n5V_{eCkC5dREUeI9xk6(#8!G+-DlAg>Z6_90SrI)bma#Ru z|Ad7D0krDCIElCFU(IJl;#V)OypO}={nfVTb&)KHZ}HnuSk8cFkf7a)zYG*JeU=`N zW@0#P1^rx?ft^ohC;5KuK!AdL$z@9h#9q&({I7IicO#z}oYH~K3qCh<(>tKp`z=Le zTL+eENmc6a>A>^7dmLrocOdA_%cA!F4p?Z4eVlWYfu}`2xtmEm$wrsg)88ei&33j9qJw4XbujcxM=$uc|Q`(gH$=#2tX`T8I)a|jL@j)Wv=rZy= z=iqp$0J*2D_rz#MniC)D`nA50_^9fT*sPOIG@gZ?cyGFx#{U2S0RR6Kn0Gvt?;pk$ zrHHa;gOIXERK{gQDJ0`tQB;~{Q&9<#M5L0^LXsk*g_1;RC^?*G9VJRCqa`C5zx(&s zd7bBY?&p3!_vgAk?@Q~%bjhqoG%E6b?A#Z@;7hsD)D95_3!63KZTU3(?##(weVvBV z^WaYT%M50$-q!JTGXtMq@i)7yXh>-L_*euI`p_xG;mS1_q5=_zdoT zpf)|*$zZ74bbZQi8rE~ORwbD;uwM0jWzu;D2SqA}62QQ>NZk3o1_RUQYgGSpWY8dM zuI_z`{9bFk+d!Q`&bgoJDRUSE@9#AcYG6>R8<t#o*ialE3#|7{th_Mho3%kkqMJ zWURwt_fXWT340k_Kb38Cz?H%ALzBB&-;wpwzDOkogocUfHB7!7URw-U9PG(zXsq-%YrVb^fmQq`G(V)a4auLCqTWuzLm zlYQxnOn;%gg@MeuQ%UCx88nvu<2tMuj2IMJXh$))_ICV6FJlH?{-alB&@_BK&9Aih zk>@^784RIlJdPeVa93jx{+`qCCi_(Seqd|hFax{qM;|PgV^N^=*7=emhf`&Wolzd`k|7u^;?OZ*n-=rWE<`FN?h1)90mEauDctDQDJjFgWwORF~ZU zB8_rzt7Z{2^j-t+OxL+_jDwd?W381Z2iIYV zPriH(i3g8ICwFuB_Uf6YXdQJq(B#Gy5;cF9DV++R7T_+lZ43fI>r zJx4j*Y|>IUmKNYq&%@P55dxf^^Jv?TPaN0}Hp70eIfTg>i571cK-yBH_v0J^mfl_V zy4i}u0lEH7a#IBuT_F(jn=e4}?>_H?H&U0B6qX zbxr%j!Sd9OjZZ%aaJ*gV#*?)I*vL0Gc|7Fst~nrH=%oPdb+0uH7y&Lvq*NJ^I*hZs zzt_W1fO%WPEXz&^z>oQ*W17y9{a(DB+Q#9lpKXA}HUYMFs^mJAayX5{_l!v$L%nhy zKCa{taJwMpmhtNsIh)qLcny(KG89eA@nO zU2!#o;nObOVx*s4=4*YLDn_H!??$EWVHy`!cxLICQ7BUz*`sbsp}a0OC9j%~@#l9o z2YNT5=S5EL-oPd}G#khU$2DR?L2u`bUp)9~gzmKe)rcWyDaIs_hex{S)g_q*I7mAV z`S5ty-{?sNEd{(^OcfAQmo&_XU2{j@4 z*ZzfA)&%!J;S&)fO|Wy>ouQlGgtbpOknNLBlNHTko9(@xzh* zwfl%~U0XTt>`h4)Ya=S%JYraEC^Xw)5K7MTeSORoqSLU?n*zlnS__&JU_Jvzuj>id)-FN%SSj?nYgBP_%yDWRA7EarA^zEwunS8p~Mf3}~&wDUjS z^5R(7IfSo1p3Fja`%vF7>7zgDmT3--99oQRpE?qsIG!=j`RrN_Qz9IFjL&j7L!-RJ zi^C!-m9qhw0wfjRFdZK)fcV63XdI^#?4NLce+fR&O)@{3msp!@IT+2$nz$k~5-+4V+%XumhH zB2fY~d$(w&yyxJPX7Fq01p&+puZ5i&4?(F_bYT8%}*LL_2YC7fW}!3sh#7!7`!yQ*`Gg+1>aA0oi^!H(e%^f#Lv>W zN(IY(u4OQg!t|{RC3DIqXH1`^@nTh*Mgp1hO3Jxs->zlxm-i#ep2y(r{f5}u4>X2{ z#OdXvzHN_U4UeU=*ta}L)M^%k$D_tF)xHdjTs!!~%ZNYP|2^e!oQ31VyM2aa9y`W) zWc{bb;_XlQ8UrsDYIIl9-@6ogcMrFu-lwo;VVG`)4}+SOfi^QtXj~TF`&xnMZbIn6 z8IQ^JJN*qg>JMmWs>c5vA4fRI`Ozf5xeQh|jpKJW(inWzqxrm!)IVanZSGnxf1nL(y+XN%7u4H@}e|EZGmeKX^ome-;G^TxTdaT919EXi4$|C2(6ZSl7Q zW(?v_E7#4XDR{Rm&0nTZNh^ zgY!R98;gf%culjtmQ=%F(wyUkLqcR;C~BHI#WHXWdwqPE)M2~oi;<8-2Ft$dhE65t zF2C`G(+5!&jEIqaeG7xQKQ#{Dq*!dPX-{42#Ntr(^c|UGo#C>}hb-2!2xMQva*V}z z;XsS6XIMywxvYLlxbNncJzYEJbNG=YCkQ8m3k=?{Z3 z=a8togg3|ixS*8K!C>);8Oq+Dxs?GqIYg#Y_?;7uywz_A%ahgUF2 z+1LVZGK;NwU&R8avrtmeJ*gK@`m->=<3v31zjs5w)W}?0Wg@+QKH;I?%BiIbn^_1a z@ID+)V{zilFK>0ieU;xf{Qj_m#p_lLFD8OTqUG{|tP?B@c0ZfqK>B?BtGpfC9}>Ne z*48(_B07-`wLMC7eWuquN`(CVldDxZm1K^tsHu6Qd6|VnbipQN;=A#emi^kjh=rSX zK(XmQ7Msp!7j&pJBWgp&^wNneCOE|l1%|UwMbYQugs-l7{PG2<(=OAZqX)?T54=@e z{N0;{{nnGXV#q>^eXyI>iQw&n;EHVMRT4~_)YSA z_?BA%#7A>q?PHn=m-G|_UFvaT;S=)u@DTAif7J;xbPo&5S7~)lOITRzzpJn$_vN+v z+Y3KpVN(4)V6{PQYZX0jVYe?M_&dUvLCH>ZyDSwyrVeb-yD_4%P@MKw|uuYzB*`i{q~?A?vS>IcKO& z&U0VN=Zl61ITWab_`f2&l{Vvuy6a08=6UyCj0@thLx;CvsD(v}@g1#D(l^=06LXvA zkonk@>}0!(#rbI2DY8#ll!cZ}yMBT2dH?6ZU2hrWPV*S}>%v0u#`++eE)L%9<1O4t zUq>EKAN5;6_F=Go+uJJ~=0#+S$&mF!B1*Y;zAS7v2g`Jokhzo+u6i_+#q_qF0d)m5 zSO>pv6IK##Fj_#}C0w!mt+M(w4;niouj#8XH0V8*vLlm;&fctRl1`&BJyciehdhHv zOJ*C2lRWdpVOGL3qPLjqcrHTp{BF&sctz6J!c&{(Jac8?eaK48;VXlm?PEn-NFSbX zF-<+Fz@o8v)_z~2V_ClwuMA1Px*FK6WkCES^Ls#S-57&+8mnsG5T7}cen#1IDhrp^ zr6yUVkKBebbv6_-xH6!(A(-U53zzQj6vG)f8Rw5vCHrqZ64$l)2$?5qZa=hILqkMe za?#D{G%ABTCzl+dP+F@D>wU!k?HMxjrSXb z^ruj0h-!^}M(Qs8CDk00XlRX8iI}dV;PgNwq+<)=v;9@GLmMa@Nb`4URHmSPa4q+` zjgLkV|BT7!C?pqL5mtG}N5FPoW9cS7RtlBKb&t+mkEX1U-cZfqT`-_rjU$h2HVd+3y^dYMX)kb*kis`vz$3t6Ql*E$L4JZf~Jh6Ss16whtHB^R&Vlk#N zA^R<^=FE93v7rHR3ifi-G8V)v4m z5GRdBto3+n75uIVZc3XytSuX1mGV=_E3XkAAyV6|?>1uT9_p^b1j6AX+P;}_O{nKv z=wHZa!n;vR!=i#FEPo_?-hK)n9Zaid(^NhL;sI8cCVZr?9$F?G&qsyibWaCgJ_>{k zzA0q#u`F`y&`XkAwg%S7l}l3yEu1-j?j#CVv!ecLkol=}z%?v+2ZgAX`i-Jd6dpvK zKj0Wd;n7q7569M0@VvQ|SN?=Tv&a5ZwmT`*f113+at{T6%an?fr2n2tea@V=ltM@R zU`SsDh1&8YX=Pgqoi(ZUHtQ**FS60t$B^f?Ki>VYioz=G8MBXTQfN(y?mc>ttiRji zXS+HLZu^eCmpmy1jJx=^>pBIsj0dOK4HPCVIBHegN1@Bl_U7Pv!cY9BDp?QmKF)<7 zXlWWZUNyw!=Mi3X?`<`Ep%!+KK@JhsBLgg+RIKzu zKx2#GiRK{D<&xxgp|R04@~?L!?p#G<_Rnv!=Tm4Xsn&-qzD#3C!D@SO291Ph?S1PB zS3S93ao2?KkEQoinUoR2Po7&R>on0geV{>v{YS%NfrD0TE#a~P(*w@-gu@mE-b=Ei zv68ny@z_S1@X54!(YX}v`Dcn8*hILF(?3=Ii|Bu^jx_HOg^w8;2R<&NkUu=gJDx;g zV(q=i7v%fG)n{Z9^oY*aOPhL_Q;64J-MaP^g>UXI!Zzew7dYx0uF|CtNMV59iHtBIifhJu?^-W)N0rSWFSFlQUHO zIo+H*?ESjX>3$6H{hLP?6HXG3n{rM14TB*Sbs4oA44Bfht9{H_%=(~hl4r|8^PAW1 zu6hQGq|VpPC49~0WOiP#W^r$7kxG>`nQP@54FR*s{QdECR&^tbj=tULpF+r-zIHir zj|brqDn|3=3=TJMPjy!fCY*!#7$$ zID%f0a&6o+4j*THQkHchb8g{?(?XKFbo6vv^9ET26;y4%v5>>n%gsX)fn2F1RtGkbS#>KNAf!BV!{vNL#F1+vK$;k z!*h!rIJ}woXOTUh!IIhG+RknaJgyH~Kb*`xz^y=62^Bwmj+X;DZm7ftSsqY&}n z%98Wh6uK#`Luaf>KbG|FO*_aZ9CvWzf3|!a>lT0dX^et#C*S?SDhBJjUu4f}pfPW& zM40nO8m>#2$3{vF9!?L93(h7!AuTJlWiiP+70p>T=?u*JBG0TQ`k$>WF`{KaBg4?Z zHIzr;--EgLa8$-MZ3inFtLv49jETOE7GAw^ z<}i&fY7-2X5q~{AzF(m>i-OB+mmFzp8p7lER4gAQeqiGHN3vJ1y5sA_pi}*9{SBhmNf8e=Hj;dr@mw&w{uRm1d8-pUNWOdL>{41m zbUEEZX5m?ue%NH36z(_x#b56+qEslbLCx0KIoItc%78Feb41kweyRqh|h9J|)0D zf#n^2c>#`nkMEavB)VRuwf<9t08ae&`xzt$_$F5`N~+`_yJC&RM5IsF(bYj4Zobd3!YFkWD>-V`VdaP`fn^LFoV3$diPc} zqN_VE!w%gczVK75DdJi)@u!>~*CYoD-eJd+r6*8$v4NRyyqSXQ!bGX&LOvpHUN|Ca z$A`*6n}6p0P0)Cwwy=}v-|EHj@ih<=rwNPOU;cX=0Q zMQI3IG?-`=V5 zr=WG+%`4+6@zL*HAMeiMBe8-Sm9yugZ`QL(6W{P*R_K=LsX-%nm$vhXIW&A${4x&m zBe`o)!)#}guVfvDy@DNyZ!FcU$#h`QEGDm!TEbxX_au8yGZsnzR2MA^BRP24&4s!e zEN%wKh_EDA(T$=Dhe_`4@c!ubies>`T=DZ{;wOt$KUhq@&SGWZY-Kr;tKKfTRTcA; zLEe?f{c>b}@A}|!>Kj@Adxt@nHObGC`j3qVib-F^82)}oGbsL@S{4<;psTyg*PGT2zlKiD- zkkT$kzHhjq(=~;hkA_-ldU7$1tiGu}{UQt;ZF#Pv{tRyKx_wKV_}@0~+h$H}G}1na z6zx=G@K2ka{IZ6I{mSNPKE#J_w_NnxaDj#qFQQ&sgVe*`vm(Ej@FRD|qyHO?`5t%HfP ze$#0DQR3sYo#fW4eLGUf=i6T!Iz7q0iZ`17IDeW!QcHxk37Pk;M`D~qBN?2L_#dJ(n9N7_i5UE-oc{ zO{idNLbO;Eg{4*YY-KPa+%S7vIfJUA)a>z37@Syh{GHt>gL?^*E=(eW^8Cc3@mCp~ z+o<0yLUMS+PPdDRr0;$wv^hRgWwBZN#eAJW7O{an&(gd&1pRSRUzy0lOZ2Z|Hn}bn zZ-w5qT>b`}eRhx#LHk_cy9&wQ)-|N69* zkIufyKtge!Q8wwvbFq#>#R&{TMa3t_lrflVIe1y*C4(8$vliqI&4OQG5-t>o)B3gX9(Q-v=m)QyH$ zN0NNil;G#ksY*k=b1Z5p$@zT^fvw`iPwut_P97rpW}&M1p=>C#|0|8 z)>BY2P7#~eLpWT0&e+;g8uISz8lHS5`&w0)t)Irg=X5tyOgL_)M(#C>bHv}W;x8X0 zeP12s=5~$rM@ZH9-L_Z$6#&i{ID3J zcl+`sj(N`+_(nYn5f(5|d7@M)J(ETJ%G@f`F$NlGPvmon-$Y4DsaS4gp}*H^<}EuG z{{sL3|Nj)3cRW@9AIF6p|TN)T?@~KVuy`swDhK@fJgvnl0-z!H$RG;0#f1@<0FDTvQ3Z}rT@9g(KmnpD3 z@OP2nVK);7h`f=0(#Yt6cV=pzlp=Z{wBKQTa-s)5c_`eh=VO3@!W>u2U=Iv( z^pt5VVZfl1+Y1YI29!q>$2(kSfaX$%dHqKW&~LcdIDpTOmpSm;v7G@I_pblPMKQo* zsLHO+oB`=sdrh_|GC?z!)hemN1T*FbD_v10Ed0~+GjL@BujD3CwhI&Lhi`|exiMi> zq=#4MF%x`z^cyNBm|)}o!>e&A3pmSur%v`VA@q4uSb`4=fH1l%Sj2)~ZKjtCUa&xU z((+XCQUY}4K5h-4Wx+}71d)MvEb!zHPAIh}K*Q4@{7xDHJ$+&wMNtG4u}1&-3y`o* z^~YnmJ2ZrxzOgW?MFQ*UIWMI!5>ATuZ{d$3!LqzU^}!tyt}H82zWtPh{v!vtS`U#B zv)-vbC7Of)`H?GT@g#&ze_#K|m4s*OrWF=qN!WWLX5*z85>iCt$84{VpkA|W^-_Bh z9%R0l++s(^?}r?K95WlD#Ahav#0Nvz&rmP1jys3a6kzfi=?DuX`AGZOd`} zXCC{EH^fpf#5HiOQG$Z3HIn`LP9$*JUrYR>ASnX6j>iB?yo{u#n={R>~ zCthSmO;Av8R8XefgvWfDCEc<#{7X+4&M>5*q4;=Kx&aMo%jPYG8BZr9F^}Wq~LY8#xm!(6d2f_ zRkj5RMrU?eDl#Z2xGg7Ax*pe+-p}x?qTo{ZxaW!w6ij-bT{9U$fo29FEc}@SW{J$O zIqHlQkFA@wB?VIf;`bA`QP3|d-<+|Q20n$9z#0o09+(}i89qY;$3ySLvm4lO;CE<7 zzX=}BcQP~+XG6!zK*d>g8p>k7w)pVTAn-uo$@eJ=nl3%w zd^L~))oqJ+JzY%0mcg#6lh4@jDgur84u1E1JFG;pgVCC-depukx7arpoRnJFR)nm;KBC|ou4 z=oP*f$zO4AXDP^^PUBO=`>ad%=a1i`;EPgcYXiO~HKOwb|8Ej(gZGPv;L+PCQA%Sa z1s&$=%m$??SiQZ`oyNY-E?h3K;7mgN&tc(Jg1DdECsf0dNmvpV^l2)Egbx?9I;?W> zeu19TCuj=3D(}mpaXxI;e=QRAq~PYI*-$-P$6omZT!kMgX!y$=OPr$se)&6{d5-l} z%sQO)j{?qO>sy@Ir&Zo84~YT_WS@EIJJnJ^ThB)g+@(M_*kf367X@M-`HypOUU^&B zD2PvzkU6^O#`^^l>#3-to`(C`xN+yB*ECKRG%oq>Ci> z?_7fZ!S7mqWcUH_Tt#5xw_of>r6 zD8qu(rS%Qfkxa;U2;Ur>&4k|i!5(E}7G!1H1mC*JfT=P)PPOx>^P$OWO?#N|PQ8CA z$;X7+HkCbGVl0r+mkX55XTqM8eva931{`VpVCP3M!EX7Qu5S@cXj*SA^LrZoCr0tH zh%5{ITK1T~j%Gs8MWeS@34_wowf}0#v78%jpV|@bQv; z#pX9GaMBSfbJ@;<7dsZ35>F9OA+l18Uygu%?i;V@#G=1=b#Dx~M}Xb4k<{^I0wg{F zctD50oi}iqVL|?z>rclV2pGTnPn*0>z@=>_qosEU=qoSqGMOOYVYJP^O~V9in-$Ah zzlDSi90MN>YDo|ldH-hW9oG3w^iShp5=Mq<^t8XD-nw`Q{y{z1yK%S1bua82VIHw> zHWb`%tAF0QiURpF^C$0TQjj`XP&)hu`&0DbR3z%V!%>MBThW(B+S|@(Vc(8hYInYE zBw=DxamL9tByfE@pYhOx0>7}CH?N&3c)MZ6wbCRKTzw^dd7UWG*z>i_XB7?q*(sX3 zWl$hgV}A6YJPjMC%A>uX)9}2aFWcIihQ{1qA!IWRS9$JFd}*LzJ+mY>eJ>3&8V0<9 zSu`9FcwD(;mIii*zyYpXG_0tMV>OJ?pt@Uft^@U_u4k8MTt5vDIU}u%3ejhsyI=E; z(_rI%NMH#*KVZLQ`{DOA@ZQ?0@{vu$8ZUKs?Km1N9N(HMX|sXIUtv)p%7%;$-v1gd z(Gb4Ti-^po;oYiQ|$ z9y3|M<{5NtlOceRUpK_-%Yvy858a4eEV%BuPVGnu3nI)%jcs4Ez_PX@K5;en>0Psl zxnUNFes-x|i{Ep3ouYJyB*5CzCXS8zBJCg(QgI8{c`=^%YYhp#C$#r(YCvwCXh||5 zNbu7*?U=|(!Lt@e8GR2DO4>hjbafFRSzcgRG(teXh4V&f9un^5I&YC)OTwDpjjevT z-cF~;ms`pRIJ0*Dc$FCmJ9qYe9yTRmf3@8A=@9(AD(hR1@&2@Q{*-kFsE0cOy;hr} ze>^JmT~|(mv&cT}!C4aG)CyL(Z=yj+DAY>|{WWkp)cDmS63oLa?eAedyQGSW4=N%L zZ1|v=co}s*rsb6@>gbm3pB>$!DEO;o|3*8MfG0^dC3ha;d#VwhxQjfKaxf{s6gkT| zFVmIfOn}(op$Xjr>0XegdeFKN0=U33y}L zc3fVXgd@Uxr@2vA$(g4Pd8Pymb&PMxZ6iRrv80&y9NvHNWiYoQ0h~U!%d6Z-(D_}| zU4gz6R8eiOf$x8~uU0U^HR=r=YZ=p zIOy0ukH1aBZWrAHziViCrXMyL-${d1>^n1GV;XLXEZ<}>Pr)$}uc8v|U6nJ-8S+7PNIwC8iA9;d?@*Jg@?cNk5 zUCFCGlTE@9A?qfr1!lVAc0XDFu zEOMtjdqKreJBw4K7rr>l9G_F^g+;QBPxG>R;nj^q-Cop_2PT~xywU$-h5tL&g?eZd zyZUAd@}i<;YTgsv?}03}9PwfbUQQS*8E-|sJ82@;YDI&qD1?L~2Od<>-j*dp!zI1W zx^v%Yh&P(4_x;3%4R;NcGa7Mysz#luacmfr>x-Na?S+RwCKq$iY*<+zFuH_bL(bGv zPMw=<5Hh{BOWB|otQwYGtP|^n%(<|PG}K$4)cW2o)Ilkiw6DQ}H0;a|y0Md_pfzjJ z{nYa`Bt1Mfe;Ml(+C7&rmP)~*KEbdtf6T{Issj@3xLzaM(Q@Q?i&niPv&AGdhNSq8 z*kYfr7`Y%#GU1o14Dn9G)=9WVdP0u95ud*vNWD61^!G~C35yDR@}W1w&HF)L54 zdC!C{@sTg>K1|s6(MI%BFwQ|y$C)@E65e@x%kW^|=FFThojXQ?L4jj}p)GQlAEVzH z>war_lC?bc?fb1OTO!Y5|KFKcFWZfu$JD=*k4El(+o34F8GWv8ps33g^{uOpJa7y7 z#at+o2YKgU>4yaRDgo7;IgKq6=);rb8}S&Ni|WdobAUd)N{7n8`ALYj`tMaOa?{I) z$^YRznwl%WD(9ep?Pr{tSxSP_T=Fv6-8gsZ@g5haNJxm%`K5vW`XPXO^&!;jv~Us4 zEEewP!gHZ-nEw~<(28gIDA?lG9zN$u!d$BLa24htx|MJ0DC(NGx$?4tT-1w0J^gXG zKdWKSqN@883|@20+Jt#S{Aq>Ig%#LOM>Kh)Fn>*bvkM(?Lk0sS^`geG{?w1WXpY!Kcd@EWh;4*rvcIgNWFJoTRDTmUKU#IcH z;s^TZm_yo&Bstx%P=cC!`YOO5hyL)#t)bw!<^!{9w&Ksh@xNRHH12zR(54iIUcOX|7EOA%H zxhjg4PS(X-)fvL*_qD_P5bk>48FSv(lI6#0C23HY$sb;PkcNepcVgVQkG{w+pJwp9 zKP3ZJE~Vk`g})smcWJ0(I(c(o&hX)-V-99vZatrHEb0mc%0o%X9}eJs+hfJe(B~fM zZFs_a6a6WQ!~LEHzW0kKds0?oKL6UJB{)l9o-zBq$AAP$GEZ9%b?EB#bft^`A+P_u zcZ`8Ket$*g`V%tfJ1eK7pFTyt6F6SBx0Qt032%P|aT2Okrx>DY=x^GwYs1cvAp1UP zIQldC#%+oA+xUGc&AdL&B_srXZ)t8nO@M`chC$&m0*+KPiQsR(JR#OlB+;aYEeMb+7INWR$_|*en28``DJm@FEgvZ%~cNX1cK;5@TBH4oY zx#-dqM`0#dmX+!)_h7<&;5D()K?bZnA}C{en+cv5c2_2~Fk$yZ!&mPpCcJplI?#!F z!s#p~#LK|~|KfuCKe<>CUs!vKw->+P%E&shlLg%StgVa!S+G^!Ng&ss1>rmT&-lD$ zK}>L(x$biov~J~Ss3~PZB2Sx*D)PNj(5}tA2atQ7SX7(sKtDg}L0pL=AZLyBh0Dk> z_2sv+V}B7~wQtR8{hcIOBz~$tv7ZDEX^uvxKVyCc=82hvH?JdeFdAUh0NL(y+} zFRYHrA0fdgrzJfpi-h#-JKNj`k(aFbbN&jU4sn)`#Fd1Q(~s?EQ%MjqE)V#I$6O_c zQX70u@7t0#rW6G~63ZNa&XbTA$KjS=fm~nhwsV6!a;Kb(N}nVRi0x98_~G(7EGZnCb90*2P7C-KMyeP-^Pej(30N%+_&av{GT%;z9cFMd5*+G|)u z!-Vb^^7Y8){@;yIVhEL%`(gZyM{_ zFrO8l@P$DG<6NF}p*kBlgiILfIQOPjISyO`H2ie-GrrJD!giRwq+{F9=`}47j>CKsoj%{O{R<5#M^_$Hy@q^pB?UAgbhQC@m$-uu(9(L4JX9MRJ^dxRL1w6@zFGdlCQIm zy{4g5f97&L)?KjW&vjFL?u~V+)%#0m)Zap$G32mYmjZ3HShzn1ztLGCtb<+Hc1P6t zvalF|&%$i@7dGme64wj**Zwq^yVG$0VL+d*7Usnf$8A?A^pOD%IpJg2C-3T{9hb1- z*W#SztMGH7G(q=5th02~ViSAJqsgCtuD`Z|4HL!!mbI8W9sVhf3Atddbo@kJ#<>XG z+j%Y@IghnsmD0h_6rB5b@ut@;3Ti%GzM)=8!Bz>4UxJP3i+!JySFNQWMm)5p0(rng zE8f1g9s9NNqG~keDu1T+GO17!^nRPgF){boQ>L^NU&?_ z4Kc=ip1oe6#&w2-7v`7m{6(LSIBVbowo~L1#w#>jholYDi^DNpLU zy&2RV_qea5Wr;mQ=LC;fsQ+nXLG-zfk2;ul#vfgY zTTx9wu37)jo?k5Jay|6B(UAoYe5(|DUNAv4Xt?){3KRaa*857LzJE`&`sxzS1ciP4 zHENrg5Mv(WskxU0=~W@E>8F{H8h*v(Ts#wfFKT*~Am&QRDur8`EI49j6&^Ihf}7JO z9;Y#L9MmZ&&=T7#93p-sydyp9!aSO7H=j1;^sL zV6qndWVe28NgE5kTwcLt%TGY)dyC9waRPd|-88(>KTNkuw7oSWAYhkKfc`cD(i3)M zj_xC1?$UmBc~KH}SW%jF!k9a>4jZICCE%H0l6RvY1-`Q@6n&E@@C*9Ux=Eb^bNi;3 zX;|-}uyn;-d*oM0H4w&J>^+$opd03~mK$lmO|ZXx^Vi{y$XKCX%I%c2U#ddEDT|)PHTb>@cr%puv{xnt%enA>53 zeuZ`YU={4LK!ChWjm8cU3L?B6%*v79Do)2BC1t{2dMlkQkN6byGSJSS#Qc&G>;z+g}4XX)}FMM7!EJ@nQ%!{W%zi3{s3cWU2f0t{`i}74A{Nv;=m!5lo_0L#)UNG7fZW2M z!No5usIU;yaX(1FO}=JvI*)+$pClXlv!|xU5X49N(=UeBI*A5LyUP>ULEB~nbVR;hNV(XZ7 zm}4!c{bhv{Q7=|B2b|eTz#vzBh&%Rarm9k~9?moK-++Qm1OdXizsET--}Zz?HRiq{ zVaQC|_0KYVF4O&RH|7j6-`Wb5cGP>9&(^O1^YZVhSdns|ld{5xGYA@KS@S-Vc%S>y<}AFpzdLyD4y&+d3g!>i+ygeo5mV<&#R zs!>8eA3IuV&_RLh)JMPE>i_4?A3J6-S4md-w3YfJU;4jXp0I|5-yP+n!8fq)SD5K; z!kp{Dw|8$Li-7+D009606qt8hP5&RqDr;6&$t;$AuXaW((wEI{yL9y?m3_H`Fzg%{dzrL_v6iV`^Ft;=r;FpyeY5b#t|s zCLUt&w&d z3kuZ-KfHfDlS0@R8-KBl6x{LxQclgG5h3(o*=2tkwXHf&HJ8%Juab|9Bk!9eq90tf zmW7O4?ZlIpG+aMui+$*%QRZD3aIKkvpZVjVKeHI57&}{9Z=%7u*t#eogpBtZ$F;B1 z$g31jUqtgTz5B9k2YD}xKZCFD^YB$;@YE}YhsG@xsBr3IaaA)CKp`a38il9&Jovhv?dp`4=cW zlZ;uB?M}gNTW?krS$D*rknZ(|De&$Xh}N|5FzIQ{$XPWCOOxN<%=pE_+QmK3jjSm+ z8J(Se$B#np(Zc&~M=1DRoRYq+hwP8`ysS-S6leogeRGCFh||{6;B7R_8^l$;YbdPP zty{QfG7ZX|^ZOy$m%w-JRkze>goTD=O(pYFsxnM@N%k#p>zRYH2Waf$(BX3*(%5F7 zI}z(fM=K6ku_E{T;opOZj-T_Ly|xaTYoz+*vtREdHCd#Id~S4IX-3la$I~@hhNF z|A`xmt&5|r%34`05whtUB}d8KIh1Gs3;T`Q(dWhaaPN0ejf!BQxpH-P{&N=6+@jn| zQhf00t&F&ed~`@g=VBHgouN+Jx4*M+AF7BqAlEzHf0t$jrI0)tww~Z?6(1sQsm{#kL!JSm@+A;`QP(4bV{X;=zQT}_7cm*CR`pynpcfvEaIWguSY>Kkq0Uu zOw-A=4d;TnzDkW;%#XA(ezLL+g1*0n?>*td=R?4<9xE$R z`t8bDB@Rkv(neWpIY?eI_+apRD<*m0vX`*uKsKhzPd<->?4~Bi;xG<22)2#dlyG4B zS#0XF`CKdwSIXVDlncEvc7OH^ES)7;^VM5-wYK4~ zasSpehsi$BKFu1EJbXU%JZ5?_4+|NG8qb4C%iVn?>O2^& zQ@?F+fQN%8MDF%<@sM;)Lw%r)hv#QD%X}ev73kEg;pR=@uQwxBL-h6T#hwbM_>0YmOaVftM9eaRl39{4jWk}C^N8=i68o$&Y7+&j0whA-sdZ#$T7HFa;I|rk1DiNI#nh=DN-lViDsYkASC+OMD{8M3ikQU+KX638chFh zl<0t)hQzMC55zyS?pB$rvIsI#QJk`u#qu+=y*_Lq{#0R{pU}-P%2r6lbVfcIt!7r9p~LMSm+P9{qGG4DLy39w3tNwF)qVt!!ek^$$$zornf^GRiJ~RfV zdV72z=T2>QmSnkN2?Hzn=J1WK?RO=^GYVG3k%2 zw)3I0bEV7yUl!grPRnAhvEZf5Up2Is5A(fEYm-ul{|I;QUCD1p;-cbw4U7t++Zq56b`nf4Qym_$j z*W66PkH^K2&QYatB2mgyGnzuw(muT`D{}wg#3>ZfJz9DAd`wl zX*@!zO9D;7z$0_{r_V%h=fAnDl}I>d^nU3b!t1ke(88;o=xeT=sh=Bz3?=<&72>;2 z|9v0CAaTCr5f73YE zbVDgaclxR5ty zAV@gtmbLcBG@`@%nP{ieE-X|^lvn;f&B8in@`~wNEPm^p%DL*u;`7Px)}gs9X6ufe z4z*z+YF4~+XE_VKB^rY*y)4EaZ}@pGnCM);ytSYQ=;fuebb4+dG9kcV8%P ziwEIcl}(m63D2GWojX@GhxEtTMJs>8XMN@(jmf01$7`j6ig*ktxw7C-1`Hmr|9Q@5 zF5x?;pUZ5B|G5@f%=OL6o?N`vo_aT#K6`6(_lNv0X7S#iMo^gbyc*~QKf|RRidi!g%Jvy zRW1Ane#^Kcu968`K*mIpTJAS-Uvl@SI;aWbZSm);qGmnfP|;z5TNlN!?Bo)VHc8^&;F` z-gA18tn*#P@C3n;B`Aka+yX8Wc{g_7~+f>fZ@dSm*>pEAqcT#xa)jYe|k;3@ziJ^pg zk~?Q58F-TKaCqzAfqrEQ;+z>fhej#!yLb<}^;f4bv(h`}4rXaZ?`2 zf2{GTgGo#F|SE9?RA}@s8Q)xtI&oy)=IrzR^j@bv60>zwvIJT03%YU!qTSbX} zsNB|3A^KL|d~}k}J_fh%c{pU{6HaqCRV*hw`IZy)yvB$@>?y}JX+$T_`sNtvEN9SY zC8Rw@`X@x$Al{AWZmIp5?en~7B!9fyeRU?`9`A(4jBujQ9~aURB+u@zf#neKBWt~t z&PjxC|MR<(=1Q)wDVY@ELUiHA5yxhd(q0<+?s^@S z#0MfK)rIZ4P4+jdK&YR*e`)cPoj-kO$PE8AZ0IBXark0X$t4Dh6qkms(P1E7H|@bx z!qG3^{r?xi4|%H+{lsS}zAZEk6?7tU0=U z+g=7?ecHEsTNvE4E-|tDMR+~&O^G#^*0u z4McxF7?eAbeBN1cG$ftq%Km&8wK4L%^qV!?PZ1xukXqQ4L`x%imy zy}HJuH)6>QE(x?bSCSk*?e*1zPaPPTbWUCJmCW})w|PlrlUW?Rw6jrVKLaDX=Z9rX z7}S3?%yA=}|9a}TEk1-}pPPM=lbfJ1lK3Lc{V5q=LhhdjOE_9e>4M8K1|7RKqAiVy z9%eq=#+k~8!Ns;uYeN|PjsCzEIWssMDf4gkTaqiDbKHB0ei$j$R~M%+(3y5;s-iH9 zI*CKUWh9p@)-Se*Cpp>SRlU~#k4k}I`_Gg8@oIj0m&6Rv@CvIAMwlJl8DJ;d>XfU#-AO}r14~i zP1Og&*Sog5d(Qt(>NjU%#`AEZ)7#eE(QIbmt=;4JT%P2IQ^%&<|IA?J!?itfWPYAM z%CDT;N^-)qJ7)~D7&u3xHKTu+kXDRMaRS@6nl~_KVD7n&taK6TP_vWey((lGi?lbq1zCHP8 z=7|RkY9AVzSEkYUc0kkgPd5eEjt^2>NRG(=cP@cT`smhl(_>z}ZSW7O`D;byyJK;m zS!^%`wE^Ml<^?>Qvhj7cBl&fI#hH>i;wPMfrxL-NDWn<8Cq3RnA>r-tm6jV6GKZHe z-Ay<#dZve~;v^b^rukQPYtZNzccfdbXyki#O~@^vF=Lv3W!GiG7Ydiofp7+=EG}w1 zhQ^zN_uMLokA2$_G;xUV-EK##MRD`_*mO&*siu~XnikQF13W%9OmMqit!an(iC#~i zQIbmxJ#Lsi=3|-X&5T!s=hZ5m*$%~aR8}Z2S8!{GzOm_)Ir#VIAADjjU_F(~y)U zjjd&)`fms?i!FO(_K5gqm_hK`fL6kD!=(=Lgf|aM*dFcsN$SiiQKfVpgHf}%1J%+r zntfje4?QF6?fKDp-;lv_1%1y-;zMdXCcg|M`f2`TlkxLqG=e^JPH*7xa8K5~;I#qa z;^Fy!I?4VPy}3WL^g9nb9vL++XyqZ!Nwn`G+5hpae#&$l58i|Hs(>aQ#sy~>Q~o?u zt43OdU2H?z+n{GB$J-ED=<(j%uMHD_-`!8o;=*2StoQfeDy} zKN9{X9rNVizlo9WayA@yK&HDu~tu5nuEyJiYGTtllwkST4+4LfvrbNOkWrWqXFIH8-`j@dsD?$d?Ody z@~g8CEN;X5z<~9CFLUw7nNrvl#08U+od0)f8#08w^8&oNh&dOepLv!Gi}+D{{VFb| z?_eyB`*X2>`*QE4C0uB|HLo`N(uONa+z_D*4mJu$R$H#+A}X;@eUUR4aOQa}H|D~8 z$9K)&q2xVwsi|9hxzLxKY^C7A#ZT#@vJ29=5Ygk=)sXRbUb#MtUfYIU-FKn{SGOT- zV@>kx)Hd|#PdcdCN%r#$8=OeDp)x{?@iyS$MStD`Wm_H$H)e5tck`gLSx2g?ng^$6 z1ta-4csTj=)~_`=Jj5^Cb1Gel!nt>O4va8`8Tm7G#Q*YeG1vcel|2QmtwAyawiF!7 z{JAoOD>$)n_d3ietWfgyD=>MEr49ZSv~xaTEgT zi-)e%kv`UGUnb>Axa{1LLxEisX69XMRuQ8y+aPpcf}s#AUmzt+>iAw%bIdA|BcAD1 z-R(%Fu$oRk`@NmUj;_4Q$0YYS^k%-?-%8fE;zZN_gEag+(qnYi6TK9R@|Gt)99!xp z(`-Xysr=9Drz99O%>UdgL-N?Bg{ycPJ4jA)IwL!qCH>`7V%wZW!{m)>@(~3Z*?uDK zUy}*HOx+f_T$9`{pJL!e{JRqZ#U&4D1drZ0eEv8MNhj;EbA)q88orAge;_e7 zqvp5}ZqnlI%_ja3GwX3ThxlZ;T2H~eKQsh3zP~J2MslIWLHs>S7P^I1<3?pHo>d#j{}txr-L(+k|Nn2%n$+;oyO>2|NP&UQ z|F1hv%-JHsM`*%-tJP=n5tG3Fs9wj%nedf|V9Up|>>QcGU3^IVtPssS&WA_&$bNNu zK4eEkv%6jSu#9NnsRZ#MFm-{TA(xLR=Sh0~MSSGuq)$3LKz<)s>oA4*gJw-_xBH@Y z)JUPy#g32ct$J7YZsWtMS>V*+8a_e{E2g-R@vK94TNKx`nBF#d{(`f_PwrN}JEF(O zXjGDG#zz+1?$WO--?6yMIJga^v*=Cfq_2@<6MwU{2H~k|rwVI*d>L%Z46mX|ZhRzh zXm-VB20XF9(oS<2$fp`=RT0iN`B8LYLmZ7%PFeT{ZKC_O&F_!he;9uV~!^CeKNGZoZpPt-`sYP-XeXClK*dQc)y0#hXi({@fjl4p5 zrGSVZ|0O&$XLT&lY{0L9l90)F>+tAHy!Ob=7uaGiw*GC<3tS%wwd+)W2H%*Idnt>@ znAdtlUCHbb%nmOvekb`5{?CngCNs;ReC#zh&-)%0`^CqV*%V;bToLmFW4Dkj{USDx zmkrydIKh&PEO-_RdG%e-gh)!;8kvMl#5giNmLD_G^RVjRWRFa==KN}3XL}xMbF6>K z>xROm{?%DdRuI<4=__}94#M8Qk8I`%p2j!z5$%ABez5ZwS*ShWi&;l&Z~R;CgMrA_ z7x(PFF(7i(wM^d&x`umhjD=@GdUu5V`SUlSvuHuYzm}U=+IdCu@tSN5aSm9UUdYCY zNRZ&-)AWRB)(XsXX zu6eop)n5kTOs`;y^qdqZUt5y#RXGiTH+@Fu7^jikTp_e^R~kfS#zwM+X;7TCLoQ$+ zIhS{~=&?vcM6Y1;dS`My`qsNt_cWY&@zuQkd>TrzTP;E9JT?qeyZZ%%V7=jpg!-)z z=q*|O+wNEhPW?;WFs2=XRW<*ns%3{DXIaPAn9>l0?HK(sB{BpJv%kbo`yPTj8&=(F zZ3#i@$>OsL$8O)<)b71W11$NkHvdp?RMPB2R7SD{mIRThb?!9 zR0X-OXJKAbN&G@#x(GTjXGX}01`N3aQ z@}J>KYur>DXj5$32cOMKa|WlIW8iJ>F)vMXI6l*8S+(8@vo1E-&DGwAnD6O7K5n$Y z(LsUL&Fd|(alp6v{Jnh;(4Kx@ZH7*@z=zM7yJB}$3urI9rR$_$E#R28wnvwo3s^V( zjoDHCKL7v#|Nl%`c|28J7v3aPQYeHBO%&oS)s1v+N`{2eKvXv+g(Oib!%;%WOkP9D zoG2k7IakprsVIq3QBssSx1 zp6Zr{4B?I~nlHYbA#_!OdkFY+W6f2gWeg!jZXVr6_}-vkCl1;+W^{eSU*GvV2Bp)% zr)O_g)Pf#bauRnZ*1Wr8-ygs}{_9l3Xz)|xl)Z|eKlSCZ4QE+Bl^xwJpnO%!bBQe9 z#a1u```VVJ<~D$@JV~wKm*HRX7pL|mLZ9-$q(bT8ieX|dLz+_zS@DNwTRkfsv+p!|n_G#<8#H*}x>`+aC1FT;4BCDy5P zYg9v6{Tm+33L6dYQ*MiD{Iz^oKkeZW8ErJYCPKYSYC)Ah+Uqv3aelD(YlF$KUwF$+ zB*fYH9JP>YW$*oS_R0|UJl^ZzME0J?&i=l}%BQ{$*$FxRP<;N#x9zDK)A83i{2{-l z=8txcX6@fC9<+e9FEP+xoaGPYsq&Ct|HO^#SDnbkcXDmXlWVL!mJ_E{v-%%ME>2vE zeR*4iY)ppZ*7mRW*2HChoj>H4wr2I(G|2N>DbY|ftSyUOjxB+{5kr1h9Hq;J9x~x- zR@$=R`~Jy;|JTixr}uWSc{H)MTAH^($QY8J71bR;=k>o0%NwzMDhSDg`a z`%}`aJwtvZL;n90PkQP1rAek(2mLr8&Fba85-Gwx>7KHOiLC#>J=l`Y+8Hj=mCK%2 zvvy)0?!y<|l$Ec;5I4bdq578i9$2+hlEVIN>FO2i{}IB&T_-^s)O{QReGcnJ>&c&r^m@#dOl4t!zdv~GWHH6N}^Zoa#Z z)k4_i>3dEXatS8E?;E`UD8s!9u?VZ0><=B-;+LN586h30C8ly)9^ zR?dUHLvr*kKku$wXVPDi~Tia_JvsIh8Z$zBA|bBWu;?0Lo_2qf)xIR-b3EL!AT7HH|qYp zu0)1J`yNWoI?0fv^mTK_r7?74tl_3;P=m*%n?__ZWX!wzLpGTVy{kT|B0Y_4<)-#61Z`aJfH=D?~84E-fj z=E*ehnYZ@I<>0#n6;JzG!0?4rqF!vmdizqt_;Upex2mBd+XvK$nW zZ*6UsYEr-ui!=Ij!*NdU*e+wgv+!57j;9~&bT8%UiG#i>oE{XB#t=mV4Rh60hNz@W zGR;24kcXXb>G25+S*mvCiyHj4^20d!niC93oTa}cA(kOeOM`qn;NMBR4|J--pZ3b{ zlwz=MVeS#LOc?DS)u2fjqln!~hs(dcDd34; zd9x2iG)~@C@e86z#`QV(4jrRN<-GzO=P-(tD8KR03Z#f>`MWc-l>J_@{CdH8(|qKF!TK5={x*c5xic2LF2cfpn)>icDUe&ykOz$kF#d z$JE4A(5x*l0<4^6h+RG+v#T^A0Ja6D+a2ZFJbd7gd&LxN3{IJy*O!m6KSj? z)jEWey+G?7N)2fExzsfL;y#M}cs1dC-xl~Grq+0tCE_93q_}G~^aPb%qFs=89Wy12 zfg}7pzKxF+`ZrTTfq;2ho7i3_LsBi~&Xr3$MvMAWPKw;b$gJ2={-HJl-1g{VVKsIN|!l<&_` ze{nKD9_L}rO;O#S6vGe$rMr*pQOBR0^Jj{p?oEPven_G29pvuD3?wt;^d0^BE%BS0|-*p5a?+cC3^vVCa}0K>_zXhE@no zjpF1pbomy><2UfnRJTOP@gl>Gh_MrRUd-_K+|V!l2D)(2USU=d{8l;rL^1HvO>xc~ zmqNsMsaIbPzRSf-aQ3+fKW=L1dsWPElh-E85zy{m7|wy`v+$xA7c9^8(}-2*U1JKkuv01kU@GKAK*D{_xh; zWuOcFWB2#tp}DyCkB~3RIPk+<)hn}}!e38sH47_(uG+C{e?Rb6zAm3%nZl6Sr|WwN z{C@21yU6Xp!|^G{rM-ZsdFQ8StU*5U5Bcdn^I!(4E7OXmm{X*9`k>+$;K<}1)da+-7XN6Pb{>Zs`PVp4&n4L3I=>$ba*c#lN zb%LV1+a+GEMjgvFmtTkhU6Z7o^lt=3zD4~ju|0~Sv*)gxd_S5Z0=8jm4U;Ky&LX(J z8TEZPOsUlz^qu2X&tmNF2s|F}CX}LUp089^fn2-0#^q7auUtNJ0tFlh{IFAv1N^Da zZf=_doD%FBG}{6^UMoN}rvy=hhZE=4SyJN29DCs3@2Zz%F7Tt`VeizEgA{QQnoK1*0Ee}v=^6u%?aX{g8|v87_@dTq z)Q{WSxpx$>ZsF)&;~ry3I8V$_8vSL_yB|*4;G3<95AQ@Bs%cdh$+CUp-f8iS*@(l0 zDVh&Z=V3DYJgQKC$(x1yChtXDXJ)1)Lht;+rOFdR8B$lS|MVH+HBG_tct84Fp^MFq z*lHwBZ7KsqCC#u0=-o2+%f|F@}qy`qe{qo-1Qd;!(7uT z6WqEU^?bWochm1c=zmJOm7s4?(ylAL(7$-ciINMj|A&j9e?08aslAldgLOmeD1|`O zcb|!$fh_c%O1yWLhw}>y`d;5fUzHtm0A4_$zx{Ur@IqN|opu56?&`(+4=;mXyzrSE zA9>a@OO2GUbJx13MdmxxXH%^h&x_q@~r%pJGo59dgtPkBAF z^ZN&Vx9j-1jgqK8POoNsA?8@#e3`EUn7_F@cy+Cqd&dXb?=MDwsQ7fOIpz@h#JssN zLNxGt?dp}+;crpREA}f8r?8auPyaza2>AC`*#HORKD1oAjkQ_p@}f56%~6Xpw-*C{ z&6Y*U$pV*8&6^Tl4Su)zhS^S_slHpIT`|W+6(ld4jPF|;75e<3N7QM#!5zrWu*tL7 z4Sk#gx;>ktk^cc-I?h9`_sP?<-|;>7_JtH7;8C_vxJ*9e>yHi2OThfhAA8~2OyJXr zYQb;G_#S7)+ns>#V_%wl&4oT^9s6HSSm(C)?zY8T*_u{1U17B4+`VpI34tnyUQsQUOFNsbc(O*cTyJgch%|( z!O&AP*2~@z{AQ_rexayO{+3mnOe|0j>xJUxp`H>R*s82q3H;3%;qi4X=DL24^KVnO zZsuPRpcny}qa(-ea-{}EOeSwwYlk_=(@^^Tdc@VjUm)=xip&W;WF?9DC{|Ehau*MC zPJ83~t;Q57I=5KN#+{-++tu5&Vg3>5<-M}UzVv z>NQv{dd+FzMSa^f$!NSI-QEc{J5VP z{E$+nbZ{X>J`Ut8oQ!$iF`*|Jow@@Rz z=0h*vr|Pya&QZ>IWXXq~cEi)34N<2=zkk6q)al{WM28U6r%u1rMitkGQ%5=eJp}+5L!%_r~{}cM@28 z|8fmnvI}wiOvh>?4|d$^3`hfCyY;&FJrnfDla8&3f9n66ezKZ>BsN>R$+tn~P z(a&~Bb+P&c+^o_@on+`6O*vMdu}(-7*Yd?Xn<{;vcpCfST@{vogMP8?o;%g>eL;S- ztY8-2`>Id2UW6TD+Wyjya9&EUenvIsvhE|tqylm7o8rkKDd2a>aJG74|E1LMgFkV8 zl}V_*9`t^BWje_V{GIL5=bwPDY_mLU5a;?Rnm*VCdw;DmrM!Vp=l2$8r-FtwK989T zz5B1;3Y?4m#Bg!UI^f;Rc}ICG;0IO1bu}u$JIA|QrkVpkBBY&jR|0Rk(rFJ<_}|R+ zb%hXU_s7%gp8;3*y&Si(82DjTb0t@Tibr}w;t-bW1WuAYKqWzt*Q&cyyn=0{d-Lf<_( z+TRWDHL{2a45jeSR?1Q_L|xR2h^kuyABD4B@n&Se-?=Z(Wgfsf(5==d7IT}rjDN>w#AWfp%a27-SMF2#<|narro5sm zI|zAe@lIG1c6cq095oOAtxr5CHj{nVCY2Wb0&a1iR$i=yUz_fgYujUfYBLXZciN0O z|k$YO&TZKpZz^k;=K?Xm-MWZ zNow$~$b`5A#IOFOn~?+NBTiq33yruZ=v9{Nh9A7T$1Pe1KjpY6aKAX?{F?6XhR{o_ z8`jEdL(hZHOU5a{4)G(QcIX$pO>>31+26+v+AXI+UfDU%HWcyr@!^=-TgVwtb{Cns z8#rA!!_@~kr`!^uHv@C~K%X47+M6O-JkPlF!<4|ZX`0i8@a}I{Y%&t?r-=DKS2~%a z6iNKL_n0K!FQS>ndP#T()QL>`nRb>= zUpr@KFy0wmmzz#mLk~Uf0>?cFef5lU+ZRwbeZH>(=+75*>)GEO$|Z~g46$!@&*st9 zpu(c#Qc6I-2{rU>#kqN0FUbJBSL$>NxdV7d2`-Y6eT8*$y+K`F@| z5edB4K0b_eIpjeN-t(4wnBj{2*FRdbf&HE7$Tja}sK?a%GuxSU6uG&`u-ppzt#xY> zQX$8EZ#G5_eLc2I$WETsll&?67~WIb*VkEjc~C^{las*XZLnkW4<%u?z8rl{`m(>9 zSw)Ork3OiZK^-}Zd?<)~lRRew@Ip-9LpCLZp|L#U*v4{xH=YJZu~NBMt+YMT~a55IlEJMK|wn5s$uW;yhav> zPU!#qjlQJQdF4hcXr60 zFbwtv8_?rcL0?Ro>!VTQar=BVj`?|CK7#l64*was@1>YaxF zhjV-Pwe1A#+VocT9*wzWc7W=XXuRLVwVaz4qkcz~oQ~JWd@K=us^C6wSUkJ;KtJY1 zm+MVcqM-javY7%%T>9bLgLC@(qPz;AdrXrR%Y-B`VVd z*txb#vVSf5%781!yB>X0E$N5YDD<$*bYsqK0=WJJ8 zbu41|{3Tx7szGC0Z>^UrL_eXd296Xn{BBF49$v)I$x=@R@(USSw0EEUD9~eBFFuVe zWVrDc!@OIuU)wv>cpvt?IAqb5QP)O*U@ZEb}NUnT8%X%FPi_labT0^e6e zYKsci-$hjS*`9}eEjKRyJj)QJ1>ejz=QFg-)MmAxu$wm`XN4;IX{OwqeNS-zG3&Bs zZAITS`(ZZ027SBOYtPor@S9YVUCH58*fl=p=34l9#QH3yUFe^?^VKOA#9`aF6(2*{ z`TL6F>LT_vRoSQRnv%UNAJH_J^IV65-RcZu9 z7xi-tJ%Agb>qAZ7qE2_a2|B9=P(;zOqk_c`;;I@c0G!g~Z1AiCK8$wQ5;!l4qBHju z_18vI^y-I<%Vp3D?tSaW#ZV;sXWR(+P>Mv*jiq|fd*@YafEw`POjq^EWjJ@wD5)#< zG(|R@|MXA$aq52n00960M0t5UmRr>JHWcL;qckHSN~Tcceq_iLLWYhc5ednx43AkE zGKDBZNl1vOG~7>`D3ueHqC80@hp2>NJ5jDVnIaD2L%juQ6!E>cD4{luVxHt(lRl9} z5m&jp{x6d#;w4#s(ISQ-;!87?b$lqYX)5M{T0F(H8J2O|oI#N@%p2$4Fe$>nw3Zgf zd_P^oNQnfB1Z3Zg4#E2FRtr?W9ihn3k#Lc{Q53l~H|lgx1VyH&eoovBrATY0bl~D( zibSmIzkGKeMJkj!lXCY^WNIXs+uVmH;~%p2Jol%GhN}R7cMwf}KZp}$#?xf&E1n*Q zWSW#Eb{^P>aqB>(x@2#f7}|HQ5RIZqYohJf6nC0bRMqd=3EAtBW+oU;6BXv9OK~tw z*qc{M)E%IS_*=m*TSa z4Mvdu7t){m(xh9(_V4jfnuxq%vd+LxmwoPSbHqCH?I+5Nm^2wH`KN$jyz5+TLQ^zN z>c`hH4WQTbeLj(J=v~!uEM6vwCURM3qQS>#!pvGD(*(P#2(q0F+#vNuG}9b$j_q%! znE^DBadYR zs`kK%CK+v!K54M`SVNG_slE74NpSlOGf1xO(i89>yR?uAZupJVoY=1TtrTI28T%PH z(!nXtHcjuy%rv|QES|bsDN`d?Dvg?e>n!FaA+Ri>rlMhLiha0fIeagAhz8H_#I3Sq} z9Bf(0PBlD9Gkf1(n<+1$$%zow!=NIXj6U$4Nyw*3oJM7eG$eaO;Fl!U5nV8Q%L4P} ze^(5-iS}FpF>mdYG|U`0%bJw z!-`O?5=izX%XW#g@PqJUr=OS7q|qo|$Or4ZUQu#LrI2RY251$1!8+cRCq_yoZ4(1l%umQ*pZ0`TSogc3@2LJ6nmKjM>Q5E) zy=7wC{vGy_yQkJ%-s5Qs(NiH1_}n?qwXd1U@rM^P>A;OhzEWR4{6(Qf{m0xxu=8w?Lksp9oa6dq z4S18yci4Ime%5QF)z}7Hbnw(iYXblLJM-=RAsO@~_XvCVQ^Q8{D)`wcJ%dlZkbWaU z&7Rn2kXE_th5eVMoLDY_{epT#dN%?eSM~1rtOt$_HH`F4wBYw17fn^R0T+HRt<@>; zquuQ1CGhL6I4#j?oP&tW;f-Mc*Z<4IvwwGf7s}p5G0VD4oZfg)vw7JnC0h?uB%ixt zPYZC!(&IT0jCEAT?0dAq6CD~GCMv9HuDSE5&~kI?|Leovy0To_0e(B|QQNeiBA3P1 zmNCFv6&W?cH}M^lG32&U1$L4YQ~v^clnK`Q--CU|OnP(kVXyoxOyTX|e}($$<>ufO zR?@BeoBU`ZE5TqZfEV5QO+CGFUa6t0yVu}6V~j&14_t7b>e08Y_%6bFUhP{~#L4G! zhhsUsz$!8dn9?K7?={PcEODL@VO@K~9p<{h&jY}{!j13cCt-J~x_F1xb~x8oi#Gec z6d@K5qyCnpiI?FoX*2NIUEPBw=B5;}d#CED0X@5~6d0M~UNW3=C+8_sWLIM(HD^0T zzF9CXN`rU0-#uQv2m0xX6*M})uM#Kyq+P)O_0Qfg&LST4*Jx~Q25)Gpy}Or*{s@ml zqUx}p|H3nt343TVq;U9H3&vaToPBi=e!^0-{7&J1D-Dxh*uvi0jD|->u*X!|r=cX= zCo@;|>qSl2Z{LCOFjb0__w{}HintKqr8ye{DdkoE^AY^{kK!NJEO05Pof)?hc(HJi za8yS7M!lDi7I5WA+w7J{``++b*(Z54b62AKmkYq%Uzc6DM$2j9Tyd6bybSSd@LTCq zw2d@P#`uBjVc~A$Ch$V$(lCiw;P_eo67^{G^F0=bPpPDtdbe%k#xKy!VE4Z_w^Yzf zS4vv=0LGOhzxD11e+(^M;of`(IKCqxTXvo%@tPKsiz>mJhoihB(B6<<-CcZ+X3A>6 zRab>9ZJlT4Q$;fmXwKQc2kUL0HeBQhsZH5>H(#KM%cE;g8=;?2HbYYf>(sn)=)Vd6 zGJos4yaW30kUmw+2CqDr{m9JVv&bIpP3O`Y8)1iww_=|(K%e_9c4fMdljE7Y zrVEi*JRLCb0N-5yw&T%BwEq#KR?UEyudOP%oSTDv6J6S^!LLiQh7P*Ij>UuIf(j(} zS+1ZyEeDF9?3ekz*)Ce%*hh?x5aU~pTa!W zNAW#nh*L~Ol|3?ugM;Gtb`9t~%YQhI?2sIjJlP-1VP2(Dxj9%PF^% zH7UR~(=@T*kOFYWQ*E};59fbZV^N0l)$y*1cHIRYn_};}4_pr~SeZ8JPm!y!UpwMG zac;@F9oxWn_iqJFe~70DJ}(4cSU2s^T)&&<8jIMbG!1)^ zxV;nNJHTI#cY2qDk9GfxFS2!)mu%+bM^UDqFMt>V#oY)t#$x4*wXvbJZynsS4Y3h?Pl^nf-Z6 z)2Ks?zn;limPe6BM!HpaUZv~J(gY!T#lOO zx%g4D4lz+~aaf0KGLpL)^-;&t_6_S`x18J5$FJxQbBDv_{8 zyEEW!8*ngKXy=)Ld+DNh!ZbN?WBX$6K=f-H6^FNh=QBKXWJ?eit+O(Cd=NKT_8*7i zps#{f#>zItzf`@rvIgM6CH9G@Dg4x5x_ZVNc_>q8vmXQZ%S`<+*=UIU{F(7%OTZIe z6Z$3C&rTuQ+=7z_zZFRz0Pe-@M@>|bhZ?F_T5RIvDIIL(9{6R(ZsVqLtlu*KwCft+ zL^rpty%_WCoOW470e?e3Mnq0y-+=${=lt^IcoT5rEn~&+102mHov@nBrOB?>x8j7s zXQ>bPv@+3u+hoZBRY>>TawTET5ZQ z`~GR9nG0SD3d>xk8T%zXsz)!;%r(|Qfg-iY%eg*R_SDi0Zdd)irS&u;DDw85Lk%=@ zbncqC+{=jDE?qz0U#3~&+?#xo8)(v#CF1Ufb-5oc6uSVqyor4Q`!HDY<8n2ZXkv3d zr~d_H#6HiN9q6A}J7DCA{WO*yF5<1D$%MaTUoT`v@7um57in_GU1jhC;+^%nwPv%3 zpZ>hoRgH*q9UD_h!_U!VVZ6gtO`Q8zh^0U<>{Gl!p>8GOUeMKrHQyokiCy7!ET&2J z-%E`i!p^@o*1XZj{dT9^difsrs336dBoFwNUDdC&2z+JoE4x1sc_O=}aK;Sz&vE{r zwOyeUF<-qdP$Pumigp~fvWuXYFYZk{KZv79bCu%@W(-AUt>RaQ22xy0kEAHIMN&+m z&qZ4&5-B1t-g<5d<3%4F^Q1AKyXll<3)Yje-+Wr;7{$^omZ=6TBth^z>V|$chah?BEc_ovYC8Z7XmCQ zipc_BPfgJrDe`uOXyqO7*V%&yDFVG$sK3!Sj-!}{XBYOq!uJOcwf-~#k3MNp zDyG0gr}^@$_JbeOo^~I559$B#L#Y$^YvA6{G+boCvKY_2>%OUx%F4A;`ea1GfJ!}vC`E5)))`RzYN2vJ= zU_U!{*~aJK%T%9_TW>`C-?>Pl<9UCa(|LX``!?))H!44YiTS5gwfxP{KW^rAxd%LI z%$xkJ9sI`VIg}j)zRMRh`y_<+{LpJniICz(GlloDuJz5&vWdtK*vWtX(T5(@HRgw2 zLqC=O-qV<7Q_Ig{{$1zGN*6G0a-%$6pHqikxcu@3>dlVu!j}$+Bl)j`YMrep()w=N zB-ajc@HF?EFwXnRW#f5VxL+ncvG1i8?7TiSlf}s^_C0N0GN?zUWL-QRP>(tCw5yMD z>Rg|u@L5hCxB0SJIlePl`tbe^tgm9&ddmv_!B#b7`{UkOQfGcJEWt1AT^6U2$GC1u z^&3VW<5iTuFW~_4hI;o|KKOHnx#sbU1{Bwpd6!OUA|L6FoNUqa<@lAtprRg4e1(-Y_^KYe8+pB#WlD??;)-~0qD&Ha zv1&`1Z0c#6X%*=l=mH+C64DS8~5mbGnRl_2<-TJd|cVd?+9YqY#(zcs{ssUy*m!oYZ#GwC`-50ZjG2XTR>S`D0 zryNq2SpfM~-auIc^Uijt%-N51SJqE1u16hJ#&9^c5B1ryJewRo)PLKhq>5hQ965ZU zG8SkHv}JmUVxRDdwb!4a&U*9mrteM6@8dR#&qcra_mcQ;C8+CECPckUIqx-7VlmL) zuKRijFWOi78Y^@VxAXF)HGQGK#?;Q`&B!BEDkm#vIC;a*{+C;TpSKJC(f-59H>5?a z+i-8`FXcsL!6)Lry+s+>9A5DZ561UuR|{j0VxHH!`mfdS>!|vEThAp2 ze!vfyPd|*h13&rCH@3hz5pXKq#W5}oTukVbk+QZ?^??Y#huNgY3X_W(a z)?Y20R>PkR6BOqV;7Mecy|}GC>N(khlSiZ|Qc7=AU$T}O{Fh#Q{A?g4!n;O_=d&xt znv?NjmG(|bN>3RU=dV1hu z_nTgB@Ougs!;QTXp2)b7Z|^cAQZQg4R^dg2^p*P4%E`rzG-{lhw( z^Jwgd2!XxpqP$wXQ0I7^%eLqRFLmwPxxoN-yZhsA zhN%FYoSNP3^ab`_F>z$wd`{gN8M=9x!>4<7A`4L8DGWTmeH*;OnojS$=85m3Un~@W zeWm;Zmr29^*4;jXPT-dum+(io!ZS*&9^nPvwZ)kU(lfMhSm^Izj^YGo6-9IN@W4uIms>BWBY(GWaMSr6%8KGurftB#zSUGh^WO(M<8*u_eqJni(k{Q(2Dux2^x& zwQbcjGl}0v&z{t&cSWl^>vGoD^4ZMVU{=z=?i{G`?V7^t>E6+mY@%oWLF}dIuz3s6lgush= zz5~@Ykc0bFCQ@O~^WW~)wxVvhQZPq|Mw`lwxOooqolZ2YmjXYgrFtko0PnDrb%H7& zuT{qnCS(4Sj}}@Sei>yadW@idsb^3^ALbA9KghX>IAJ_97?Fl?*T6fOImkP>lU8VE zao+c6xp7(4F&h4I)2+arWK6AnIsCgo=)n53;G_I&pVwRC{#l(tddA?PfrRkVF60MO zaaLjTIXu?4jko3i{Of=JbIi_ukzU-b#Ce~2GUdewzDhN&9W$c{qvc`kirw(r2l8#M za*#GjNx|#k-#LF0ZW&W#EN}D@!#>>sH>lIT^mF z`*-blzZG??|7c(Nm)(fBpC7!g4#fJ8-t~wWAzmNtmj3C+d2jf1O9H%6;+W$W3jZ%T zdC%C+k|HIwA9${VH<|Yu3ww}9_=gon#ljvIa9R!ExLaM)R2%1x7*~%HfWLpb6FIq` z^B*nzmvJrfvW!D}k7$8^dUCA2j-%gUnbG-74!^gD$=QSVBiI287Q>#6GSNQV7`Ks} zeOiWf>ni-aU)XZqN4`9N4xDAM{x#xdg96*ReVdT&lc zIL*cXPeLjKcs@1!+ht8OHTy}=-rfoAv7%M01;IacEB_>gq7JVpF=waQQl#LOSZ!Sx zMGOUYiz#|xUX|FWGVC@syY$f-*qPa#*E=o(JFDNFhyp)m_&gPx3_#xV`0-S?BSo~o zd2_vV2XFL=`()#Lm7o9S{(}8FW^act0nZHj%}Dlx*Ib335{Y;9FI?6ZK4Sa4*9aZSBo3D|C}7 zA}2a{T@v$D4$;qf@txN%{&#OsKPjAjx{dR`W3r`a|1;EGbMKX8xuNcvQhIb@1L~ux zqj9mfu}(?m7T-wpJ3ck@3yG(Q%*`a;ov456&v%|%fO?K4_u`c={7Yr=;!DvH$WtS3 z)SXAWE5Xf27Hh%$0RR6)S$Q~C zU$ovzQYk7VBqc+kOeKZ$MP(|PDntoIlF%Si9TE{T&t#sbOqJA;q$Fi1jU+=!C6y4$ zeLeU0-22yh_C9M*Yk1eYzK_JMYXjnl2PcZRHe|U@@dDca9*TDbl_F{<{?zm)e*K=Io=$In{Ru zR~@0q_}+9OrK8j|^GuuH%@O-DZr4+tD7LW9Y2HB#ii92e%gEbOq$M*{ZM7#uOw!qR zNe3|G-O_-9UYa3XkGqq%dox6T+2OO_LK$*fCgfj5I713p)=@T53|aAhf$>N*Lr(8k zl&HWuqxXAyc1AE{&YClas$&@PU1+V-jWC8(KXrGi!hHYY`K5)JA3V8&Re*K%y^g!1 zA;%2;vTQN0SKi&1n2dM*s=4zdgCPr!pMSL^lOeO;S$#6kV#q@KlMz}u4B3A}<7X$v zRu?CRPUJFVFJCJ6SRO-19LwW1%4g`bPJi{h0*0Q~c4O(!LWcg;86!<%qnGQmw)p=wwE%s7q{EI?}C(6xq0E$b*7en|Kd_#8ADUa=D(84nc5wP*bjPC zF!b1UHH83-J#Sc6c9b!-w*1*Q#mgDiu^w;t{m>89^?Eg{jA5yS4jxQ_p5#Y;t&RA; z@?Owvx{M)eA$dmjkS6O7?^%xZqK}26q@mAuU9(~?^nOJCy3u@{A&IGPIowMalC$%I z&~w~dp>WQZbjb4gFDEk#7-IQtyyq|8om$3YB9+6?S|3*BOTkX+G-Z*V#*hbZC)v*@ zAg&~XY6c@2qPxm-*FMk9 z+8?KA-Pn(FZG5TJ(@)&oTC*rtjIcR(a3sa5;#cttkEV#t`YmZ;F;wkZ{a;a*kyP!^ z3ulHGMNs7HnSBcEaTF`>ps$B=1VzV~wzoZlbma8EI@=%nSCL?&Sc=Ufx#iE}WQz9I zqPn(X-Jg4Bh3tbVBAl<0=oCOrzZfvTnGr;h-ffa@m#$LN8NL}_k--#embsV8yfBJn zs^ytXU82aK$>$%DJ{0kD7t*qFrD&hdN%sanihg=Ry?WIZYWhz7n7f%5MWW~I7#g@p z(XIm{KZ<=Rdg@*eQS_xqOa|K=k#iIY)#GBTa>Y5LGUa6s6ft0XAaA3Ie6v}g?ybrY zUk}x*BWE!d^Hd(+L6PC+a|K-n45=+%+sr3V5!36Z3u0Uu;#XiSnsk~WwAYQo2oHwD z`HO~zTQP(+Tvt2$2t!1t4K78WfFD<}7ET^!2+#A*_;VQ3@tMBW`x!R-(dv-ZyOGy| zI}~)>8DiiedYJKINalvl{gvk#;=o>`uY4T3=#02Iwywx#tqvAS0TH{1{SmNW{tuIP#BbHS|Cna&on2ho8c`mksR|1`bVRp3uCD`#)u!VLO&N;z#{Q?a5=fufv;?CTsX#@?3MZ8E|-H zvDPuXgP!GjEC}}uQ)wta?97noRtr zC5L#s#bMTfxD=L)R&lkXNL2bd-OO_o{g7{3>KgLczqR2`kt;{k&@Z8( zM{j4d=GJG(%}u924#6HI{cK&L8pS5u==e|Bj3QiHCmdWYsp(G%PDLSlxc|yv>rXZm zDRsGg>aj8WtbW&C@F4D$Hk#YH3wHF4(RV;x+jn$se2x94%3bapguM^m7+W_#=>Pqc zEq3eS2>d(8y|DEs;xz2Imd#Sc<4}33erE{oac1w+BE-SwL=o+cu?*=xkZs+Lx^&mK z|E3T0*XQKD5Wzk@UsJ^$urBrj=hHdy3<=LUa-t7!t3H2+vB);9-cdWk17 zL@2yb@(I2Nr>t-=29D}4aXy=tg7t2(mxfTE42M6yP>25D>au53*!Sivmpefz4BgFb zZNZz4`Y0v(=}aQ>t8aNa3+v7-`fHVNjUn>}OB5fZqVBlGq;;e+#a_!&L3;Ce*)eZ;mz+oG*5&KBpS%Z`n4jO#;4qUDn7<$M~7_*Q|Ja zm*zOnl^o5`YwaB)d(#>EnN+XO+FXV{<}OgJfqly9fSd0UJv^FtjSc(A zjRpE8LMm$rh#iOCR6wGO5ym$fjLL7p4yM-pLFuqpjLAFaYmlq7+-B9{UAabrE#F~> zwx{!h0&ss1?tU#t*kiJJCK&!ywb7HsJ_beByB{N; zUcFh+d;xJzs+T-1a6mq!S(sfmX4q<{Zu-@1r3eW=(lw@tcxYRqo}dZ+sqYedu^*8; zek1V9UBWslFfV#9#tVh`jh8{MN_H7H;<9#;fqEhEH1p==b^XBOaYlH9za8#Fj<&|n z#H)?DUYR4-u}&}sPt~Wt>tA+tKt7W?+s|wFBhL3}W!{A(Pa-xiTL|1T`ckBDn3=xz zWi@;A0q7kbV~gI%5a*~?>p;|rFt=Y<-tWWsyMU4{#x1<&*ZlFGsWO8zkAZucO|EY& z@!m)D&dF226D#k7nIph~;R9Z`MsdHmjHiWl4ropM+2T+)$oTLUFu?I0z5gn#g7Ag zH#IhTZ?F;8OO-6LJw_3$Fd>OZJ?N#e|C<0_-t@e%r3>#F2wZUK*HOGjW_!dD*t_cZ zP(&ASCf8*8v!FeA_^4c<<2v~3yoBtxx$wVHb$tcwC3ipNais?{eSzysYBL3U#yhi5 z!@fKrYg(dDB0iQaT%$C@m&S}d4{xD}hqi8R3GB8#*pK>#I@f0|vVtFYvvW%`AC0^% zu#L~Z1-bR&w}xxrzkj@C*xQgtRf#^_4Vd3)W3g5b__F7d=JKt`_eRb0v;G2KGPf2? zOe4=toU9w!khdE8&(|%^Wa#wScg~06dtqFf_($a7`k}F3-;wtz3sxlV2Cl4K;GyRZ z-uSz;=+p%GWWmJXk!#@1v*KE#T!9xct#sZ1^t3yF2sL8=ksYDR9oY<#?=TO!3jMiN zUB7go*HOPh?-2O6tkd_-`_Nb6RL!f)X9%^8t-A>FpW-F0V(91HbxA(}KK{@zV(p$H z^b?DM!*X$+n3sk5y*%Ke%7*R(kfoDuk^k_HE%{wn@^GI2T)hYN*kAY8j;0HkPiPbk zS)0Mo2?_OSHh7<^X{p)=yifDDo6=d>?Tue!SUc<%;b>ow1Nq>z9ghs~TYpF=I0JQ{ zjBJp#2F|pMSNDH}oLy5q>Iu81FR2=m2QGE|(OS9_dP&WDK0E^s<$myz4}rfd2D>cN zAscdv`(7bF{H5=$&4T~3_X|%&qV5z*^s0Xc-yl?8Q7ht$({8}96!C2D=U+sFC)l^H z<7-0v%QZ=K9Y>yXS_^LEnBg0NJX>D@&y-xsC8ZGGn?n=YpCd2Nn>#gfAYRC(*EX)Z z5wGDtO4z^)q~sOt&Z1uvO?jp7qk(v;U%Y+^c(``>N_Gvq|L5mqx29U84Du=Hv6U8h zWohO%9&yz1%SR;r1dyla6l;tEX807ncx}2l^1$HanRa{hm2Hy=YfgZNevw+Q4Sla? z0@~H5D8g#_mcoX*{pv#2W(B-M>iN#WIjGa3l1%kayd&4pZH+VXI6~-#4HxWFt>5}5 z1-Ra^Glx=#9lbh@9Ib&*+i$Hhc@90R8%BLI{I0=p(m5XdNyabvWh(aLoQk#>27eMb z+c;1RKUjr6obqc{|A9T@-i$sifS(%vW~GcjPy&`b`uG)_SNLg?pUam(NJ!eKMS#XD85C z(@)%|nwEl>m*3WP$NJR3f`9jSf_LfEqzj^-j+5E;(|3lyuU{!0x)*j@Y5c+kyoZEo z?kIZ|zor_p{6>>4z#aepKJ}@+d`qK3%^t34MvD(V}JOXNXkqLmmE5id^avt}_p$ z=*Ei!bNIul>6a5?qLyvXU})n+RaCw=d3wD zxf!w|H+gaa;%@V3!`C~A6M3n=MoaWj3Ta92Ij&G_Pxth{yN*7vJ7z$!#EY69YjJ*1 zk3LLv_>J%#nwr+pTHHL(6FBXc{0UDKI}vWuu@vV#`gxKk9QLB)Tz5!pLtQKop7n1(#unk@ zD#(Wx0}k<>=PAPbrn2z|`0bOnG~EnH(cU}mZSbeX1=TilXNu%L*AM+`3;QdX=~f_r zL|bx`vUfpmqxA+U;JZLbh^W|1ymP&()B|62zCTxD06d|)cw6CC)Dcx9g=}t55r_rB6(iV52|V zUc9H2ZvM0WKH+d+YoG z`K|V<@xl?vV)-(+Rp6DPrpHRwfk!WHpD5o1oL4Z{$t0+2PTGE&(x@{NNAwiRP#-KK zofBG7hvaVRaps`D9Qk7=FJFjyuvp!cawO8-TX0=r@w15M7(NM+I_9#p0IY3Wss`zSaIa8~@ zafd@|8N>P&H$igBm|FQ3XJ63@hV^&NyuwJVxBDIN&7~6OomX!b!`O?Z@%d3X`j$gk z$>Ze=ow4xLz$C^e6-y-Y${CjD?SZM>>kR$CFYmn?H5$B^BXbep$P$ zP(KxSMyU6rK5DeLS>DBav)h{W*>ey_k{%g~uuHv^*!&aV>xWLHuCM?f7h)SOYy@xk zwC+UKdf55-juyXq_(4?l=e}I@<%1{IiBrH&D`zvy`-oSvs(dRWj5@gOYS44!LwM~) zNnYT{h6B|t$-xxsn(l(+L%^A|myLC&LMd8`cZuTC0BSl#(AT`@3RSE7b3>hHI7Jgy zvIZSSvE44DiZ+E%wfrrHN1dW6`nTYtHrH6HmQOp>gD0M1DS8c+=*3X11A-#n(viq# zl^^k5(G;ujJx7E?81Snjf@;1BUKPCCH0L5k$2@$+trA7meiL9axDqMWx6*lb62Lcg z-<~Py0E&)KE?w#2L($FWHOZjwLr%o2&y>lW?wv}9_NEMGuW78#yws0`M&tN|(=F3-wOB7p# zbVa?G7e%f}^>ZYhqe#R_6HQy-*KpI_rhH?_<0}qS8o&=@?blAafJZy+clfafdENQ8 zwo4RvD5WtTvYR3%DI)yF$b09b5oQmOS5Ksa6Apsc%54ZgaQ^`6(xMe_uOn{|jTEp7NoVRbnASeJ~=ix3BKX9JFvVVr$YP^Jx1B`Cl|En?<(j8z|Oz;j|Ai#xo) zy7jDImxUpJ_?~((1U+)Z@7PP!)63zhw`GyvUac!ib!O_Z$iXHd@S&j>TZH1U|IczR zrCjhDuB63$E{M0d?92vR;Dtrj`upNo&-vf)Kcz=KH{_tNQFl+cdKzP1zD+#+*tg=t zhiXmK=kbrng!jNMoI%<}!MIoUzQKST$l=|+ymP=G1{~*g<^!*sbGFqzLmWFls@^#Y zyH*Tq=^h9EZNI&>Bm#D-eHe4P5xm@Sfpr-dc*ywZ(?oONaLdC=WmVWU?7zOkmQ%;h z0s8C;#(8VNV_Giq-I|1bQw?Qf_u`&J&2B{={9(1|e8gAmH!QjQ(teEXMUNTzSR=pw zWq&h3-xH%%M27=sdBXTUHUpo}U7Ekx7xhRrIaGVG{Y*U@7B548z|zf{8Uc?R-jnj( z9lX!)%4F|6yu0SV{^Zf^Rg`nR&NJ)6d^*(7-*j8v>#_j<>Ar40 z)(M=>E&Hc$i9UvOdxZ~eK)u>4FFYT-h3*%XdA|+ zr*E%DoI1XwKbV5Q$JZ}i{Tn>ral7x!zlggvKRGr$fc}-9#IRoU1;Q2Ye}|wikk;5{ zIT_E8FNJKclQBPXQy`%#3H3@wM9?4WEf!{1QZv5$zd5?3;Yvs1*pbtB<D~xC2Cdo7#gDpO)wd+n2zmCVdpk4JuXqGMdP*TrpTu#G49$#{wVr*&ctg{sJ3FvX zp_X3koy#+PKSbpk;#f}g{)4s1OB3nPhJ4_~tbpgaZdk{2R_oIJncoprSh>zT6p>q! zBlsG)M=!q}FNrt~yTa>gVS>2xd24(|AH190_qm@I__`zQ^AP)z2`ZA4pCJa$@43R! zSCOgRJ%QlwbU^RMxrqO;d4o!Z=vR2E<-YP#1Vg{q~Dvov6CexqRetsqfgFES%5zcXiMnlp^!M&1m3Bv0-gLH_UCd8!};UoGF}BdX0Z?R+(W-Z3UAJ<`wE41K>y+6pl&zLiq*H^Kn2@?fy8XFT%Ot7?tJ zOnxtIrW}Aj!omh2li@=DCcTOHzQX%d^7(Xz?pfvUeH?k}VkTqbiShS< z$IWVx17b?Q4nptkLhjVaREEy=Q7{-qUaLy5rG)`!bVLqMh2+DpZ@*0n=Q1R*H}f$y z^S|iBz-{{=mzF7~|Hi(7x2w3rG8j5I!naZxJhGhsT$>Q|^>+PMScUz9C4%q9<9n%c zO!70}N8lGl%|U$M#O>+*4f>W^@A{H(-Yw>?mK%8KrMbfkj4&@Rr+#%k_-W5ifup-I zUYoZ`7W>j~-?vX4299aA%Px}#U+-sC=?-9h)@1hg&zL`MRasw)b3|Ke7Sovw=?gv} za|ZY9tyeHtyvC4(avmK8;H;>J;Nv*F-*3Ndsx$EFOh5$aM2YC-8*gP;&(r;FnS2*;(5mbN~Cj=40QW@*BuEPeoIFP?zkhU-Awj z58f5!EI)vC@3`M|G$W5l#sB^vF|<2AU=Z=(x6jS41My)l%~nT`x( zTT%Z500960O<8$3m0kDVrb3e&yhL3=89CN$WTHu%Ohlnj1`hjk;o8= zhb&|_OAM~0{_3=F@thaq%{-A>`yZ;pYN z?hb|!5dr=PoY!J8{qz@_AAhzLnKrF6O`1+{jUjW=N^0mfUC@ zL-rm}ns0*d)=N&*XCGn6xL4Uo+#%Q}V?8Ad_h3bii`ip6r&U6D(1amhr(O+=h-Anu zmH79&vA&_a)8}X~&cEl`dwVrQRCaIvxe()YH;-f0Hr#9PyLA$N@Kcgze6%z}<|sO; zs2pZU*@M7>xuwN_ z)0ZI*0$BwD+;{R=yJw0!L$a^)-UxG~h@4%AV*vK^7L}HfbcX$U_d81A7l)gpOBzkF z{^yjLv$*%#QeZa<{}b|~TMX;jg&N<7^kJX=*zY%P6j|W5ZBWCPB7p}Q>Xlt69*2@t zk=O1NkCA6?cKacW+g^D1Es!D})vkAvf+*5dx;9|`9()&=S>ubi(Rn`G*EgCXVJnZP z8YbW#n#0HBA}Km{qmXt$GDSCDx5@gJM$zx)=G%CrQpD}Tu5A8PYI10{oXY*96gesJ zXUV}tigup6qE$8L5l;xkJrCSlV!H``bvS#3vZe@&ZSe4s z1zM|xLtTi+?iU~9i^I{kUAE9pfg;zI3@M0U-FQ!R{hZwtDfkgX)f4s@-=9Ah`NFH3(RvB~i1^zkacdwLa!f$;QC!Kg*a4$!xrH($-|acTLZ;iA@Jw7Q@TrI7&2yO zba6bDAs>@+NExWe=Tf&fMPR*pSn4#Oh zrkGikGGupo>qC(;hJ>sym77z}aLhy9qP;5^*4(7R{>_&ea*=gh#N`UZ;mvrg$gX5K zdmaX})2}j|?8Fr>CaM@Z+A-v9Q6)ovcn~6LSIMwOrtA*fgTAVOcc|MHhIOoX_xiyr z45<{94nL0dIf{AiDfs?%S;fO(e7_@~Fyl`JL$q55-LI50bj7mLyPjw@m361QFK1YX z4yh=wK)=^3TF?yk`muvl}}L81iFyx>n=`hFGZ` z+ia50(6jH@zF^KH?o{GLo6a%hLUZTq_%nD9QmY-5$q&JjG4 z$dLBT;O5h43rgnw`Hc4&C^irq#ycioGxz91-Wc8Aqt=HwN}hN2fxd^pm<%3w-%#y(+x)2;ygBs=?A^${}e;xaiXT@dfGDL!YBhXYsd3OYN1Pdb;ioYRM&x4!!nX@U3s z%cC5nsUBZ^kY77*7|VvDA6z7B2t3NzVbUe-g?_-vg$7Sfvf-Mv;*gYUth`9Nn%LF zqlwtn_^z>k`HqrghV*@lQ)<9^xpV$2Zh+54+Wd?~xN#<*>E(s*e!UXg^KowA7ba)~ zKe{9(HVZO(+* z`U==FllM#hDDGFl=XliV7(-Gc!&)}s9B*}Lo3EJHF|@&51LN!#sxb}o7pC;Ay$v0r z)bTpC9{ymPh08kuhnJg`96X0}lIySWB?IRJhaMU%2k!T-Hq|kK|GgF6*$LM0x7(bM zVBl_s?;6c=__5mjsiO+srPok4Umm(5wt05UE$AvG-DsI<&`rHACB~}%LeH#7V}5v3 zw7*N9do1`^)pt;vvBNv;{^PUQk|OWUo2XP#;{Td9tXw$qIPTsIr@quf^4u&VgUgn!E z1>RV1mF5Y*C5L}Cdkg-nk~lLp5bqIapK|&9GonSf1-f)?&LsX%_)YQ z`Lg=3JKC!$QH7pZ_n@J|<5~(s|9hc)t_k?(Z2FGaid^9Coo%-cNQ0b0x;B#8vcpVAq+6?V%g<7`nhRr06>MAmX3YC){&V(>$_;z@v8#?e;$cdo_zI z*DAvg4iZ<4w&VT_lAca?zB4iMp#HO%-dglN}o&K z0((@Ao2J_#u5A3vdVin}=r9P;{o}-tPoIm1Uf|sClCoW6Xfv8Nq{-sk?v1YI-*B&% zwO{6WK$r9uuul!*KIRW95V4n=TUV;74|8#4^g*NQNY1aEt2OJ<#i__jNg}?M>6~{oQNv;zah(LWs zW(^(j0lvF6evI|v`tgx(L$fo(Gr-Cb`Qt$mZ@zhspKKW(k(c}mdAlfLu9lvw4PG+J ztau#?ezA7X%9Mq_Sbyt1R!m^pV@>Ec-FW3j?z#USo|T1rSlf!;a)y69q}_``a34Jp zrysuDdP{S|s2%eE+!lq=Xf7Vs6#52Xp6ZRW3lhN_4lhNH^>OR9Y2zOyun)c3V`Ql* z@>zSlYJ&~dFV%2a4IHA?Pn5jDJNR{NcejQg+mxeD@5TH98y)dH;E;Dl`kH&d8&alv z-t*Z8lKh_jH4k_pGIzA!1pXp{g736|3vD5lYU1dd*FV1X8UF6I&RHM59d(fIA{`It z*yL%A_k&Pxky1L-W-diGe|O2d1AK1VpVPGnbz#!8VxGPK3-RGXtlyeCnP0%r5@A!T zFGG*+T2L0FiFw+CS3Qe?OPBIl^0x~aGJ2@=A9b83{Oz6a1n?}n{NDx-^c~y$kNN=@ zU#$u7yn}n1-AtbT82239F}h?ETIoPnwN3D&Ph0kFHt^^ei?ewR{CQ1yJtKzi^wN=v zSHSZs>*cW*H+RDH{4E~)iX1YWax310X!OVLDA~*a9|;E3R2@Nl?VWt> z_8f85;82v<1sqAP9X#3NiFg&P=5<2-{#|JQjcUYw)slLp2N?HGpAo&zn~PUs->MxE zH;+s;l(0|P(g%h8sGkbT%%8h^GLsTI{4JZeBmUg?zr6__)mq%D;g342tu-K78u3Uw z7_y$2fG2Z=BfPn|cz)h^A@l`Ds5xZE25$Uvc)Gc|<>`jcqR5NTqSGZ+u!Ggm?ip%; z{E?~cS3^Gcj;Z_`Z-{$k+r1TsE{%;mwNn8&>FspRstEYlAijZj2JG!PcINdl=oZ!H zBF=q`4?l<~O#xoGJu{jXi+q#(VO%4PxNlp(g;y8rIG&|XrUF0m-DVa}z`yTq6)B{` zPsB8Ln+oi>qWw~egMQPvO!Xu9J!7T!!|CAf$|gN-(iJwbzDr%Y_4u9EDbM$E((4*=c_pCe38`ai_fBN4P2`= zK92fEByZMB4e&|tK&eh8a4FeZDV?}IE)3`J}e#DBj*z4Nv( z*Rn8?;!)r1pSd`WBCC{Cwgtvxe_`3Fi@+}*Pkt1aMx7%b!|8vOM3DgBE&mjNe~#9r z$^SxKWMZkg?;TC?e41NyQ7xPz*OrD_?)RsNR-EH6E8wWZ+*nOZnj(!~6VG~JzTDeM zq2HM2^5Ze$uQ}5W_3FTmf^*wv)Y;(N@O-Op z=G@=WZbdOW5wC}xN5qhKeQ`%8*@!c?vc(!-#JiEQ@mX2qnbuO(tzkH)>6rV6t{Bz@#fv=a4Kl5q1pj9p-{ug5xO{Axo0ZPh$-Xf*Ldci8 zzrQ;wUDIEg4_;1J`0BY4x}Kwr3n6bs^1P3GgXgaO{k@4jF7#!a9XC&B$wY2IoUw}e zm#I+X)6Mi^9pqQr{pU{ekoS_$g{Rec0xxdtb&}Udd{kDwZh-v*gW`<|u*+!C=JOw6 zzt-%aef8k?j)nJLZ%6)R$%>kNgPo!BF#;X`PsbaDt>~6UK6Vx#Jnsel_VussJ~upn zVF21btsbFP0E<|*qttk(f|RZlLQaKgCFovY5VT%6TAum2dhyk>M|$131; z+2nZjLEti5A=t|g?Yqpn{S{dZz5H4_V-B2Gj$Ek!4!kFvlKbfl_@P*`Z0A1kPe^G~ z+8?wT+g)CCf~SW0FZ&pPcUpyI;_bjU?uOYrY)gO}XAB?ZmoTi*CV?l5%NSNm@FU}I z<=}hEq~I-yye>;aoQFwtsUFjmdkdDYlsB6tM3}XgR~uE{j@b zi*X*SaJ>`d3@y`tNn%Dh!%+>iyC#l(b>ob?~J{ zamBi3@L+9k{{p3x-1;T%r6AfzJu{p)!T**!b2c>NU9x6+uE@o^ODYVHdvJdrY&P`U zg7@a|pXEzXWhTGXUYi*Xy{YV-+oKgoajI%JMShH=Sko80TE!DZvFzst2#>{3w0L(m z`$7V~o9!!Ee1zhhOI>Ph7EQ5cpO|Y>4%~6bQ&$vDp>#rLv8PKVQM75ImPBI;B^N81 z>!FrGv7}e3U-^ELA{7Y>yDLsoz1styT3t=2dWV-tYidof7!sWm-JDay+rZmNp z=vsO2*I|nFc_`X(4($EM=4|wD+@~(cCO9XNA{l-6+;7EF^!pg83WFmQk(ZD!^$Dct zmF%bHZzCys&9joYOyH55MAz5$2#R)-tSH$G{QBHNGX=oio)_A<+scLY;3P*|v z{^UNtQdoN3kzl z8q+b(-go<%mKk(_xO>YL?(a5>b0Z|d8^qw*$1v{BiICPg;kzKCM9B zdN*o_$6=n$l}^bNoO>))`F#R(MUH>J@Ezp)rYT|~BFM+bu6eh19^ux*7nS|NuUb8V z*2&N}hf_{HI-1Jm^_Tjm)4288)AH}gXC=!yw;m#njP>Y2265&ma68Tsy48Yr?CyH> zMYQXGPQ$pOOy#9S=+KC#BTt8s$LUMP*j8s4qJPBk-WBNES-W2{-iJCrPTm7xACNpJVHMt(c+@d;!>4@zBmEAbxt=obcL`eU6+rhWc<)XyQl0=j2_ z53ByUzO)N%mF)Z^S1PSvp#-kMWrw>6SOpNjKDRpQoq(Ub z`IfM5W1n@gO4d_=i+Z0}JJ(~KQ_ZISc;KN|tLfL9@b9K?J?){WgIPWGr4o1t*BU#~ zH|T#I=v+SnT-7B0=>)pytMIb06VRK7!deyH;5~NJer8v|AK!Do=v>7*qnq;v0x|E` z`&$Z4*f+m-({*;j|9!W>x;v%hjX*&sUzZP`SPz0R%pfM zrZjKk;)X`Xf?DXMnPT=^Jh{K)Y3_ffj=qtdpkmS;y&ZBi|Gb@|9ry)N*Ppi#7=59(f}$ma6h&{OQN275hjoo8S0suBE5i?;n{z?(+@ zt^aD(+*d$fdD~7dkKq2VsQBm70<5P6?mX>5{mFS5b2Sb+iANcXu7Xh=6?VC`#V`VC%2n>|G)kt|Ml-`c~KwkegD2M=kE4BEnL4A zKrNh{=4*&oF z7sHn2#Cy2aD6$MPYAcG7vNgIaL=X&AF_0b;G>&*N(t&Fp*fnU)lF5p z0TF|Mgd&n=bqop8Dz_jCRYaEl2cC!L$2;FQ-+TEc4Ap2ffph&d{m-jC|F_S+KjjzV zGs85Ri_hCnQ>KyUI5h*$|J#0kzebaNxI7e!v4l3Xb!JM)6ShJeRmFZhDopXnfl8T^hMU9`IDV! zIDQT-<0rjF9`6z?h1Q~R+fFs^D*FfPehX%g)}yatJtl7I#QdMi!t^`Ag4*ZmF_>&Y z=af#g{!|v}GwHLSsk{R2uWzjxEO%_ZXtViRZ^_aP~6D_;SHuC(ZDl8qS zM@d+(IX$S zf~h~(qc7Zo`N~c-Z7zGA_YPHIGFOkOb1f*1?Nrx4D0`#NXm=Hw2Q9-yZwvaybfV_{ zvN-+ct57>+8Cp-ZpkZ_;n%c_}eFh%3p!MQqnEtK>LxxT?y<7Gs=l`V&t+A!(f4K$I zoA#*jfwH%Vo2oDsS&F6IFJov#Cu$O9Z}(ZfuS&JwGBh7+L5r>vd#lRZ$e*vm{D!5d z+4eF9g--05SpE)k&QzgvW+@uRu0!jfPIY}k`McapXBFB{E=8wd9qMk%VCt&!f0Fl; zD%6}>ikXq?F#X#MYOgF$(qFC$tB);3|L}Eaw`8z)e0e){ZLLE8v88Apu?`JWGMKC^ ze~5p4}VJ`om}F`+DF97y3nQWI2X*Z9vm^ zpJCLX-NbkFzf;lv#&Xo|*nqxU_hIxwZ3q1XB`j@rsc|ukzWZ~iTP^&H-$hA6+n5Fn zTpz*2;+z^kE~KdAu!MH80aH^VsF{~j*Bgb+#61!^DjG04DS}pe4g-zC7S8!v!hq1A z#^wk*Z8_9=g%7FkYYC-G8_;o0MD^YrI#&r>$(xtZ(7yp~S47Zk&7tEF;Um7!FC;V! zZNR80g1)&q)IK6?L@qx~AtGcJPu+jA&6g^!uTehEVZ8!$UIg3|3dG(RY$`93-& zwEyVBz?cX+4)e=|PpE5`guYWQOdBFejf>77JtIik!NBr?8iMc}GH9j|;V$$leQi zF)>T{jC*-g!oYqPI?jgG_}4kCt`_!@KPh4LaTjXNhS5JRhtX=`bLw6uVb5L{CQpUY zI3|a|8Nz<b zShXUDnrT9gz7|Lr>~yK|;V||N&!PP~;or<*o`j~aTv+M}V{&8;^OJ=ysOugH4QUs8 z4uvr^IETRr!k6?_C#hy#XgL^0^ROIhCJGAoGFL+BLl*|W31di`L)%rtSJXFG!oY49 znh%B1GBSrHlaOalvnBMsWUFSo)Q4kbN^HOl)+aH510n&t2%R5WeOfr%R}7 zbD^{|jOLA9nA|et5cl!*bTr-JQe6?o zdyRz7*IcOiAgtQcg*`)rBfLLZ!u+!?OeVwF^JN!i+JvL@J3&In10M8vV`z9)!Q^)F z7=8R8qiL=Ob*o~SiYci1NIcH|lQKH*_MpWbL)|(BwcErJ{U4RlX7ymt$`}S-Qq=Vh z@dWcdA!BHk2W=~2=zBpyX_NRJ&xe@|3MSjdljKok)ZXpEKz$4y&nW0= z7r*Deb21ul@nE$hhPHr$hBomB&dcehyT4O(7 z*oT&v#j~t$mN9kOjrKcZ7-&$?`FHUb?xRe?)Im2|XT{LDTEX5I#Bo*SX*QfDa8PE5Db~%QQr3y+47O3E1Q za-&s>VZy6mZ?jlNzBgq|?RTSTT1<@>Dwu2*FYYtFS;pk&ZgkubL(f75bxmS9^}QjZ zz2HWtC5Ddq3Ywk}`?EhTqvumMnx@1s|B!-~MsWb=g=Lg-ZVXI}q1~on!Y683kIJa| z#Ep(?V`#fuLGxqcK<2PsM$JAqrmu=&XpVx0RpKD(dPPS67B}ilG0ZMd(B2>proXi^ z8n(MJ@S7NxW+~`cDGniSk8}^S3Ezd{`97_neG@9d6W&jiIqc!P1A~Q08+? z#?nv^<{M%dwJE4wCJrOd(=r;ix-m66hJhIhhL(yt=JGiwJ1T~LNkQ8pQ6$e_ zWwdm-(fU~{CZ;NAS||?Z`I9ncV{XjsX&ruHE@+uAj$p2j%b03+V|I5dCaM&4ED-;T z{i|gRZFFP)lU9sQQP6mgIFj%4PcmBGbz|@LRy3Iv^wo)a`tr$`47oA&Q7dL=C}^n_ zNAX>GWc0_~Sp8uurmt2oGe?FFX8vNLPpbiH%gmYF+Wbh zz-?j$?={G%`#(3P-fP8-QNhqH;%MenFQerJH)h^#Me`U1JvWP&lII~AJpnhGwzs0~ ze-uou6@NwD9WtK({{^E1V`z6OXnau|L%x)Z<^yij4v3*suc*(biIhpR9EzgTa=JTGcs<_dniJ@k=g7zwLEcN_BM(KGsS|Y6&xL?8Z|F8X;_ur8*y3dXF zGp*<_Dp);1tYrOnGTNVVt8u6m6IuoHW^o*`O-7B^jpmkCOb<}dex>*u?&VGyjceR$ z{8B6G$`tfpE{>G+wP>daeGy>8GOxbtk=;9hgARiX!@6(3_}xj*OwA z7d6@hW|tRH`@H^g`hLF#Q^&j*yf}e@`XWlt=&vB2C1dp$UbOa0V79S{ny2(v^1Z!X zgQadSdd|hszqp9iPwKDY`7JV*_IojKCXUG^MKt*JS2Kr14fYninC^{ZXh9K;P5NuN z4@t&U#*6+R;@4c53pyJ0*V0d<1{3?eX#Xyb)`}uVpV6E7Zl}ta-tNWhu{Z`t7BS$} zPayw4YEZl1i|M0rG!HLgW|e*-bxoErvDJ&oZ{nyKTSTi{KZ$v)tHIv2PMf9)IPhtI~8no>2qOlN1f1-fNG5RX{_RDBo=*7V5IA%u{ zRafe-l2YB0FPi>W(Cu*?geJ^Hr#8GpifXTb{zoq^WGHPO8On)3l-!BD>*6OFT@3ETc z7xJQgYaBh_7BF*{ULubmqwW)p%1}jlV2l>L&fo z#LH_izs`%=WL$k-C}47i{ub8H%*0Z&7aecK(N-#8dYb-L;w3d0e9?=>cpL*?6fk+C zzM6V}n2D0#i^*6Vb-4oiE&3YHSyY44b6(W8#?j&}php>b8{b8>jHWBR=$IWx=T`*` zP1Mh#zTelN^GPpSUX5dBdjUPCM&8bxkIh8?V_wXL;+WW0z`*wvchJY^+338f5mOJh zp`p1OOD8I3vrj)89Wxp+dtV!-n!C~PR>hq>*U!e#)JD`i)P|1L-Kc$|!peP!voUZ( zBO2zlVfN46n2J=~MPItv7_Dl=(xNuB_`1>dTE!gZK6o}}CO2ZXu1$UZM7J7msHo+4 zHfT2XzS4xA-R-D5dISx_jdQurRkfIEX+rx)?U+A&1Un2QQw?83`otGTHJwAO$mMDD;E;aszcw6%^0|^0}bbnV|rZWBKBG9FmXdO`WJOz z@aN;|`q;|*na8bl=vcW1o%1@d)O#GQk5n!uez^{-1I?Ius{`|QloqSsUF8z>yQ{-Q z#~Sq4b)e~wCs4Yi@&WpvQHP0TYtU!w!2GHcYOJqxFvlC~(6n$3=I3;v&T~SIM^r9l zzL(iBKYtBs@9IFa>jX+-M3m#LV(b`M&FDN6kgr8oD&B51Mk_fRX8bES?`lpisAb-wC@qySRd!dggc7mg(_C=(J;4LY-jFA_)$JJiY?75w%)Cw zb(gr5{*Llv_0%ZV|Dt044h@qPF~Yr!^kZ^n6a$y2=v}U%dxv;4_i(r$)3c&zzC=aC zG7S@7iMI?G7yQ_ALKK|~RBXLjLrYn_mG#5?m~=!jw?M^8yM~c%;xg`WkRNmQDEcl? zF?pkg&dGinp`xfP@(_ip9UE*b>svR}hyI|1P0*N)+v0 z73gx+Nj6}sdIln4leoPdT zb5x96q3Q9x;$779ql6Yq6y0-GtT$`=?<>T+>2sHa@ljFiI7P+uWg3?65LdAO2MNog zqnLO|#Y|em-cQAQ`0g}6TCR*@vQfp9U&D@N;=T0$jfC|PQ4BPy=(t!z!!4rB`}|Tu zd1w@iGgPejG)%OMQTo{}Va6CmcY})F3pBLcB;H4zpG%lBMD=*8isAD#j9f3?&$(Yq zm>U$uuw6yr91V*h@d4JiNtpUo#<*3**0VIsUn|Bqw@*Uz=qSp^sQS7`Ltm@-AnRKt zO#UQe?|2o9b2Us~B|d~(B+LzqqC8&3j?*-3y+Vu=e=K2OpN!TcRrH;zp`lrPnE8Ax zVZ{(d^ARfc&eqU-x!B47<$X!_M;TKl73;G!Ob5kB$p3E%4TGatAE{#CBn{1%ijPvq zS_$L*GA52t(R`wYsRiQS$*)Ri`ANpyC>4DT8n(=je&i|)`-lB~0Au5J%(XcfsK0#lH`LVSziY4aWHCHkL&K?}^2d4D@}7+D9a+pAreS`T_#AyLkkF#aSlyo0W21)l z6UFCQzf?l+S{d`(vluy4LwUOR5Ap{jbgYrFx0Kc6Lo^g@;!5g~B#gf~oo3>>YZW3Gnoh2ksZxlcmJ9vLmU zEDGQDqi>k_D)lu==zL7Zj%mt zSw{1#S&V$rkFEPBzd?P+NLXAUqy3ev9{2X6?^@d$@@@=bxE{mg#C3W+uZHPsY;O`j z7{uiM7`9l~q1|1>@>RAB{oWVEr13$lj#-E0IW;~0tL-iNj|New#xOr-9kw>ru-bNb4!arh|8omxQGiz91V0(vqx+RFkXJeQix=xR0)G)Ju+Pm~`4PwXHF*LlI z!^Gyj7#?oRk#9l}t)7^!VI5kg)zI)K+dBGh52F2v82VB<6h7LEFq- zK`h=E!;T+wD37gS>*=-+=;O*D3egyrwH(%us-d&V_91;<6-4X(F)Z%Mq4S6ux}CQC zfZof4*pY~#<@=nzZmOYUmhC^h!(b3CD`IHgnL~L*4I?MnHt>BQh=$u^82BcK!mt{8 zPq1y|-7E;AV|ffS-{dfPSPff_w|&I-7X>jMjiJ3Shvr%xQ-?PEmwEe|F>+-m1~ThW z*jUGwhK7&HJF^+RD>^a!?0Pgb?#GUy4L$6e-;Bb?b!=0VFkFCez&N|8mW^AFp3!Bl}+==OL*P~n5kIoYs zKK&yvhHvde!@&(`6%V4>+qjiEEm?^5#N!zLWdpWa4`SrZ#v<=(@j?v5A4lK54QQBn z5FMVz&zS3?g_wyyj_KM4eSO?PERUM~Id#lfgmzySme=%Pu{7ul;zMR*>-0q^pWmg& zYkSc7`JfWtjhKzjsf)03ZWrcW>p|bK#%=VwU^cp!FG9=8F6ZSYO$Lm5qb8GvBLR zn0zXPnb#DwPu+svGlZ}7cj>~`2SR%MvVvjj7BskouQ~S$7rGw~VPv&}z1A(*;uOB& zelB-m%UvN%zNn!4;{w)a3E$Gsr7rY66vD&{3OaiWSe+y6pq`6e80ZM;@pB5cY%E~1 zNBEBYeiv5m3ZeU11ugl49?uji)a!F$zCDD+rxdKND`31)*h$|Px_1822lhU#pmj+B z%byv)XO6Wd-H9RHxeBJ=EuiH%VHfL?3tOWhEI+DX>Yc(a{k;i4-~}#B|1E^>P6bnI z3TU4s?53V`U0A;}gvAFHOlArwPZIi>v)6^G#UaexuVC`^0t({m|s;u^LAkm=b!4r%+e5A?p84Jask6f3O_RMlU?Y%Dx}99 z3g%J;Y#Ax+W&dm!_Ff;t>TQZ{cLC+$LXG-QaG@m_!pvO?b|ecJFbY30m*ZV%xH^R4 z4h7Rn0jooWpXqD53+wYkm|Uh{?-K<~8H9bTPjg|_A41E`3I?7mpm5Mwr@kpJ6wV2u z`z8e|j}$Qet8qVlPj;c#A3{f1(c@mD56)U#MW_p#tVK<8RbA#)Tc{hS2?2Mfa3~zW#*qAoIvJ zVdm>42le?YXui9EmG6zeli%z@`&l7$U#95F1#I1IG`uu0hmkH!&kUjSQU!Z&FQ9w1 z@sI(-!(3Q#htPhpg87aDmR~atV%_LMgCm616$(}&1+*x}!27RI1imuBiMRpH(HkTVP=GR0`oh59#;MBm|xb7-lO{T z_*K(H&fn_6bbcv%CwF7T)Q2srO_P}SCJ(yzwP9dlH#&~!!*aLj7~Wrx2OS%iqIrBb zI!E+jW|hfG-yeA}v9}HLW4h5U^kMmV(`52(^kB<@HWZHRM!Bh^uPY{z_yZ3ncC}&a zsBZKMeQ0^cG==zm4@Q1&L;K;~Se#kHN|)(a>V4OP*6-S|dRVs}pHxEcRy$2L`pI~(_xm<94DQCdy@Y{BOm@zH z!-Mf{ZF+3z#D2Rv2O~S$(DGXf%~MJkzRz?V`Cjp0s?es#`%`E+unnvC znr6_)Y7ZvLZRp&WLiaHxjL4=2e((06u(?f-Ybi8LC}Dkt>3H&Ydoc1v8~XO7usXJc z`P)q=P|x!oH2kLxBU%buk1L`1Hq(jhS3DTs(uVaPQdk{b!t$*q2lxE62jvgjFupT| zxltwTXg4+f@g2%NZD{!}h3*k0tlwZdiMkRVEUs)Uj{ zNnv!KASr6UTRBc|i&7%S=w@-sky${|5j7|Nku0eRva9+Q;z} zv_=p*%My(*K)GZkxYkVu?Gr#CmMVjwL_jTq8n9DR0V!f>Bq&iqgD3{6GEwjeC>jff z_#WS*s0~c4QAC0zY}$1(DnbBZLy^pGzr$aj>i}IqqQ7@$=A8T7=ZwK%F)p^ZI1Gl+ zsMj#n)s77V%SLn?f4mBFkw)}=6GpdlAKDj{jU?}_LQk;~r6I3j^k_T!&1IvyEnilJ zscntu*%8Ku!|mw2uADzt2CM9&vtbpG0oDWPmk zx5DBoEPtU9W1offe6k(=eagl%@6swvY;45T$6+i#(2lu2WsYtGo+`8i8!`Q17!60- zF@8?jwaoiq6}q=JVjvdASf(9o&MK?oz5A-r9%w|%J7LVVw`1N=Hm+Oa{3=wQZA8PH zVNCC7$E?=3x?9(rDzr2=>Umoj8}_v81`nz_tpX_^mw~o82 zF!f|3N-bf1{7^gQkM|uGBYgGrP z@9aN`=UEIG9H$~7st^=bp`rpVoe=#22+q=;CYsF2hKV=q17dK=1#8$K}>cUW< zVlw+Y;X=otW|XdPMbE-63_MxkWd36=OkLEB>9MW4bGtC)ueh1_kGL>=K{F;swW7Vg zOV5v0Ou@Vh9sQfpXK%%n+=YeZ6;pYhcVVJ`Ge#?0^<3M9`IQyZ*w-(vX=moc!d0zk zIqMWUAFsHD`VP3zUDk{VYb#oA=|bc3id*?VesZDH*sSL(TG2DL3*8S_+(uvj?ZULN z8U256MQKVG#+Fvp@ZCNa+Dn_!IILCAH+7+}v0^&;pDxVyY{tajT2YzUh3N$qw=?fv z7g|rR#lYZJbV^;QEU1{lIqY_!xwux(<*jHL--V%jDrWM3e&@pQ$+cKMpcSR6F7(W) zxP$k`7wiMGeE-MVb7Ij5Sk(Sa=|* z=NB|IekRs+Yxr5l&`m+~FG`~2c@1km73VPitBm1EL3A!oqH&#u`42@mxl=~hgdjHD zn?(N@Lp}R>UqtgSGA1Sjv9K_Sjx`#l-WBhmzI`&rs)FcuCo!~I)AL*6T;9*f7``@$ z@dZgVJgH$WD$Zk_-7+epgP53|)U#j1hKM+yI=+`NF(!yEIf;c88m6|0_i`>N8AJ9U zhVMwC?@cmZnN0Hb5%yy@F2!-OQPpN4Rf2sh2(^c=HWqf z-JV425)BO@@jmjGGDfcmqG3uBg>wyyxR>iijD9YoaCs2p(~>CNuc7OC@qX^br!pEY z3!-&m60;2&I-e68xep)7x!!8 z1_jYPDT$VOnx3B)J><7#3|}0?yd#OuIT}V+i4Rcsn=%$I31VPe5*>GIXkRHVAxC74 zn}TQ^mBf%s!^8^F%Qz5RF$SG5fuyXP@{W^}ixx ztX~it>`AoOXec}+KE%1aBxAf+5Oe=XqV+Zn6HCNpth-T0rB_hTViL=5)ll+?KKi^t zM$2{u4VNdeFj>Rw{o=#a^}LMfuM|vNk;K3x4Lu9RN2q(9jMB#nI))_CeuIXF1>&RB z^{kB9j}$CelIR()p=+MFoVwS@sJyFS!+<0@#%XA-7guoZt7SCC6coynm~d#Q)QOML z=T$N)ZzxzWC(*a~oX2^;w}{qC8DqCA7>cWC|EY*VFVW9EyHZBs7De~3Ni>eoFn@=* zlKZh-M*ADe$}{und4CZtXNga69>ZibPFB#`Cy9pP8aivlReZlf#`G%+TKXkXXfI;E zXnT_PFO@MrK|%L9Ni46>P?{n>MIV;Sx-ThDomm${muuMI6j#%a`(<>#py>8UV!1^_ z>y6^moZ}K1(~5#puO!BXXc)Lb3~&w$WVAo0p!-i1<8{V0e1F)6mH{$a$1142s-nNO zi1y!Y&+vUe869>7T_;o&F46RSt+G&s?v&9`uVDNc70pMA8_%q}iScV>jLuf{{J4sa!$sYT#h0jWyo}D-3g%a- zX#K6I=l& z#q{kTZRxI;nrd=-5UY3Mm>+r~K$lCgY@ zf`vsYT6PxEde|1_yZ$oPj8rgPr(*W2BE}Bd-r#>Q%jg)T=>A2;)Vv~Q*Vx|V`}b-w zyKfx^W~gZXtccMAwzv5H0vUay6pYVQG4OE_L!Gv_x!1j9^k1orp%#4u6!eT!_3SR9A!YlJ zbxLG(UZPQlkD*=bG2GgQ z*2O(PV;}n}u|~KD4I?*Tysb^o_x1do`|x8W`iu1_{cQsV>f124p~rTf@2N!L-Fj@; zxgJ9eZJ2wyoL{39-Xyq=zpT*OMIXb&9ByD&6n%Z_emSN_m_Od`2I=^ zpQzXKg&WX)XB%2pl(h0ZauxbF)nmhV>(Mx?4dV}&B-q!|N_0P4kG>DrqjP#2);v_Q zgFe1|73P(CjK|ia=k_)fyd^uy4_0FA=Xz`qHlQ@M4Sf%ksGR48BT+eb0XAH{2@PNE zLg#O#N!HJdLSe*wOkB1}&!6wYhS)h@Q`dPTG1_wh#;@Fj=J+mj=1SYJ*GRNh&d2b; zO&E&r!bE53H{E9Yj6}(}0F?oo&|bY8joH!^`RtKs{QG=tm=eOknB97AFa4HtDH)03 z9t+SoIfVYvyD{Bf`kj97Mxbx#e6-#W!rYC!(Xgj<7w>B$(0}?~^hqIoe8g@v?k@eF zb3Hi%U4!OhLv;v+dv~Gv+tS_a`@{&84lP7a>1GUHnMR?x_Yc$)8-tep3-#P{Gx|$@ zMAtLD_fXHfW6+#gh?X9k(K zsTxBgn=m!I1>-9+SpK_^W#2+I=Il-AzN-Ztk7iK#Md;xBe%0u^x(TDVw_t2p2JJr! zo$RA`H5!IDp>$gdI+tb8@-N|E+@oIA82d*PCZ@HZXGsPN9l}rSvT z89ir&e>1p?&_B6F&-Z80zE3#7KD2R|9omGBNiArm=zB@Gz3xk``F`)(1^D=1JCH%rU{y7c<1Dh~k)q)9k1`BP%ugrUF97-2A zVRUQ@8r&HSsKRgjpGU``!Q6z-(JknZGr#Hg)pU^cV-g1TdC}El8#WB>L}`ubclP;? zg!#Q*Gz{IU=OLY#SYtPP9H_I?Vl#NSONGi$=pX-9eq0SZ&Hv z*A@xmDKDmuN6>vqC;C^Lj?kCaB+RvWQ7J~yePJgWSDKFEW(i|Ey%@+xu;GGEbgwiW z<9uF{(73~kLNS8*{+(!e)bz)hbus>>7Zblm(AuvP^J`4UdEYPrYivvPJaHS^>pIb~ z%5;MBJSm;f|Kp`-y=EK6dUaw>H2tSr^F|3RpLo%8D1upIC%Ubs0)2QBid{arc z(FY}TZuDZ|=oSq8(Si2An0hczlZ53Pyjb`$g0Z6=dKOGQyHz|A3hTY-|0aU}+XqJb zn9k}pyGTNV;zi@f5flz~pt-;4Y{u`CQ2E`fJ80Yg{4W3i0RR6i(|ddqWxBxeST)2& zC34YNWz5R1W?hS8r4q_2@t#%dNh(ORV%w7w9F=H9St|t{B+-JmsM!#V9A{b4AP7;4 zjvyF8$)&XoMAzt9G^ih&WxQm)krRzQhu`?u_w&4$d7tNb-!T{}vpzj~gTr8O_$C<- zYufEZ@nA0|kKc^e&kkT_+@vvwH7szV`H5bv?AoNqpBzAS>?G4+W0DgMkM^SJl}#A_ z@BrG6nRE=}H#@OwWiRHpZ9?Zi4(M^iq~9D?>UN^#pc84XqU!`zH3IXZi>_=QWz?+uLnu{+Eo2as8-H8$r_z zjVEy4t~OmwM&Q`IPG+_iQ(;FwFw+*F?jQOOBrS~B&( z^16oM{eq1;#hZH0n%)u4rQVtw9dkk`-J_!VjE3@CLNob&bKX4BqQm z?P!=2!oF=PmiBAW8v8%y5>_4q~=`(zDc>x4gX zPXliB7(*DCtLpI*4aK#>1@u4T#^P5&UHf*d?A6e6NVt&r)OO5V974;rsvajaG_Mh6 zk?$Ti%Kr-LUaMkak%r-?1;=5XDL1;RL9|`1VqZYh<5j{%^x>aw-A{w)xJpI&4h@qL z;o`$8+uRubB#7b_Dh6)T(D8(D3H?^xXx<-0`(-Msw`iDnOt_T$=yzk^H$jvgDkglI z9zQHxMqV$w(e^Je{AX-Ef z9dk9T+$mf`eyiN5?g(P|v)9n#*0A*1l>cD)9LFa)fF5ZQ4F51ps ziH@gsVCu~ZCO)3xrj8@$Vo%dbENi_(Ju|u|YJmW@Gj)`D0lg7ZI8iprKy_WqK zbfcv+g34eT%RkmIY?(Tn|7xHErFju_?M|bj)zCU=>KyWD>Bh_r5j5{kW8m}JoL|qq zj=J9IKD=p3q{`eV~gv#$HJdb`J%~7-DA7a+8n{Y`Drxmtm)&QH~kmu z*K}a!oCwMtX{^3p)5kw)@^P1O(3=tj>O5wu>L#?mV_EPvP}aj%gMben{Vaayx~LjKn#;(2GM%^C_0~NzKwpp?L+$~F^ri8(Yat09Zxnd;Jnv-=-3~_ zYQrFACK&wG{a7=)cKJ~LD2CEegV;5H6zz{R-_E%&`_S`245gn3uxVN1? zOuZLF>(2uyca37;!R7$#Hu$h-ZwzgR1~7BeD7uz6-$`As`B2^$!^HOksNOJ&VYzuB zeO~9o@IVZ!x8>088Aa#P=DWx%>BFvE3ZI( zH&{nkpt*}p<2Kg&LJj9rbU z_8eM!>L{%hd#Pi!4>PaCusl15>fLp;J|iwUY-NQHGn-@Bb#)Hy3+w1uB`&4UF&`#h zilP0g9GY&gqY@GCqwf7aEE`s1__7?@ch}KS7Vqaf2Ypy-SdD#aa%g?4j+PNo=6kPs zQT=-idmK5m-&#lOBjPgN%cDLttc_v$q8xVl>Zq&`AK*SVd9ku4hMt)@40qRcL*jDo z<00R2y-zW8U68}fygI7O#UT4%^kQXS6s2i7-Htl;$YO~8$v$*G9Yfpn99lhftS%KF zq#tX&Sj|LHIwyy&>*^R@EI!2eeLl41qL_bm0G0MS#(Km)&Rye0&+aIeUKv1xtB&F# zaRuXxd}!VsMaPx_tXx&cGeKCJ(* zb+o)KKEn7xFDm0!p}aqf_Dkz1-YPyyA6I#?xHXDh`?F|s)KR)we2n}a_M+kCDCYl> zMc0LOl)d8Pj7Pm#*&N02hgmeutYfK5408_;da=AQit64h=4aM1Hcxzl^TS?rZj7R3 zUls%B*HP&ZpJe|sFBaEDF+Y$+Wm+A3JmOQVTj9mnx+wMyWHBk$_4zqsg!9hp#F7%l zewk%4g*D-OqxSDepdr^)?(foQAJwhFAmx@o5$FxqY zJ|4x))-1}W*0JOe zdNHsvip5P?>>FQ4*)IM!=bYDxj^$Al*Jsi2{+MU+d=VX=N+=zQV{*zcT7nG$G+o+b(c1*WB=1FnBOg-T8*RU*kO#_ z*YG@jUDbm5l!TVg;;8&)Sogw)7kKZH7TuzRmQox|reUa4#zR|{Sd|`H*6xW2U;-o zvV?)bI3^9ldVEsDX7X9qvia9OV*E9D_fj%#>@dhTw)@EQp%nK;_M8p2}dm@U*Nv|z<8Ve$4j_B}F$$t_3p zlZT}RtrtrD`u`b6d2|TNgT}4o-`t8$uOBTBDp=W2KsjrCmHel+Vr;e_6H64769o*s zV|>6+Kt@vFjE^ zj~_2!V3uhIdEeEF;phBlc~e2>=LM`x7_*b}1Fbvt|Jbj`+ZF7K70~jk@lDpB+=_|I z{Fv!hu=rpBT|0~^>KfmQorq8 z`}PbhpXJArOF`?R0;b}|J@h3t1B++)(R8(f^1=eD+sCBo+lj51>Gfk(QS^9E0nJ|< zGt_%RD~e0}=u9e@T2RpAh%w85tj<8|X@0ag6?EKMz*N|nV}9!lR8M&Zs~0P%++4t} z$BYB)@1HTCuk)jMmVyRf0bNfT2kHCf8JM^DQNBvSWLE(_ea3hB{>B;Tn&3y<3}W$a$^o;(YkOBZ5n?K(Zq6tU~;vHQq-!YmB;F2v%q>;B*W0{{U3{}k7EJk{SH z2k-o5!@&259KJWMWywALOH7`1vZ?fmj>lj(wLX5k~^FYP|8xBr(-6V#6a_7$_#$MZA zbDFr@{>_hLM4nKSGlz)*!7-0xh{7G>oKWKP_uN}PM3WbS%iW1TAKoywBi@a?)NDu` zV!!OtBz}~MJ+1Knc>lz9h!a=izo)#!v32tDQ_C&jHZr6&OsomGez%wCq@XI*Mx>!# zxQ=+&-@mqkXxeOT^N^@hB)#h;+;QUXD!%q4;+~vV%>%?O zRJY3A#4F%BhZ5~gyQ%|;)Ii_+zQptsmlk>vdy36kR}=Yu32+>VGJy^EI7H7LIXQFU zB1Z{717fVcl{}Rg_@Y5xn^<8PC4FVSyeBe#?I zXm50F3(?VOt93mw<575PHF4wOT(K(RfGmeqPJAoTZTy7T?Vi?ppSV6IX1b90ob7R@ zfT$^4+i`_>PMzv^iMZ`@IX8=FQDoVAg19?I+&+#dr;{odL0o()E8dUD4)zpuCo-Qu zv9Ki8+a+(O5iR-i{8fql;ahHq6F2Yf8k&=~Kt$`Ac@xC2jJEAV#2qJJ#=j-bU$#WG zj_4G>IH`>2e*bLyEn-=DWl|2YQ{-t=I*~utw=15QK6Fnyf=DqGF7qKO3_i_tB9>Rw zFEk{!Ds#$K{y)x>Ph}Fstn5~!`NVjQEuP<`$UL1}Sl31Des4>wA^NUbe)=KtYwEwd zSBM`uk5bMN?c#WD9w#0sbTNw~DzpyliXdA3HEs+fj`$_0Y$6^Ds#EYFUP*5cu_dZH z=eOt+SB<2(X%m&c4g9A-6wZ|C5hZFwjs@`&CD$ILOf0oPQ^#W255)P04DPoRL#+OY z*AjEzesOwA{7X^rxJmq(uDv>o7%ltg(+Ohffw;m%;$)x_HHv7&o&6R-O}}b>E0rJr&FQh`s0DU2GzntS@=^oXAqINO^v8I)XSTH8!}0 zxcS1&b~l$+EYC=<4T*&X*yPlPORvvGOqPeC%ipZ@#x7LoOTJXXq?kK|cO zo^;S08yglq%;NdW#MxAmal9mN>z_@M%a*?8rJX{X5;w4 z5#gDSY{UgdJYGb6>uldl8)9Qrmd(=rzy>X9L(Sa*HqzdQ`HkB3Z+cY8Z}((UT+Lbf89-c6OEyyEG+od$QX}AH^*<8Fhbya z!(Sb@jqtnVv{J@)BdA*2TS%!9pS?KJ_`wi19?G_?>xNL2*HS;T!w~Q)9gHrRV&M#cb`JxX2hQy-za zu_h7q`WQYvoV)O*K1QleXnGvghe>!{^qy_{=s9ArXo0;x3?A4#xUZ#;)H^PEfg<{F zps%f7J;8!;JWr%e7YmEVJ-*T^S-Ai0f=qn@3x2C#zY;yo!kyTIA=7az96u?$LMeoW zx(x^B3cXpddz*PC%ZY_-IydT-DGLphrd|IiEaY0?z0pb*T2r*G%w<^kDdn{^aS03l z-ClcOvs2fwf@Xt;)$ZR8RIAurqUVHYY#9X z8Zzi~Kaz>dcb^=36v#xvre}iJH!?AIDDP(0Y9`KJQKmn#Wuj)wB9AN+Ci*o!ubEMq zIHUB#ovp@1vvomuz6=xZh3A})i!fo7dbaKHd?r>$`m2jfGSK@%`qZ*v28314)V}Rx zfInqH_WU{q0!{~b6h39Zxbti5f?Eu@el;x$&0-+GtMRU23IiR#4)N^R!@$#j^+!Yl z7?9QB7@MtOV1ctcy~msZ(MGA)9a;>e_nqVUEXBa19lJ(i=QH3q7Qbg|gpSjUEtbyB zbQ~*>n4kWbj>NqOI{xL*aruRsbk`v|9w%5PT?(KhIlX&s(2fqfD9!8x8gz6rH@0H| z9XHbxQh7hnFeTpfcD9@b<@RxlkaIN5i{0*ZE1ZTzUaIwGTN-$y8}=TTqoLqbLb2)? z6@tC@{gOb%%}%38`bjFz>-hi8^PwVKOg`?PHWf34m;P@3OTi}J{r-~G6wt41z3}EF z1(QmLB&i!Im}-bG9?_s+LZV2@aYzr(dTX@a?$JYX=1kivQ9TGYS-lLpqKmMlnXmJW zbdhQFVSK|I9XRpu>+l5X;QGnmmM$~enD*2V=tAczPZ=PsDo)4e+ zT(poldB8$@NE5Ot`K$EyYhvV4=I(D|nxLD>hDsN#!pr}PI~^=nAtJAZ->y>w7Zw)s z?}*TV%45lW2ShZ`zJ7I7Wq~>b3KSEz+N&eqIqOCL7d43Oxm2_1kQ!nX6*i5js-f|? zw~J`aO4xHR@fruO#N&^*Onk&w;=5Vr^wGyF;AXmK->)qza6{ThuU=>c&d4~8w3nzt z<4>i)`v6rW6pPPOSgMK-A}PJIFI15DXs>ldlnN%Z15PEXsX&6eCtA8w8AW>!wDzSc z<0b3%>wVV9*u2cgf z!khV@`>cYoti`m|LQPmjZM<~(rY77kzr$^=78+i>ikLU9h4Au2XZtg>5#fDpV-Z~k z?jNN!_P6SQJAP?0GF%sb3S{pb5!S=v^;LRLZ|Fg_T7lP4nSwf=((dKK6bxwo*s}gH z1trqks~h>K$ckH$#&M-WJzhD?`2rPQe!UVNpQ-qAXk>W|iw1U&zLR?*4X;W?%I2DB zc&^?4wqJz~qrJE2t&wzyU-{2?Ni`i;x)UWz@?dlenhA z#M4}LRf$9<9xnX0vZ9xX&Ko~}Ju_h;r9QoNQ#K1XpG+t*XIMyGNm=;DTOa+}7ROdq z>O(T9%$2HQ0EskCW>b;@oYuFihkP@@wE3s!CtMA2PhxAd_#;Dzu9>DrD;Xi)tm5U; zL?fIW{4V+Nvk_#Ej=$=6GseANcDqj$8-r2k)Kny40-CU_UFtp)n5HY~ruUh^yQZ>r z0oxR(W79V+x@HPXM*n+LVKWTcT~iqhHpA$;9^=dw^1Y@6-_A5Lhw{4*;Xf{z(=l3#Rfg$7D_cN@Jc>x z=b!bYzr4n->PxY}wI95KsimZ!n)|nA-lzq(j>~+gRJ6qN55WuXxmm*buiFB4q9yuw zUD>?hp(TPfhwoYsTS6t_wqHF+0Y&sbw$QeA&xwKbyUV$%=*vPK5ahmsaG8?>FO-M4YA4eW~;mK8}h zcpxL&p!>iEURj*oOF!6PP`XjbNx~L&$)kJAEN$_&sAF+#m@N`i!|a^1ZE@Uu+h};b zEmG1(mbgsY;#lv~r$069P^`Z4V4$ZR+MV*Xg_G^D-(US{$vrzTH24L1-rFHZdB$z2 zh&^ik#)HI-?4e-mw=LS=9&FWo8+y7u!mL%i49dyxpfa<8VS60&U2->9(g8pEYBI{r z9RSa{eaV3iP?7N+nxEl-8|OYxbe1~ca@5I0=8yxd%cnz}mN;TVL7mVRLr3uV?vvc@ z>xlhZ`t@A@bHqg|rQ*|lqGNJJdygZsZv{7GFK|Nq^`~10^_(#9bp1b$rxTtvh-M5N zbVABx+_|}{PEhaJ&X0O0L@1PQ&6;#V{n@_hcXG~~Kcl25#Q{ zlg_ZutQ#76JS2Ms!IJ7kbgd8uwnk&oU9jz)+`G05E|}x+HZLl6!8#?^<4<3>z&qUj)!lX%jB-|c?-_Q%##=XP z^M1MD-Of0^-#o5ZJ$8L6U%(X>*Ss1IFLA|~LR@c$q$}1ZWOQaNcZEzvhEu1!D?D~2 z{XV7aiZV;Vg;?PVA9Jr`=hR&>RQx%Dsp$$Tby`(H+ZB=zlvs{Bu6S0pTVRCPvL^h( zI8m^@d&mEee@zj}>DO{agIAhD{VG?4IL6&#lQ@1KcDD4Wx+2Q1u{~PR6&(3OQ9~J5 z6c^FIc1e)&tkf;qCgcj+_b+PK@wwuhdW~w!6q%PrMTHFmE^v7NJondY7aVTRE7E`9 zf?pX8yLicbOx`%ZJ}}+|H})N#74&z(LiY8)8*GWAN3XPMxIkRfFwbofxi2+McYKJ8 z;Z+RpsY)&qm$pc9bGYcgx@PaIy`rLEK%S$oztPoHtdmoo}l`+}W;pc|_{TRX#ZU6$iJ1!q*ycGK_tbb_7eyuX=s zPVhTEIyRi=1Zx|IPNO|e;QRUaIGgK)cb2ymg;zQu@v`c)=CmV5FSPt|&<_*78S2Eh%z9DKoTR z@~8u%fAh0;`8c4dyQu1-fdl0HxUJEmq|O8m*NT$5JGW!pCIt4Nsc((_b5R1v)Kig*q1N+$l;Zi&N`PopshzbiE^j*2SHdNLI3zNmlyr!(-ro`4#e`Af`ZuQHwZds$O{B`!FBi3ka zoS)!N*3ENWeXLt-YfP0aA7;y2W3z>K*Pq`UOx1CdBw9IeG>TGoE9BtV!B*+&BOGX{ zJZetd!a;fW!}E8IIJg|UA$OTL2Zc*Fy3P$-K~?bl>ih~TDA*OIeLZc374tPa`*v7i zU?WeaoTU{)Uu;*4TW*Cr*L{yOepq6DmEAwn8cP`a%edUlu|$LMN5{NqOPF3Cr@i7@ zVtQwtQN~J3#Bsb7(`U&3e$GPtR*MBM)5Jjv0CdWMG-TYyqt)5 z{?HUtp&JI8y-jh}UP!8Sfhl5St2(6$P2hDhJ%7f-1V>iB?2wo<#^+_8LJ8N5@w_6g zq}at6hq|;hTK^iM)BEyy>&r&qAKFsi;bMf!J1V>W{WCEI%C6Bz``*CR1F`z}#7(d`&(cRJ z#pR*;PZp-a-?TXvvv5|);FN6y3+wvqj)my6Fj_Wg5F=-paDs_f zY4x7nUQFnAkF4_4Vj{IgL{9J@19oY{nb(>bC|O{B^LGIQ8yvNEMJF@x^<;O=Gd~7` z47kpd)(lkcIaKDZ$$;F9g2S3Sv#j^67|pXEL1pg#M|8RgRPe(v&N8+#Hz^{a^thmL#O z+#Y0`(czu0<0oTC$8CvnV>W~A6VFlSa`fovsWaHHM2p0ik3CzgMn}k{pvvo{zwGa* zC@NH-L%#3FkJmC}oZn=5o=cH^W|Do^RdG5_w6P=Ch|nQY`LdBANC!JR!{swS9iuk_ zozv#iVQ6=9v&<|FuWttJi}_8%`A8n0!3i3k^qbY?eWyWay?M*VFErfb6qP7^qM?s3 zYIDZ`4GKnrK)t;c9d7H4R70)Gj`#piDfkGSRFW;SW1J)t#+wE1Es0q5NK4gJd-g3k}qUb;xs0YpYaOk-oc4PdRW68IRhp>sD{c zIG?#2I^!!1uDhOiCjX*=G3UQ%84n$Mr~RzdgvtDM=iW_SMn}bqHM;Xw(BWA8y{(AM z_r=6D3L(aH+|BXHT4zhg!oIb1@ilbJFhx?1Y@*|xc8XOldCvlCFIXqA247y;oC5_6KREe(9ZL z|KC%tVEKuThhKAy4JOI{-|_2K3NHgY8GmK-L>Z7Sskx}6z`zpUcLv#745-L?yTuza zkg%=!yOb>hTV>1U%G??7Uy-=<_!b5%POjTe4`*OR<6Sz>0S01T=CB%57%(_?{J!Z~ z2Hwsk`kc#Spi1}X;-*^+c$+@mwfZ3gN5V1$JIWcDT+|dP`;vhOQR5WWYX&|~$y^<4 zV&G+zY0bh`1{|N%MseC0ST>qp!%N)yaYvz43j_DuQ_oA2>wLd#$P*>^?RTa`jgdGR ziMK?*fq@6F-MRChFz}p*e|)%zfwmlff7Kfd3lw+Wr z>1pLAz<|}=5fT0=I({#@qYynv$ETaQ{7)N6JutX2^PkXBa6g=W|1upJJ0k9gouEUl z$=95-hmMxUC8ti1`c2y%s9Ebk$Kb~Y(K2*8xVn0ABC@2uuBNR{A$cTvYulEz&os>Q z9ueC{^8V_w{);XTX>jZOCjTajhIsoaxz+I`AKz+}dj`<(!!7YO#gPVq`k$kE6dG>) z{_KQ?T{c63uuf;%(jf|{C5mRe4HVqI zZSu$G5e179_>4?*DY(bc^^EMp`DAPh4IGh{=uNk2u$6ZV;3w--XV(|I!{mF=^UCL&_$fM6&RYA04Uqh-@7i*h z&Hz(u%&9Pu0m&iW-bJL|_V@}0SF13QNGqX;MKBSS<>YN!#ze_Wp?j7KS%_2Me7x$) zLWX&8RM=@2j3x53K6bJoXK1|eyu3bAuQ@+|?5&Rx)dRbpo!7^y6r-v1c725OJqxfC zHNfEypDNRA4X}Amx&BbB0rE^<=gu!OfWbh;n{NXKc)0n?hsBbHxDzkL(BK$itFCGL zqDVu0Z+x-fX)fs#Vj6;WHyMK8M{(ZeIYY>VZIqqRGlFfVbr{#z2-{osC`X+#!swgf zwv9DLkkV1tT|8@q1;5_;zoi*t(2(=Rc)KyWd^07|E*V4MQR05_PGfxHKeFkPxC#CT z009606j*m$&F>dCN(t?>Xz#u6ZQbtfuC6i~QfX+RQj(O2NJQFEQj~~_h%(<46+$Au z4T=y=6=kH~{rz=b=XpKnyq?c_o^#&s_b2F!|N1c(2h3mcOk3)(1Ede^@%4P<0M4C_ z-I>CU_>|$Dl}C3(ndEh+!TpXfT*yt{*XW3C0}(6Z7Lh>gI$*BIAwhimzq2QgkZ@~b3o3oXPi+fC6xlu|O)Q>Me%Y0JND6gtk4uk-JQ&@riN{P*nrP9Kt@GeLCxusvWC6Vao^=j#qKVSg~d zq3%2r^Got{Qyw#6@N-F==r9vzLB3N5#hvlSvdOU2%o%ol?UWKXXM~4*B-KSb!Oy+8(ukM{>X_Tvmefg=}F7>lx4v?%zy5b1q)*2TUjgISorPw zzAPbFIaQGq%5uMg0Z(3RS^W|wW^$QDkQgTM$39-S@Y;^V0VB?*A zqx)$R8@D~A8%Ec&acHddoNpW(L~Tn)&1^Qltt_k3t7b#~zail@t!%UtxH7v3*x35- zkJR-QDb;RusRHRC&okw0-gMjv)@TsTy&wgt@rVy)-&Rl?&g01g{1H7n}Z@cR1gb3k{t2 ziVoxAn`T|HYcdxdm2<+|P6+n*W<^X~;o^43@-?qpxp?!;D$1jui(5zchwb{s#XEm4 zTU3gNNiJp6dtDw1iuL8w;4tx-$iq3dDsZP`K|W^cG` z)Vjih6?KEy(qIA! zudrsjz>zPv+RWDlGoHmWt}!miuqEu0Jmi8S>(s2ui(CYKH#U6wiVGgNJf8Uc&;{+C zmR#wU?nuDCKn*^|<^R3;X~9RIa)et5m5+|d zG4(-LJ{bC+zR&pbu_EQN_<_xQ$Uc7aju*#AP@P({_C7v(7G90lIKoGAT-l%1*?e5d zt#OP$$w%x4v6P?^KK^Y9PPkpp$LgH*UuG}x@m^RjuAqvKwk8qVyO;UEdN)#cEg!e@ zT!T8V@{#R(+P+U<|G5lks0b|aXXp;UD||e$SXvcd&Bq(B2OR;GeArY(Jq{G)rK-OO zTX~v~ybu>2v<&GCra;J+}$}a)IPSy<>SFToCmmU!MBd1(UO_ zHPrvtH}h0+K)wr_3KKd^5?v7Fts|M>=K`a__@DQkT#&bWH)C3Ge=+|K^emp`;fWi= zv+h40w7J_u`mga&xiX7(>ljb)?kVoJVLaRbV?dn0K13U{q4J>rDxrm{#6!^LoEp}5 zF8&=mofX;4#f6bmmr_r05x=db$|#zPr>mb<<~wsS+L*Ijb0rs+Vad8m6C7m6hkKrT zB(RCJK1vY>eQ^~ZBcnL@aWFARkIuno-7>{oL0|FHFF)swvhn=eZ*u>AHj?IT_U7lZ z(bSMw8xqRKiM6Lx{q5Mu{v+38xs;7mIg!+7y(}o?*GrC9v(Rbn^D2HX3*mu=e|NgF z;Jo#g_6=1Qvfka)^%!$T?w;3H%kDZOqFzx_G2Iz1_D!o|*E=IqV&+?|o-C6B0=*CFuYr8lDW^pKs2@iT7EugZ~)Nt{E`c(8fUg%e#Ai z6*2HiWrrVeGXs>^PjYp34E$P;GpCm@u=$sA!-+0Bit-<93BO3kQmHfNHFndH7@N7n z+J%mdLK~wrZ4Fw`Z=?hsj?DAOHpAk%hR9fY>Yyu5EOgU4w zC=Dr(4-Qhhsi3VE85O-m#e2CwiOUkHXo?RHJjth`VBN5>p&AuKfu*~jj8ov9p?X+Z zfL9IWGusMtD4=Zm+&vpafs$)Y*bxE+)6CP0UWiffUOjYkM=u#78~RO+1-R&WCZE1C zm5hE>xy->0WSFe@@5Vd}GR%`a-&u%|v6gi6o8}ECEX)%xqx(5Q=7ZS4Hc=;>Jh(}% zu!e-y=UOsS>2>vyX-B-2DSz^y$Ps^D#gxR798nQFwDDWN17!CXJb0bzfWhgc zgQ`XjXgDu6@T7q93?=jFjH@14gpDG zYlEza1bmG7CG_l#4H`l#W@i#@P;L{jagn+W+%Ibdt-524&O4qf9X42FeXp0>^Lf^g zG)6>ai52*dVh&|HS;0TQDz<&l5-pU};oq5-xU=bk`7tX?M6CFD@_n}jb|Oy!r;6tQ#?Bzwta5Y1cR9`-rnS!;E>s(^qA|$*mJYWadd?-%8p-3bW1gY@!jvs z*Z($z`|YaZ?b{4-qrBi9dDsAngRMWNwi)2?0}l<(oIccNBhT+Su8;5A176LT>Z5PW z=#$qQJ$T6vYpNyd3Hqg-^^~B8<};HkR{hY$N!jp-ldOwC6}7%2t98-k zowv+OR~NK}&eCre=%RVI!REYAIyf#F_%x(V2ivO(?~B~j0sU+10gp>MsF2FK9d%X* z6T$OOA1~HH)q%*~i>Gw3V~y_O*is#kbAKslR_Y+rV*TL5>pJ**);I3!BON53SatGJ zmk!Q4mu_D$p@YbpcYd-XS`is7nN<3XIfdhkj*mCILy{@%}pmo#_ z-rHx0t5JGx2Wku#}=E-`|L=egFkwnh+|U^Y`jj1XF7pmi?K2y)cT z30s?uaIehrxzaBq-iFg?#oZ=&@=GUZqlPKO3q_^3Y&Hd}L)~zDgDGed-%WFc%%GTJ z>=9^WhV-bj3x2qpVKkZ*{wUcDsHy2Osx-rRiubAqugtJyirIB%&J2rWFVqd_nS+1c zw?=40IhOd&`kVUVo+V=aJI^fpW{I?9*I_X^D^UD5T5`x%cpuXe+ZS#Hl_c%2`nguv z>sEJE8&>#qWzV_ZZ&o<_g3gbTwZ`{D4?6-$*2v%U{rbL8YXt5!5DzX zHh4RiX`y+?2G>o?^P^tdz+(I1iM=B>2sS=GWhz9#f-`wPbQK9`PQJJGp)mnVRkeGf z$OI(X<<6aOBVgy!>m%X*1eBjR7hx7jz_~|XZ{0~CAe8u*IVWCEz~Wmn)lDG4{k{10v=%}B&g%w>F9h+L`{mZZ zA>gOp;%`DvZn~JDQELH{vx1=^2{W8 zmVji`Z23Hoh@hp`GOY`VxM8{Pr|BXhQg;zml0}J-dUEPRrx+2lR~&EYFC${{z`Tla z2_l$%8BPQlB21Kl+Ylv_yY-#NF zBI3md?tr*I5o!$T_m`nW_$j}zzZ^wGYjQqcBA$p`u6fT;G7+L-ONbdqh_KQ7L%yF& z#J*D{#m`EJsQtKIbkijwVqd6)N7obaS0&)(?T3QztY`Yvb`Zg(urGOiAi^}}MDdj= zB6jRDDoPcx#l7n~3{z!Wm?SQqXKrST_``om&zZKcaZ#GQ?PCkesx*aDv9^ec@-+W^ z%oai+)c$uBwy5I1>tAu-7PVPRYz=#CF}`Jt%$>GH`kHRfebRP#6Ffl_HMPTdXPVFo zt{oyqN+Pa@+QICS)tJN~JM1j}%G0l~!)wd`4m35}q4|kw*zRw3;H(Odj$URjz}ErY zW(#{LsvGL_yzP-xUhvrbpgo4hvgcB-*(2Ypj0^E408;K*fZCkeW_qkJxjuS`nHri3>nB5=l!||uX>EF;|nO0~||tSR~A&{JoivT57UXJ>E| z`j+$Ov*5JFcA`>=g(WX8UP!bQ=$a=A1vOk2aswW{I1s>sxmUJ&NIVNa?;Y;cIL<;| zW5u4_au&{RI(NMCCJWxSFQYr3v+zj4KqX*6knh$Si;@`@sBSw3ZF~!&!HhHL`I|K54ABgAIeJsoa^5Y*Z#z%=>SW4c(W$q{@XH=ogo^zLMr( z*BQ?J!|EJ}hSY>_G~*!Lm?acW;^2>Df2A&ug9>X0(k(9zwvp2MW`jB4iPP~mh69V; z7q{%+%KJ4>ANF#w z_S3Nvtu!w7#XKp=&g4Q&rgMS)NiM#KoLZE2MqrN;6|YuuG1*_&Y<-oB)d$~;72o2b z`taXEnwc8v~iJLU7GasH5aBYLeJE^`-plYn-E`1ZLz#!H;x`sW>O4Fr#QH|)@?gVyf56X( zhmwlY!+Brw;--+TGm5PkVo-_!ic#656)dWK0h^h2=a)^Kc&b+p_+upS_vMM zG_;c*3eH*SL=@vqbMcIyQCIwpi&uX}>C1b#80Ywie0aiziBH*zXhA(9R|O>GT;SsL z=+4l_TtPiLdOc(r%)#@7;Z-__G@$TDOTg$axpIC zCt@i*qZ|wt^#@J8;2_2~qAs$QgDvvmsuMXJD2OT_u#M#)O+G*C^coJ-ZoXGCu;9RJ zZRw|A3Bh|Fv$NVY#0J~yX$Yf*jmOI;!+)G*BVh57QI-+nf0yx|LAa3-CU~ml#YQNJIgK<(9shf5a6_lj%zDQrq`L%5nr0C**r_b z;jAN7+aJ?lk$Tu&FOP<0apjNx_|q^cGw8L`mHo+>if-q#--iz6ecsB6Ii8X5Pd_pi;9AYHF;%vLGVVoV@%a(=u%Ge{ICZSk;R)c@f}BIM)u8hzMJM9#DO)yI^HNU=P-;r2}ee6{PfTD=Ll^1Us7 z*_;hDE@c>o2=qhgQ^LnmfxhT0-m_=*s5Q2IJ?zktX$`wD?=3&|t&wCH)Mnadg$|FU zje3z*P-@v%^?aEXN+a_F6fRkUlNhc)$hJhkbL-dEFBWi0PC0n&fCchoMuksmSzw}q zX*S$q4%Lc3=RZW5qx|SiqKJ|?8h1RGzSk(wfjix1og&PTl1uJoDVX6@x&51&R8y#g zz5Z>|W`bPy!!w%dCiv;)lwK8MjGVDC(W(1JsF_abe=BN)^ZyRsDd8AGvF?;kY>okP zDxdh7ztcz6$l~9sD*A9|n+IR>*TbLHHs+c&y4ZhmUgy$D9jw(3o6@w_LFr3!79(At z*owZ_fB&Qfqn7hK7>-(aa?`^`vrrS42AA2y%xa*Sn$W8qsDV)BK=$@Vb(~3b7t7L7 zM{~8aM8q*Q6sCWa+VMdZn$znQtIn#RS-;14aO+CApS!wAowNcH^GG3KO3HYcxz?$9 zP7%ok+G(y63YcAb%iU;39{+A^-M4y?JfuXcJMvYRBQsu6b($xKofYgU>0((#AJCjO z{w0IfiiG@j9~tZ%ywMc%Od1rG!sA!X#`uxpSMJUbTmx`{}^=k0`N z#Z^gM_{i5350k_h{bT8dx{^2@7~%W)vjm2c7l=p}NI9v!e1ojy+e%>TWU|wxn z-X&`ZxamY1S}`TC@>gEQ)HVrp`!sxZy)A*u_h$bIOG;vVG(GP&PZHJo2h9p|B(Z$$ zjjI_SBvJNp$}Pc83M(0Asj5X%=t;e^DqKh!lP*7Oig!pucEc*+Ki{R{`T2-(SELNi zZ9dg)^Fszv=TrR?4$49*TP2;YAcxb;r;pcG%i;Ra*l^yOy5AX@@z$Hx-a#?iLQjTz3bK0#*{FlmAGSXfiedDO|;&y zSHS*}P{*D>D{#!F{?p5aN*4+6;Ksx?)#~$B04*DhSRBv;gGLy71?SqToE!-gK8|`Z(qHvErD60m8mFwCulV0NwbXudXT@ z;!T+G{`={MAkK46*uB6AS#~RE5phQ7{IOiO>bnsRORShP+inceEe%q!l8Tu#r%-DWW|~I3*LNm{V_i*zaJ51!K9vX?x7@*SBKa2xeHxNh7Py zH-~#pqJJ^f9Gsbr5u|!nUEfaj6y3sSEaQ-m!GCmefgrj-W?~e0Cte1NHI-!S%OPWq!9*NsRA!c%2yOS-#;;Vl= zjA(>~Ya=bk%^ry#Uvh7Pbm>I8)p{ z@V5YG$bszgqmS*;bT=~*mJx#xhl7kln+7;u2)h)dbp#g2GZvspY=pwoTxT=Q$zIfBxcmtD5Y5yu{k z%+EjVh$oF1o@W{zp?&rAk?)@!F+It%5)mUI->_zyWK2TiVd+Ctt4P>9`Sof^GztF$ z009606j*sYRb3Z0CRFB-c?w15Irko}JDn?I6N(TO5h_a2tbtIH3Z+3p#x$$@RFX^~ zR8%UJ$P^iRQ+?oA!~!^6sg1L3!6uv3!q?0Q2(<+Hef z;@>p*|I@F_Qln$n^oi=7bUKcN9oEUiHCDrkX&&en<7`dIGN`*=Ih! zAt0Zuwld-y0rK6*?Z7DlrwR>^8;d!?yvlCy<$Nay8*$VV7CIrstSqC=#tAju%ioxB zov`)kncQ4oC+MD?Y3_<}Lgo)q-->-sNGR@}(#do}d3bMzYmpN+$GGDmpBgWFPCBr| z3I8O$lRpkRLF>?HWQ~wBj(w-=SSmXsK~$tO&deEmYOkgL$8iRCXP)ZdI%h<5FSl-v zr}Vo%x|OG#G4bSXk4l*{cI*sXKUMFHjLYxO()yfHVpndeA;Q2R?Y#U7Z3ZrgT78Rf zW}xZgt>C&K2GXlb9ZU~0;BjbA(8a3^{1#|%53grHptSeFuVG5oPAxeu=YmSuWy{*R zpsV77BH!NyXFP7sUVOj>v=4L2KV5Ud>cSNwvzuMe(`7PaJm!MN^UJSIDllQtknWgi z%Y=%_o2V`yCag?KVn6I;LTGel?CCR1bZ{+)kKJUVZojFXc?%Q1X{$d+^fS>WJoq6+ zfQ9P;scxDIEX?~%yKzFFg49>dQMt{n?v;b%>0a!DWyngJ(+E(WkLkX`NieH{xg zo(?7%1+%b4_h9)JYMlR?VvS5H-r&0JYfn@26ni~=Q%vO%bjbd7;%*k!|9!?*I>>?% zZK~WOg@w!8R9<9evanR|yu$DW7OJCM>!yoXxFYLgyZJVihxD2U%WGKB|HnQ{w6dVb z_`JiVhl*ELTT2^ep~^w`)S^EuWYt}w|DD5zSag+qlNuY+7FU`UE@30|>v4-Q8XK|i z-pf~duwh~Kx;G+-4f!MBZrR30Mb|xT#lvi*SM8OJKgWi{+II#@rEEm+jlB2y5gV<` zS;yyhvLQ54qO@^<4Ue$1CTV}!IMTzKeP2F$JJ!hu$G zM6iZEjtYNqtvdQ6^PD`QI&BUmLKTMA+PbzjahZp5$fdN+Ke_VaYx&iD1HQPXdd?E3b7CKb%Qa3Jwhl(n&B+ zcTU&ZlTaAB-(hA=;>hsI6rLH0bU$ZP7b9vtdpcX(sdc}ojoP(Wo5ZK6_h|)cBrZ?t ztjMG4qbJ|X&X6N9&;PAT={yom&8*2w;v_sTvmOMAkYEY;ED)vYyVt3t+3gn>(MD-k zdZ;YqxL~`lwK|Rl?z(Ru+r)tE?P7i4jy~Wh4675T5T&A3j+jIwHmni9e3b& zVht6C^+sWm+TZaW=g2p=xlq+M{3cz=1?TPSm@U`2NbtzoH+Gc^5km*jOBcD&KlJjK zLk<`Cwd{JyX)a1s3~Y=}aIx)4;N|9IE{-M#3tvj&BEKqR&5nIs9F}m>2-(erM(gJ( zuQ)E+Rqa#A7%muJ7I-d*;9}0aDwWy|T+EMOE5r`sV%Fr@>uzhfc#^rlzIp{0A4)pT z^ty3z;JxnGayAzcHyY~e=oHQy&oi`bxLE3D6)|Z{;rHA0-4b0c{?pDelUl%qj?n3p z^Yf^6M0EeBB+SL-g(5Y5lN?wKHi^#};6UEv?GKVVKXShXQPM=&7Y>TGKjdKK^xbbS zOF4KobY$D#TnZ^FKRIpEV8cH1!_#Q$zPi@j8kf?|!lizRjT`Q;&?*|0 z)o_x99#44HEf0iTOUU66Nf zPE_z(7c|T!_6wQ1ASmsotcQ>bNN4Y(UL6eh&LmWBD_|hXcgm)12LmGSJ{1X*4Ae^8 zP~WP;z`Uxn!{I~Dz;K%OnupG~;H^?WJIxs){mM-$LCz3gJZ>0m<%|!BZL1cFQTl?~ zQu{6^T)G>jc&*e4Q*z1tGkcwoQGBPZ!pjMYvGz_uR6nvjdQoiVG=V?zdi^2K2`tF@ zm8X_X;E>1gr`O>Gq@Stpj&mUJ?O(`_i;@H?ZO-Zj-J;`SxGI^kf{y-A0b$9LG;}$f zsWv`MgIcvo^EpczOhu3XtZa9LSv&2&*sYF`JG9@qUd9nCcbWX{D_@H1t4CHo_gIQU z-={OmM;zcC@%Bb^x&yNP?_NwcalnN5qk!kl_V9Yszr}cqJ$&{Zk5Qj%kLJE?x&6g< zh}mTDevzvkUa|$IbOvof)a57l9kT`N;Gy$&CblrJz2>gaYJ+awCCw*dY|u6D#+3z1 zHV~+O^zi9DYqTV#Yxu0OhLz#H#Xf@8IBovkjG1o*KdD7SL2N6mu5Q%H|89xe%>~6e z8J6fN^emCKv4mF4BU#^W3#1EV9XY(u0xfdRRZsOT;Ief%tgg`y?>jikg9? z_UmFyV11AI-K%K{YKVA+T;nAWxS%V4IoTMmFFOkM4jV!8v$n`HZzF_!DDwr%*XX7c*+d8g)PEK>FTlyZMef_z;?!k)EXu z+vct7V}EGj<_pokFGwv!hmt84g_;;PO;kTHOA~sprUxe;szde_VWk$Wh67)`Z45M3 zQN&+!GOuF++G+$>b;T>=%?H1#of=B0%&eNF(KH{$oQIm(aSBND|DyCxa6qH2$pnUb3Gx7t(#c8_W3;pbfr?i!h&!B`&n~sT@%($eTE^ zge#1He!>6z6$G(rsm0@koB#0dC%lVX`+S<;yyM3BiG4r$*^{cW?TVv(e=7<5?UjA} zz)C*XxT1%za7b^2(eZ*`ukgWPPJ0@^YSY{E^6TsAeL|TPL_(mf= zyH#Aq`SPzjMDD3g@sF>5N0XoWk6&eHlt2#r-?Y6Sh{QW0YyPs zi1K?GtT}QJ9@lvDTt*(`tg4S9S_)X#s(j~<^L%Lcos0;LP(-49k?EHUN_a3_zLWn- z8P_Coh31Q?;MToD4&kVZPru8}@^-2rew2v(RH2Sl9t_QE-!<^mj~#F)Qxne)e>93- ztOdEn8)X&mYoT3XnMXZO8@DdjC3tmf!-XDL=^LSgchSbv8MuIzZoLR_DJfbql>`!^gttJ(PH$4sarp2S&Ti&yCkLJj9?$_+IvI67^ylQ z1;JIuXui-Q)8w%Phw?*btcI3gxv$?;cA5!#*6f_-Dw(3~y*;2ms|EJ`D=4))X@MKjd!1@KEl{g&+B0i`B@CnHIUZeaiE6)n$!jVt z@%(qZpQ4}@&ZV^Hy1H4RacV5gH`@v_pH91P>9<1Xo{Eptw$|9NZNbp0Bx@){tO~b! zX^o|OFVA<@wLuB8;!_FMD+5O`7SozL&Y0wILyi_|=yY`|z@=^^O ztG?SKx%aE0mW=~;?GoGmY_9|EcrI+|uXDhg!^)f^GE4EFPj0))>ZQ1!qT~29cPVD8 zNSZ$AU5eJuE;mPgM+m;S+ON6U5l!Xlv-lO1E*Ecl?A{^62IP0*~WH;yY(M!T(mJ z#IU{-;*WSfI?r*!%8&;}f*YM6#Yq1*ndAi4$-c~jt4=UY5i?G%bwbLOtd6oTP8fah z*V;qW88fSU-B0N{nEkv4MFhFX=TIM zn*1;92OIYk7ppFj=0LwObbHzo4&tJ$|CTM|pmBWb&i}$W_!_mVZ2mEd-=4luXI{ub zQ^wq-v2_$L4$$oo{Ki51^4ZdV#JC{;?AdnLfD4(quZI_tT(BaYb&qc5LZGE*=42Wd z*A6fKwdw{J;?MRgcD&+ZsIN~>a)yhX9_0nDS|kqtv$yo5_@rQ*vDLe9il@5xthtd& zV$*3xPIKBnicols^yW^U%O*WHngvu<1aUR=O7@Fa3;4jNsu| zWrVh65)VTI9}BoSJS;k=|01P~hlp{hQ|rNlyq3uE-OW54EPEfn?+p*qEq&McA9;A@ z(DmN4kB9P7Yx>Qu`WK0t z8uo8321uNfa!(HLrs~veyx(oU0@_yc6uaa};ki zlCS@nM)C4@!ap>UsBzkpBbyUQc=U>h-`!5}>(zQWWsxL8ZU?W)*+>G1ZuSzvB)&a2 z_d4iL@%wURa*;2I9!-;Nb1B~bxFO=^KZ>W5t9DK9rue?y;y^X^6C_j1atztzK&tD>aVW;A168yH-g~e3d>1DHuZ?7f6P>-~Y z4A5EA<$UPZfwk;pLIBzAraiSWYkPIoHby)T!v(RNYsJGMuj*hk^#xP!FR z5fT?d841x8ekOJm56+yT<|(g^Z_6eT@V9B@l}jW#XIIMaFC_8hZtT6a}KwK;?>nUJ`zn zpBxN+Pa-g>;whiXBRt_y{k1l#Zix=73mT~Pccsu!bDfND4(j&sF1&9&e8w>Ke>?~nn)sTnaFYZtrQMI8Cx|rkk~33 z*Oo@@&vWx<6H0C*X!@(ZloAx)PF5X1YEI!T(M$H8&#)fRPI4wP?S_72eHpueqq>H&3cW;n(_ z+&jZYyscKP)HgQ#=F8^_wzIL-H|TT$pN%@VQ(;|2Y`j$HojQD)jVxx_lXd&q*!JXA z(vnCvcx8>-fBLW?+~2M<$z(%7Dddx^IU8p;e)%<`#>S?HuhkmF*{Dgs6>dx2_wU6P zSUvf~!l}GrmHAC9JQ%aSRehI*cO~<^?_Xu%n6g93stgt)YLC8su!n_f25OIghqEwu zx*(LliiN~io#Xk=EXb|gQjl)ULh|I>s01YzE`>?lmJz1>1Zxem2bnN7eN-{GlZlZF zRf{Y5Ox*r!xHq_fi7}0rX*H=#G+MHxq+^-X`98OzbPW?b)NF*GJ2O#2dpNqnfQjX5 z8-JgbWa8nO2=U{?E?B63E0RIIpR>x2V>YFwn|96M5x00|M`p4EKjK zpmX?)56)1tm@o9G+8I@PvaJc3&WQF27!BUy zjLPs;y8diutZt4ds8w@@_=*)Vf>Tb&@EW=v(c%Q58y9>+3!LyFG4$(=L?<{UzcSWa z5yx+v z6A=5Ua7ss<0HIYIvx85^LE9(NfnjvWD?RoWn@`8Gc@s8`PiPogG(JKLr{U%8T3(4P z4OMQ>T~}8-V(s|#H^Lhn;kABUM1Z^_>UZiGtbM!`ft$kuLnD@A*S%B0e3hkeJzBWp zbAtoK{J&bX$2-7!vF(0cBL{3>=iS`#-X1F61=5_koasfLSX6TVf0GF8RgReQe=nw*JH^5nKGz|8y(A%m(fo zr6n4CY+y=Cf65WIf#BtnA!kahvCQn>ruD0>aV%MAu7#jA`U-?*7Zq7SFh9Fn+S>|Q z-&b}e{bva;;e*P*E?NR{)q8exE#XSPdDv*w0yDwlWs|8E;H<}%%T^ZH!(Gdad}oe> zCSU*cCz)eYM%uD(Cg$)uGf{Z1+YB0G8;kcHGlNS}V|6*m@N zw>JhyYG;MhRU??*D%o~W+6c30X4aE&i!uJpXzF0^B3zkNSLj=|2>Qvs-^42np&pf+ zKvy&b;ksEtaE}2-299sP_DLTNNp15Evh`6~$Q{!yTZkz${Jt-{5DWh`<;HB+LrB!Y zpd)W}v1qQuUo}D(q1N>~=ofX+kV7}$BBq1vXvcIiQX7ZfmHTh)(8BM56$kmwS{VDu z_fjs?M0;)L@J&@s47f1XG%9JJWku}1JL75~)^Rd^*Q?^zcx$!D1r<~$vd$T7Ux56; zsVQ%!G9pVt-d&xegwlIPwB{G{5!@Yn-*Hpg-So^ zm#-kNy=RKvcS4T%ap^bxiU+5q*zF&kyy32V$y<<+J9cBQ!WSVz*~a^F`e6~`=*i9R z=Bdvjx}N0OEKL_9zA}&W)%=-FJp4S<-oH+Qn0U)nmCBbSwvszmdiKmAe%l_)8W){M zJUejF`i-;{am-e`ex0y1!M7<|*c2sAWZ!d)+SMRU1ZS~r-(n=yMPMkPRPw<}V5hEnhg)>XFXAuKV;&1a@M2G;P z;;arYA!6KnXN{$c0P#3QK#FEDLnlOC=og<)(bax=MjfJ!)0tY^Z$Eb!q9=_C4MtS- z(o_Ba6PPT0NtaeAIq_xoHvXd(jDgc@+WC)0j~G9T`OM!pi~jZc*I|Bf<~qm0?4NvE z{nlTrzy0EC69Z3&1OD+3k^z@iuNQ)K=-g#INm1<0{y5})PYm5gXIqVeB;cF5aks(n z92D=^9XfSH3WiQx_pORDSaDpP)4NI*e%4x^`WNKzKL7v#|Njh^cRbZ!7{`SWWo56d zl$Aa1y||a_?%ghx5K&2#ltNS*ipnUI1}zF1iNYs-WfaM1YmrK_5~b*O|9Zd9`99~I z?|GebKF{Y-``cc}{H6xA`sI-!<{FTogde7C(?nu5>yF8NEmYlACy;09z&%PgNp-a@ zW-W6p;}+{7I`8+DN(lqF96w*|E1U<1bta!@E;od(f7+!bGmKF0QT~QhV1$pA;jv?@ zj6pS8qW4G21S>B%#vUm!!RU?iRn|*Qp?0!bxBHJNHYdAtZsyI$6aVaowLCNYJ~&!! zIc5fLzsV}&^9w+)F=*zp7Q#Qok2f^B5blPO=Ty&`gSO17U>Cyz&e?t#8MVMYX=3<+ zbC$^c8)t0BvVy&Et$x;+6|TL#xzXjKH6kvN>tFB|VL*`W9V%~w35DwepUQ1u88dOY z!qOIgW3Ho&y|!>pxTL)exW%oU(V}dR;)QFM zKl8K46wXZD^JO-IbHv2X z$!%L29icSzBBRXI3Chpb!Y zuk`9IGZ$pb$y=|9a)Gv_s?3Q-7sMG_1sIrVAjkQ=&*L;XL!+`)cmpEa4` z4&(Zy-H-d-(HC)kM-asWKidNSXrz04f)jP8g#yz>q?(JrD0tnddAY*a z6QY~@-s|!_QQ1AHQ6A-qIUm%YbzJlW->r_3@z@g*Q!^e+jC;b*uwvNT&D>owN4FRhPzB!WG_lJ>C@- z73YnX++&mXu6kouSf}F4r``y?{;{iO(i;;G9_#Nkpyy3V5_8eGow?qEjKkl8yB zxcd?fSL4VMPLF6%(YyKK^$!{xJe=ya^ytXBnd}isqobHPH^E;VjY-O%0>4+JN5V%TsTSZ+EO&dMdfLgL$i%}V2zhn zpJnjyN@o4=*3CSqqy65gWFA(lM)W)>;o(N1|Km%~cu2nc=D_Sp9@f21uxr)l!(-#a zIfp5H_)Kq-JM7PgEPIPd^8r3~t+S22eua<bb=&z&vp^w(PLB6 zb2}mC@Rr9USPDV1EOU}H72@b(<3qXPb^Q+RKFw7XVyzs<{;#YMjgX0d^;>`<^XenS zj{>~ga7H%1Nq{rv$M=;N37|_WFnXCLfO)4gIbyeX->odV(^>&ypZ)DGBnwd7X0zkD zkpLZRZTsI+0wlH`Qn>Mn56?qIeuM@-I;7-iZrAx3Y3XEECh;M&koLfED<7GU>MI!{ zK0>m?iItAxIC3GkSCbFX`mV3P{_v16awc^3dmcKgZrg=C;32H|qG?ry;d0_ZQGob-V}3O+ zLjPH?X8aK@GVK#1!(zD5V$rO3g>ykYIsMx$hzph7n%M*&E~Jl@xP=J0_$=da(widsjjK!Toe@_TajnTg-+jZ{Rf&{#IZ`O`xUuRka~SyO@@ml zWQl0KDGrPplGT@uanSN}YVYoE9IT%i@0s?I1KAgCA1}P*Kx)o{?cr@4Oz{MsdJP;j zsg%6Pt>)l?d3xMvDF+i1Zx3$G=ir6Ho>`q2IH+0OT+^1pfn8PD_?Khic3z?4y95rN zN~p^n+r@!SxnIkdP!23tY7H3#aPYC>!M*=haG>;V2dRd`!MU}+()N)#C{9gQ@U!PY z<=4UOdrdi@^xi*9*WiGpA6O%j<-m3-`RIQWY>Y7M&2_)9@iYC<$^*~Y;4Xe-9rKWl z(M9^3A=VSa&WID$7um=;pi{<37JvVt*s2xHM!N$4=amiOIIH611AI2Bhh&dzab@E} zpTZf25gS{oWe#ka#m2pujm^0uES!4uXhYWv7V6DRa=EoE)FQik(G?aXKM!@hI>y4T zn^m{sB3Q^ta~z+uk_Fv8e14)k3zgEQZYzvf$YadSz9G$metc%n^k*hkZcUwZYi1(l zVZ2o94JOW-J6l$;jv!cP?Ol7wAEE>#NeFn{+ym7f&k*Hqhjb_7LEq&*_aiKW2)+*W?+mqCt zw=efbd1@am+TI&ID^f`2O5UjUH!F+&PQ{ln`LD8%skm#Lth_#-il?$amUP^EkCZ&NDX{2W~sEKNntxt@~ay`kN~-LtDewbt8;w$Ax{L{D=Fgzdg9$qQ`dG+PaJy_`bv79C(aX3`x^YE0H-WNsyOVuiGsi9H~5ZuQ!oop78@B*5IzzwBR5D!3vp!aP%0Uw z$0Ea;sATAFpCQc}^+3JF-fH^{4=l@As?#U-TZ!9^t46-M!(h?k8!u0}!$;Xh?j_M3 zHzQWuoZ0J!K8d!czQ^6*?R7xzor4>mdIemX*-gS%;qm<^;z=;y#y#j}LPGQ+|FfqX zi16;*XR6UX&8>Oi#}wNbD;Gnm>*fN)pgD-&fR7=!&F4;>hBa zu2|@P#{IseE0z+2xSAwM|23Y6!!#(+xFX6 z=4d;@@I>6u)~62W^?Uzs@{j{sy~l5`JRM-b_?1yQWsg_9mAA61?9q`#oA18M9+8(V z)PFeJW9{1P+1Wqs;56Q_rlHghDh5YXownP-f=j-sVs8hd&q@OMVOz8dX>txXZQ*bG znYd(=EwauYKci`83**Z8Id*k6s6D#W`ys&wRR`6VyenFSFOT-$J!`fIZlku{cg|Zw z)%siSZB1(|dQmN(ooog7r}X{5WUUY~CvVoJeU@mC$mY2IvcOR5eX|eY7FZtX*+v{N zhljJ`j{8C8h~D5dDAThLS3m2llkr^$ezWJ|PcIi>PM!2j=86UQm1J%|)?o(KO{IsZ zLNiF~oRsr@G9RzC_UeZU=Ob|)ecMQ@DUMB!JpU;)#p6Sl611L~piN}&n7zydgWun) zg}pMy6;aEsV`Wa{j9WkS(7%m3HfKT?tERpW&?R(Hx@5U$iKGtZ(N(r^_jHQ`MTSKnu;0q$X=sv92a*zt>HEh$jL<=^RkET6gXUmTzHC|nhO z0+PM!F%_63ElcURq72a&$F3u%l;D46nf#w;b6{(*x97OkY)}@w%59F5$K;jVeGfb2 zP-Lu64>y;^&UrQZb9c^!KV4Mtr%?(wwez}$G$gURDl?41m>y|%VI8_@Rl;=3_ z+V9%rru`9)`s20VZ|T=19UrX?S>V$luR2&uicO!481Ji{OZu^EtNHud)5aLzXx34? zYY&&iY$~aJp?$G8TjM@?f4^PboCB(^8dFWYaym>~Mhu zJ;$35D^P6H9d0kWJDbu-4-b9zU=F26QD$LNg(4;7aCpaw0wv1*kZcm;U!i#8<*XhLYA5W0izWO2~zxW4PUn47N-tYif?%i(HDXkvza*?s!a6~&f z|5d!n^>Y_%ySCoy3|jrX7U@$7{^Y*enN8A(`P+tTQ+66W*o>M9w>+9x>Z~=9R--Cvn|iI%t3s)zf&St8CE${ zs|h745atZT*eK1#wNK3l%C@QD%7bHM)(3T{7TG(ja@T~p&Gpj@(zWoujQzPj6K<0I6(~bxGJfoanS(((i8ww+D&)pQ{<+Ol)HJvj;{n z-eA{safdO!c&X1mz0d>=J*)Nn-kD&L;~)0Jlcvx!zO=WKF&_aQj{|EZ&0v`_2mygNv?os5Ai(&bPn1|!EhS>7 zjS_7!+PnMHSg$R-e<=SM@Unw;j(SkkB|BWB4Na*^+T-NhVJ|a3dnnI8^Q5=N9=PGG z_S?V#LvuX&0kID7uYp(f8wV(C?Ro3r<_O{Z7s9)ljtC9X{?a<(2#@(;&pxkk!p^x* z{$rIp;ewr%N35zdlD@9)tJ&dAM_#Mg&6Nnp|IDwnXAqH{ z`?2`v7!k6^&n>Q8O2Rxh|M53vBuHC$e;rYEL#nQX&a7}Z#Kdv-sL0flp zezo^jN^wWkATi`yzdHyCidwmB57;>_eYO0W2j2X5RE8)`M!rP2uJw8{Cbqfw5NgPH zygE}ocQyrB(Bp|RR^FH9xn9UFu3+nVdx7%dlWod& zFX$;#p7-W>;T|#8>qdhY_9k-qH-^3N==jy*Ol>N*90~XG@uH%Np58gKiHe*38Br=} zRM^{d_n?{z?uKsZxnMK2gsnZ7)cGA#tt5dc70u9<~FN|HE&@eqCbo1%o zH0b#jztS_LW4LAhmJcjCE@}3>wA@ZdL8jcu!z?;h(3Uo|)zi`ZI%{Y9cRKt-jGqQ- zFpwwuuCGlN`)S?iOFqF2Bwcv;)$J4m|Nd>=uW^romT6;OW*-A`2AMGzl$nr9pZ7YE z$i({a$vNymCUOIgv?ru6(RGMz<6FhVsp7;vzj~P%Sf}{3UXg_p=l{x|^AOhyi=xe& z!&nf$*L-Y#k%gGZgm1(S7JAMWRgOxt@$|$I6_zs_k4Ls=Vj~;wTRii$ve<|>te2K< zVdFw(-#7L&8ycN0_e544g!zUB?_0$|(q~TO!bA>^X2{)4xy1qhn;Uhan}ge_SIe)- zb74)^Enqrvu_|ibDxdXSR6Fex7YJPVGvc$R%Efi8k;e?lk6c)-@S7qk@{st6)U8Y8 z!MCLDYFZEvO?8@vsi{0H@KSiVuZ9OhMfLQyejb<$KaDc9_^_L#tShAQ;ha>l^W-)@ z_G&EoGM&wb&$p?HFaPl|qpkhH^FcnWPo5(m*A}2Wa>1ToUIJViu26B_B0#v3;(@pf z0XUnE62oc*AQ!LM-t$F(rv(q9-^dB!QswWzR!@jurgHzSuodDAb$(eZRfrua@e^Uo zg(zFb5DDI$bf=Z7VUsq^(Qi6-t>VykAo7RM=^ z_8}}dEJC4t!5`cGB5cTdI8P=$AMioan>zX7Dj#OFV|#8M5%Zt*!AD#8&}ONncnSH~ zov>H9*^!U*9tpX2O+J!4d_&j&<>3e+bNcW{9@x1xq=E(>1Q%jV{ciF={A+o`KTUk^ z+w1BK_waD8l6Z8d9}oMLvVJMEc$jWut@50_GGn8A4HqARY!bg;qy9uza&_%NH^SSI-aCy|CcG z9{1=8@W$eN}AM>g>3xGiAhPE&4z=y(r=|<7H(gxrc&Bj znDwN=@Kz}c>We#zCDK{2+_XjW^9~m3x~_4bEnz_^h5WJIjs@ni3j1AR9sT1TbD;Gr z6Zd>BzS{a96Qva;OUKVLp%SP=^xnaQM((Rqk{l*{g3_ln4Vl;myuB~(9S1Wi)y{_ef)5P;J6oD9Z#&f z;NyiO&9>fi%)O9xC198{;R%xpb9(1PPi%}Clu=0c#1jRP)bjvOoV7HvKJMTN+uSor zaZ;X`cU|2{vy+0KQ*(_P@+b(tluIv;qTu!+pIgt>U_+XPzmxQD} zr4jx!NpS!E+?g^;#6@PgdB{g1L`TxP|8)_;O>B!ZdPGFZeb0-f_lek;$2nY8Nd!f~ zvfinLh}aw7D$4VTAgRP9&CMl(SvP(ETDI8lDcF7V$t0rq-Un*%X(D8bPVKyzPQ)0T zy9ZN=2yYSO2A?9LPWU)W?IaOChMR($Qi#xqmUweInTY1Aq3OxTiRfGNZ=m#;*hi){ z4LmwPgtfuO8`FD;P?yUeP})w!!{_V2j)xF&x=*q6_Ie^ts!YW2SBT@=?VGB3MC_Vi z|B&}4!uxReIaMMNtov&UlStac4rmcFe1XBAmYy0JR)K~s!5Ryh|tN>FbvQlV%ErK z>A9*zbZN(R-Bl1X^LEh2nM7=xSb0(99|8ML43esT5zxE3t|4HQ06X~~4hjPVT(}%i zf9n$gXXp=3FMdbB<)32=)ouc0{R;d@uL(GjZ*@U=tri`9E}qA<(xOW2vz7EF zsqZ=nc%0#SOR}8+d&Bha7HtINFm%+JtpxlX8JrA$Ou)|kKZMEq1bqDPuy^Zi0&cBq z%=?s2K%?r#&fxO|?0D04e>#-_wJVcf&m1PeKqXqoDu#f_;)%O0;RIm#=IfXs@qf(G zdZpw;K=41_{mUx}(6Az0q^=+!I?&gze;EOD#tRKDE+xRp=F_s3O9)u1^~ywLF#(!x zYk~Q~Nd; zFJ=K}{E(HHL37vceZ?kVsJ=QsMa)m+u#KK#CN|R7mA#5+7?o_9<#&F6y@-9bg_aF&)HO2{K{<$^J z4WtVlUq5>h2`XcP?j1r-`H0|2$fPIbp03DaSHp{h9Lz{CeIH1e_ZI0;df-KCBOSB@_wV=Z`u+Py!C#Q%ZaScl=L}> zJc~UfDk5iQ&5z)aL5j1s6l9VgEr$bgz+|r93t4liw>%KZ&1q5-ja+Aw>`F%F*~pzq zLq-kU49-JdAkrjPBKg%HR5u`<`X*&tkYCw$hu>F{Bi2J`a z-*X=zLs|4+HzU`My_Fk7ewz*LTt;$MbGERRqU$0fmg2}C(SJYbAg5kOa$ zk@B+s3-L%{uaB=Xke%;e*cAVN+*yOI7s$^&w6#6RSP7k%KatM_0`LDr+P=7ag1>?U z#j9~!O320NX+aa@pb+hrJF*RbW+V#PSNoXf7BV}t*sTcpU;XDy45?N;(ftW2b&r~5 z0~x0QBB>^R=tlnk`j(1DD)P^@%DAV< z^pV)2R^(gyj>-|F6@7m4H1gp7YwvfF-KVq*`6@|3)7iQvjeLEmk4G0t|LKvu9rEm= zh|MV^lbEUFCFJs#E3)axlguK%1;{wU8~$>nSHr+|3-WvKdEHOQyKe>=XOQfp>9HHg z>3n-&t3q+|?)xKgq{~b?ryi0JJSKhwsdKz^*#jv|qE(1O?%a_v&PCphVH+t!Zc|ID zy+$6cm>e2JZe&cz|3-#;&V8YNj`Bk1K3*=Qf$uu~LFCNsn<+9#G3D6bddN?$Jswub zuQay~97i%J!`3OJ>sfo@7-XA;XKN;MLPYGwOC-yt(EWGFq9I?l3FL#Je?{BK&&(Ga zWvfY$dr}SaMw)ox7SfPWmo7-vA+_IqJ~fYg5)r8)Swn)MUrO9|$d)+|asrZeZa}^c z3HR%_XOIO3U*h;`Q67p#e;=95F`*NRbbp=CoR9QN+Wy>&e8HU1O!ET8LkUGf70InU zFyx7BAO<{6NAlS+hczODKa1|4K;EIp^l9qQ_cy5hr-WqqqQK&WT#XA5xP%l_a*WDD zUd_1jwdMc)A&z;!kqX|J5pO+OSG2zyw2=H?%`9w?gPJBG!N_-Nc}6+NkzD;VwaC!M z;ZK7|2Br>+Eo6%W@wi+A2|8Mee}*Cxd-%o+koi|%e49sF|63p`zeNA3iYq(_Im?5W zP-{f@udio6dxh?sn)zdnk$|q_T#<7t3EXmTv~qNzd}jVG8`p>8^5VLO;22up3NvE0 zQzZDHWldt4B>~&engq{0iW_Ezj>bi_&Qs-akt-x9EiE1jSVQ@AQ&FsAodlA*s$rXd z(EfB+^RMqF2{Ouzt&_G@_wcq zAOqK2IIdZS455dj=v>vw@V>)i^rR6Px}GbiZ`qI`(S4y^)sqZNnx;Q~hmzq2z0!gcQz~ zP$1|UA1&b{XMlVJ*6@UskXnxKI19Rp#~R|+^jsl}a~ zrohu)?t#R0niGbTp{IbuA2$Zhf(z{|r@E40_r>qd*RF!R7 zSTh0MXAqyZr4nEzSFrrICjpjkO2u`n5n$6H!aI(d0K<-zVI%#>c$JQB}u|~!q&Fg$|jN2H7*AwOgzZ!wYccNfjl@S=fJpVO6-U!0G-iPfRGXmX+ zIH^HtBY1|tZ9@D5FfP*MbiEy5L`r&Pe-=O@^Wa&r(*P!OqY)Q%0EYEkqv}`ys&B2W zMc3ouV|iOkof96)xOFbA?->G%Uqt27V?$6o#C0H(YzW$CLK&xi89-s?(Lr3Q0Vv6r z#|dc}0MoFy;oVVvur&L?`zcx<&i}LbBa7>UW0;eo^;J{@i=(BE1N>0at z7oYQ184d?;Bd<%*e%6Mr*qX)lE85V&mTbbMpbZiq^@6K=w1Dw`^y=t2EqFyR{GBeW z1;J~1u5aIJg6`vLtIHofZy_SWVHe2yt4q4EpiFuRgB?GT@ zNyDpKrGjcK(oi+T`)u4<3Vi59(?Ea<%L{?XoAF_~u+YJRPf{(?4W>r3c z=bsn^JV;HMwG#ua*S+dK9-?6C-@A54SOkRkT5c{434>*4zGBYp1HkU9(R%xc5GY)g zvwOC0Kd_GxTv+-9pzGy?me>t`_`70%e#e9ljI0MPInwc>b5p@{^;g`G)=npr=)(ny zo3sOaLYy$Nt@7kX;XWvM^@9|#!~#^+dv<&jZ{Mm{yYEjWUZdI2 zju6t*1CfXsTdj{TA zm{^V12CkU~^X}{X;I>7FF$k%69g9%y#s-@M6PLQbhHeyjauG@z>i$yqM#8_J#zc!QE`9r5n81XcXQS=gx}} z+r8Iy5AtFR*JSoWT6wTbvyaR~op>s409_xe~K|%`EpX@dDnxp|R+9;R?RK-d+0L`Z`|5?%VXV_7-01$Nk8>u$!w0oSBeEB<`pfXc_h)ZNaU5G>eKyVt@AQSCZD>5^Q)DJxJOo5%%6 z%)o4Jo(p(PuKez_;f9Olw+{WN;|8Je!iy)RdBA8=pinH02eNQpKep(3;rdx~Tt*Zx z@E&FF7F^N6kQlD%NJW6uu(k0L7X4Ddt9t)172M+6|{WfJA! zkN}kX;la&K5Zre}ZRJ-4L2P39`@O6CVdH2u>4v-zjLBO>81xE(ASqmSCiVb?6EC_6 zs0c&+FG}9GpTZ!2VK&^O^dMAK^`H0}CIaV^S-adxqVRIRvEnTbF_qHCyBK{Fwd)NOv=`x3SXz=FBh6 zr4<^`eL2N^fk_kkid7z-ch!U=ryidutJQ>wQKf+=tXgn`Z){G%Lkl96KLk9h(*n(K z%d^q!+K_Z|!|kc3He}y#&$(Eu4I2CjPC`sL@Mx%GFL%Phue9!L_HrCBkY4v@?%|-U zk{^Hls16KVestTYSO*G=q!O1mb--+YN8dwpT{wO%{>StKUAXS^B9*+T3*-T*fI9>| zXsz(@4$jttnU@^L|NEr}{*_PV0lwx#y}Xng);%Q}{?U z!2nVsB$&Pq8Nl~X(>G=%4S|nE_(angL-<rl`|BUrpC{-W!N5v27_&FT&q z!CtyF)!8j0XksmvDv>aT1JUx|qAiSJ_Pg!VL!rhn6oVJ>$Tfzw z8y+%&Esl!$pkpR*y5+USdV~p_FjBzz=9)nNr}p&5Hzx38Q)a{My9r$VOfTb3PXhIo z^Tx??B$(g#gipwn1iLZGG#aN-{pHMI&)Hi^*Go{{e@SFSx03`u?Aj`Kev%;P zgiEXkD;Wk;qV1Cv$zV4jVqsx{>LTZ>x!?TBAgLAmgP1}F|NZ#jl`=A18Cu+&`#^?^ z_J@)i7Rg|5Z&6swiRuHxqLUV?6xi0%`?+-l)g@hY?q@lZlYAXo++9*TqN4Vq@o#xQ_wt|&* z+8l_Ax#uGH%;EX;a@fp%3t(5hJ;bVE0sP|g&0`i8kl(oWwC|(^sA(}q!FdZfTi?(l zl4$`(;lu9^mRrDa;4qMEvw(8*(}}^KEzmq1oeBJ70VUAjlF4of`HZp5VX~I6#owLz z8Z6;`(1QTw8~(&kUmWHl<@~!3x-98L0K?g4U8{UjoLBV07Et{V-TASQUC9{Wd`T_F|74^7iIrn*r*#xsX^SgT@IjUpXw!V*~N8 zv=2FO*g%lp({_4R8%XKM9BZYwf!f5SzlwX-a2?0zePY=fV#RaCmcCen()iY&@m_1_ z}4N+b0;T;QHgrm(M0F;rG$XO8RO`;2HYYUY%?SVWa)Ord%zdMfddY z40THoYb{&3!e|MuOmW(6pDe)eWbf|#3JbVwu=Kb3vIS5JI-JyVw1C6Hh6yu=EWnic zR8JAL1vKBx8`w8&4)qL24X>A&!?5@A;h7k7_#X5;tLun4^wCzjwo02rk$Csa^G!1d zC3(MpC(%nnARkaL6MO6pt64B{#2_f>3eA7oK)g zaCgX|o4jWVtp83_*qkwi5o7M)1QSy@MpA5B5Hf|*NO~imMG8Fq$2n);LVN?H&JbZr8}bvU$3< z#gz=3k>CDms*$0(FY)gtJsFNuI{FsJNRX&uH$PKKf(m*&8qGKo6sOc55wRn|i8^ue z7g-W`;&_J6?wCN$qC>&Z2NP&NE!3v?&;+Jk=s7-ynZT0GK<9Z=6R^5?VWvvh1k6qf z?C38MpDa98xmnF<8hrm7ZK=Q>(adcPJo*y ze)p)=6Tk{L<)f5B0GY}=Y|fqpnAnWp6VN7r+nbAyNh|~qtknP1G-(VK?U(JmmBa`oz?m;7HNn25=TLKu!3Cvz^0m#|P)LP8|C}T=Js_X+`lQUQ8rw{OB zQ(V`R1K@D$$Ca>FJg`cu?~J0eX~v~gFl=|jr%*6qLM`p_GAi4wi42SS?#J}fzU zK;c@BVSIq`-5JENlgDx5eK?27&Q^aua^SR;IV{O{d)33JU8=wvUHrv`3xV53QL@kqu z&R?vd_`C70T96fa!{Hu-7O?K?NJ)F8gen8(df4gSk# zA6K4L1&0Rw3u2lo#2w3!ozqo?tnZ^tf!|eN+b{n4VyX%xxm9yn>8e0y+Gy%xi!y}I zl}(t5Dud_bfs|m6!$6CD*!=WV2}+c%55A*Qg1rmz&(9q{1YJZgE1Dujm?hL}N$n~C zZeKyC%n=3Hn!MEE_COwboTIJnmgK-W;CsnwBROzNd=c^YhAf=qXx?j?kbzQ4fv2I8 z4D|SUc+#PBd{-9!npck$lpVgKp(-W?)MeZ9g29r|qt{j|+AIOmUo7%FIVGURHz=>d zO&n7B`8{mQ#o(zv--Z)IQgrh=TBkvc=Y9lXom z*L8HA>-a$@rYm>PEa9c1o{S}$&fx#V)yCPzkKogJbeVU}3-PC_`t`(KmREyb5nd(@bo(KgfRd^#+2 zGsi7Nfe|~a>}%m$&y3-7See(I*s#RtODD8;*)d9bd+ya%PAoSoguutijis_&FgxPL zgYi!5%sA%rVrwxzeC9v+u+Q3i(wZs)*t)~D;Wx(xv6zN8x73pNV_M8AdPjn4N$Q=N@Jumk0jM|rLo}KxO+aIq_LN!T@MP`Ww4}? z@#!{A8BAH`+~vrlGT8cSmO!ghGFW86);LXo3}z9>_AS9%1`~^Il9Ec#F)X+L{*7uyF>E{iBa6>rQH*x^regiygV+&STbJq%VXRN{ciE@Z1K7*2r`q1x z31M^VGz+By`!Ruk*ZTH-6u|rkYIZYn`LSX8eNE*j_^{#>x+<1Kyx0!8K2T+g8wK4AE#ql1{!PfR@uJ2GZNr?Bg8nr<<1TOVG1zYU9{>OV|Nj(NcRZEv8zzLzGP3vH zdvh+%aE^1F(jsI=`HGezB{PLW84ab9loTy0lozFxR3a@SQbyTCQor;2>-xO!v+n19 z?&rR*>mk3d+gz+NTlYDt=g!Q^$vSEGsBw}GwPf(y%oOSF zdYhuS40D0lxid2|X9*tUpA36x$cw-z`|IQ; zKDcHaNHX%{hbX%>^}w(I0=|1HyX;tonL|t40;hza+$*DWC0YcT#xr$K$3-!#LE{m# z5XbIF-Ps>g;!v5ZDtUB!IVhjiL}#|IKPTad^t83+ge(B8aX7FNN(RnF1nkjThN zxGF7=z*UQfuJ*~Ja4P&{(j5gXK380EAx#lsuf%LG`zt}E{;No-oidIpuGBRZRYA^- zSHaQ*70^u2o(h^)fmP*;+RSaLc)xVX>IVa=*z6T5KIEr{?oT@T7e1>&^-->H_C|F` zOdVMD{ewE1s2Z2Q_-lZ-FDrp}Py<38Z!7b9Ld>AH8dng&xXUDhwLl=s`uz;8Ieg zJ~9k?_X>&`pq6%M&18iEo}C%H7UOOR^SHv&ig80|5YFGC@{F*c{RRhYj3E+rY+rki zF|Kx#tr93E2w3ELpOkNcjkDy2;9(Oin)I;rVG5y}#Jj#cQ&hya59E!Qg7j5DI+|<- zjm^2t=LKdc`eRc5Xvz$-yz;HwOmip}Ej0ZqGDpiYHK}t8<`C8p-t}#*1x||jH}sZS zphD$v@dBSEhPVqjye?U3Q-4<>Mv#Os; zZNa{E*Xz5W9psf1-#Trz!=5$I zaDYASjg<8T2aMLzPUQY^z`u>!Edkz+NL6IVC|5foL!>8U$4V#sWNxnC5aom?6ot2$ zZ=7(C^rd)(Aqf~Yo_0wkfsv57|9lS#S6k(J%oKrlccWS-7~tHSaPE%1K={K&Wwpz| zb{nf`DV;NiTOs-`<1*iBHaO zdX|!Ymd^z)=lOjdj9qY8fx2~mqYHjkb9Kchxqz>{sl%bn1)<@#OFZ7XKy@ce^w*pV zK28ipjw+E+rcJff2IwNlJS&r?*vg!#@mf#W5?HIDBS8N)lQLN zw`Hm0h%^OKcF{pRb`*3d#@9aGM1j1CPijd51y*?n%BzbhVB3VPBbq5F9uv@?9i<>i z$a`jw1QpF$-B*n4s8DDR=n4p+;&k3@n7|<_LL8_TV%MpNHM(*+;w=@U5@DAv&ruQS z>SnS^g@#fVwdoX%hQ?)goMu94aIy*Q*?)wFb=E@Mo3GJewMOT)*>f5q<$agr57A(| zZQc1*g07HU+izN-?TVM)FRBEnt~lE!+uIfBiYJ#2H_9D!MQKefNvyyX9^2oZ{8QzM zePdTIX|=h+MsQbQ#}8Mmwhd9!<)>rCh16Rrs&rf&-|}|YmX7VN<=J{`>7d2Ej0xLD z2e03N$i+i+T)xsArhT4{M~O6l=6yOs`IGYU-q2xWa#*oth>q)m{|(DKuh5?1L?Leg@$f0 zz>2dzd!&JZO^1%nN_R3aI4hgBIKr7{_14KoE;l@QTBJjfa>LxmZv9ufZZO$wl(^K% z4L#cXBpu^HO($cc&Njc?+W3t`SV=+uM=t z+L&lKIT9B2l?mAkE1xc%Wul!`d`^R(g@WLcf+-mmWCDDZ*?KG_X-QEI*s<`($Z7ix zCJVjEUVlIPvT!iqsvTDZ3mRPxlcjMiBtOgY3C?6eTso0|X(0>2iQTKKZm{6Uy*gyBHU z1yeHQ$Y5Whqc{jK<$@~cJmPiG)aP60=+nSfT_Oqq7DPy zn!M-j=IF2ya(`aYM8}ridvW6Vbm-qmee4%XN7|cLZnYM4yjfy8B*90Ad4)xUcc&{d zPT6cdcEuI6Gj{jdV_YF{pzKEo%N3ss>!yblUBUBgym{w14X?yp;FM61)WkFB#vDOWX{hk)gtSlKM)TjG1jT3Ho;z=&RNw=H7FG znfmzkq$4i)Fj?qV A8F@QsRgvM& zSiM<(w!zUE-p) zx!V0c+(5g3&AXE&BwUR8?4PiTgp}82Ytts3P~x@kP)x29>RUy_2ko5T7QGtIJ&rhg zH71=B?+6hk^;2gx9g%bQb*A(S2ULGHTxqb)0jFaM%vUUTfcd`8LE3!|Z#m0SG4QoV z4&AqL4YxgfPn!i7mfE4Hydtkwu3v3;+hqPR~lorjf^UcR>`wM1BczB&c=J3ppiG!u*zM3NbXYaeT zR8zPJ{PMn{XNom82RrRwm>@S+r>ryF1S9#IKiY|yAnXBe&hs_Km{E9Q$)9P2KXED( z)z1x4{Vp!Po!bz7{JP7ZIvC)z$o0vT7<~xvo6BCmsfS%Gae0jD!p2x;nVGIGt_S)A z`E1gG6Zw_u?ep4rA9z4^Nw*e+Haph@i)rEQwEHF5RhpQTUpM&kmbgZ>egY?EprgFF{yaNIkB1=?o+vuNfai20ISLk0{5vc^81Cc+eiwf9m zt1j$$N*>H$iDC(TIb;o_eaWeo!PbF7^+1o6*j~RfLcCWBi}U`uo-|?-qk_o>Ttoc44eM==t`*dqEKSuYGLaEk%;dgJ;U^JlG{()K7WO z1#YF;o&ZHay1&RL3nUBc`sedaGo)KQLg#Dp#z<)$xu!{1`bir+#m>Z?YbELK2zxHF zqrOh&B46kl{ocByoPlPKCtEcL&p9np-e&2lE+SOv+6B7UGyb?2q&v+~$ zytYbK$}Z<4&TB@VuBzoHZmCmKzlSU%HlO}rC@LgEJdU+nrd1+FysRU{_UkSuZcbcp z$Vym29HFZ=8MR0d2LADmf-X{ofJt2MmNU}C?dHcy%fGKAHt-5=;2aq-{w15Dk|IaU zR)%)VH_H>UCgZ|%K}907M|I@#S|y@5`h1-H31#B2TU4&;W))%?d+RS1UR9#8QL}8W zP?dPIT4;vPN{#q~$ljb*HR9Ecg#21xbs|A|%f-kcb;3VSgC)5~gZM7D=EU6@4I-x^ zt0H)}CZWmCkTagpB$9pAzAlDp5pTzSbp80KMYKF}QoO*{CTwI+KYUxKO|+d9_u6Z! zL;M|h{yXiQ4q@RMrk%pAOK>MXTYE83m#|1yxm{PIOH9Z9uaA#)IN0kGJR*7}Rqp!4UESZGO*iNh z+=^bK(d+byE7lPk8(sB@bZ(WM9wwajYr4&mqWXkv)xH>NzaEjjaZ9#&g&uLnXKBce z9eTtjTm9X6I(o#x^BF;SuS@KBdTi3~pf2H)J^t&4f-Vso@l-wQnhvqL$)K&kUWaIJ zD0?{eSeuA`%o~1|p-qIxiC^6DOpBPX{dqJUTEvfv{i}s4H3`Qr{qfman#9jvHK~p{ z8pJN$6z30%>csZ1{jvEW>O}ZDiS?n)YD7cS=)G`5HKKjwLe1cI^!0i3b7_5mqy@ggs^cU`&|| zp{}rOeY)>T!t!3Ml#GNlq5f{+_-L~v@kjUD%j`r6qEx6imfvv&k+jc0=+LA%p{07c zIWRzsa2QG88~Y$kIPk}YzNRlDMvq7>(|N>CWJYS4=`#3;t9NT3v0g4A!~%b7d%18C zJ*s!hZk8<6T^dvJ$#^td*M0jeN=GN^GD4b%WcY{cem|rUx8!^43TC&Y?ACcv7y7w- zK~$=WLTF`*#9Q;*bW!Vxd(8{jg5+Wyo2OB$8P1GgveYI~}fPoZJ)cGGw zSW07`k^Qb(=arDKX#c&9*XEO?x>Ptk00>KZ}RM!3JEx}dGn2x7(O^^*OJLCNp@caGNtq51z_UiLM?ubQ;R#JeWA^Ex!k zTG$l(wa6x`LQRqQPx5a)VG8NLG0yd}X83xpV-@diGxVzHsL8dOLDHo0WVMbtu6LdE z8%j0@H#%PO_nG6LbKGgWlF7kw?{n`F~NW$i(c z64n!sx5w<o1z-pWC_pV7e;+lPVhVni~q=~3EbaD8M z(-LMJAK3|q3LAT8t~z1%+DJ(LauQhS_DAAlNbvW1v+Ped2?-5+qxUob#SH1O=#7AF z!07X_qd;0@`j4yzK+0lDC~Xd)4M{V744hH+@J`K-0B6oP%0YzxmrF zyz>9!40Fqb6V)az7?YN(Y7BOP!^uN4UimHv4L$XS+Ux>pEf1Bo3oZyYc~+@mKn8z* ztwHQ2GB!ok`d`Q*aG`wsJ?0aiW14+H;RoEsP?7KzML^C+N+Aqd~>j4dU8&WKL2Wa?{ zqE_-|xhwXO@|wiqiYo8S7SnK7AY;u0f4(ccG>@KtU*`&idsE-f54gf{^5TT3FdcFx zPv>@<)8W43fu55W9i}Va?BtH4BTlUE22n&uUcCN^mM3&P`YQ1F?hqYzb7a z?tGPO!hnylRAk#a1`;$`J%jrgNcopRA2`dv&H0%!~zwRtont(A%WWs;ssZA_eBX}Kl7gNc!)n?ygnXF{|8@RZVL zCd3wd)^YbR5f`Dg{rnduyte+E81Lt-fB0~i+&3m(?ije_%F&Pc4!?clZ9%oZwIpUSonQ-Q1**43+{(M@7`|7f@*)tOuroqJY`E-CrB)ul*@JQ zqp)yfw_|)0g9Wbn|MVo;ER5e7>$hLSLZrHb0DA)qm*W2!z1qk^vU0He4__8O9K9hl z>CZx-RR2tI5DP`oCcg(Zvmh>OzWWSEUoWmWcB*6x3p$g5J?yP4^lWn~FXQ0DLFKGl z98}rMm6FB5R}%vkt{nV&PTKi7r+@3es4tcr%p4L?59G{ac|=#A6vD!N)uK}k!7Mml za;fhPWMRHVwM#C5g^k`azvcZ{DC@pZ-QmN+uPL5YDI7a1sEs@EB_4%47<#ZONEK?TWP+7P|iTK;@!b0B49-&H(e{f^( zwXF^;7~^uNpe+l2<=2hZaQw(KKheQw#=^19;q|YLIDUNpRWMecWA}%eMs*z)NaAhY zFEv`BQ)1!Uv%;1X&Us0C>|Gln!|{`SK!Cdx3yP{6jRKdmP`p*r z=A1AKKS?L`efU|h_&dK&pA!#Z)sJ2d%rkLdAnnbi|Ho0to=^rS-V%A9PX6m+BFERE zgP#+>+ERv1Cm%Brdy~ieW+f8}i$3QqiFz0@DITOK276$x+WgNYV8Tfp+YCtrOf%ee* zi76WxD0up*VUsZf>$S&jwJl{JaH~`6s!w$6-Zr-}wt|lEncjJ>WIE2?@Ne9+o{n6> zKI*g<9X?S*17UNnSiZgPvS70-NTotgZk}?5xxG#MpDnJ)C_XnVZ{v#jEq1Na0W?rLgLxM8WqlN|JB$Z-D=9ekh;m6JgTlFg zd1>c^D5&#p9i6bIU~lLFa=aJ?ZSAd@+CyY?HM&SebL!K6S^w{?r^(3u?B*B~MaKBR zA$@r^8LYgsljb^P?5rsB9$7+0x6Z~dTwN}>RnPEzQ00QA^ws&#j=Mlhr9UDq+y%#e z-MM&{;(`r1_h0@{bir~eJK_KDBKZ`v)9tO!XuoI{P<+K1Ri)Iif&^#mo^MXJ-RO+Y z!wRQU&747>FL9$QiUeciz;e@at z?ZWTMPVoHf;5+r&5z0G5kBcTbqPM70OWVp3?R&TM`3*UMTAVz2{G0ONgZF0k_$xVm)nd>N2R`iGf9Ikdazh4MGJWh| zXtZb%EpCUtM?_?3vn|g2{UkM#YzrziI5g1S7R#(yIZD$uxcn>WT~37!cC|cM_dLu7 zvq6E+pQ+hkjk~wJT(>puOnaKPoU+EV376M_YptPfOdjA9vBuENh2SestuT0$OYKdf z6-I((qkr33{l6}s6qvHamG&2nrDc}jUwiyvNU$aTI~P|eDPxJ$CkII~uPk6x=Dp7) z)dIQ?A3@vE0!xa_<&CDy5y)G!PUyNhqMiQB_X{yc%Gh4ddPQ@5x0(xn*lC702Cs%H zk8|+r#3}`*8Rm`a=I`*BVal{n^hd2J_82xx8tpMf#`Y8t5yWek>));`Y-!xBK(*P-7-&Ir`(}$hx#AE7|9xe!Z+8S@r!{vSTE)l})r~~7Vg*dVPPJxd5d`Ti+so_8;Pl{l06Yo3P$`D-@RywZ9vP7w^ z!1ksgIYKsWQA`>|fso%DF!C!^kvM>=hdVzi5j=P5>*4EB{`m!1XWx1tkbCCuyw78jO zOd}D!Vlpk2Z%G9A(9tzEVVZ={@=MkuB3cBK9LDWS)*|-5duni3R-4Ei8#%loQ=1rX z`MkeFUWX9Ss`}7)T!)aUmp1hKqeFby?pqbIS(m8a;p-9iSeLl^?&N+|Ej{Apwv2sW z_v;b5NzoPi8}x{~3mT_$6!eMK7~f>_dVS)y;%8f}bNYk{<+JgcMt!28^5Uhw8GXX5 zouy?-G9dEpYVA$P21L_%yrs6M0YUnHCoOlq0bwwHYjSk00deTmkC8T}0kP9)EKl0R zfLQI*CFLq+K9d1FOCCiEIyzWv0UV#PH~aMB{6EgshS6 z?d>!@;(>`*_rVTbLhX6-o`)NC3D=vwC%(PYA?&49a&CC(5Lxtntk+MpiMvK#iP0w7 zL^cM_RHbVXB^~XyyMAjDKb4l;%v_~O@Xl*QgkK{Oo4*pr4FyTW{xy z`xJFTEuv;^(8FcK71^s*giQ0lghTd>oNq>iL*4r+T<2mfQDU=ma89uI0zy4glAV$$Nc{eDqkOT;51tO89^a$#iN{)@ zJR~Rjh9}(=BwO9EgRF7ypYfTw4szJX&=>E24Uq#=tVFJ__(3k!(4DpU@r%4etw#3e z(OL2apVr^DqVw=9=<>BaBlA&UqhlssBaE`ib5yl(F;pL2VP@;G5ZQlQ{+MV=ARNlpP_0ug64cPS!KuBvfqmlA$=agJ{m}CrdN5_`ouQ@TZvOpbiwUQS7D>bk% zbBlQ7oCZ>gjEP$%B-sAv?X9*>6S}gIwJU_QuG5?=XPy z4*doFG0VXgs2EB&HAMfD(b_LvhFF9RYBEQSP&A-4lVD~Hca>QA@?K*UPKU_^95;c~ zOj*C5iYXqh|7jr?VG7!Q%lcmpriglTx$%&e89W}OOy4?ehBe!Z%RhFR!Dh8ex`UND z{!vRjADuSG$+m@k=ELT&tyoT@x>&#{^5YZf91DC%o>x0OWdVBDzM=TFmIyHW?}GRp zOI&nJ|Ho9aLW}4Zle+y@*tPaq#JxT%Y+&{{Y@}L4sq@OPSD`gREnABQByC_)K%B_k zWdk9xHrxIV8-&;kElY5+#YuwfyXmqmCh|lgC_;7^wpN+0477t|tM=cIFYOS@NEwYa zvWG~XU~P7iJ>EObBX1qGhd_(yoHyG6nUhmCVb>gx+_|pGPSz3HAsXQBbi~FGhaU$U z9q~P-^~WazClu~cos&#(g5&Vf5sP6bTy98+U(9rd>XTCy_lun&d#79@NP-MA=^4+_ zATk8ss>|s#kTE{N`~6xTs7?%=vvdWPefSeQwj0ok;)NW`102PE#_VndRM!aG77I}D zW_MWG24e~iPLdZ%Z=m2st+B?`2@1kC#fXjGp@2CNDiAV2!65sd#E3K%^)y`DZ zubC>&3Z^2WD!n`EJQd1@%cTRJQgN<`QJ(*cij+ncm#gi9)6t^hw^q48{agT3H_ioE zGqNqR!Ub6e@AbcZ?*h+@F5WFtu24Sr*TI+U3NEGHF(%X%r`8^>ioNKH!EFjv#V`5t zPs5=xGp=Z#Eqcwg}i=6ZV=!mjZjrKiFhjPVnN76kyY#kM&&JNO{piW&pD(!~;?F-gEad3l= z_53F?+uRUw>$%<6R5u(8n9$-qaKrDw(&0m&+)yxo{L~|9239zT+*Y+`@Vn2``pC@; zOrIAzwk45)ffyBbLj{BXueX(KdlL5&9a%u+;XJQw3dmWq$EYXAtuJ1^5v_=S*Vm?a5{`w*qDCwe#r_JIs$j!`@5Tk z_7~wTZ_-$J^|x_vOC<|STb1sAY3K9Pj?MojSfE_=uM$*X<6o58y&4NPyvo%FQdY3x zx_`yWpF7x4(VF!9dx8xsT19YRJ{vm%%?4la*dTeyluB2mEd5v z*4A&&%yc)Y;(Vr9E|qYj4#^C!J0XpjxGB*xTaIo(Qt~dzj30>JBNcO z7vA^YFXh1J@Vdg78V=4m=)3=V&VjI;$H?_|4(^(W$x+^Ouyd|)_omMrRQB|7e}Cto z=g#LH>wa_aQ!7+GWtIcmZk5{)1h}AIt@Y@e&qZ#u=HjXaT(F*oh;W6uC=JS8*u&?S z8fnT|3UMK@ws`NFd0fc2ILUXpX3wn*{yAqXtotMf%q(+peJjjKEoB@r&Dq9YgnhO;a8S($?nb_uV5(k91 z!(DwP4yb{rX?=XZ+&FOCI#z)HzH;ow?UQW$GFVn9@`VjeqlvS5eSE)ekiEI`H5)~0 zBJyQV*)UX%Vd&SeF?D_J(eH9LoYoy%_n?3c+cAx{&6#XSlwWn`on}LH_30OB@oW?( z>(jLNu~D`zW4wbOH*y(~=D#+vvEs~6i_SG{yv-1+Xl1goJk**I=fnnF;sz|u*w{#R z+yZSjcFM258McItATOz=rIKu{J~H#XTYwE4z1xH5`Elwz7}Z1`X5mhs;*!Q57FIQg zZhhUvg0M-(@cTzB_?IpIeDMwoHJ6mAM%P#%tM`Uw*8LrgXF;Tr zXSy>q`=?eh@s=Vk^6DxRiIkEe@$*dl{nTk|ae@i?r8jA>_A^ls5tCIK!q5Bl zxogdRnP`$w3W(;{fyqD1pPT~|h1a>Pw`NQ<5EJx55)&Q`)dxi7m>BlhwPxFVCc=#5 zvl4$YaJwk*WaUQ&=0yiYersi*F~<7aqB;h;ZEuV0zR7@O=UDUJTn2u&mv|*6GtjlQ z@1o8@21ZKcS2qMRU=k?nkhG40%_G8gX|4>sIXQH?&y<147Sq8>6$U!bUk^4~z`%Jw zuhUuI+_05yi(8?q0-y8oco4S|wTr%6R_xKcoOJCy8(^*<#)2!`{|l^hsbR=eT2 z&eMYp)^0E;XTA_pa)SqU+DrVVgL~9D(zt^TvntL+!D6*ppj>7?F_66FE)AA{l1j<;_&6W)^&SWJ^W1choSXs31n=3T=ldP?tJeyX^r5 zl46yH^D-#dnm(v28%n`<^N>BZ41Rxo_MxMWL_z(1S=!M#peNwU+K4WI(`xojP=7h3>;5z=exe+kQ8Zkt{N>=tB}2S(hhM zw{pqQe7*AZN@+5rBORRznw=3QCvx`E8E2g6zoH?v#u=`$-mO|n&d_T0uMKK2l+2S=O@Ufq28mjj|5 zQg^Pt>41vINlr~c4sgoW2)L`~fZke{7|YN0c&mIv&av1YHRdW!?m_lga4+G)jDbC* zHlCW}eYL|j#^aP9*X=OzY7sXh#14NaeA4zB+F=Mcu9$qa#k(b>?Q$iy&@6iAeRqp3 z3_RTQEJ(H}Bb_DRduM|Mol+v#vTd;IxuwFF^){H9r`7DIY=fTmQQwt4*4SAl{mvrG z8tQ-djazN7hS1xDQ+XQJIR3f1$$r=hXG?ayG%dG+YSTHBf_+xFedNJOBNr?DlQ@>~ zXOR^Qf=4tty_WdCOMOFkktN<{Cx`m(u|$U9(Lx=XB_yK-(mj+cq4!_#*q<*J7`m<8 z7*=P2mt6`aI++%DaA?EGp2{O-Z+@9UPEZv`pPRwX$?VFBEHm8r zueod@#0>ivYI~m|o59-X11Ct<41 z{>w3r3`g#m0g^m7e7+N9fXAV(^Ir%UAYEavYj~nQa$79+*h=eTU#e*Jf9ZM7%Kq1CE19+lvBiv`h)gb!%!v_kFCc zcD@#PB7%awOSSMQi7XnOsR^k&{u-Z^G|@3Va9HCE36$it%R3j4u*PoKD>Oy}{kc^m zZ)Vh??P(S26Qqta;}YrjpDshNXWG`>3N@TQvtFh>VJY5o#_rDFrixQVAJk3hDlqjD z+aRW~K0b-ucez8s-vRu%RGBR{w``W>HP8@FW_AH>(ty%p3BQLOCoBJcQV_tYdB?$ z=lO8Q67TY#Jh_Fdj)pIq;#DZ*AOCcEme;R5`|8^k0iw1#@>$gZL1G*0>D6=jLPQ`( z>aXQ3Vd7X^!DdR0DA6cse&omtaiTIfLe`>tA+hNl@8!MGMZ~3f%d0A6%jeIW zkRg&(Q!- z(zJgEOBNH;O#@y%xl0Io>dhTRr<92o*Yr~QB2)-HS*`fX>r{zb@$MV^%$E{Vug+gI z5>q4m9=HAwe62>v?=3#JJ#`t;G3@McLRXz=>Q&rhd{~{Z>~Fs7+M-U>#cKerE za)WTc?HYtlomk1X>wN0R7(e$}gXpwxnI2Ln5fZDf#h0uk5mRxFW>=y~#PhqyMW0+G z5%TZqOcU>rh=|O417Dw!h=CFFl}arnB1F>QUD7KOAu#Vo{T?2PSW@y>q%faEG#F6bL0{mf`JSc|y4DPxWU-IpS`oI~?m}h<8d) z=JG?OiNlFU^6r@|A_N%5&$q=%5LesSMZs;N#2J}w$us)GL;&V~vyRLs-nX)x9<&P( zl3CBP;Cu4nsc;A>Y&VuB6{g-UD3cMg!?EUO-J zut*dA{@NGHcWU9va?gXuOtjG}HYm*bsf~j?kR7UZ@K>$(nRTQt{1kNM_Sxv+%gSmaIyUr^<-VB{% z2Zss=%}_vC4%yJmaYuh$UrnJo4!?IB@)ET`*yUpp3EM0XA^h$$03hX zbV2OMaZ9}Zx4&`quq8$h6+U)lS)mP%`N_pra4+?~O%=Ds@Q#NMTlQEZhC6vatlb)s z$sf-aTG>FIKjk~5+rZ4xW#r!v8w5lS3tO$Q#XPG&=UYo{aVF)Wr?R9SdiHHTNDZ~a z?Zd08$*=4XcO%gDqp3YQ8bnv$$*{+PeU^QWQ}(DnwYU7Yw*%Nys?@6w9pIrAtk9$G z2>asGlnDO(Qj+xb_VWQp{CO65?+D!qlPk&(lk=Tm>GfxrJKq_Cnl#f70nWIZq!2hz z=L{>7+QkkM8QtX7qqpP8uuIYYnEZi^=;}-US?WMVU{Cwj6~GFiz8;0cz~$&eB@4;` zs~5q0zV-sW>$BSl2?{=|%g^6zPr=pt2hmE~DJbuqS{QPUf>oTTB_>ZOP*Ln$>O4Wg zgW1D>Zfa1`m;Ciuqz4t+3M+T_9H1g)I8cC5LdA2L!)DLkP!VXbMYwc<3rLg;8D$nO z{C(>}XUZlQ5Kl@^d7XB_g`T>3X%Ae`xHn|#;)n~n9qxzQEp|of(*(0xnkzPcNT(V^ zxT0)|#c$HC&}kg^B)7U^&)R6o3;`N;3L0z&r&Rd#}b)sIe0?u>@>KJC<52B;4lyuhc939(C!>f-zqN7tiag>3JYYx3RsK~^LuC#Dl z{(iMcSypesb|$ifVpi3pF!9rB*VBD>m^hksw=<)UiMWi5+BV&nYNy8AY= z95@$R^xR&~f!z1Y+Y?0en{4LO`SI?L!>zb*|KaP~Y{o^N=4XY?hFpv++h%90&4p^zpV?$pF60liyM@Yf z5&I}X>Y6YYGoPu8DyKQ{&9S$d;^S*o_8AW1<9!!#>4hR6e~MXmuK9fql=r&r9_QP4 z(D{c&&v_2QPuBMM9Ov7yC1uO42o4@)xp%Jh=iuR_(xx*W9Mmxxp*0R1j254471!h7 z)SsM?IC&1HgfqTm3h?hS?kcVvVS~cmH~PMvjeYnvx{+XG^{0vF_9bj6RjOJXNMl1* zjp>nhfQ^v+qS!rK*vNfT%9C>E`>$VcdAc+#w7OhqTMW!51n+HhZ&|{`R*nFtX+9I@zs|d`@EZd! z|E_z!vWtOZZ`Ke0u4AC*?vmBor3{$;TthED%Rrh9%joA}24+fA6707#@W&wklbR<3 z(PIobt^)&yl-wGH;*8Rn9 zDEl(dQkmk0!#)wegd^QB+&Ew3^#(V*kMLXGL3KlY_wNb`JvSs@TN>ZI&*WpBm zdY*~PZcV-(7K!JH(vd*3%bgmf!Og)l=X@&-4vp@WuKfBn>0!Dd^8yXGv+p&P9-u)_ z=lbYYKN?OXw&}8|G>}7eYIU?}@Jrv?d_t68_XI0$6@GQaInwqMG0mSM40}3zW$)iJkcS3KM;}qbmtir)Y13y)5TPTd^j}2O{C&|V#QoRFcoe*frJNK zDopqKO8Ob`_35T<+6$?08b}LG8=>I-r})?X&nO_)Eu=-~Q_vz&J+kEp1?MXtI0vt% z;LE8mBJV6Hh_aNrcTAFkS);%t-XNfs{ir*q1}NwZ;5F?Vq;fd>-z{Eai@}Yiecr0J z$Vu|;3Lmt=$L@6YXt@nWwxk*TI$(p`8v+V>OdHr-_ml5kY=c#$9u=;`)(ALF{N8%U z8k;T~ykDJQjf0oFnsoo;%Lje8cN$ycNX4)JCgxkibaBaovprUrUZJ$2k%<04uy42=n;mYz6Z~Zr-KER@md{wCT)*CC(P-tyZe}+G{v9%Ubm7CQv}|*HdkL}ie5vL6XyS!Vx0nYMfNIFOi8Np^_rQYZC7SN zrKl-XwE~SrhfVNNeDvz?W)l<@DqLP#WP(Yn%`1EpOt8zUd%)4(1R^=9=TDfJ;GV$` z<&dQ&@LwKEu^2XnL`zG?iigIq?H_u%xY!sOl$C~~`-~y_=#J0!U}J>TK8~2QF~-Ka z9}2Cq#&G%N@UeHs2;0=_>^{6SLfbvfmyXwrAg0cLVD_jHLOkMHr*<0Q_TLi0nw3WI zq`YrFXKjSq)y?Okl#Gxe=Q&@(ZG^`G(pfh;3~@l7`*U%wAu8>1=in|fQW zS08upH7Dy`)yIrXCdW8kAIkqR2NvUzVS* zyQ_zoiA8y1r}QAXj)#bi(nD~c{c<07J#-03uvyxA2uoA-)#ld2W5fCKeLcG9@28I| z)#-v-QK0B~To<1^#2)Y4stcdCX0a76x`^EOOk$~~E=)Ae924QvMOn{6yWj^MoC)tZ zvHy+^wy)l^COuaN5#e*$;&D1CC~6hGvQh_Wi)O`@&2-Sdxskh6Oa~)>)6V_-LBl)a z9D}r08f=a3MjD)_VUL)!_o+QJw3yOsRxPI?JY-_>GKB`#>kIpB7pPcjVsOvknbZwM2WUG63*{Eql=+L8A5nWnvNt{SAkJo~=iTTMKRV_?e zX^SefY9hy0_=az|Cj6d!(re(;1h=3NGw_lIE|wkoE#;&E&yeQ_m-ee8(MrX+C0QN& zzF1JS71Z&5S?_}QH8m9d@~?FDQiGSkhhgHYDvF}D(k%9>V!VwKy-7+HoYGq+4+2$? z<-g9 zz<8+KS;f`jD1Uf%k9o#2RHc@s#M}{sr*_JJi{FSMUZ(1^BXcPVeieT*x+;u5pH>4e z6(Mw93N?CpTmXNsjB9U^;78+^tox1Gym%FD^>(oc4?f-8x^&Uu#mMM7c;uttBIx+W z8%Q1Gf>i6k)MN3#^ge}~i3aL(biZxavur89=@CR!Rg=Rs-Fj0$%RT5P{b8)@r~E&o zbm5?XY0CEB=;QK7Vpr@Lq$_)CR#cU}rxQL4mEHke^g!7kk~e#<({H6d70N28wZRSoJo0a*DU1dCkq` zO-J||Y{uSt8cXmu9KAi~o}Iwo&}qcGO7`bSq`vRxYxvoiU1n&`*AQi0Z2c^Rw_(QCXEq{)rvY7W zeN1$hG&~}Pm*2Rzs3E>_vEV^{?uK83-@A$?|8o31PRy$t%y9w}JlEUPe{rbJ62Hrq7NB>m)HI@2uWH~mlyP4r0S0)6lC|7>(DxiP&lE@M~mV$3G%wFgP? zV$?XryJ9y#_8hum-11Bi{eu;j`*cO{F_>TUeT*n}dgm9|^orq)Y~S6{`DFmZlST|r=bI4Q`15@F&1CLaZ^3H8u zdA%C)r_U&f{8fW-7JuBPbLvPddH&GZP6NeXN=klx(7=zUZ>bq+nn)rN{sil5K|%>U z!7sJ2MV)6lD@_}(f29Q(n^3^Z3gDW3PeFf`f9ak5R2&ey#9d%XL&|U8r?g=jItFjY zTb_sYKt7+j@97f7~o=yFS(|#J5!I8zB9NwAI%^12mR| zcP`C0#1DnUJW~TBTq^aNqGT8$JF=xb|FaRO4ArBTos3adm7F$p-Wcm!-%pkNHO7bU zyz`pDCRlIIiWa_Wf-4M5opti2u&uuwAil>G4?jy8-g;vSBl(5G4ofp!3LpHw?X($O zFJEp7`DF&R-;3t-0?e_ZZES3=)*Krk!}lAhL3Cj2e--|4>obR1B7b4IR)j=bJwE!8~0bn)}`zNSFxqK&F|*8q7(i>&Tu z0crks7TW57=au~~R-XW0>K1p!WdvwS@Lyw307iwiQsD#&inj!693wDLq-_8FE&)C3 z^;}|K2>6+XowpWa;HWhHRjCaF1NHiR&o?lze%0Jp#Ul*NtGZ@d)-n*(CDtW3z`&bV zGRNKuFv0b~Z@R&RiRuTH>sGF2;`kTdGa0E&OdKqg6RBikbBMi$*$XDRRrfp&pJ(D* z*cm?yO-Hngs(oGS?ug=?_qlD+j+o{t@|w?eMCH*+z1{{#@P0{pBkW5#CnAx=11X?^J7ekbrhl(N>i;spK8(p!99IN?!`bEohhCmd1;J+@!f z8P{ZWKIOBVanHo~q5n2#+`V&jR_VAiUdKpk4Awd0*x2xik$z`r6kn376ktK0EqPeM zl!dPk7TrG+#DanNrj643S=iVpTX63R3oILJ>)cl?oO}_^y7HHWbQA7V+q7MvGcH{u z?CApG*g}z%T`u@g63-ew;{x`g_JOjyE(r9$xXP&C1s+d|1ph5|#V*Uz$@|)_S^y}dc+mWX=B+%)vkzmbNz99mn#C+<;(3DcZIrAxlpdC8)`}) zM;05nAuC{X(RU9we5fz1I=Iyhx%2ZEEHd11Is4gzi843r+B)JH+T;eYWF@2gk8XG! z7$5U`-VNtIbzVxBaYse)TN_&wcc^x>TGzO{V~LRbZ|4o}a4$Z-`ck4hf^1vHwNJRC z_!{pKzY2Fe583!Zx6vJ42b0emy>iFX)a<)T-`&BX`|u0>b4Q3*6ML;B8!NVYjCg3X zQRtG>@z|1$gT`)WtlZc*^LjF7XCNC~rNiCJ!`SedVm^DllZ`t6G7qJFY}_eSwJ1Hv z29rBkzA}f6D=W^u%s$NqBk4t(!#Osp)m%k;3)uKAe=X{HAsb>ZX&O(+c43Imrsh00 z+6+Y;Xykb12kF>$lnqgyvaXRsY$*J2iaMUmMtSX0@9f=d{ID~yCBoTwr=0TIklat} zlQ&c9u55Up`E-L#?$;8RJ6|>%Y3SD?`v^K z`L>IFA(!28IPPZ-E887$z02VX01a+`ckl)WB|Ncqhvv4z+G$01?6E85gmAfo zukf5;A{mbYHm75**$q6CUS-`E-N4xa;)!A=+C+M(}Wr3<=@)`_ZTy5Q9H-RHiC zyMSwloAy^{7tBA9S*fn+0+DMGey6!yV0YW!(&hsTKRq4CYwB3we)3Q9-ANXF?Bo+2 zqgj}0YEWJ4$-?<1Hj0aMSjfG>pZuPOg(}@hkzq35^c>Y+C)YbeS-(c)%qeGFXA4mO z>~ID*x0c6hwln5lddCV=oe{Eis{ZB@XDset{wcN337br_uNT%kL0rdrZv3jb@%AMCw9I>Pe~H71hdi0iusrX$ZeBKxLC z%+pv$Jig)osMXgIqJ$!!laV7{^RLQUE98iYAHG4EpPA6^lAC?^fQd7LQz23XOeov( z`CpG?qWP7hxakTe>?hMLKN&Ew_DGh|3w|a9D>}1-17986 z1#ROP5WQOQ>-`GyUCl{+ns35@u)eOzBT)uaSL=2i{z2eGo3n{#8v$$AUoSgL2uSdU zhs-1sr0%-J$qFLiYIB$GuLXfLMfWS;#0WHBJ%0JqFrZqhJ7L-ka^J3zvH8G$9aSga zSn{{@zH|Nev!xiU7ysd6lsq+9xmo;O?!9+9L-F6 zZ->V01DOHG?GQC`pACApN!$4u+n`f>hmQ4tHJ&^e`%!z+8a|by{%_gVurOEa`25!j>AeYi zm^D^7RJHun_sz;3AkNpGBRv2OM zMYw#pf)TnbL~Z4s7{W=wVDIA1h7kNB)8D+r5M}inL?lZMU>aep`qSM2B91cwU#Ij@ z$mO|8phzDQd|RAudFkWSSFW(Ni}f-6THxwry&m3l?~Pp=tB03qFM|kkJ?z(g-O)6w zi|f+$C%Bt*L3@&yA9+}p)a}k(Evt30!R2P{Gd*1_4NaV`_^X2qVtetgZc<;D$gfy` zSqHptgB7|{b+DeVdda2`9emWgW%t!i2Z^`V?B1&YPC&80qyu%<7cKw4G)SgZ+ZGPc za5Jdy@=8)~hgu%^)>A=)qWbvfHAiVUc}81*ERKfe5t(O2p)~Bb+Omtwm4>kH&Luld zXsD_^zM7#(!-BTtxB`%$48J7d2aq<-%ZUDByX#W`2AJO1)i2-Nr0Ugf7E zLE&fW*BJ^PJ$`Ud;1dNndECqNIR*M2eA()a6r_JjJ#SM(!OUafJr@coh+Wk0>rDM9=#t;^A|{xEe8)Abb2m}o>Ysc;ZwCdDTldm}_foLT z#^j4!1_kOK;^r4lQ*bA~ZO?oO1(V^K-~FypVE6Kmei(-W1@Fg;#ycs{rL}abe4yZ- zqIs6i4+^ej=8Xybp}-*f%0vYp6|;Y;8NO0f_FBNgmBPb{MX!ua& z5UwstLpFQn5KD@NpIQmqOyp=Nqd0H6L-NhOdrwcx&|v#=@y04~8YSoTxrYV1$)9t2I^iyfq*cFDia<=s>aC>=<;e4mO!vtr4@aw_a@314Bm&XfXQkq(qxBf3~i|>HypQ2m!slUUr=GzKZ)i6a~Nzs{2SQI9zBuf<&x6~jZj{UkKuIkv}~>zxMP-AWued|m_X zmGuLk!pU~);l1mOHPF1|D(n25I7RgC?vJJGmL z72PaB)w$)W*c26VeO_G^&!m1Y%l@u{Iim<2s~i<98&&ePGF8EU)+2?Q@09U#!kw3y ztPEC*f626#GHA~R71>Xez{zF){JBdBF((42comc|zbVOae}f`YO9-i58x^6PGJP&w zND-MIW?xs|R)E{-1F0z+6tMK=E1*~${tGM1Ok8I2I_zQdGLBF(lEZtHb-+L$1 zpZu0X!UZnp#Cvj3xjJjvzF!XbC7f-zLJrl5u6O6O<-khxD(GL3MNzNJ~~NdJkc^%aszn2`wHozks@hawV9 z7WPqlH`D_72^fv>|um z=$CC%+Q@Bs|G+oA~0}lp3L80 zYx_o{b#SOhoXc=X2S@WlbJcxy(R7F^Ja%6fhqD}a?$Fl5->C??@L@g7DnwkSPUzv; z8l|dPZ+*1(9(gH$O&?F}C)rt|1{n0{iHq1`0PXc0>!?Qtpheyp)z&nGSohmSKKl$Y zv6^S~mL5Yy$L9PNRx-j}<&N#4Y$G^YhMn7xXoSo4cALeo7$I`3CX?A`gw3BLw@Zo} zLwrU1ZgVGNxL9Y6r|dDt2E(~@JpO z(hL#*+%^uHiq;2_6f45Z#*M z>}7#Qj=j*~a~4Q3s^$6q#R7>v!KnqNmS``(SKyao37-i1?Xjnp2wkzNJ6F*P#s^K# zwr{b*S$=P>hj*+Xr7K|{%5ROJw}pZW{?<6jkXpzuvxcf%sO;w%Yg~xU3G-vwVEU?p zf7L0n?n_9wfArY~B`oFnbW2-UrVHuW9<)WAxXPx=H?~lE;%O+NYX@P^kb=lWI~XsQ z&q?dF!@R=U*HJ3=Fq9wVnIr2^uhtWzx*U7NDET(ZFLi)fx!mLQAP3lv3GE0ecYub2 zx}^8C11jI?-H&0=;imBthKK18JgvTQ;Vm6n3k@=t#Q{x&>3kzg;7|SJW4R!p=Io+! zmHz;FFU2=JWkA}h=$B<}q`Y(ZuU=;akhrZihGhhvHGj;MFe6ZObMbHAl?1kRAA1%T zOJHSE!YAI-1S%C&>%(plxcD!{`0xt?T=CpG6%z!GDSGfymom`cI~yvZ!yxrU!=)xi z27*=9)(Wg)z-K0IvmmJ(R>|5lDQA=YVnp2Q5(YHy7q~2~W8i`N5^7UB1CL6sJH72; zpsu#t^3o^+Q3=Z?ofjBnUaeI4E5L+>iN9#A6cb71rHuzvnb`AT^x`;;iD27`1wRue zzAy8cyJXFT&(Utt+jJ&=n7&)N&5^V#Js~LV!UX+ke&!uFCYGLh=e?Xw+L_C2yiQWI z`_;L5cP8#NzIz%@elHBmGwNh9F+XHc?MB)sc$r@PLC&|mdE2#e8zvNT7cN$tG2yYB zcw$fLrnKT@R~ChdIT>Q_vjqOt z<0k{3&Sti?ePLkBu*&-~(r?wzr85g%3|vl^?iy=mV2t=Qp;5~~qrcn0yUPs7o;^F} zkk3G}##7b@@*IWNl_eUaFtF#o*F}R}49Mtrg@kTmU{XB1+aQ1eD~IUec2@?(qc9z0 z%Ru?pvEB|n2C685mVL?$v|i&Ky(Y%M2FBAGuEh)-{Z`C$oguJw$h(E|jldNP-qeRZ z1hmrQOWt=8@QKe+6mKCw-EiD(`yB#%*sEIJ)DU>l5}fz5j6k(R-I9O#1g2gTC25=@ z;1xNZOg}=vRw4hHeL8^$&rSSn|0D2rd+PhJ1OmM`n*VH#A&^oV%i)bC;Mox99kQK3 znci9Lq%8#g+m~ZH9Zq0GQg!P7CISW%x@El^2r$+4Q{>hYsEy53@>@$_^N{<6^fd(L zzkE6PFql9C(W7lk^4RI2#%5A)S`3BWT1|4Ob^nEl)dcF8)q^KUF5xWUcO;pdo}@p$ ziooElyp@$CuWYjs-9}QQ_uYFdk{g=V{9F-0;OmxSvDRc>e9^CRl3GEa(NZepvo`?& z0dtirUIZSG)Y(ONkn7Ies*!gm(8gK){DBLBTep%e1Dy#N>SSK-XA*cPySd$oq>WtW zzkUV*^ROdF;z*uJp`8^YxmD7*x||>|>XbWSPjZ>Gh}a7dc>m~%LIlaEk?xLpI)MbP zjNWXLyLR99Qg$Hlyhkzkh#i6L-t*&gHUvTrTkMapCUEcwH_t0e0!nVQodl`78$R=g zR+4#Mv&3UT%9K2xh3v{CV*1S@j&iIlFN4KPK@dk z@arv&-a}F>df6W?lIp|Xhtl;3#NGFKDoV1BE8*%1T>{0%e*W?#L!%Z%BdO#(+ymG4 zXc1T^ylQumL_lA+#X6njucB|( zMkMc?++XulkU;de?EV;%w6@YF6_Rf(SXTW1XEx7|2>}9jN8T&+k-XmdPqu?3$}$6P zlH?7L+gV6*XnlTkCds5+iKG~k?;Os^gpy2-HMKuEGC_YW6&&+?c!ECvyIf!G>jd3G z^2U;XZd$0>q*Gi+}dDXOM;)_<(MVkNq84*a4o%>1kZgLUH2jbg+Pt3x^_BL%O?yd*v)FjjU=LNF&jT+F+({^u2(#F^gM_xeim_~G5;WYyt-ow1 zp?K){UI_<^*D=q?WD5zbo$fofZz4f5&}r^FTN3JaGd}0qPiOPSw_Trvi%)%21j|X7BN^~ZOONV@ zvYY&WOGtE6SA4SyM+rEy`MC6LE&(3} zGjYWb0gXC()r`$znmsu-t~2oMnMGl zG^R%0^(UZv+$hKKBmwJ#H?FriPOUv;G#z~i*vh+=rs7S&@KiO;;}8M;?`$r!4-l}c zX5NNhdkKhJc6KUjHv#NxT0xuK3Am#npL}r##lN!0$;Fv~{5lPp?(GB!H$0zr)}E?! z{aoQSI|58p-cC*1MDhCR?0IZU0CQPxdd+`S-A=u_|Hqoje{;L{Hbli2DwjlBPJR=2MfaZe>D+w<2cYN1dJ;;R(?K&myJzQ{7P+n!)&IP%R-+HYYxsbBb^8C44 zE<9WOsJ^k93s)hnIjVvSGrX;4S(kAk>C*LC@o%|ss;irCR>TGMhZSwwFSyXx5O#g} z6E1K9mpRvFaUpUD`s&lUaKGNT45e~m`!_w8cS&4${#!l6HJ%F#qq7>X#&F@fAY*t< zBo}^{=han(aiOwaasfM-3tB&)8yWg@;mRgE$=%1efNrK}njGRnq1n$xEKe@%nJ{RJ z+{J|ht0rePx^Ur>*jnJ_z=cqOjLp7HTqvCpJY&Fy3!0Npa&)Yz`@~YVEK4qIttkF4 z+l&iVzhqf9JdN=1$fM?Zy} zD&&vAnVT*%_BD(E>P@or|2P7{&4&EXWg{>WZ0=zAZUnl9EDNOyM<9h=KgamV2xx9R zvcvk(2t2XzRU)!SfY_OrO57g-zsg-&$*CjY80r~v?%D{XCibR%IyVC5i3{hBdXK<` z(gS%mn@2!;i|FNq`UnVK&s;UwI}8HJ9WOtm4#V87X3Eia!{F~VHalW!2o6Z}Wxjhc z1Zr8!1kM3NFcP=!$d#o-uyNPQW9Cl>;qo5Kpvmz8(Cnol1^od4=>?l>9s9xmY<$}J z&_3vl$-iY6^#_(aZ1i_K)C;vtGS1Md2Oh@l%a|JO0%5D;pM%Mrpw(cas=K@czVF>F zeblcFlG;kP-;ZpDJ7*#p!$H5{5xd{o)}bB_t7JRn`2U3aZ>QG04*Letftk546TiT5 zL0@i8MH!H-+lJx~mVn=>W5@efJONsAcCdk02oB%0{@Yf`msm~jyzD&n_gGE;e({fr zFZg-V>-!6zeaGn%0VSVQ>T!DejXqhoMr^M!wYfa6759Z|a|@4kV7YmngGa);u!ym= zj9=V?y$Zi2aM^u0{N2t}O}PQ=>ug-Zo;HNTjehMCbA~bJtY+S*4j21J+*~#IAA#eQ zJ{~>vo510^+O7B8NX$yV!iL`@wqI*B{hZk-cJKb(td%v2<%6>a+LU?N-UlDnJH^9t!vo_V^LRMiCZ{?~z{AOWwRv;x_;~1)edgvn zeEi=QCz^jVAM+wF7&B%GaO_I+uW$AWaQKO7ahxIn-n_)>>x4*v6?U$RDOxDR#NiW7 zryPVhyKP&F%^o3+Ul-@?xlf2~jsMHZcM)Q(HTFN}?Gj>@_R=J`gF;+%almr1j}S}S zR0Y%@7vk8j|Cz;|5n@A>(x^mXtdhfWX-^@(9s5OMzlRXZY3(YRN%^hhet0CL?6z+j zXVy6hvAv#qr>eaW`(C_f7P^5tmsJ)OLZMcOFj@r(vCc`V1Jt@U9;xnFFT|#XY6?-- zLi}W(>&DVGLflX-UbW3oh|6zg+?$#!#LuH@y5pEaoOrFIE|?HtwUgtg-C6`#G?p3G zRw=+=rxzY8e;~lw2FJqa!2;|{UR`f-oU$J^9#8kA>U6i>(c4mhgMRF}IA^{9r@N_5 z`y(O1?O)x_<&W@j^V~mAgMRUGWYIxd^eaBrIYPIIN#W!2&F5osL-^QN?$5eBst-C5 z=dz2H`1ncJLg?z?VRYZYDYAfvpDa5~9}MMTS7T}KSSxCMGr4Cgn}?;>KJ5#w8N>1E z28I$>$FRJ?rCWlvV>sNkC?!jJ40~04m!5n*ih1EGOXH4>;`Zv56Q}2lV(Cl9x1N@f zIQ>F(itAYt^Ui0@$gv>tZNvRVfs+JwZ$#|Np9rjT$b3suI)RHcwkswcq1F>Vvqjqo zEVbkQJwF2i)9$&m}2zPf8QmV>f;2=qMMfT`}o=Jj}(mE&fV_|G3z7e4&e2 ziohAWzYI*t5m?RQXT>@lf~w0ucg58N4stDRSh<t%RM*O$O=#)`rP zeiZM)%5#>X1U`Ba`|e93aFmn7*+LE#_nFxWANvU`N-!hxL{yx`N=zpfiKX_}jnik6 z*rW8Ob$~318)#dscBqrs(OY@-Nh1<}2zZy)Zb0H#?QQ2BY)LGyu%P*&1Bun1U$fnL zg2W1tdM5B9iA|$;j79fI?B8^FLvS96%O5{tuH}%};$U6CmuWc4}X|2R#V@_$8x$urK^5Yb2lhaw|1uh4^0@qyW1XbuIA3KOELHCVOWYjkB$Pq#)rfjdQ;w zy{W>B&QWo_(ECo7!O6LPGAQsBgA;h=^3HO5CPx%nEbmj#l;@XaT~NkCHk(#2wmi#18K*r=)&UD0Z)Fvh zGg)Z%?R^cOs+fpYak+5(J`-_ur|zD+z(i|9noce|!9@E@Q=Ll>GLh-@>T~H{Of);q zE+NH_iGG^C?VlIMM47)I1<1rQ(Y&2^uB21v?@OJ(=3K%=Ew=+B&;4eiv)L`p&TJOi zB3!;Q$&iH{pT6V_c(Txnz+aK^msx0^u3g`&d=`53$tS|0mW3V+q-QMa#71+NnNKtCu+fdQU;8rOvXSAw zhEl^uHnRUcyY1948}V3MF3|t6(V;KNSBoVi5wWfDp|^}A8j*jSou(#Rt z0--T`R!O3okM9y}jU`d~!iaQd(R5@^nt2aAU!kZx1M;@c}EkO%Ef zd76R*x~7%Z6gt5|F3~GgV;fmWNj>>c<2x3*GcZqE_5}-htL_O`yTw8`kkkH@FlxS@ zIJX^kXQ6|EuP$Y;W}%m#-ljKdv(WHb>Ak^fEYz~5!}gv$3n^cb4d|h<(4p=6Zi|MP zC|GBj+i_}MhPKUqs{E6QbhV9^T>Z*K;^U9rqcSGSN)cp0F%!iUd~TVY#Y93!-gs#W z6J3{xe>p(mij23V88?_{N;NIIFNQ*=*p1UdDBk>luD}D-zPE}@$`&Sit94J)4>3{y z>CmNKW=yns=Z;*J6-<<4s?xt)g^7lXGB>NqFj2(zttQbz2I{XWU)|8fK--@SLuNKH z(5qTc$DAq#I>DLtmyH=n6f>4EP{csTJz{6we#}6|%T!e#r!vr^%PWQ=ZZXgUQ(=Qo zA_LK$pZy#eOJRM1#otQ|WRT6o`7bH~}jfQ!X@OYY#{?1?$oJ#`!+fyqB ztyNo&zq}xZ(|bP#OX`SWsfF=`ZomXs@ayIT-Pce4 z8-rzjg;sa=j)BF;A|LwuQAi!$H=w>~6nM_<+TvgmrfWL14K-5w^7MDv$~^>3N(p$5 zlunf2YA~;6FBeYaORPIwGy>1J#$D1E4ny6#%Ht6*48Nb83HFH?f>n;zFC4#7`r(#y z+NRxuuqoNysNmNCDEt>>{?u>)497fp+^vZ7215 z;G#{)pYl~baD9H*y)sIN+-=BZvrH*}_Ou#J!yX8@EYlpntp~=X{pG$2h5jd&6?rW1J!!@nn6JnX7;Nlg!Oays8g2 z_5kgMx!QT62Ns{$b8(#33#MbQmc>c;!p>|d!?|+3@YZ?b7xvs<$WW@DESBnpr9bXy zjZx^j?#aW|^j=uhnp6?-wFit+bH^+n^?-##^3575t|DXh+U4teVC%XJvjbH8gTK8; zZwR~LVSP_wB+(54YhB#lF6w~|HOf8%ij>~^^Ll*RKsOvveqm`g+zlhQThennyFoeo z@EQHgZYcJv?URY<1_i6Tf2W`6242vNpt8trc&%F7aK(q>^~u}5-?1C~3?Ed7%XULg z&5yHj<6W@otL)3ssVOQ!X;kUn z1#CXAd-~cgusZzWZ`f=Kxg}TLH+F)dkApBdsuL(F_FqU#o?SNKe=15Fz2RQ0%6Fu8lPX=wvLn3;Zn0yup|~9;eHgwOw05}U8-;#Lw}Mgk zaQ;K1X7IQ$=jSGuMo4AXELb_e0XFxpTXe6a9%dcO%YR>43qo|-g1+?!{BW^N8aq}4 zXRcZ`I=uY?7V@nHc6UDlGyPwJX9))mE!MQHwk(ESrX{n0DyIh5Ro)IJ;-GXu824tUxyJeUZ?Ib*?1Dc-8e|->7 z<{VSFkTQg6nLnFDl}7Nl*Z}&@JT7*0o_QuNk-*=^o);xj?{uy7To-*x|1`h+d!_0P zg-u-T^Xtd3&ILuimX0y(@vPE$(3^)RyS8;}Ht?{i)xRrl`h478MfZrjO1-NurEb4D zz{ejpYQB&&7vSfzYmWw>6yQlMzkjRq1=w_BiXKP`anLU1jWU$}>|0zH-gi=n-O2AR zl8Ka_HQl@N&l3v&%IH*nrSx+3{VST?LM;C-H}JlI(yw2uO1#BF?C5dv!sI*=j?Z=4 zzEw+vj~a)aUbRGo4MQbQ?NAkA)0}DYLTwS&>B{yPu@T{*J8UogjUwEzHSI`{9rd0+ zKV3uDO@u8HJC$0zMA%)KH~-#I5$3gKTLm5z;g#23JHFa4!ubsuk_sLoTx9EeIAo6q zcb~ghQSB+hx0B`{WKs4E7vg=EE48o2D}S|3gwyxBn{{mv;Y8!V!*-ONb@2%6AayQL z``cjZZV^_wHyI=8BEqi3xk{ky$&+*EtluTVQ7y+wIu%!9)6-sETM=$9itr5HDZ>7# zx>Z95sQtsWtGiB#u%kGrBK9&Bhs#8QWje*ToJ$(NqIiCLueWTc>Y%&F{k`NkmXqKw zVycZ}1+B?xIxvn+2Nrd*LdLOZ5$ONU9>*by^f2`=U7o75a>8G%ty9ZL8JrmIN`@nQJ$5!(B19FmRrgbwiBb1irlS@FsO{_TwEU z6zZuD%$XJ^#-do?{4B~}RP88HnJLCmEZvuKhldsS7ab>CmT)JsWX{53 zQ|R!iAXtn!Z;UVP+ePt-H@T~rQhYDTS@J9~-XCCnepcrME}#ARc|zd?)$g{nqcIaW zvL#@#u>)1ds!fEc`~+@r=+d+JIgTekS$nvKQT!U7>lumZ--)Wc4$Bs=Wmavog__q6i zINpPgqc%>CowecP0KY6;cm*_-K%a;n^!ZZ1G}R2RoRDb<7++QjhWQ zes$-D-(EcY)n|UR(k>p(UbEWH*OSus4UICNsQvCY@`c+1c=(A=R!-X~9`;QV6A zVcKE$9_BfU_hG}9ybC<+STtYNKZ=KAU*e=M)P3l4`t8~(inr<*Y12!cyH$L{Y>o`tA7@y|{onAAWOI&3no}Sv8??kdHkc zD20yx<6}`%2lAby&Zj52ES*mE$HiA#MOA=n+4V7zx&q8ea7){|T!4cv)m>4x5@16& zNxcR81UTN)+1ENnfXh{xKP;LAct{Yfw@QnegB4QTVCw(sRasqs=$8;H^ys(7n22zQ z$;a`ct0L?h@F9qB1-71SaO6x*C3p`X3Yq{o(Mb`F#^E_2r5f zo6b_`2wpjfRic~T|E-?H9-iq-*9HE?dfqN^YgSI-?5@fA`D0VqaqHwgmv{fLfwrt} zsx6HZZ^zR3^o+(Sv{LJstwiToY}M>L8cFBmXeG}o9;9=M9^MN6;lSXem#1trDqwKr zUhE&w)?;$c$Ke@&J~KH{Y3EiGhuV)Ke92Y z|H|gL>;Ij-aF-+}`@r;^tHY8Ux7of|Pe)2|n#L-B=&4QPY~W@oPm7X5m-PbEK8#4B z429M+?_4BNl4M8zCJq}Zn%_&D(qYu&9 zkcDp@OYO>y%h@v~u^<&DWZAbkoUKIOyWR{W<-I0t-W3M=X{V+EnUsDs?cqecXP{wgQE2ZE2HHdpOV|Nj(Nc{o*H7e4p8g`yM^Q4tzt9->;?P%31KG%J!y z(nu1L%1=bnpb%wFk|de-QD%xv7fGfvl_}xQ-}(M}pS9QU?!C_1`+43|>Uzp-%U&UL z=6?Ork0*r?!FLGp3lc(m7o+1c2|}ohxp%mtSP0E@r_aspqt=Bzz3*^@5MHrTrA>^1 zg5Ao-e@QY>$>Ht!vTGQ~ML*0hdItl|$={)LejfvgH_i0i@?xN?3pXE$y~#j-p0m0Z z$1~8gT{mXtXEIQ<2pO=Ykb(Zr57_;(nt{ATxI05z7--MeFd><426}t2T%+nI1I4W_ zXjB_!pyiqJi@i`Wp7+@+=jbqy>4@qVM+GWhT&Htfh=HnE!=;aY2_a3JKBdc* zLa421C{vIkgj{cy>3#|nLQQTNEY@LaU2jfB)lMOlai;I;v(-W_cKWDy7ae8tN)BHurz3B^@79wUbR>VeVC}nybR@n?w2pq6jM;jk0 zYp>o)N3RFXZiyPw(erhEnzO6u$VE8upv^)$3fj(hQ=Xxr?rn>@Tf1mzZIE|sMl}sN z*d!`EEuo0!j2G*CdP(D5S;~Y=06+F5^FsTR#XCmY{y;K9fKZ)(4y& z>j>m7sdqEEl0c2ZK85Y&1WNr~U@-HEK!z(tBOBfl$ZYjZCC`@x`jApSVE2qbH$H3< zstqTQe}?XV>p}=*5+c-45PR^es4GbUD z@_B_z2$Zx@g|=UgKv5O(4wF&@3MxOg=%WOIgqzZX6Xy{qez%**YGDFpB+nk-G$jD# zciu6)F#&kJ@YrJeT>!^zEOSyz1#rORg>(KB0sJlG`r=ap=y3VNlGYZ${F^{9>oFUDDMWp*qWY%od79G``De%uw+$XReQ_YD8IY!>RXEG|YW;@`RSdG!W)DbfuF2!K-BUiW~J)Fq_n^>Z>^gkFv$> zSKj*zCqL|YwEXuZxUKu4<7GbydCqrsd@7rOo}Io6B#%sh_ZODA?c_LoGurCdX*dpI zJ&H|3BcpJ*OIyvLl2qM2`UGdTy zgyTUSLADD9;9Fx)T%yn~7!ETx5|aN31+^3R6pZ>|pNUO}+NnP9$c}}v&R+N>Nt0m& z_QIkIQDd#p3)__(j2cRN;2^`S<Px@39^aDEGO3hCaC#G)7%palx=zNH zd#@q#!-t^x@oP@SvM+F=-vt+HtW31bZvz=F^O#r>snz!t9?)bvjukM^r|}DYXN1o zUg5m`EfDOge(yh4Gt70!5t1ryhO0zQke69AOm&6-te9?sH}m9GFIF@GuFf#XOl^Y7 zbG5#5UX;DKtBrZD38d3%o<0n20-04kuCo+QMRW7aqnn`WL+93~r<>s8VX@O+p$RVj zQdWp(G=Ys?Lb=a)BaD|DIH}4sfv%!uLV|P?xIcC{C^pmxHG1Jh&c8+ocvJ4uo!tm4 z8uwehJ<$lZaaLg$Pd7rAU2W|ZzeZSn<@ED;A&qeLUA^Ouy^Zi_l^{Jd_A9uYxE&ue z(Ey!aA3qA%&;XI|eiiOls0Zz+rbAoHKEolm9gWG0KT~}nA4S&HftbI-_=(6`s68T3 z8p^DJ%IFG*A?q6OYTvzK%jp_;&&>U@;7TRKPhP(w*zat|nk||GY;&@7`iEq|5z^dI|16w^lQ`whXTn(l_m~ zs=DL?)Jtt?A-j*x6kSumT<9CUGLU~BUf*^ zSrOBXcVryiV|{7jm|&llg_cGR>!=A_g!SArTNcG>AnO zPZhn`Jd9VyMjmqS8^LY#{y+XF|KRad?PKF(qqykv+Z(kG<2Z9o5Y2b~1ePzo_13;+ z0*7U7t1x*viTe|B-+Z$Di^E<%$f_Fui_5OJ{Cx3b3a{jiz1XAs509%JvY{9L!%p%S z$`Wj*afp`ez|G!i>^k@8p|f@~*mB#H2cv8T8%S6_IjuE|{SNF{?Ho0WorkMf1^u(Q zO~`aTe;W%U%Rj>bFIl)~bo`--1RIz6&bX2GY+SX9<^A~u8~e?#Uixo>jbj%--`Ane z!GqZqmIEg_SSllaIwppL%YNJm>ucj+QavU;X(1Ok-1>U9*_?}Yl207Dc$SO3$`c-X zr*LtmVO!UD4Hy4@<}7E{%f)R*iYKCfQ~v!48>A$8Si|^Tc>YEnZm^)Kmg@4bnWO9A z&=wxH9GtMYV9UdsO;tipTk!BfiJMnkOnJETLaW_!V;=UqGIT<0H4nS%yR}y;@^IMn zg3?q8Dt_CWU9G|tE?f1TnB?N<_U}KocXRQMX(@yLb}r68{po&w9~X0X6rRW%p!RY3 zjcC~q%ATD5`<04Q-tArU3kg03->lp;u znru2aE=G{tl2=)F;siObgf9Pi4ndYZaUA)_65!ca5pz-rf>in~9M?9NAf3v_GfTMw z%%%I73C0Cff1brSQT2!`c}ZbZeV>?&XBPRC-!Zv`!}$G(pDJ-uu$Ek|5<{eO%t5HXVZO zUT>Y{vxXp}H98x_sd`be3Nq4*2-5jW^mO8=0OzJ>n}ie!a1xSW+D8g-oqU#(sJj6F zmep)~ts%f>`Y#t}4e_x}gq3S~93LChlrFM2=402&5bymXJWR^Gxv}vP4@YlEG9s%_qe&$e3hZ>D-FgUepC18VcrV2uWTHtBBv%)&Bi|b`+}Qk zZ0xF`ynId+8;4ZbDzpYu_eyHfIQtYEkB2RiH95=1ZKe~;=UKCHzEO?bKOHvCZTAb0 zS;5Ag9D4aVSvIcgm@TkhNY!7o(IlTju58G32*Jilk42;B46tySwLGt~hJ~lJZ7QF< zVqxd=5umx_2_jJDG*um8RLR z@>qCJE#2<~$-?7j8VxL~SvY^?_%8W&7WJ+)Tg-H^FtiEeW^UCpV`GonD*Y%EYX7ozJ{+LVyR6Ib1m#x_ZuS#)p!$+&UuEyf z#za4JBQJO-)Ekrp5b8;W%8|277ur)%kYjcdDvqo(p)`3*>{>- z_Aln+=v`;FHgBWmD$?p+(gn)qhuu$q!pBasF{Vl%Da_hdFH9F;hINYeiM;}>BPSYh z_?-YN{cO6aEDD+=HVPt1Rq#-RDUjMcPiMwt70xWli^^w(o~qV$!7h% z`%#!Yn$1}7WUmM*6f3b|&0i5R=a#yQT&4(`xEmJDW{4mQ|01pT?!xH&fc|2$mbvI) z#P#bVFc*1tT~(^cnu9zNI)?Ws&OzUg>$b*4F%VCaJ^V)?ge+>>3g2E7LaF1zRd=W8 zXvW>FKJ^S866oZ+A;;lBN{=PqxwKG+ zK&DYIA}@Cez~bl8g;x#;;H6?_{I@1PNVe7Ax$4M=>XXO3?Phq;c|D!5$l!sW-Rs0c zHy)^M-r||7!2|1i`%U5`d602m!nSWN4{nK;W!H)FKzebpbD|;-ob`vBTJ(AFBcgTH zx;;DyTUPfy|0)lNbJs!(;&~t-Y1x`NJdoQQ{*7JF1N{ZHrv`XDxT$v_uT7B;r8M!M z%XaYL)BAMZ_al4|a#c2170rjPZr|C0KbmOi!R{{plfMpUxXroc61(TTcSsx+;#7Ft+%7}VqoP_@i0pFT|3~$r*v)9 zp@RJDRG$uOnRawc66n;{flr2#H00~4aLq-ZhL&f=`V~9VkWb*6(I<)2uji94*d8@zf z8lWM@@U1<5^)%$lyw#?jO+(X>3hVrC(U9F#k&m7$4Sf=oiF4gdL$&trGmTbL{k-&B zVz)32MY^OeN$e-kR)g+Q?P3DC>P&2RjU$kb{()H2>y++yiXkbP*GU)Y#P8|V= z)jT@lCo2H?$kRVnXaZQYRY`ifpAULAz4Q7i`OtTE%UAI?eAq9v_di=|?riois_HvN z;cn+Ebi{|4O=<7_<@nHAuuzN7lmwv7wh*RN+euH(W%&qLxb<+$)#)bho{f}Mu;s8<++ZOG?4L~;?R>?7tMcc= z-ClBFKqSr6xrhT15m{Pel^i(Ob-q&UI|rKnV*&p+2M+Ht)D!#5f!oI4&R-|EutK5wUYzfN775YKX5=*^QE@l zH7ehvbZQ83K>Nst-o5f1@Int}oZ8s%w&eRxzq@QmkhpDl*oF;#fjPcT>)9}z_h;|C zZ!E}eoor3A3&;%_+ilWkVTqD#?h5T$c%rW>yCH1`Cb=3;J_a+8N)LCL z{WuLn{|Pmk8BD{#mJzF{Xa9g%Tks)#=|3>f{2k-)ZVFC*^69J5or2R26;X%c{=!+8 zpU;gX{{l0}@JrS6NvO=!W+twjgdL=A&sf3)=qVJsjINx3-P?nhbw%T#Ypvn=!h0M( zzfY~4njM2K5(XdRQP8KSUu#w!g_iAlVJ5f!fWpq&>GB7^A&@Ox-CQsN5V-DDCHtN7dtm3t_S6j)-7wtI`0!=PcVPQ#E%;{f4U(j#d_&dR;qa`L(GG$M-X7KS z^+j4haCEm$+CU>jxs9j&G5rd%-&?oKsWm|C+ugn6L7yQ$eBTQrms+^;(YRmvWDUFu z*4S$-S`8~ampf+4SAzAw1k=+Q<Au(C6a3<97^R7pLfXu*(#m5P%oMAHZD)$% z>;xLI+Fk%M_Y7v{SG(^VmJ9sbtD=q_$brz4LFPN6-@rAEZHsOy zzkzJ~v#OepvH|({jxyL;@WZWN(Yql7G`4J?t+hylKhgi}YDbd6JJTdvYg01hH+1gI z+L;XdBG+B3I-U%z;m4c}J5oVr`SGZl!8F(wFZ&jOz% zzpILUUjtJ1(#XrqhU1ANJ??F9z@}n<>g&oJINGx=-nHf};E#{hG)i)z{LIl=?bLT* zx#{Y|4fFG0;UXC?ZQu7$8?wUDBj!CQbeJyFRLuvT=JxB$t3QC%eC{Us(gKK+Ci+yy z3t+eNn%T|%AKiYS;_i_=Qz;9;3Ts!2?sjOESOuH zf(g#WVqLE^Osp4a(*K@@0}aDk4=KIGgjJC`+ zrEu_bSV~SdCO+hR`{(oqlXg8zWn^+NY3QMvY5o?Y-s$GRX$pn&J0Ha4V$x#4Zv(Yl z9C&WwtkbU?jFx<`^-+C`1Lf_WY@G8J6C0V{2@`KH+N&>Vm;D9@GOp?r2vNAOvwFyw zT5tJuui-4kd!8)0vXJ7_uQ1&3ma4zvn4#zH_c(Ch^K?Wn#tCU*gQ5>habWnd#?HVp z++7wy*0)q*Qd-TkjtYl}uYQd)6Be)w1I zv+Y>pTx{LcrA|yh`r9R;KXCTS>u;=1_24wIk(AD!ln?vTs$Ry z{E{<%w8TORYp&q8OWseT>uzT#?f{ovJxNhR$mDlU}m{9(!Rp&|Jj~_ywZ}_?Aiss4o0`FCI2WX@Ymka8JHDJqoi_Eq?$Utmp; zen|{ZOLu}i?7IHgIe$uj$8P=M5K53Ge!~|biXfftI3)F^PZ;~Lxp6J;r%usQQ8z){(6J%~r&Hi!<$9-C@m;570 zgRk`}>{)_z^qNYuXAz{BeQRS2WtW`1JbaSMBQF~?_xvTuqH_!RWjum(?~E#(5}}cs zQ=I%?&Zm*{e$M!rGiYR5xKgk#K_d$yw!hZr5~T9eUgM(_zn8zVj>H5({z`b__l4rq zTJ~St4~l<#%D1vniYL?ZY@jH`6P@pF?870*skM%4Uejr$>+^{eO$8d6eId%tZ6l2g zNzHg2Z$cv(v0Z8zhiPQvst$So02qo6eSKBvWJpG=eZV$4+41q|D&@U&a)O!8kKacp-(Zo0u?Ohn>@&W9 zf;)wGq@0HW>Ezrse>ED*U|#$WSbl9<3S%PFU4Ag zeVIQwNyDz@eOYv6R5n>o#VIjz38Ow-;!S{)OqUd_nmz2M(z8) zRHE83I$4sovu`nV{vxXc1#Ct2ql$Gld<&iIwAA`>lhU)1Om)rKHFWaHv-)Dsc@(eW z*P1UwG&1OfdX{_>jZ6>^9?%R~FF7b-n6D$uL27JdJeqt|7>%eUt2@3~D~3ZQV`62{Lwbp#+nf`^+`D^Y<82 zbNJ|7eCsM|UMp2KoEK8_B)xU7*q{KD|al)g8=7C+%8YI6X3|<`_H%82=K)R46!zQ0S=D7<4?E? zu-Agfl%LlHIKg1~3g-j?)+qQT`=U~ST^q+bV#)=0cD>!z(N_W-t)#f`c%%TA)hlT( zqIlZ0Vz1lnqUwd;v7W0Yz>Il+@0BeVV0Yftc&DWToOA#-?f(CN#4s#(W0sHGWO)r= zhxpish;U79}8O z0owND?b){z0+d)`x1@4XfWjp{#ON>tNb#QA$$?q{vU`0|W3*0yhHXxck7No^e=aX= z{IdYfo;clWo-ROm=afOt8v*(*r>+$rBS6fI`S_C$1c>_6bk~v_0!05!!Od3%sAZKf zqrgRglFK8N7

y{2jgE# zcl3ujM86yZ9ZJ}69ewa8LYa+h-`6A3#cb@T{8zQ-Q$3P9?s0ZrpyO0yLaC^u2G40PUs5ducDY=x#|kzFmfoNwdf1Ml$)hB^bV5a+ik@v8tisH$HsL zt=g?PLYVKnuRPI2h|Wh(nlzIH$TS%_nqtd?XX2vU|IamRmNcIYBl&K0%Y)njRURI2 zx&w}uvvJJrFFV_hjUjg5$I|ch&x~R~_Y&&oE)U zDNtrRd9OcS{1csTUXM@7ebw1BnXp)0W^bI#!bM-BkZ&a{93JZ)8bfkpcJ?!tbWuGD z-p#r9&X0*MZiwRJVLJ3qq%;I|GH@W}$F*kC{~r4AcD&u)=B#x`?j7-1x8OGp`YPZMx|Txdxg%{G4-aS>OR4{#({oD^GG}s?zP=2*?>l^dEy-irdI~!;S8;JoY`vlN z2M?EqtGrH3<->rw6*9v^1e;;a!b8XSm@ym|S4i?_k5W`wa5fKLOztFJKFdXm`Bt67 zmVBJay;8;}xzIB|&hIkeZ2TH8J(YR^ezZ1-!eq(>_ekQCr&`bcJYy;k;r5G7lKnX_blLa(yeS9G?d1TlwkSTHZnSx+b)65((RC3K z*#gYV>!LBV3aVPi|{~t$EsxYQEwwd_Y{*6^tmc;)KhJ@x< zm(VPKm-PYJ-Wd@G?_qwCOl7W^LS}mEu4AjQo8K1s~0hPvWj@g9_JZ*k+ zGEtX-wF4_xXfWvLNxZHbKZcH|=jKNytz*EvJbAU;Q#w=mYfbUhHFD_`HIN`Nt=wC=1DXBV-T%Rb)afg|)y~LdUU|+Rkn9bU0sJa`;<49o)ZK zKL7R;PL?v7yPWA@y$_D?BIoyX82H(PSO7wK25YWL?X2E_Jy(yUW-ESP&xd!Uwv6P@-l(#>=PANaa> zhCLmU2mdy?#WLX9;230d;xonxO}kx4p90%YY>UjGL!7Z7?IM$oIZE0Eojo+942|zI zaG}Bft7~q3{WF+cGx~n=%TsJmS(geeC25KH9GzTt>pyBza+G33tG)T;D@V)%#xa8L< z_9i~yt>LTw>yPNL-^KatIKV)$P^LAX_=-OtIETWG8PKel^mj3-|LweYDVIne@02AB z9rY#ipd9zXu$%#Y=KBtIECAF5ba57ngj zy*^XxG10e3HO#!K5pMhA04BP zC6Ru{Dj$hSY@=bXT2$Xy&@jO?DbjTV4S%F*Dz{?j*x1lhOkc==jP_!KX@hj!%hFTa z<3>kyhX2|<)9C2+d$HKepAJuP^qN5{I#RNGRt5Z`gZeS(x18wzt&MT(gIRQ#dsZmA za_E?=zFsF#iGkyhDn%+<4CEN@lPVQgJa<$A;QW%~;z4h5_DR#g4HuTI#iXC@%eVmjmg>j?qXWb*jueBOK zEh(W$UaW3(B>O&=T&wy#L5gghf+vdPepeP2mga&&cAeWhtv)g8dGMyZa>6AG%NZTb z>o{0HyU_7-BFU+?b}OFOvGCD5dtr*S2QytieCaml;(q`D0RR6Cmv=nXUmV6|L?k;T zva+|7gr|%Ksf4Jg2t^cy3dtxXqeNRuqJd%Q*!p7T1N z^Ev1BJkLAVFupPGEd{!<1_zJ)BSZ7e-sRk{8^E$+j=QX^ho1QM`-PwCP&y;Dx8AKD z5fbw}YtPj|zxd0yEta)-@N!xDqm5MvkJ&hC7+VhQ4euF624%R%clNo-WC?ccPTSKZ z@fM`i)Wk=(DxfYVsLk=JMB7;PvFSrq*cPEQ+i|M~U&jq3T>jO-Q?j4G*uM^+s+LOj zo7SP<#xr_{R2@FkhX1jON@R4=u7@6 zo$Rl}yQG|RU6FMto3+VfhSfo$?P&P(7j>x8rW7i-W%oyGYVnt?F(*}Ci{;c0 z*W4b}L91%@4f&x4gk>L|={nm0PSJgfJ8}((bbKVXPq7}Z4vc8k`dYL+wG5AluSL+* z3YihT8tAS)Q2N!d8g(V*%SHlfAZj_K-epsZW#_jQ-dC@~2Ft;zJ8g9!jq%vKWY(eL ziO^>~!&-C;IjRlOt3ei_COaRigw@l!@@d6NP|ufNpKz-LdE3N4N%W=PSD`H*d8r@9i8Z;L@cv1SJ7DLJBR$Q;GL4QE_y7@mfSo(6EZqChG{3<@DtE*Rs z7Ygw!wr{V)@`Z8xY3W*=(yP6&w73deGXo#qvZ{hih`6joNd*)}Q$D;sT#nk!+>1l~ z zUtbG9!_|@k_H_{L|FvhPpdR~WmdX_!C*zFH%h>7(Ccd6)yL`Co1MHT)ke%{rftFQP zx`b#8q(v4-F6%ep)!QSdzc)95p?lqX!E;vtpS z@P`-`%X|#ig=JE4`|?tr*hC6~7Jo>}PEj$HhPTRJs2D#P6X(8_j+C&BLhY+GSQ+=$ zua2W&M_N%qYC zY!^DV3~%|GPo`t*!~VK>Wg2eI1fS9}r6I#!$IdF04zVVs_aY?}{I_T1R^C=BByQ_$ z%eSC`^!nN_)jlewYhA`)Cev`1NuR0Ap<)~VvAT6KG~_t;UcKQ!hdX7VNUWQN-U{KL zq#Qa<6^JR=5OsRR46vJbFu*mEUjMFxhN%VPhdm!D5S0EEYUV_STdJ*JZxtC&x?8O# zC#iUy*fVT$k%^%W!{W~#OdO09cPZ{-A|kx!P=XEvKMU-xPaS9A-q3@BgttsoYvuax zmSUp!UXeoaUIuh5`NTB#GvKsMK6=>{9m2Ea1E=QcczL$x(zZD!0#25MCdss5H*ZqS zA4wM2ZmDs!w=DQ3E;moP$%cwTM@xSP8#&8dC6eiEDD=puUe0GDMCEg>t~m$hsT-`L z%{W-#mW~u$&cXMWZSsrTIAHkYe=&F9;O4G2ftdsjoO1S`lO(a>Q@V7=VksM@Pt*SM z_hO^#_&8;{P=4+rUd4v+c)niT zC>ti%`uD`K+1Ma3c+let8^h^5M;I||co@1?oC;#&ynK*#KOY<7ZV~TX{<2`R5F}_d z#X>`6kz7v~3k$VQhj;g}(0);7yO#tT%gYY*latsG%-SRRvX+g2spqfQnQUa;nJMuJ z;9!e@^?QLN4oWV~Gb7wNSd27`9PMFaA+&PiZ&MBigUAy)L|t2#Wag!KaM1p4b!-L~ z2RXYO%vy>0WuL$LOOJ67uq(hNZ-(fX#y8)fOKiNU`>`w`hlP*b+ngUBW5HPTbiAG{ z8@pJK_=4+LC?AnuVz-3_Rb0McxWIyKvYb#rE(?VoAN<9Cv#_f5dwk$t7MAF@a$C5v z;MU2_-PFs%mdP^v*Tk^&a(=Y}lB295EMa#XfGSkBz(Q zQKy>!$XM_xTIYREd39X{f6jKr`x%~?JeDxWRqO_%ADxm0$}Sl6*_tr-+y-B+U6trK zW`btZxNSE)jbI1Yqrrbdpr|<#FZ;j<&Q#f9_6;MLcniiYxR~O|RZlAmUR^xV*;!e6 zUjy$;ZPi~L)Fpr0~9}$ z^*o}W0xz)(M=qoi>!qaIw&f_{AD>#PVTT-+i0=q)s?&k*k-Y-neN{m&36T35sf6t! zc89i~R>R$%{NVzxwb&5R|L8Tp5>kdHGV69JBmJa{^D!G@e~>oQa^qp*Wprb8KF z>XDPUr-mT@+aHakl(F~1@NpAYMOb_ce`)<$3BPO(op)$eMXzz@qbxr|^gIckxqm|u zpPXeQ=TFKZv-W@BOS2-k^=+&lO4b`{nS$e(!i|kqS0%_I_HFriv~0`N~-v)gY71SG}oN1VfBt12pcj9RYeGr1Dl6K7bVjV0`nmZrp zt%{wsq(}E+RUq7(ULM}40(akl-&N}saa!NnC^AzMt~y08GA(srrxhF`Af}FH-{FE& z8R}pM(p<~0tDtA_<#|grVeIKT4 zv&sOPay4D8OhpX-=k<9yP!l58J=ZDR(t@}`cwxne3Mwl0$L@30!|7d4Y*8V3=-gIF zP-Mu%>+QpXm&?~eXu@fQ-kbu;Uwl3RhhW>MlJYH%)F*_;(4ft?>`9_@-y0q=~yi(MkI|3FX!x33aRcZ>RbeDs(BRvngbdoE<$ZoF=&sqso#8HqzS*!pPd2NfW5zV} z%x)!^IG;7;8`gr!<92BMTMPY_eK}XZ%0lIFVuu-Z6%KzEjvbj+#t=nuU&H)1jJ$r4 zd5OIV9-908o21ua!qPAxuE7ju<3B%+oV7;!v*Fu${p+#j;MLoI3uBbsk&*^8F``&e9fhCcir02TWC5%^=*eGr=aU)R~w|F#wNlY*pRRDd9tOh z1%5>c*Sqlnp*?)8iNa{dYxEZEb-sNQ~eZZ1`iB3}X zP0&)f{_bch17@NClXP)^4cCfWrFCVSza`?49b28@)&a?@E=T#RwYSG+aM7+dxG|NNkyl zHWh74BjYWSDHy8ks%~CNi$r}|4| zo@G5+OV_UHFeM?rJW4Rmt`YI;UnDov$@m(x>PFQ78Ag9*$jo096#Bh(p;gl0q|tF@ zVFL|nqg;N`&*|u{@3&mpN<{*rNUN-ritOSFil-t4s~H+kv~fPlYe@1@D7gDw6h|;Np^^;?I#&ZS%5JG*HP13@$jhI&$Nfdq7h?qymw|eK0QSt6=N+!{-kZY?`l|`uN73{6+ ztEZrNK9xdhpx}>P@3W!n6b$rOJa#dn!fE!`QSXOzJpVhcv->X{;klKj`$$x1uNnyJ zHzI@cQXoUhx)FE6c)d1nCqw?Q^?{x7WF&Td6;#k6WBAEe<#l(-IB{>|(8LQ8LO)Qu z1vzB=>pe7KdfrT)WJt9%14>zn46lH=w}DmFM1d;{6serFWjtCHglx;YWSlh=zo%52{i~kWVR` z&o3vz{GIkY@^Uh`+H2K5MNm-9SQ1mYnFb-4+28s}huVzp9)B<}aAf9*rZvGwLHqN( z?3qv=OORV-&cx)W10iRRGI3a6^;FZNCOnwSy`8s|iEq!W7A>AIkuUJsjT+H}GN8q7u7R4u{OZ64SMmm#NX^GvA3>J7EKLuxijfWOK)13n>n6+Pbl)k}&w1`>8 z2+>!?$Uk3)*({j*u>Nf%#(n=KG??9Cfy$T-h{R|5Sf3nwRu4G%nI%zk3yKzRM>E5tq2Ed*@3BgVm-_`Ms4 zS95T}_PNHRAr?+K-VnLAj|~I47`ZWBHtGZWwrdmj_0(hYUk^hz)|m`63lscobvU+Z zSq&Ri^OtV;2y)=y-+aiI;J^(R6}96CPE4EGU7mG>;71S5410o;883G_j>fS-qr@~W zzuSu0zfm{q(pnH=A7QclLNn_5Hrf9TZ$bq#rKiQ91)~1nW+M2Tv1aq89BE%VEE1oZ zIfhUXAn<*h?nTA^6i)-&D^$#ynv!FyX&_Z?8f+4x!#TqEpnWGDhf@xzk9gD26};iq z;u#7YBKqwtWofW^^Kr*w77coH`(9_x5&A0UUv*!Fj=TK6zk3B3sQ%~ZwM2>uKY4BW zMngIRcgWvUT}RBnFX#5th>ohl>vXG02Hu6xo^=rZb=}b?rdgAQ_`4$>nqoA_FX`A> zc#rU#yT;kY(KL+d)BP7mX~?iXxX;R&26L}ZO!_s$2`Q?V|8B2XrfitVTKRBsY`b*&(5^7?No@*VEGB3p<<`GvS>Vu3PY-TtrwNpXM?sE)Su>lh;bBte1v+AFZyQ zl&9fNtz$r5ECmxg`d*|aP_RPunC|CD3Niy@v$H(NSax9QN7fNC>UAC5R!%j7r*+ll z%?@N7+{U}GF|iTVXI$;9Hr`nU-c9d^=}StjH~@}#caYC`g9y^HDt&2VZ9 zN=UPALfaR;A>#oi+-U93KTI>RBX4cvwF)NuFNzjL?Pn1DdgF_uCmq$IQtu{r(r~r) zXJCmf6$h{H`rO(>#c+eex#P+-?2%gSlBGq(voz|i(mD#{6uI5+9HqcwrIR@=hK$xj zrIJQ8G6F*PDDHYq#((pq2cMgzHdcgdpvkeJH{y8Znu5ASEOZMjmRSIa~ zYei%niStVy>%8sIgt6lB**A}y!HhpcpHFW_c8G^ag;_J4zdpRzNaTVlquc8e2|cJu zmY(}2Pvqe$2mVL2CcM!Z3gdBQAj3!JvfC*t+ztu_ksniFyDwtnSR z$@WqIPDhTZ$VTR~W;`y>qDd;YV&Yuc>ZAj$koMJh_&SgU=R4h(TnRmr<{MUz1`F?o zxMm#*U277}*U_qGgT1p=F_X~I;F+Sa{IhKYr|`(XI@E?Yt@R@1r`qr=Vym>%#Ww7C z(_p(Sq78!$+O>C9v_WP^Ri*yAHkiva?at}p;L?+K&TKLpp60hKol98|jXomG(GnvS>pA!nTygTHVH>(SzVxWHa3Eke zFnCa_4LXN5%KHkn;YR13T?HcTC~+QZkV_|g!=7o?Zp_A$%UTBUTZlR((CQy4_zlQ_yZ-H47{cN1D>X)ZXuu)m`tI?R71E0p_ zOv(Q^NI2cra_<-iC)WyX)XU-EBbP_yB?botHO`r;H#u-8jqtq8=b-l5gBT@S4&r2^ z=p`#T7^APfWYW#X*;gZ^q;L+Rd5W+Q1m+s{^^;v z!$h74-(XPmo!Wx9-TE;HVn3il^t~{?eZX5MW1BXI7TC=5N#0WbfD?{kZ?@B$K;D>T zAg{-O#jzxwWHrK1{LkO^dq~4%4p&$MgNjF61_TmL6M6q;iI?^-GG43Z-Dyvx;>gLq zxBCm}a2hCf{Xb#!*7?hlm=$UiS)`*It=<=u>1*~I;3*^ zYTqCgi!3Agwl*qugo-CS61m!YmDb_>`wUo#O0Ipu%f!?DA0tGSm}uekIkH-f2_c;~ zT`$DxID1j%*aio}C;6=o1bZXF=$ZZ&|ASCI(`?EF#U!X$b9>p*Zh~;THn30z971jhL|foNYVMfcBeX zrsD=A99_6ja(h!Fy#L6n84{?B(b33I5PHbNWwe6a|N! zsw4VXWQbd@FiP7<#$0ot-3wbXbUK{g#|@HDmbu<-O>ZMYG9y#!ryCLKFvoq?n2b0N z)AS|8x}rBK4{wpkNNLxMn*#;e<21ykk`X;vCP*%5gxS8m7MF|&{tq~BC~}{I^_R`k z9uJa{t*<9rVAF^S-I<@HR6^HZ73J>DBtfFLIL7A^361f-j=FD2=<7|f|4*P1fj^QK zDG-bga|Mff4t>nplH*O5`Vv7yRLgN!mt*lc$g1^3)PY+wG23~%Y@ek~P*ANlAX z|E$eGRM1h+4NDogS@WAjtzp0|sA@~-R|b;4Xa1N7U?SIMGL?5t6XxRAGMc_H@IKrn zDx4Tkc5a;&zRkdzA3Wnl<_uh$xqC;_gN7)vl7B~k(BR@;A0eDdg}PIyuy_*{)zeJ{ z+rwz6+VaONRFaDLz*XO$Pg9XRrFoG1Br(r=Qobyh$O#e89=;~>T9}QC*@hejq1!s5 zo|ov*y#2(|B9wvX=*I=CE9pqk+SjK(OU0%CZr&46r(meA@It$?ypt@!NuFe8$?NXx?Q@G*4}`!Tko@1rPZV6B45T_O)dB< z)(Unt)Sy2$tRd4A03<(Wdb+Q&WDrwJj5K3BYT0|D0lEjgu|NcfB8%!#@~AWhGnJAE06 z-A4CHbc0Du$}Y>uQxqYq{q$b>0TOcG^TP#HUO^$wMoDko)c})aT<7-S@x*NWcfSqQ>eY;K} z;%=xmb~g~%++f_$NuPtMC&=P>X?}X0$jSME}Twa+b}QW#4{m; zW2W@?KLyy+-uC#Lw-7JGWe&L43Zc0*_*Y6W0kh#(zlY)p&|6bwMo$n}G&}$E^on=* zXD5E${tSUCV?*+Hr~oF-C$uH&n=oJSrb?951Rbu_@|t4;JgZ_UcvT5uv_<2Yqyd2o z{wBkO0*TCAGqDws1d2n|CZ>85z|hs$?jr%-3W*FM`V3VhzDyOuX}iZ0B1?dT)jwW&er|$dsb&7jRRVNOwe>bK7GPSI zB`JNZ2~%#)7n8DTfPQJ-s`MKySVZNVwSUHh_?Vb&?0@x$F|5idc|ga!rZ)@5cGjan zDj;fOR6VS_8?u%zszXgrMww1XEymu9`o?r>F@N{V{3L4{>>n2vUJ=xwZBpBsUsr>r z-wQq*DX)Q7ubNiRp1tnRTGjl(^hSr^g+;-<0 zEKB|?!CXqi?($&8@x~e`#NLuq)2;>U_u$+1b2L1bi#_KA)pwUiD`8(TZ~6gm!Hh_kS9r~|h*HRrMh9VwGZ1`_A% zsroOE?4Z_}RBjm(@uMESN8NXYMALCUFfaDgGdhNUMwD45&=K1ew0g-(I;@TUeXAU; zMSqCUI&R@r? zfs*9Rd9%W3Sl41kS2d``=nHyDV|E?7TKzAG4bxFWn&Ll#SD>#^J+pH7dz`?CiLr#nk~ zS4v6g?M)6^x6bYB%Vxo|p=aJDUpDyt&Tsh>99Wts%IJl$Kx^~sT`12&UZaF_#RnG3 z#1dXQUS{D=_#F3jaZJd3SoF+o9~0f0k7K>Um?+$-8z)F$BD_h{B5M-^i7Q+_Pq{}& z$dx&^7gLznW$H2xrQ|mH@Sg`9|(30Z8 zf|I$p`jusD#3$YNTV=z9ea!q)KDECGdW9VQjZ746d$Y*8g^4|*+hXiKGI8TZ)#K++ znec1LxX?O_iC$ax=i;d>{GGX{Nh*qkK{?-mXd zEHvi#-C*jo(bE=M(d@%QrNPFHy{}k6_S5h#DXNYqDj&Um$wA$SL(VM~E>=BN_&wau z#gel>xtpyyFpGVctZL6fCwG(P;w3EfeF%Rr@|1-`y|-sSw`M`XS9kA^P!^7*O%&Vo zvXJh-AU;!*4g2HswH2b+Sm+e~-^c(9UjmO@ezT1UwegGux-AQJ-KymHJ0|w_|5ov% z>MEzc!JpJtKRda=fA2zC*PE@_uyp(>~_J9RVzv+*3MNH_bpHloj z$;6YoIJ0-RSXipiCgnrbB{MrPLFC9rRLq0MtnF+ZIx`WmER2nuw)z={bsW?`-q3iY zgpDoY6?)8b)VXXkf21tUL7Acb`0t-AIBIC!oM1AcwW!myqkxH#*C&jbsw@<%tE}AS20IM*Gae;`FmOCf4#%P?93r`LO}+S$8ybj`P9SSy&>!jgPP^4JA`k z_+Tt=8Fcb*#EJMtk3yyRIIJ}@v-Tn%Im6Qww{8!e_pQB8z@iYY5c zq(pe$xqI)c+a&f?y{+1qKw{{)YeHx*35HL*Vsamehl6VN#&1bjNfarxZ5P36%Z|jy zcS*!X&&dmUd~f))Zf}qzkUuhbBS4Qp!bX#+0lozGA6>N}_%eZ4Y@@0{io3ku3V-jn z2+f!`h!5~uKvB#S_u5uC-puhnShiJ)4iNU z;4I5?p8anE9i=4=(QX8+7Umc9@d*SoOkA?4=XKVm4kp|u;IqGIuqA~6skp}~;5M~S zu196#(+TwWS{PPK5XibNR8yzM84>xf4J{#Y;9HzX86;F%?&TZKBq8th;bA{jXR_(} zskNh2-szOOzU3Q%_8OLFcMO5_ilYEBK+V6yj434a184eemLM@VaNCrAYCh4ut9ur5 zseS$8>+v{{KzK&kZex8ROjF0B%#;MU)Em}6uvh@@w_i7}tQMdqt|a33J^|4Ah)EyFa? zRxX^rht*A`xV4obFLzgpi_7$;e8h1P*uD0yM>Yql=Q#;Ha}Hj3O}}zWn}zGnGoq9g z*>EUW*lOm*hH$spZc_#7eK%D)4!E$8>g2k~ESv#N)vjOq;!Jcpsot}zuE*C=mLT#? zJ@{9Zn$Nyx;9O|p?Q>Lr>YLGB93#WU$|BGAe$?k=xJe>wIS2ck)!1wU4vMmp3v8)= zHDgOn>Q){D9(k>)v&QJSL{^-X>8r!5y{ra-oRXehRa~wbhua{ zxD@4!idHX*c!s`hUkZ1rl)yhAN~e%riW7SGOV)3Hfw>WOix+!WLq9S!ajQKIEAoyw zXeH9Hf7e$PHB}nqLbt6LDWYNFi{~-S{WSDtTadrz)?g|z`*HA@DjaAElfK|o4VFdW zsV%G;uv%%79cyY)@OALt;jc~j*ga2uOGP!ljm*y4A5abL$D3!Atf@jx>{UO@y;Ud* z$!HZEm8d5*_b?r2#;hOEN=K;Aj*tLAXztO)2=ZUfMd%@L+2&sFp*6lU^ z&8%8BC+szpiXIPy@?W8Gcu%eJkt!T?aI=%8a%#e}iRN}gI^MV`>mInqLPp5hr^_y| zV7ku2GL#BsnHR*$|E$i|YvfbojU9K6lfT)A?R zjheH|YWjRQ`1t3x%-+2mNL9OfWX$29hqzK}N9Dj7o0O2P$U#HxOaHF(9JIXid#+Et zcR2c5YYw$8Z}ma94Ll~kR#;`Wjj>Q$d@%XiI*Rk!S?iV7vRW3E)6J)J$_3RzY0stFiTXN3zvt9_tYu)2=Xqx5EDj7VddIh% z;^0kaOq%jd9!$HBbp!!8nZW6$Lwz)(2asfQOz*k0yJIDFUDZ{_ zW0KI2JjsvDC81~Cm@OtpaUeErrK5nraWC7BB#I+inSI{_9~0OrH+%kzF#=`W4@;CO zpWX7+N^a;p<(=upr#uJ(J9?To+@4OtJ^7J*LnZ;kcW(2GDgOP9{X|QBNnngjewQjk z;wXDn-lzi!S+S{=k)H_6@%V9h^%DZ#Q7imb9wZ>Wym;rGI*OCxSw0uUNzh!*Y`z#k zpjS3@dhNg(kWaO;C8NCue+GfJ2|wG#(ok;KGrDcp1vyA6S207JG-{ zX-3{bb&BIQk#2JvYac$~BsOLx&$45s0@MMb1VNO{LB&-#8LD-8SV%XPKI7eFU40Y0MdAgmnN6s^ z7&M<|+K5jB8~!HtQs2K8EK8a#z`3sqt2A_)kdSor(WY)5lpa*6MQJeM?PhRgc1SnDr>PR=Fz<`luxEOC%nE{M#q(X$`>1q7>Hc8<)O?Uif^xW(RP_Ku=lT`bLtW% zl%>`epY&lOEc4E;CzLm-o89aF6vV>5kL5PEs6G*y`y)@YmyOLVzK=mO7mN1!&W+OG zVpb0CTe=+|@7iCg9X`ZE6OGh(5yC@ZT;_^kIu~WOmxg}na#8U5*(h|JX(IT-I)W0tp2)_ls}cGJo?8`WI@O{8$7X-iPTeD?{CRw z;<+>7_w*YB2B+4Sx;Zg$cv@2Ah;uzEH^dLoC=VX^^3anfs)z5kwBA3I_i5Lk3*B8# z<&W*@qO8wU-#$4rBG!llJ=fEMBuO^tCnej0_Hodpvx=9nj)PsFX38dIvT^0kWcG(A zY%G`mLYpFFL-L2JRwmV7=_O_HQqh#}J<1sU^dAHLdi5vV&odBw?vV9P^?GE_(i2aX zV&c>Ilnh5{27FgK+lce(5z;er_8)%+I)|7FOH7!kNmYNu?_{FgN50{ zw7XFr>E2Z=XslRsw%`~8Pt<1qAr%?0d-KtULwRyx?47i>9v1G+b-uQS@?(Vz#cA%U zY<%ocDZf(6#`s~b<#84V&-U9$>rdli(^9&-+Zk%T$-csc@ zHvELgemw|f!}5X0*$&EQ4ZKdf+Q(AgD~VNpqCC&)T$Vn4Itv>ryuITnzpOHyvo`EG z3*$>j_1S4GbPXIch+V@%gshFqY|6iH%;Fi?IJ0rFqAP>9f&&}9|K8q-WaC4Z9p^eV zze@gCmh3?`2)0?}yhav|eD-0;q%rX)=52BWwZ7M~RmZO!qHbZwxw^~=EX-{hcG5<86P!^Qq;>& zQXZMTKW`h=Z!=9!TUb35;M*_Fg8W+oJRsA&Ces8+c|5u>piO{q+o9}nQz0rzMVrlk zgiwl1F1SkhR#BX{Q>m5+J-WH(_x6jh|AhDHZZ{D|<=1}w!xmx1$oTRl1tM(tY-E!g zBf=Tkw#~W4BAmT?UXZBQjK#wQJEf+et zmc&09<}8L338k8HS@9qOJ9Ubx_EA0-us*FUb``~$QIiHe4-!=?OiF)KK2-IePNx4u z0@scXX=OAKc&`*xv5(^GIxD(*+5iFlJQ;~sl(&^kxJ<15MSy7?bIqWTfQ9a@K9^?d zy=ER>N^AnVr`TK=TS>sQCEgj7(}?vFw=6cy;$i2L5~E!E254|Av$eu0UQEC8 z<}r^4mcra&dj?hQu2uIH*21y{@%~^1;=S zejSn=z%62U>JSsYdWVmy^ z(0+x5K#%CEYu!v3r(|_p8fPH-d)zbY-AvF`bADP%aS&)L`=*oP-|1gDyIA8~O!er? z2s*$+_8N;Xj4(FJrsb=|KcaHCx0ft&nuW~dfT9_P*yvbV{&LzMHrRSb!R_@N6kluI zP)GIg)C;$xcbM^@u=SGj#ZE4cy>Zh2!EE|NhiZa3PVls%MTY7m|0^ z(nl!nUg@44JoPpkz5UCRGY8n%^Y6&~luvAgo?GX+oW{Xp>Gu&5860@#TRUY_{+l85 zDE;1dHaf-Pyd=!n_*@rI@@+30vQwq^4M#9>k*O*zLG{DiUs&oI6lV>;*k1ma%z*UF z?pp8b3@DfUd)}B%dHa?y^9=?pq;V40jeTVx+b{4=B<1s~M`guF9O`i_(Q=07{(7j{ zD`^mw^-zxw3odYG;C4xVw}TG@Yjn>1`gn?gxS5x=tA-hvo@ZcwX9)vJReEP$QoOc* z(&IP&h7OwDt@G_{yN-;Xe8HuZ?R z+&FS@1?B&`;VNSy7EJzbw{G-c;m!g_{<;tbTH;;Key95E1`8>6atGz%D;(?$o0<4_ z{#5lVDqo!c(K+T*NA+QiQlufIC1Ee)S$8+I! zx-)NEAP+ev^Rl888j$g@et=oULs0&Oztn3-rd_5YFd3{c#^%)c+!>w#93{JqIsDC1!OLCvz-Fwar#6&>v>bUm41T!>$`kr_5&}!E9bnzdZv% zFZb-Puwh|QbE)Z?U?ytw9zXp3nu)z%Dy-e!Ga+7Ybk1}s8xI9+KN(Bv{H__h_bQzQ z(VE%xjJph|y#1=>d8r;*CXf0|bQsVRxP*$1voIO%H5taE&Q(CN&mzwT{4}C(@eSqU zhI8Y>pfWzpJpYE7e&9pWChJ3NBOh^les1}Gv=Lp&$!p&~(Y7-682Yx4Y{zeRcYUQ*`I90*hG2$qO(!3k0-WGnumA0J%(*0`EVN>TJTk& z2}eow;!9Nm{PG)Ja%wGsrL~*ufBqFBASuQv>=+4`a3gVZ%9~`ayEwk1`k80ybl+2b z1eBf`zuw_VqDFQ0?sgu5gw$I<-bj#Wksa63l_gPdce=Bl48=8{%4lvd0l!Cj%vY2L zkp99tF>;LkihL!K{0;t|ayuIWNd z2{QUl-!BAv|M>jI#RA;XTYtn$T7YZvp5YIgo50iAWY*;*fSTip)qWa6q)!PC=};q( zGCj-aI^|c~3RRUL%F{wbx3v9|sPQ_qesES(Je&V6uv(EoVBkf+Ov>}t{S9sGq{a=c zE~_aDB+%YTero<81Y@{)20?N6LUZ*-7m!%LEAG<@eGhwl`Vl_<9m+vrEhOP<1GgvXoMPK|mt3gCS4(aP11tVkt3d-)5;>+EO_o>Y;DS zswfiQPF|I%xF*8&%z?A(sQotH({W3dsuz#_hsV+&@O8;6y;=D}jNdXWzaLBOgX_i+ z=G-Ryjb3)#R=NSfdFK`dbE$LuJCE;kk_{dDJg$!|m-_#o`Q_cig{DXRNRA5^I&qR2 zo=bV?DbRjexQquejqwW(|G3DT2z0GYVPnj-G44Vl8~#?CKZ==fAm`I%;GN9E^B-P+ zeo{I4w8U>6+FBO=2LJ&7{}h*bJQeNx$L(5G_LQ_IktmYzL95atQVLOcd{YWVrIKW; zY>6jJO6rj;Nm^t*`^=nkEax1lltPw}B%~C-`TaGoIdjjPd+xdJ>-~ABxs|<(sNtb6 zcxw%369MV#S^Lg>AhG*px%A%>3YRCgeD^-UhkC{u(T6AsrWe${+FTJ}dG@0>Hr+x9 za;n3mmI)B+m$zq3ONfckwG*q{g!rPCKX$;a7EA2DbuN<=$b8LU&~6Vv$E zZAJ82?x*myB4o_LfI{<=L%G6W0vF0^!vY++us&MTQfO+9;8!)x(cU|DEmC=rr8q;-R&Rke8ERjS{^Ux9EFV3 zqP&sU6!P}Ah*}QwQERhJ_z?kKUp}%c>LMTEC*+y4Zqs#Z z)9>mTL}K`2@Pk4h3jdjH_Wp8_Ku>La-_sTn#})WLRk|qXhCjJv@Qj4b$dQo$$|wxW zzmMlmkO)kCxlYT452e{@Qu{kdT#xdO3i?1{{uk%R6|oeSk($+0PV?bg*xz?-oI;W1 z%OQ^o6wEAhk9<)kplC*Zbd=^I&S&ZHeIFj;ZBJgkIEz55{qOCkFOjG^v%c;0B0i|G zwY{;0bRF4UU)ga;2*rEeo+bT4+;iGFTT!7FW-h){&7KPp&{e&oY;P?ZrL?W;_XrWu zrs>EG6yjiSoT|cMAr3JjZfIBwvE!!_U+)HeR2*EmfZmVBjAJ^#OY2Y-=R8S{ti#8o zM?;4vH^5_aQF_ee2D zYe{mjS&W27Uo{LP#OPhWc-f~OF>>N{4lPQM!2ibMg4jP2oSM#S?(ddBu4jq-kYyu^ zx=)Sp=-;bnUU#~(u@S5L@8$OoNzj;WDDqTqM7mh1_k}_uI?m|I6i-MnzIov!XQf62 z?8p#59+yBN*Cp|iTqB-k9$J2!CBcX2jouE?5|H~uS|MQ)5Eo=e9*&5yQDP;>9Tnk@ zv2F3JFfml7S`z$oVz~X8QWxeV#=-WJDrwqcDF2%2XgXC4cQg{8W{L6l>bjGcCPavA zF*4p6Cjx0WXX9EUF%JBcUnKY>La*a{jSbx*G)c`|euEOcx<`;>W8+HX@u~ z{IK)dwFX>=mPnOe*Mqs%q|>0#CM`cL_{#7y_680`tOL*i@2h~M+9&e~Iga=5uq1d8!0K{S{BLkuF$U3K`Q7-u>= zPH*Ll5fbNhq}yGB(yKRIX7`FPH%#YRPO=y$oz(63%SxamQ-PiTit+l~-|`G~G5QM2 z%4NSdz{F^4@{^Yh7;P!a4trUT-fjB|bDQchu&|_NNR@t{wOya2+8SUTmfo~By&l8s z9oBwn7r-W8#!~MpA5%)6oONZ9Fy>3V>Jte>?KW+0T}Hs+)llaMkB80Y-``ojj=;+# z_UE2@0{$Y)Td#U}Xxklg<+&{n${&ISx^oDW%p?S59|-(Xt~q+&jD&QbtLlg>fxU@3 z(jgKajK*)KwWjm1sB(1T`WS%)cQU6MH;}l?dT#I{fPmY4{x-!y5>5s`qBhd!cQ>4U zpthEeJ&&Y*4Gr?~(f6)`sRtkBS8gYU)4WRH$15FO%Ev2*P|}y)|5nvO8+kuT=v?D< zBwZmf;$2?0gyz=n{NiPw)!F!WB~v5o7z^`0+^wuAWT3F{_{jS~CL-n^BL)IkP#!M}AZAaAJu4{!-X9NEKQ=Auw$?Pf2u?!dKHnO2<1%%*a{&yqxZPf5V+L z3|8^sXL8h`ogk6oa6mfvB?W!Qy`K&yQn*mtSl@0*;c*Y^ZJ#xL9Ix^{kxgLw2KOh0 z83e9`&yHIkPQWF9TCx<~*Jd0URdVg)BJZTEQg<{LZqxeCba`@-^tNj7eHss=LDTQ< z{mjLa{tI1xZCv#H_he3@BY`5r?}_K>?|30)o91_W9&){-SICC&a3J>S#WA_22UYyX8c~HWgG!{|DJB;Uo_AEkqWM8ATaEu!ZTE&u-s9R zu;5epv~}s*d&v~8`<^P>M(3kNArk|x!+h*rz42B;28CNaCWgnd`S|uvATf6xA68r$(Q6;(K*6LdGin63JM!Ewt6I=C2=s= zx+9b3xm-{~XfVymmBLqdg6m2AHavFn!ZSXE(aTJ)`tUJpzh}*nS_t25pfyyO>o!tNhhP`HEr;GE_D^G#24pRALfqo*0k(+B5Y>8t`m* z3Yl_F1fywnM%!vd*zRa{-Rrg(6|e3-uyYi{<*D<8YKR!xc74xmUx@Hk=KPO+G9tXF zT&`oapaFu1?e*z{bpBoVNUiA$i7kBYEq@0NzSOF_#y+aSlF3(!Y_zMe#tgMy*DEpf zOWQ$byc&M1d^QzD)L=^bz3zz1l~DLL$Hj+ViAf#n2KT+J#)iz{?7LGLkgW4$JO5(f zWB<7^hmUmrJ-IZ|Zwd=@vR+7kQ)fXb!9&&9k%brD?bLx~EZj6&wa%fFiDQ%FGR+lO z@ZGQE+*8iPkMesV|8r(S{|x?bMnoeENAd|H}7jJl=7#`I!v^{_B1`ig?XHc=6|2=~YZ58Bj}XFEU_LnEmZ! z0s|+#s7{Aq1|n|!^$4BKK!Tp>wD)EVOpM9?UOvdcQRC$L;X_Q+xpU9{E@C1jd9R7X z1}2sUJXAX3$i!N1uyWfICbrcUDeS((!nRB!f77!pl>YedU~oGVPE*~ss@u@x-X0mT z4q%|>NxVgJ90N(VgmJwa6I&Opjo?_Y(5&%p6P3fl>sT-Lw@5bD54_F%H;WA^ia{zi zvvITCdfh!njO-#bbCFdcuVFC zJ`>^4F^h_9I=8r+t?aw{KM9^bFDdNaE5Y;ic0L|{5_p`xeBQENjF@Eu5h6V?BFfgW zcSg`0m$tfpx1s^j_C0f}b?dS6>ZqPNKQ3bm*D} zpZ1r<O~#h;;5Gd{bAK7_FDsmbf9$8<$8Y;}M3R5py+jNbUd&4%@rd3Ffl#UFLjj%6>NNtjY}ZquJmZm+d1x zd3e$wc1S(P!y}8+RUAD6LB&gV>zWbhjn}ttc9&V$pTHt+FK4u(C_B#9=X?{(h;rI41-$Mk}tf`3otwTaiXQVlVP2a!qsNwNi0?zH4zRC6^ z;tYHi&CsXtMf%GWV)X=dS3u#}29-efFbaN$Z#QT5Qb?-O3>-A4^U4E_hl8|t&5Y0w5%1yQ!FEQbof{Wl z0_2a&zvDvd@{t)k<#-4i*}7u^?Ty}Vx^J&tOXr5IliQwb<|3Dx;WwAbLAzbeYH~Lh z8$7m0_HXAwZNqZ0TQPxUwWB>Zm~^f?-yHhGjl#8s$qx-_zSQ#;Tu+GMqqDo8WL+bn z+^slu)f76fJvI)=qUYJ5cwpO}YZPXN>3w}2#Yel^>wS4^1SoptEwf31J~rDq&G{>U z(P~?Hg26|J#yyMj1`09blQr-E;3M`y*7KX%d>H*+cZ<17fR;D8zg83paK+I^A)G^E zN5-z7pLbEH>9Hx%qjTqT(L&Wd7b&nUeh(ydP_UeXmM9fI{Qb;XGT-TSb~1IfcI4yt zgiJwi8U=~|&`L3#_l`&XyCi=V7o}0x)UsT-I5|y!>48iRS`uEqc>96{*C#1M>2yE+ z+*xwdznF=_ zA6inJHri{2Ex+a)@ex<^g4LAC$9ad*r-_XMRG%`+c}~&Xj%$q*8w)Y-VoXcP2_Xu? zvKL#f72>*CW7JqgEmqjQ+S|Ii9=;_-DJ@nFNL^YHre)axwRx+d=qmzsW)tx#s{xj3 z=OV~Z5#W?+^HL~6P=(BFE827F*SuI#klToXq)iON0}^x&m;N%l*oe_-;{N^@jhH%Y zrm7s(h*rHj)17}c;*-$qPt;H&&XzX2$rFwETVT2PqsePL+#X(b*7-GjhEA-~)@?-F z*N24E>PF0vYSZ@amteWG@bW&{Mr`bnUbgJ37#r9C=tcIUXzKARjnKed|nRmv)Sy@Lb}kCpc>aHr>|(B-ok5;RR* z2oz0C@Ozu7%^Hz*gYegANtzsN4SYdi;vIH|i!g|BBBydjL zJtq5Bg4cnbw>Z1#@kuY&xL%f^Hq|`rs*VIvPqzQ8pncnAZS6~+2nk|z&xb3~oQXBh zQrPxe3?}b{j~l-M+QLOy2IKW`7a}#ZsTTL56I}OI2x0o)`a*f{ddM6;xf%|pxSkwjz53Oq- zjLzfeDy-uIW&H1(4xoHsOi zrftASkGthE`F9kwEB}$JNEIMtlE#J<2_J#2n!Z`|e%@_zsPY~CJRSQRoNpWXP;4IH z#?GDypHBUcy3k8L^mSt?(>$2aeRi)B=oA2=_ z!J5wNWUgGD-6+k2#0w$ujTGWiFK*NiBr$CNqTSS+M7Flh;AJ}=$gapI=V^a=(egg= zgA@;mk zY%T%M5AxxK+O&VUj&DmUBq4H&T9Ot{;)|i`!|Z4R#cSxk-<$9yJ)ibro1^Rh z&ZS^&)MmNenZop`5%yIRBz8X_w)}iTLU(#WozF`WT&<>m<)2b8@VQ&o`7a;&+h-4) z3?-o;w>2nj35n(k$!^VJ3Z^}T;-51VrcK!teBu)YqQp)2ApM=})to|8PSE$Is?9#R zpF+?Ii@#@0NGzQ8sHwb=!o>hlmSZ@DN^56gW*`si*>a4x7br{(-4VobAYs!U`f=4b z1>wEen?ZC=u&@zTw+#@m^^YF=OnWhVritN9TMFw3_hdYg<)ir0`iFe30FphM=dSD& z;3%bJUz}EpncM?k_0I~C61;(-_m%FCDHh4oV)^L)eqDVM&C8mk;qd2ueL zfO7n`oh<*uk^#law*{_?Sy1(G&*5%i!}Hh)RZnXU)*Y#s9IM90DspPFlXn2DDrIdT317TO~}cx}t4bNQuU?fa>8t}axcbYuYs9m5mXM{lr@t??i$ zVJaItMiUB7UuB^(%eKd$fdzisKby`ypnagOFK1;Q3nS_>B6Irs=?`+dmsYaS@@)6z zaFU67c0>PF6DAnE*GUR%SZG*W{UAS-373w=D~o3^ktV4)w}bYPFnQBidSV9lmzC;k zsxdID#VcojGy@22mSjs9NDF|jo1KtcU%p1FD!obCC#*yA6 zCZ?Fn9glv^HSTaRC4;@;89j)hzX$}YWX%nxN?ZScVN7&`{^vKGq-CTdWou&^s& zb`8e&ExPxMsKJ-z-3rZ8476M`eRt_^4ICM*I%QT2+>3zAuQyDHr}!`NHDLkbAn71F zPw02M9+qpPpC7~g6(nRLGig2J>?aliUGnpC;@M~p)?XPo%)vmRm;Rf-Bo<}Z?Z}g< zN0IV81-;P*G&+wrDEo*p=|ug`n$;3)JJ3~6Y?VO6LO(i^=FpXltIQ)M5=j4}VR1)a z0;|=v+79>WaUTcvYFJ5dOcJTFl9Yn8xcbA#*gP6;B+#wqI^jc5$>ofmA- z2)w%Gb|2@F|fs55IHD@ua{w7t(^o(t40-h zbUxYYk<(6dH%eL~D91p8l0AXC&ey~+xpnWw@EQpm=Trnq4~sCt{2SKoDMIuU{!!<* z4S3jU|Mizs19FEdsA$W2D4b<18F#Hk$wI%i?@WX+kJ@y8wGtnG_wK}~z7fEs`DZjg zRfv6wt*1V`5#l&|Q1>8HfL$NVVW1$ymH*_P4aEpCFz4jQTu%W~SDdlc9-%O|H$>oU z#KZT*qz_BVI55wCP(#uEeP*5-sa(pzgv#=dX*4gc1PQjt?&P6eX@iTY6Bk^gUuN&t z(&N|`OXDLsSku2L_P-D=h>^Vh&fPrJ`^oOQUC4vWwXgAa_Yx3#w4P=hCZHWYd}V1Q ziT<~tdp_CIywzA#=rm4Xs!FN3b1B{5CrZrz%cr2_P}S~E^We*cH+$wt)BX5d%!{FS zblsf!oWY?v`gR|2{63pR-K&@38!pk_u=7=m=?xMGHcY;G?m3CgKkDLVSMuO*@@BsF zRRZayQ8^ZLpAWg;sxw+jz`7RGC(;P4H;edv=@b|5ui5!BXwTkf>k~6SlZUYq3mbJU zF23)*qSvOu!zb38u=fExy!CqO)4hp+DlR4;<#O@(VEe5>2Oc#474?K`5a>G4vS&BV zb(ryvhiCAhy2iVA`A;5teCyqtKk<{d-$qwZT)fqKyjaDKfPtl1C}R@| znKaqhjmi{4zg&G#vw_6Q-~(0xS+rM^X8Us`1pbC~NKZTIW{P`aThK4TpeSWc^^>ovNsYYzrSI=C>T)@TU z|K06u*v`SpxkJkT`^!Q359!+WiO7NStGUJ$Ug{ryNVN0u z%0^{|)*QNyy#Cm;75R9#d_*;53m?lW5~o|s@$pC@N;-??dED9ULPurV*JO16sMGml zxQjBk>!MKjdFjTGp9CgZJ}dckl7#;HfasEZ0=1qsYWdgc?_K70k4gKb=69>yQMxYF zk~*ZhbPnM37Td?u_2zpwIrR$d-|L0~Qy43Fa5hiiAEfs~@yfx}a@y~s0}sqGqj_GO z?IVW3Jv+%8LZZY+Mi6Q>5rfmt$yGNe(&!jmBXC?e;cjaL?Yv;a(?G!T0 z;)f1L3eaS?@vZS!0q)*w5p13=#QlfY=Phm#fIs08GTtVD^#0b0F`f|1)#mY0UW-M+d^XyXZ zBV%naU;Frs`Mq|S`gZ6Zp>g3<(3)n;;-R=<)5&174pi;zyi6+cVQD%RB6^ySdu1UX z52f?*dV1{}))PMX@7@n6Ea|{l-_II>MV;st7auMt?10dLorNo%JCIf&Am66g0eQ7L zC6PxRxT#h7)n&W`jjp=&DK;JW=Cf&h#lsE+FNtZZo$7#B;^vva9UW+h>igu*;p6Up z;R zjGmW#T=Mq37?H_`f5|iTNow8mZdvL`FY18oP?AgnWrv_maj(llr%Bdco8>9;^?@_2Oel@@fX%fDh5P8=_^qd3fmj zev$rrE|zS*Bb?^g4%s_fX~tgdc)h4|gKt(F2&=;xJ-1r{&$NLpms_FO(6i^Bbqi$0 zJpmx_k^s(Uk+^j_FCJUaa zUT2rQVnb=mU&)as0^=vcrbgS@=r{W$`$m|J5F@ctS78Fq7ZjU(o)HjF_p{U)W~0Q) zxKZIPf%P>f{_uK8oD!`UuIV5#ziCQ(=OPlf{>7JtQFYxXXsHDx3AaqO0zWPrFYCNl zUiivJ%G;n@`W^(7jL)tjTG%)&^Zc%tCy8*~P6?U$B*GRfGvUu8peS0wGOr;Ju}R{g z_B;~zGr8rq#U!@vn-%%_5($>>qrbUg1acatEyjxpOt$8kCIxb^*EFKmy^jDt*zb$h z6bn{%@n#*NY?$@@7}@`wfM=g!#}7Rcf_wL>8XX~V zmO$)_@b+>~7Mvnpe$>}z;kbvFT_ttDQ8`gdn7XoUUP?u;Wnpuun}fk+21MfY*KK;r zg34h*OUWAy9DKO&uF1_NsPdx)CR9fV`G8t%%DS25S%EXnv1N~=* z8F(nPq2<2?4D?2YCr>-jVR!k|=;RQGPLrJPpQ?WPJkGHa_DKRwO!ILNj~D zseZb9%;D<^0vB8^xw^!$5zs!OcatPg-8H?reK`lBPkcrDsQp#12rV!!B>)HQsJSax z=#byC-_ex`v+1URv?&G-Z>=#KVHZttbkGTg3NnL=RH z(BF+2%7KVABV(M##=rY}*X}<+;PpE{Cs{8x?iBa7;5e|O)KUmdBaNyd$xp3ihGfqa+GO|vzz}w@V(vpR3 zD4%>Bwt&@!i~rWIG+N(|6${l<1a`OMK>ktDB($M*PWGxNE85W>m6v*Ac{>yn?+I<% z&PAto*!P4(Tuh55-bzm5V)G|A$3H*0m|f77f1{g=tfwN6pSts){86(;?KBS|6&8VS z*K|U5JWx)&yaNe};^(it>wvh-+_+=n9r(^W5+1s|1KS2B29@*q2!AKKmzc+g{2(p6 zMUan5*S;s8P5H>RUF~$%i4W!MqUrWQA)E5SF7n73v0Znz{19P3j}N5?7sVt>>4u0$egmLt>)7wp`q)$9V8rQMs4Hva-b44ZmWKr z4fB;ct1L4ZxFxNsthI)Tb9#2i7;720*=2U?ry3160z`w~sMp~tt3d3>ky`9>HX%Zr zpJB2&)_A$*6RbqH_9@=~v#fPk=rkey~gG8gAzc(c76<@b5EQL$)Ci zH|`oTUw%zQ-y`2M0=Dy&A|UqD^0UhI8xVea`LGoK3IupT0RiV7me>ToT) z#<|{mJ9LhX<1GlfL)dR*L+Wc$## z9zsouL!)E$7$}@R|E|0NKgWtV+Xw1FJLrF>WM4gcKP#1g5UIyTd-0l1w<>(T4^klh zIcBB*ajTrEME@?OZ+AT_aWdTPPHjdx_SL11`WcnMZ+N}Wq;@&JP9HQb_pg8-r((e> zrAqkM^`xjTu7-NY*`|Y=s{Ixl7zKbWb-0cXP_ zWyLkPX?}3Wcc~iKXD|-Mjn?4%Vx7nNRW+!#C_bdNqz>UNs`^T%)cRhlrvD14!}OZ! z-7ikn;nFhi2En;?h_xA3oHf4=(tVnuk-qhK;8LTtj#Upa>%yfM5*ncUoc_q|8Vwf8 zyYh>lGLaDZA#RN;i9=-<#+o#nv3tN>J<7fXb`yNxWiyl?uiLw!q^cRW)9X!-4mM+Q z;?BAek7kHgu$Nr=kAo5VW&2SP5)D^``!*k?^mcCZa{EaJLN+CN%29O=6~zBaL?b-E z=&CFYt4F?3dS~mQ27Dg5c6G3=5$fVGyYEiWan2#8Wm^*i_g_06XP#kVz55cDL>&t# z2)oO` zhFv&yAL6&|@x_*8OIoCT5w7#Q+=Ymd_X@2urc0#^b)N+hlzVf2)BN7|0W+a0{ph`A)>7t}`C zQTgY1ixfAkh``z^$92mI0_11WuTOulu3-gqqr-4PWD%geiq7NEnn>Q zVj^4V-W;o4&tY%gJZfg0idS}@#}mYFKvip#6IV10Pj6R*I7o-#v_O9(*>f2$zIfg6 z>Q9HynoYh77lgopCoxBAc_^54Q$siBP=p_w#gs_PgdTf|;gF08)(N%qXYKGr9)-7LnzNlY*Z=oj~<{JGIewGYpqujc=a-}%_ zqQ<*+?Q@v5C>+qC^w4i>Uc%`-2BLMpp4@PNfwTR$?(cJFAR}r~UU3}71J@?>f7G*3 z(7&vGq@BQTrgz(ZRwu$+Z=>CH%ADZYsGvugKsP1+i=^sobTY?3^F&}cG87J zchz{wu3rSU&DK!w2_tZKo^D}u7sVfwFY606nvlMb(_`_4z_YC5<*xThr28x6D`rr9 zBl=+{-rxq#~_dT~8D#u3&R!*>a z2@Lx#ef&o&h19TO4JY6k)`)dHmK^gGyIorAHssRdU=Q(=E=Y-A#)45EQ%=VpSPk^d%GyjLj%Yiw8b z&Dj_ad)arte#xuht;FeJ&3HNN-kp$hO-vT2`B`6Qom-FZHb&Z0ht}iwztqmagX^Ik zb!GUP+AX(17|+upQ?f5R*^HR4Grj8T{M zd~_nT5oQl=*NWOSfX@t>lfz*n5GMV1WKL?tVxD1BC{;tU$Bg{+ox6t^7P)v?Jza(xq{)1SE)P`NS@wU-3ZR7^LxIjG-7jG-_6pzM(oU2 zYYnocq06A^)5{Yy-26ap{8!Y7A5+2uCnOti#eCQ1jM^G}DSoj+g{*+hE|y1}N-1Vv z+ps<1HRa9ZF-!aq-?j`+2u650X3M#?5SaXw=_hX9ga+-2{b3hIm+W z!Ys}MFH65>_I8?Fc(WVL>hW{xhy`^|HYHH_Vr4M{8 zn>Jq9x`K}-eBE*jZ!Qk)j(C)KxE&i*gqB>AY{MU`xwkB?HA76&EVz7vjV;ZEPw!0A z;rhOw_-sbQZykr)s%RRL9ZbKrRny=xk+?NffrkE+yMxNbG{hQ7dfwenN21i><4cR_ z&`n@_>3pIic0_P>)h`A-UaJ_3`Lp4+Ku+@46#}os_kaBuLcr3-qEFwGK#eT#m8LR@ zReFjo8EGUm-2axXp!iQ-dQDDhJmuR7`xCcJkl+iro=;$qsQwVHH_am<;!$ZVtx3YP z>iVVT3j}&k*33T?Nb&cIh>b1k1gzC-?;w!}q*(^l%SbKF-e)HPR_2$3?3I#jUWw+8h;=F48* z@OT9S<3piSxht6X&nBTDu7nOr$DIY{BUInFoj#Pjivho>Gd_J+7-*dLF-D!qM671O zC;dPe^;WWl0BNMiaL3$1JWE4Hs^gMaQ{ z_|Z}ptkzAZ6lRhbtG)5wt+5GPs)H7Pztn_FZg$s?MN)nJu}X*=(S(Y1_wod!N%V|P zJ$$x+#Pv-RLylCRr0y~LyRnIlut>vWy(d|?vzYWQSVKV3dYbEb8gf?2S0ORx6*%tTb&)ou|1Hcs6W*J+`iCm;Q( z<-LpviA2HTz3Z50JX&0E>Ms+n217mFqb!KN?)6%> zH+yn$@a`L#jqyz=(o$J+&Y=kwLt!0TW;ekyZ{Fz8_GTEnkIkmPYC)ZAwDvDX3qHJD zq1TexfmGf6RUJIryX&6clAc-?ResF zeJjVm9Xl2IO;)S9kc(4xl{m%4!!(+sQ@TNw26;YFtK! z!(BZ)sc9~jC~M_9>T_}NT&t&$3J(*1sxzkad3ZMX z)wi0?#q%o;8O}aj$fV@Xog>A=`SI(Ab?SNem$-+)(&Axpsn}FpCJ!!iU!32e!-I^1 z%$?urJX~F)duEFW49#{TRiPB#LwFQzq{I^ss z&AN>TC4gWHV>Z*pvmWQ`N(3C;MC^SRCs4+I{ObZy_f_htfo3Uog!Ho}6IapM> zVCz&3iKu3GH|xJ_JU0CF%P^LWYmJR*GgO~C-@jNJTS7psJF5899|CUorVMB8BvD@d z^4w7q0WntqCUw zK0XW@9MDI0)qXzFj55FMM_E6cP;<8-Pkyu+q2Dx4J}PU0r|*1=r}k?Ib=c*6d!MN5W=umLN-;gCLPpG7{SfWZ2WUt68xT9ntofH_U{K z$v{_N0}JeJEz=+D**IU#=vo)X!Wxn6D~{4kEHAruJvfJsFRwL+Z}Di*ko!Jt*4>CG zyY*M4;u~R9kbR(^$}v?|z3~%EX-HUHUifJb4Zi|cC`~V+AxrIwg75)4{uN)np>M~8 z*u;5e4VAB>zi6I4>CA%b9{*UCVv0*IrV86px&Fq{q=^00KDizC^3XD%bfI$LSvM95 zZpn6$W^)qZuIGcd&8IkFm+`(W$s|s_HWR!~>7#~AX6)@x1n%qgj-7r*;N z-6A)5i?P9tDm5x}AdskK-_2c2LiSI6?dq)@q^-WPDWsRc-mJySMgG*h)9($v=M$)^ z)Xr^LN%@LRg4VY;ESxbZ+j{#o6U8M93TmrZ7_{B>O_uTvUkAa4&v`7AdSzO*ykfy< z?eQ;9P1rbQ5M3SG&Vtg3>2$L;CK7ma)>wxyQL8HU-ybO^v_$&+m#tyJS<*Z@`4S7K z6rxlf>anox3}Gp_fQ9sTdR~{cnUK6}(xz3;!rybj+cYS@vweK2Zp9qR5B_)z)O9jZ z8dz!Npus|7#_A(Qxdgb;+a}#+D4xnKKVnfxU|!cPIiE!&>NR4+uRh{n&e5s2EHkk`4oT}|jbXMIVD(y_mK*+=Q?Ibi0QM)RFWc#o7=PU%owe)AD3ayTfM zta=r=xd}-+oW(x-Ie2qM&Fu6TffsYspLe8YH4Lp0@k^oZu|Gc$B}I5h@Uxzdqh zcpxY?fC2C0juIVtOqeq}1U{;;;PG&7@Y=^r482p}et1jA^IpH|zjK(F`FdjWN2_|=IY<6v|Bbr*p%O&CtsVi;U(!js=29u6AKNH5l}doJIC z*Cw;JDi*hZ-*{?|&!QI4cEl){$~0qgNNmG9lV%(@F6_7<-;BAn;_DkGnxT2vfwAs< z3kIu}sj?+ovB6qB?eRn#5+~4e+pryXHxvY2KFUR%s>_?l7r2NOFWMat#D#MA@iXyM z{&Srl=-EZ-rB?HH!I6tRWc;~kzq5{qRm+Xm-nz^~jelG7%vB!L{UWo%jCfe`Q)aJb zBo7)zG4WY;JZRgcB@evdK~!$%H@Qk4QWM+?di!}0e5@cu(0TYD009606qk2ARsRFV zjSwPPA&SaKH0-DzNufnTh@_+<4T%z8GD2yqBr9nXqLj^@=iF=EYn4<&DKpAS`kmij z_jShW+;cwT{k)&!`y}@*RcONQwKD9wRZZyXIwLmO-UPGRe?&)?HsebBj<(#=CJcSZ zZ_|rxLdy*^+8wKA1i#Fe=FT+1ZPK%!ncf8Z>3?<-VNH1Hrm}hHSQBW5@<-iIQrEre zjA0#6P90z5uRW4KM>KV(4dR*4sXw6&9#efCBptOvGn|84lI;S}(f#3Y?TS%B2s;SFrlh`U8 z*#7wofomUXLdQOnz&5cG2Egy)=EXpSc=+8D<{LbLG5{FNNsXKuZoqCg_@;u8rcE&;3gSz4!r351IY zCSD(8V`GeGI)9vv$A9)16cw^TI_EAvXTe5BOjh)NE7-W>xt#I7iVgA8hnmigups22 zze1eH!sh;C>Oq1m?EUAk?NJO9;hidnm;c8CN9vI3(z$H>TKPU8RE`bv>+2(JeONf6 zcf>$QS;*;SJH8} z_g81$039m_?L{_TVIo`jR@Eha77|^o++BXN5#CT67(7a#+GILw)-GxuV(WRX;{^02 zJR*FoNyL>Ub9YP+Q=y)*MQNsNZ}r|TXf@W=n{ zakU9HG7B)(v4{j~dFpoU#~jGJYJMGf$AM*Z+T1aD4w_#~JTW^>VB&LM*RLHUxLUK; zeEY)2aGQ=2jT&bo=i9B#qD<&I3YJK}WnhCT|EuCr2Fw+h%{gjxh}zzNe^rNp_6P3| zpKfKMb&tpzneQxQEeLh5Ol89i>9czeQ{QKhel=c#z-|+!p+EqEwT@ddB`z}|dTXb6 z=K>Zg3bL9nE+rr%6UvPU;(+5cFJosV2YOp{6t87-As2JgGUa?7JPOK7GRo`FIZAIX zdCi65)e zJ3fO%o{jE}s!S3L>+5+9BU~IkhO3$UZb>V0}k?Etjp?Zz)-}dvS_77*oy_s zs+QoP_q5fARl9kJ?G`Z6yxfQmp@Bo@#nf?ms+Kd2hf7*v&n;K;VSayn$|;kFV+$|z zSLN|>v}yHW8|r#=#pv#fBRq`NrWnND<>SS`tn(F)e0VzzmRCgbajWrhX7?lyOC%DX zW)<=wxXov3T(b!gZoB3yg!4f+G)r|=&OsF`J`Qv8UWk3=LGz{hh3yO;0;*4r z(n5H!Sg>$&=PMo_50X!>x$`l3I8t__cq^{8g>!Qz+d#zGj@T!*p)&4zR|dNo4h2F_ zOh+1_Wf-3JWKTVmN~Ge}-RGce{_Nn^Y7Tnjrnk^|T%o%tOb#e_=BkmGw}7R<9Zy}fJ0#JuXk z@GISP9CLU$;S);jm-%Pp_DM7GM@zx!=uZY7%wG5RDp+V)_^xPS0}GSRDtr6dS)lLQ zo7tGl#v#cn!QM@5tPDLF@>+w0kMj$K4u1k!4%&rts|kcnoPPLhnBu&mjeu0{O76CRS8(%F%(iLB+#@}`n32o0eHWy*-P!u3x98K zI=z^LVa^4j!IBNX%ZV|+Tv<32X)hBT$ilg~FSjk}XJKSXc)?K{Hd-}JFW#JHLD{@! zf%Zcd3j-)LTVo!U#B~E{WTkMGf(nKDK>Ju7RCK1&xDhS*!Z9Vb$|1@ zN0v1#c*&`njR>&O6e3A$UdKW`^YYB#S{9Nqk>$FZ%7Z(aMc)pxu<1eA_I-{lycD$S zD7I!n=~R>S&pB)e33<%nP@EC(Q8!bg_-`=cnj^T6iH{$0*E9N9sM*mQq}##5yF+G^ zL4MS8w|r!O>|#Mmq;Eun$|*~>i^hRC0*cq2Dq{=S7&NCp%lgKK-W*?xgIXLon3;C1 za^fIlPj*~VEeG{}a#6!P4mN~oK8}CD!IpL0_w*7H4W(^9M-~!znOx12&tPNg*!IzW zA2uF2x|V+RBheS)7;?drgog(|In0rZ54xi_y4VCn4-Dkmo?zokQXA=7$wv0eYx7Tc zv9Zk}^vPT*cl@5-(JT&T;mmLLNA)CXzAP)df*&#=ZhYBQA&-H@OHa7|^<=_y&DZgb zj~P(0=_uaN#e_)5_nkJ5Ob|OqYXyo~@aA=Ylyzr9SzNIsV=)W4UcNS}-H+m!A2_s=XuC;xr)Hh|(`AUQvC6&p7UjjW%G zv++*7Bc;Qh4K>ETOZ7}PUTjFbt3Yx6!`=@nO`;^Cf6uF&_)6l%h0q-5eiDnsbxU5e zxG*mbGQH|R;&|F4|M_Yp_?l&|*9@p!dKJh_G2!4`gG!I)00)NRN&*4TIPi-ttc@z* zVD-{`mFRW?b;I}0A0A+%hjAf}L4BWbXq5MUEy^P#YhMrYS&;LLoHvkdINh+^f}y zWum`Qvu8D;s=_oswypu6dJ=bB`qqH$@lmQtV~sf1yvf3M4i6P_T5Emh@v!OHtH>Wd zJgoLJl5lb4VYZj>Duot`pL#mkU;gs2SmGLQc`YCJd|x-rg9YcWA2c+kBhqfc zn{rKxuj21_IXW;96{?}5ew2wH4}$yUy_qoo=&{0dgo!QU873P+VAG$zM1tbw@?)vd zV?zWapC=hLR}nZVG9Eg?qdZJ(sLgye#nscvkLvgoCl{n0|8||g@1%vY(yvKK+%=ys zMXlFz^8unvjDyXhVIiSwIVj$0pIx+@gErg5b8(b+MQ)J|S~gaTrb@TlENWkD;YED9 zPWi;p@Zj#%&)BH6OF8bnobt86>q(!e_p^QKZ13bi?bG}-Qbaog=`v$&NofqYH!i6x zvt!_X#^oywl!q$Xws%@TqeI#~U5M97L+&^1nyW|Ujrzfj^F|m*>~#qg@ns@wo><>y z%4g<|9J7!$VM6k!((Hq0Sx8HK;XGKx!jn3SUw6CND6CJJD?uYcb1_ZXW=o!**p61Y9t-^v(eBPFQ8w?doZMwH%t`dR{Xt3F|IJ{$Lo-flfharnf#8TFlg zY^X-9^nESJMzQA^31^DuqAv=CPi0U!u=loX0p#yM9G`D7C={!MgT>A8L~b39ctsgS zOxMC1c2nUO>yZ*Jek0qr4hA~0QO94^;j@C@(5sd82!E(pZ9736~nrW`aqkz1$p&Qk(a!QdY+ET3sokPH|Mi!{22H#u_Z(28?~-y+x^#gfPw16 zVkcjeF>qVI$MTsj6A{|?Y{Yw+n3UZ;I7nyWO|OxS-Z=)!l)UBQ6<8J@FQ4jqC* zQQ|$+^Q{uUGS;-vVW;+T>7Lzm#J-D={&Jj#<+C#W9QUHZ;kl8XhYth2lQP<+CDe1I zeDya|_b1Joxu^e_hKi43qxMd8*n6FGJ=Eza`bGs!;l?h~0U(8uvW*y!UUYLRkOL<;sJVnDA6uJ;<+uYD(#@XlmS3 zlz(4&BUFuwu<8sa$7<|UUw>dzd=;*}i{8SEsX~zKl1teKtKcG@EIw^ig%i2S|F%7? zg!%HkBVXk!@wfbxZ%A|{I+i_Qq}i84L)R`%DY*=3^XSzF6Dx66>R#+glWOeC`>a4F zRpFMp$+G6{HSlViyI)kDjeJ#~3GFm4zP^~A&0%w)5;!t{AL?*WK{z>Oybe`$c4qHC zH(+vCVDi6)2FyG>xx%o$5&4e$<(5!6=dL&Y-Px6geU^vzZIq?@gWUI%E3|pI>=d|c zWnUuw5E`LG7ccapICe`~bP1waJ7m%nJno509 zK;TL2#ml`r2_#4jbl$OLqx8-nYZ;1zo;QZ4?uiok`*R)3_!5Djh=DTY5d!*p+BUkj z1Q?#%hdTAyh;M7U`-k%Ork8esN}6m)m?R!4ro8)gYh1bJ6cd$)?X?Q~7*cAp#FuDx81ElTcfn)On?wh4})%?52iUm?s$7t1n5y zWUIn|?UX;7-spF|;70Y}2*%yVyGa<$vK2i3mPFi?@kGmh4l36P-N>jTad7ROOG}J7 zST^uM)~133uaekXzZfJYZWtDQ+`+-u&&drBok*0LE<0btB%x4kE|uHLf%33u&H8^N z++}Bc%7VDiEJ<~nbC-lcx7EqdRBv&<7W4ApC#v^o)$fRIr9pnv92waMG^}tA`Okpj zf#MQ7sSuLlSLhA@WF-cUxy0L9Qru0DIU1;tO~-BrmoIzc83@k(B;VW0#H>Dd^?6iI zW?#2YvtCWWSh!`XBAr@KGS^nM))EN$6`uc1hD2y3@#{9_9W86>Jov&KnCMJu-Z3Fj z_hp!^?ns@#8{u6^<+qvPn16shiI#5xUi~&7JQ!#qjz=^*9SR}xYo8WA%%;u z-S_@Yo7BR#OKmRhb76HY!NECz1F3~Yo7DSAY=yL6zDr>u2{kcyUvDf6GMfSo@-n6xy)eCc+EbO^<<{-Yws2|PqPgy?^G#KUW=u?wZE zd6-@<6ddBu!-%r=pq@Qc&DG>%+c}#fQ563=t+E@x+~py=*KgUUA3PYOu98;F z;GtPeSFis758A?&+zN_=LuQZHsr69*=W|VZSuGFjdvYE@mw1?Ws_(|Thg2_+-yl|G zz=yzZrqP{sd`NPNIODB695;UByVH~pLaqDRdFdv|y1hJb(T9}*xwdM0X+ zG%PA_>793_3TszYbA}A7(bicIa&vwa&K^AzEKcRl$=|2n8R}O<>1>c95K&Yh5WKJU!3i0iyBd-z=kxr2CiR2)u$9XiB z+K29Jsj2%(TnKzt-xK3VdGoEJabV^#G?PzKzIm~+H~t`rZ(jX@>NO-R3o|2GNhGeOmCzpz z5*Q9r>6&n%zSph6K64Kn7xQbkJGZi+e90wyKjohRL#{i%QC=Z)njf z8IY10*tOs_6Xy%wjE~=?yw~5Z$LBYR`g9SM!%ryBw{{(w6G9@lXnmPMEEj$!e;$>X z;G%9Y{a9lt7dvwS`hF{m&@=)To-QA0u)1OGmENJQAn#i#^>u z3HD;X!u<@~s23rsmeMhOXbmsBoDLHuv#hC9 zD)&nUYI7dbu{Xn@krlp`>K}Jnk6- zrTVssS7RAa%kh5qH;RGFGDA~~m~^cD@!2+x@?%GVt-iBJCcX;&Fqm9VCSE}0bF;~~VLTJl<$3nj0}L?Yi34KP{I&?(u!vV=p=@;Nr_tLisNG67lDN!< zywnbpQ_o4P>#v@FEQo`hS+;MFQTyut%+W(3>a|!c{59-SKL;m6f5`Smaxoe(Q@Xc_ zgPTXJr#ox7D33cFbC#?{mtp5&j#3>&KGg<)_o;>M_6s4SyQw}?im!E49{6b$Bp<%Q z#f?i~oLgUq-d6*bqe1of!T#m7=2<;5f4M2!SJz{0p)vCAG@v|d?`Jj5MvR@!7%8%D z#Nr3HZ%~d7y+7s;N+o#6{H{~#<;;VQ7v1K_5D&AaH_vam&BME2>JnSsd04w#U1V)K z4`#=X#TCT!Q2eWOr6$F}?xa6elh3H@<7K@y)097s?5QzX!bi&`&+fC`JRsuY`F2@8 zY-^PTH0JP;Xw6gH8pX$(goQGYlg`F9iP@oEThQ#A@2tDxw(BgwO=3JF`)nBI&^EMB+tqq=GZ)I<}7=!#XS z_L9FAO!caN25Y$npDLgce_O?6TQyD_7xukwrK4cU`y3M^%8P0jzs#}c;#S#~x!WV^ zQ5ycLM_{@EswWgg*HNB+-O6NDNqYl2)}!=>TRqNJre10fC7_&FsP@X1gT;ns1+%KS zxV+s^yCaT7N8a7%F-vP9hphX{sC8ghp0BBOjSEAkv0J$m&rDAYebORW*t)PkVWm71 zcU>kw_SVy(mZ!SV<~I%FPXsp0+SBk=t?fyIBOQLU-!*@x7}%8ayx*1TtA{t5>WB!i zFeo|raz_vg1KcwL*CHceq_+LA^h@x1YET~8n#yw zRL`oD*Q9*AAw5RbN|o~PS5w(mI|#%)*4I*=O@h9Az5T9s67z*Ef6*mKFbf^Mo;s5V zObnVGzlOw5NfSfLi+SRq-1&Vv7b ziw)=eSm^bP;B_i7k<|PnAz6clJFB1Fc-uomu>GkefwnZ*^}X7CJf#L(M!n*+@6loW z#(p4n8^vLbi(7mtLEV%94mswTMf}S2-UviX*kg~)}ZB!0Pdt|EmEMs7y=ilu1vn;so z{*k6jt&@fI+ii{rvTWUC+C;Qoz=2TG3x5hOdrxFhH|{$pspceT=YJDz-O5lc`Z5*Gvv^q4qUdeRNsza;BC*CTVI(Vo}m|QedjG{ve=K3d!P(3Bm(8557GjVdO7i{7~ za#Ccx$)QS=T3fxp)X##AYe#;LI}1kHmVpC3ENHzQk~lDgjpMz{Tkn^!VYctU5{?!d zQ-Yn(Pkzn9`4>rLhuzp1TDsjZTak^Os*L=AJ#6I4&0h6vekBH`?z!m@%t3lmkLB32 z6gqE7Wl3%qVBAFxEs;RusLAu>E=d|r1)KIxx2AD%LHMwrkNEI6^Shm{%7>%KMXF*L zA6M5kFYPz+s4DbmD<5am+}#CS~_gu z5g~%g&EOSCBbm-rdy(!Jd-l+MaQVTwYB?Z`)%%#!&bkBzveF3t#>VCoD zd@vlH@6WNLQCwXmXCfuQ*qL#bdEI=7cCIVgdx;O;MjN?vKl#WwxQ)?IErs37;00E+K&L`w6*^Blt+w{dO)wiw9NB_(yI# zcxb)+;du5=3cMxqelJh*komlVwdNEbAtw@YjoCbmdZjYBk5 ziieWr`5U`0^KkpP=j{tGDfmxFEwv7yu&vqT``!pHo<+awpw+qPKls_;C7**cO_vYe zy-)j%0ywyy@nQwfUoA3WPVi3X66@k{gkrYZC8`rl<@Q~s(gj#`6`5@EcCtVCBS0#$hY>yPRo=d%l3WY;@q6V zdJT(8JaNW;({*gP$UPX}ug`|1YDsL#Cl(4*n+(pLW`bHB7*kioz>1S5gJ0ffpd$L7 z!T4qd)Sm9`x8BUa2v5~jGjB1_=9%+#LMa0?9x`TaaACreH80&Dk%3nxPQmeNOl-J* z>{*kLiHDna#7N7t;P6>l+j49LmNtJ+QdnJzy0H#}&V`gC>&K3*o*x+)Zv8Y=x0eAe zjR!9x?N|uZIMDk|#6om?wmkbV3#Aq(M_1XiAonEpsrzv@+``LU^>?wbuQp-4Q8xoK z>ooMXMKNHS9yWZ;ASM6J)W*Y+dn8V94+J}ua%D1c2+r$leQ2)&ld4U|(Yy5i>+|C}I3YNd%)jg=UC z7b!%C#)^@wzW!@YvKZu1(5fsGqn!S>!uK_Kucwal2;+*8A-FQufg{GYuvM)_QDUg~ z2Ce&&C`RV4hDZCo>#%QJuFSQdI%r=Rf4y5n488BG#-D1h!OPki;uyUuxZe%&?9->v zHPZK?k4_~DUW;xPYq6jm(=)6&gNd@p=4|aCCZb%oC|QnS;cktabE_j8y4$j|3l)fb zpoaB)TQ-uN#T#U%vEUzlS-EE)3tuZ6(@xn`!s5#t_3Kk8uttZPJ)BD6j7rUu?B!hK zOVk#As1sr;wbbMCa522UPsnWfB!-7UQt!sHS`-Jwd|b#EVdB7|o62^zsL~lmTeGY2 z`QwcE6|Z?PJ6XQqu00dh%Ss%=_@!87baK3?yBPakw;8h;g-A(%T(mj17;_3H98^_f zfhApTKy{SEXS}Iw7Oxy@-CFnDU(SM8`x{xAsZ5;OG9~z4Cld;RZl;?RNnV$xU#hvl z!o&CaY3=oFJg(B47;RaJq0=snan`NGoe=&P&tYubDZFz-p_Pf3L-Tg0IIz*186A^q zTZ!r|pW<9B**Ftjcfntt4gVJBjT3EIIC|2k>fji1PMl)#yDkQ{vi;-dn=;|}chw>B#1`D(|UNEkJ-}-^i_0bDXyTm0{0BOwB@Wx z{5F*hni9Z*&}e%M&zk|MI*Uyu%Zl*@&I_6>?&HxQ$Co|ZWH$`dAd60Xl?ykKI4*~%f0AG6?TYLnhd z-i`a6@@h9F37(cv+O@L?&K`Z`SWRaBvdbdXj0KtHt0HfacVy?{nQ?h{m|zd~)VTMV z?8}lV+Ov#-M=kd@$F5@{H?U;z%w0?rdx``e7ddzsGSF?L!h+HUeY3!FCQ82aKh%86 z!9<1Z9~vLI*qL}}{@yMgG8*Dcbm%ImxIZyXRuW>RX&c*{Cxqj8)Ac93Xn5SHopq~J z2&EVozR4~jc50WruNWc18lBa($=xCh&3*ms+0<%$3)=DR_@pX)+V$?^!*BsAXYTNf zP2k~PXTTJdI0~inojUe(b1?Ajs%ZHK4nFNmNl_lcC4H#H{LU2|xcjw~%T6Hm{fdu~ zq%#+h$7wx5I0Xal%E_6#1n3MnpS%b z`mun!(5bl#2K>Ix%l4IMk_^ zFZ*@ger2!QejLPvtBUkhC``*(xYS%oq3rUDDZDS0$j#d@$he%1!i7BW<=&O?$lN?nIUxY8) z9a#-Uj|!!`xgwmZG5nD}q6X`mE*fl-V3kEf)DT2TddIdi=h?!iWqSXMAEmo}WmeJ-fAS>Nz&73TEqE)MVj> z^IMzM!&#VXCHZ+`6C08T%AVepV530nvVP-2He!Fs7He3r;UuX0dA*9?3 zlRBcJZOw(*$D7YzI+4DpuI^A~GllCnvd$hP{m1-;HCD@gd64DZt?wpvW~E@-xbVR= z>K|SoEFL33lGX!P?*lYK`V04%68?cOwNHl}1eo#cx##VAK9ZYXPxjIl;I+@vqRSTv zzG|MxpO>MrJ}sd$%9X}_$q}A+6nJRyG?^Pg`fc6YIScm1aACJw-T%j3E(SZ5;+g{w z@AB65n$=NoUl~KIJMr-So1E{(RPujL%r)mB6h1X4`mh-sRCzY`4{YY3q^dkplBz^S zq@kY$!Ply}(yzy@qp-b%In^VDg3a-K7mZR1;c-u28<9TQbHaM#LH7w>JI0(U-p<3Z z_N=sMa~?RiD>Kuqco>^z>Kt4^Ver{6p_@1HV0>OQb?Yr23UUlx%Nr@IyY4kFLW+XY zSZFRZpz!qR+gF>9@sL~OUEij{gT`X-S><`;KKfYNP$Dh@7TM(8P^GYFym(QsE)Q>l zQkl0c`QYScK9h|U;OXvV2d@SRkaDSOhb@y2y~G`-grskNwNqEtauFXNlw_vl8}g74 z*>J1GfP+KyyMZmFKX^kgJ0PD|iL)Q1Z8e5-k+|)U?RrPj|BjEge6d)7!up1^Ey@Bc zaT)F(8_h$fwC0lJWDZi+=5t4pzP4kVM()=M9JIYH_$;}NgJY#K?tL0u*zT4!*`me4 zhc1!HxH#(bTzISOdHC}s7em6wHu!gOP#xuF&$`Wl zm-W~;eZgGR2c+(}H;O_|s%WA!lZUt$i!fPQJJ*DSn~dT8CrIRP=omMJ_$E@XrAz9?F(-nf(zF(ZJ+RA z7c?gJ`3f$+yf(aisD+2G-t^5wEqt7EiqBbfl#d<4NH4X+JUkyIQWtLIL%Pq^`PmgR z$KAh|={$`G$tP#E600dtWiS1uy1974-1wq3l?#Pkb@SBSC=AQ~dD3JR`QMYd@#JC( zp-s}a!XFCYb}30~$5B!rG`FM{9IeLu6O*q~OBGt=HDNp7MOeR!WSVN0WKUt7F5V12`uAE+&n9#4)fdk`97&+iS9mG*Cc*Ke5&FK#1dqWIhOU~0 zJZx9An2}+_#|5JyG&hZhSwSs(9mu^u((tAwubPKtn*!F((d6U7v?R&=RvxbTUhL>A z5MWo1gQtnD04{FqHycz1P}D2BqIXe%>OJ=J!4cpf$GO^@%$X-sS6Xdy<>Sk=#m6EN z`EXyP9TiOSn#Z-BQCGsl!_eaTgBd(1-g;!_zk@>3J<8_f77FJBXmOqeg|jA~8huK+ zc<#UdOX467tm4*xS}}-?@4cU#D3v%ik1;S{WL9^hnu%BZ;{oh2 zHqI*u?KJGzaA-_vHVtE;**>9- z$i8ruy_FJTuBJ!$sT>h9OJ~j=y}AbJrs45V_SK+j2qVKOry9?{zkO5rpa$9XCSH#F zM9>$HUZ}OT3W^K+t+mwz2r1vr>Ghzn^-%U9LlV~-t($3T4LrynZt$#m!h-->K&8Kn zhTh99@)Uw*$XlM8zcR}q)t!^ z!shi?^5CwwL*CVe^gj>R8io&$xjt?1yRW4*HgJvG^T~Y=x4B|-TT_5Do3_bM>Et11 zX83gHMHGUmYr%P@r0-Z;?w=vch4!ufaEn9=OO9zqENm_ zl{S^7aQm>r%eFHdxJVUURV}WBX};8I%T^9b-3zQrcThaBE5~eorx(eGj?SdG(ocLuD$jZUI8XrgWjYsVxDOFkek`Q0(Xf%BpvOg1yh32C)`nF_hvN~uSw{pKN+bqE1vlB;Oh@w&EB)!Hxkw(cSw@IIsX-M~M z@R{61!}9)&j-e7l2-nu1QtP3yuqw{Ne-@4Wsj2>LV`*#|&Hh?Clg7#Rbr+4@g?N&2 z{Z?Nv$?NA?)mIi&;f1}WfARz&ehl_o9r39OGh5V$M699_*fs9>nO8gvZNG1rkiiFb zwZ3*)$U|SQ!o-TCO0W_`+|D<%k+Jc5*oufs3{!}_bkdQ775g4Wm+Nzp>X>RCwt$Oo z!ATZB+en@3ntpiqXi}e2^62a+E)GmTJ8xYFg-I_(Nkd3qk$d!n$flEzBRgl#o}@(H z-=di^&89R4O?G;`Tat$9Ir9U3Od4jr`R6W>d?;-7m_P8k3VDksertYB{GM38_1=CO zcSgw_4&m@2s{MYd`3}?D9!hNWZ)Ei}DiLE!A)daQmI;N!0Z|He+o!C3`M>+kN%)ita>7RMz-kx%?2s`|Q zLT18#<8i}CAMIeI)q8?MNX6_!BS%uWIeE*QL}v+=V2rEtn}jJ@tpkuf$8Kuc-HvYg7j(ULQY@5@~hv`u-2|5 z_#8-jXd-={%sH7UuCuj;2-&kx>QO$8P#i!YCy zIftS!Msv1bnI{kV5r!9LEaXB%QP`24#Kl&VDY7X?xo9w)Gu0@ci>{qt3~fBQxT)FL zxRdlhm*PA>Y}m?$(XCCP^=({qkC>r!=pcow4ms_*6y>GfjYi?e4O$A^!D?73{~&Y(>p4_el3~s>c@NpyjSl`*e}3(#}&+O@{X*W zbV&Txfb`+@dnYO@6!)fn~k@QL$Cq79IR(wYMa7kG|`dSq>dbpRV^jG2X>oCE}JR$mO zJdSSMNb2D8pAsWZRpGR(-$Sh@G*oLsdCs|2I3d|-ar+ew3&|Gho*9j`gFipARHebZ z9W(c~q7e1L^{Y?H2@$00o*)nj!SLA?xGcCD6T3}EpKY&3^6IbVJL_s-eEFeFmQ_6p zN9tZSb8EorrS1vWht#7bz|mnVng6PT8%C{IUxVaruDibl)Znh`ijP*xwaD3gt#^4- z4JI~yYn{ieLAUYBsFb&rkUaNvx~o(sW>32&yXyRXY<>OnQBH0Of(&P_{_J-YO^!vz zU+%BM+N!vf*)yZ@RV!K1w$&Na`<1#^>^TC*ILd}UZZBlC@9a^#8;OYVb0l`3KMvzC zo!ZRDagef)t_jOHg*;=|Jv9lZp=`Hve88@B^n88qRN0h)IsNYZ!k3xwINbGQ$F8gJ z>Djkdw&p5+Y;w%Ugfuu$PPpNJJrx=cho+C5l!6__J1(A(I*W%DMo%Z{Bq4>jGUvkP zlQ?uIfANTdSZojRt1U-mAC~RGw2^Y7+BfUtr|dcVT{jKz;#s9dQ<*+$RQbJw=T3%J zpP{vxx&b643^%&Z8eTClU_fZUorFZ);t{?hD7u*T5;EIqie8fCJCGBh^T z4IA{PSME{T; z$+5jeUhcpB5)%0>74{NDK4Q}2+vCZ)>HqBh^`Aj#9$8DwtV$k6_*(7F)B4JP>sR{2 zXAph8p-D9BxNgnHjNclQ^at>V`#Pv}Zl#l0WM zz8T>oWtE6OqkqMb{I?+fekbQ_n;^p)P1Y`TX`6rA{oD83kAL!Rzw{7!s|(*6Z^3FIrFjv;M?=?5}*0eLSMCneguuKf22Q#ZBuEe>sV-0)EH&7yYX@X;Ff|I-$*f z;`?7b{?E=liK}wI?$_Tu{dd3q;8^hw4kYo<-oJ7CFD`cfaPn8*ulGQ`;y1nr%Krxd z0RR7FS$SMe+t=TTBs7pIROXP(Tk?^=5;LMBDkJ?TIRkr>Vj){OqeL zBSdOFa>+{xA-yWzj{BWWNQbn);+65gnl15HLTmHIZn!4q-Kq8&ppCvk-~E5LN59nX zQf+J6vYt%JKin4MX)!goE3<|1Y?-Vlzc2n<%~s$14dW$PSBiE4`f6C8wRHGw1+1HZ z`Cl+jc7|z`p)J0*b5m=KukGLNMi(llPldItZ(XCPT`Lh<;k+;Cs|fTzQ=R_#2l|z* z2DIVtF+sTh=-1ch_Cou6N0h}>Ez-%q#fp!Py6E8M&u)Hq2n{o`-S-nM+`~oOoj8AyyeGJ-Z3e`_+{`(9pk## z@9%6mKQ%F43%bfA!v0KwJX&8pQisa<+YR%LyRLrQ5&ciX`Az(gwA^3ZSERp*57~k| zMY)M`&lb)@TZs8@(caWr_4qs1Em1M4S7S1n8t8kDzOuk?aX+~{WU@ivSA|3->yxN; zO@+4X)1(K2+-2guac*CJo~5wP>x}EXyLLjqfd7v+2K(e>3v$AF9b--J z8&JZ1*nG3kP)4{RV?AO9P$IpjKjp$$N^&N6byhLL_`*x^afaA`QtQChlNiY<{J4Gm zILtE|y!h&PN`fs-A5_~@qPu)bo4qs8_p`53a-zgpqkBcqZIq-PtT-9Am69XHdZ|x2 zN@Nj6J8TbA^1$Hr@0632lLTkE>cvq~FgCw%TL>krN_XkFD$)`|LEejaj=~Iy|1{X#G?_@D=-NjWGG0hVkj!Jk(pApyYB* z(vUG5DJi_C7jEOuh;-xjM3i#KFPS`4Yr%&Vi@;5>im)&@r+ai-Wrz_!^na~l6yZe9(TrV>#+pJ zRceeJ5Q1@)*xd$i&<_4+=d}4WCmUF(JP*D*AwICNYQ`a z;a2YrCm46dCPZ-y_OWAwo+h1OWcQybLEVorq8@bf-s63Y6i9+BqS0ROnz?gf1S3j6 zhq-1XGfv%VV%ptQ#_0?>aOC+FCVjvB-q3$CnY19co!P0YOuBq&m&9A?j0^ZNK2{z5 z(Jw3Fv(s44)}kZot``{RIFpN9oXT=)#yg#tfDh-Qu8sZ|{c}6Q%dTHwIqgG}ye%-# ze@^(~Z|50jHQ!ouODrQNHAdGPhBM;bTh_)K_g(m6cIE6)M$$X3VV71gqHL?!_vU6s zHU=fAE#1gSugk;ooNX!DXzhESEMlZY;YaY`xsZ=)`ne-Ul*I7*J_Y*S)6vOrB##Hz zUWVwSzX9g1i+)a%-pgdec)Ue_3~;LfcJK#sSXdjnt$o#Jp2z3^;5d(W zUGV>rg{os`0T)svay+Y+h$nHCq|@On#0~6`&u;` zQJE_}rAyaR(v{~AM`ce(`>Y5*K*Hp1w4E(q}It zQNEMERBmOY^x(GblhA4}>X-S*n-Nc?qN5hO8R*XGv9)`?)Y; zZqv`(g=6IF<@WbCyHhzngiTBB(srijSho9$1fUDDRpd| z%1G)S|Ki8Kj0~BdZ&bL8lH4J$?ivF3qvGpUEcO6j=1oaC?MaE**o)ztE{x=NvFQcUYz{EE;e&Fi>x5GF0QQ|k-;X|ucl%&T^n9+MD zBSk^8tNH~p(%5CxBBeu&WLEC}kpz6Kowzk~*&0TcnJyg_co2Rn+r;S}*4MhKR9$qT zvZ=c@4Sjc@U-#|$TKL;wo=(uMuUIfI)tQnJUzHv%cA;eR$K@e;K2#y*X4#ySASye5 zM(H3Up*bIV8RGm=-TQU&-2%NZf3e46BUMmd zysOU{$g5;%#?Q$0zy+NrDX-^KVjGgD=?ed;-{014JNT|Q<H&`-~#_Jp61!W$eu)cdnr(K^mux5NV=l#4jB@UG}{?DNgipy%4$p68kMWV;Tu!z-3ja`AIdc&F!Oe!^!mxEB|0%aWu(V2t*R#j^giZeFJgcYbEZnnAg46qD&}UmdzySRl&*$50J^;Hs-s5Il$i393 zU7R)ispg=XzceAA%L%Gg?wH@&ZFzw+>^AFLckO!o*Nsp;77hJRo#}b={1N<@b{W4O z`r9z(>-`PeU~dD*%+!ZJP8wYkT*>?Evt8B&;=E-w3;Pem{12gBa-SqIZgZ*0D%)g6 z?nSpASC+y!*DDnXgHsuqGyRZV@ma=chU9Y~d>-~` za5wyY1@zso%lbN#NJbv3ed_BAz9-KqFfYbEhR1s6wnzU2<7 z-AeR-6@5B$2K_{T&Ac1H$zLA!$A$o}7DrUhYQ+71+3OAZ7jjV7Uf1ga8?zTuqeTd(|w8Zx6B0wh}CLO~3(^J>)>52Q! zIWi*h5cDWC*yKem##4EGgg!YLAb?%X6r^uHKOHp__N0F$O=}(_`Y>B<;9sIFx$gTa z%;W9Lp6%M1H`2N|h;n>4rzH0rS$5f2)(c9y?*Z= z+#~R9ugz}oBT~mz5C1~H@Kb4rTRWNVsN}Z?@IX}3XbiZl>r#6e`Dc;N_4_e(4jT{}Y}pKH>|$n;t#w;Q&4cXqn|!LhlFj zcm{tF9j=p}=L-MYBmlf`I;Z{p#uavb2|&J%ajLwZ0X`--06AetUp_%h#3Qp3yUI$$Ep{V1?%uFM+4r zf`-=`mWfl*AD=fM5B`mNwIKe6AM|jxsnHeKwPM7vX}rC>D#)(VgT^J;s3 zNq+wagWMid(OBYC3j4IDUXFcB8vNA3H$y0cSGC;@Tq9(n2g=H|J={9JCng551|km2F*d!peF^Yy@_@3Nz}Jp9QzNFru1Sai;EXdE8&piSsgDNo~t+m<(UDm*%vq$;-0j-{W0>&io2{-Y{dr zux&1sbIs5nIBo;%bmZb0mWb0{<(JRMh5R3kxRjs@x+{&8?;gf`46onOn&7)Ueqhb< zlC*No)zMgIJg@zLP}qxf$)@7Lu)EK*#%Vi44+C9p-Le2qoY-O1z8&tJw%}FZM&MiZ zhQo~+u2e=}ta;ia2>!prW~(=jLR^jWPMFlVs(@b)2lR6H$GOgB^-161@3ka-Pa5-f zwRno89Q)qMNI#$iKBnq@K2Z++owUV#Uj@!d;r#&i9T3c1kmNNdOtY@x>ol{s#ySg{98NL(F8bpG^NoY;5g_?h@IXCa$LV}$wno}D?a(P znHl`*Z6k>Ro z5|iQ;AE)j`+{?%3%V>FnMeo;MUQ}x4EIHQ^xcZiVcO9m(?w?X_4D*8jU;~KEfsu#~ zcYgHPNTsc2wCXtS5Y6eTajUdrFqO7Vjb6O-5cQgo^cLxL_uF)Qi$S06W z$$0;6?L%pfTHAIO*};@ZUrKjv4WSC1zdxGLO9LEoG3(347mPI@Z1M+%=` zHN*JpRZAvFnQZdnsFC>*G-v;T?Y&)&P%>%qx7*$!l-n3;v9kMK+U!S0Ea^>LAXnr0 zTYeisj*+gFW=^mVlJw&FA_?Q(xAQq>?p%1GPLp=F%Z1_fa9jxbML7^ zk4=qhyBPr|&tC$8ut&!lJXA5Sl+R0H-rY8Mc2ow7l9D$AzVhXV1E3@8ZPE-a@F(78i=Wpv=zFA_O<%mfJE>l~l?!=)S|QObgue7!=^y_R zI6JX$>bjo1e{aeU;Jx=yx6NG0&2yt+X*v&+)2w}(&2kHomhI6aX-COf4slIa!$9+ zpL#Nlk+}1^_pQ7K=MX8jrDRg=NEaBCm?p?H^F{HR>w7|S@1 zjEof*5Ld)%I4_a$@zGw>evYsU^BF({+^@2Ix$j>y_&Uks7$*bxN##5G9(}1izsBbW zUkUXZx&Kz+_&glqODX@q50%$V>YDR_3gp>P{d65F&$sd8-3-p8@Oj90LcUC_gWUNi z+M3T7E)?>S|2I#_)5F)Xz6$jfF+bKskC2Be`cM8*%x8*q7d{WyNyu9k3j6($5RT8Y z^cUXqe0zbM?9l5!`9}?`@4;H?Mwaq=PjjC2olwsa^NUS<;OksoomDi@azmeA=p)o) zG~wrc%hf0JMPEs%voz)L#5xsi$+ybysX%O0OzL_5@%1$oK`yFdT?yxVcQ6098~P^v zeX@l-C=>T-$#aVJAn_crP9*YC{~=Sxf%dnXePF7Jgh1 z^0J~niFG<5?c)9WUS+Ne*w6DPT8c9o@T+~l7-z>^O)PFHAFW#HySE1zp>xo#W6Z6R8y~R9p zQ{Ftg#eTbjzwIz?2fgR(y@DMy#Ygo*-L?qrH=&*?+GP_x*)9BN%A2zm`Q7I0#?bGs zf_)2laUmbyj1$dyaQ(d^FPTf>@k+jsmf67~NzI0&YHBG!b$xfS;1>>97$?Fb1Y4bX%e}YMN z-@k^|OHsKX(;g4vC6M0-|zE2CD z$?5qY00030|4dnVTuoaWUJX*DNf8;+C1gq>LhFzrV@ZfeNXjK7X+XPCDJpdnNr&cn zP8nLK%w0p~GL<2GAtCB2&iCv(-ERM^-(Gv4wchm(&+|SjDPq&htZgVIq%Nqa^+6dS zy$h!&YBECR^mBUE2lE!Yzv}eGbFQ%Es>nnv9=X}l^n(c@s=IdU4ZwT37MUUP7#+6U zovwlL+`0)%q?lN&jQ0w7CKzvE-D%!^d#V2Cy9@YE^*`$y)|Q(qV(j|68TF`E8qYIU zPh9(}tb6|Fz9`ie?7y)1+(|XOw_c*M=QG|fyf1Y8jd?3Pi^~YN_munXew1+cmMJ;( zrJeRynGo(Z&Z&-hyY%Bl7|C_)^Qx?SjB>U0sI8}Ap+jTx78o1^Dm$FX(-!SRg zpAZw?k0$?~kIebUw;yjOe@=pN6dzak&1A-+aKwdMp|6+5`|Zr}k&lPd&iw~td@b2u zg#B_&{*4n?j(t@n{&-{39ar8D-@4*2$*aK_Z{c@*{ED%T3X|CVpZwzIdAmMKkLV%y zubpD?Fy3#luiR)!Ja11|T=?&sOuGHwm3JL}!Kes-$#>;Bz7xP7pG+k4*k7Mtr>ryI z`1!Fqhi>%#kDV7f@|uty$ahU9C9t%UT0ELc>HzaLpEgWT$5_#Ej?TFKudF*>U4CxD zd4802uh*3)C6f4c#0&F$-pa5}d*9&u@vujWb=zyk=R4*%@OjKSSAUZOBO7+cc%p1&oNCRW&~>qQuTcBcyf? zBTX3@(nV&J)X82d4aEDMd_K&fM4#ED@F=I=Hvd;SD&)3Mu zm36)!f^pk$g$f=Qj_oU5ALyvXlHJ=Ave$fA#udDl? zy13j?4-!A%yOomqlK4Tu+cOg9bG>c8YcZaA|1G5C{k_(JRT~+Z)BnNQo5vaF^5eE+ zMmi%3ZEk9+*-TVd5*j-&ml2JXda0@TjHv&y=&f}z6Qw?zGwxO?BlA3$onK$dxEEL2 zcD3a(GSwigy*!)|nWMQoM*2{4bAsPQon82@Vdh`=k1%pQ@4MnlcSb%2NEiEIo_u$B zux~RX75;ZKw}mk-&3D;?I3XiTwv6;kh(a8G-dr8;OG)aIlg~cyq(olUIC9D!M#fvG z_jdQ7q;kdB1IvRbd8X7SWZ7OyB8mbny?m&Ynz`GggfPlY9^RPO96?F){@vc+V=$Vg zynBw(@Zx3bIMIc7WDR&wnTfp@@cBr)>!_nnDcMO=w5bgv;oAr7j7DCx zzeuKS8)#?U;60azheE{{Akiy zkJ|sSr=91yvQ8WT4huY;PmdYK;|NJs9K^cuq6-H*>V^G_kK|gj{|KCeGY1a;K_z%X ziO73QO&-5a7hX#6hTHX0VAfB9LrrBwz@H1>Z3{8bvfqgMxO9KaX4Jc;xB8y9wuonx zlVPbfCHop>+j9IEk)AMVThw2SoD?omiuZ?~9?ZV+2BX2znX_+kjI<6JKdsT8N<~E! zwGZf`WDBBenCDq{cRU&20Zb9`lRBU3njwnp(T~3jMz>3 z$07Dlocpn8rNTIO=SnDt zdcF#Oz;0)U=7g87l=!Z+yWZdie{{vGmX9YR{=Ge9jeHqt=IwCBz5}$*)tFk{-vkHXWAMzvu*sBEl|KD`&kFVRY5i&^ z7b@Nx00Ob4Vx!-4Hed3jVy|A@7e!A>S`$(ywctGN3wwSLZ)4=Z_C%>JnnydyKc_JDHZWAZ(-e| ze4m5!-di~$V*gGmt`BqCKG2JbpJ@EF8-V)$bRztbravWPdpx(j=Saopr5wuqc2J@i zD>eSQ8~nXFRJmX;_Fq|)m;k#xlaFcsjkpRDYs-}Op?=ephkwTW`zygYZuaoY=P5f* zV$9u>ruq|go|_$``U3u$TC^=|0`kc4l>Dn1`zSGXvk3kGd~!G)cYiGKi(A+rYl!+0 zerVen4nNer>7)N`CME6%)n$fn#r{)X8_rn)e~beUf{&_b`ISR!u)nY7`zP~}U!ijx zW%>M&@W3b{j?x2;Dr)Z=b=L)Xd%34u`zqwYi%TP}?We@iWun|8;Bb$XO5^emQ!;d; zUqB@Mpg-2TY#i(&Q*s(IbtxHgzIT+mJLOb{WuLqlNy)(0WqsQ4{fUMf?FsRe+jn=! zgv1P5cePq!LU|swE1tijB&?8wwaFCMgrnS#2fuFrP;z5b}`cI>7 z<6LVRZ^~W@W@Pf`sdMKaW#oUOU4lxEgFjj)sK^Q#=k52S;dL70+N3>S-p*nI!}E<< zX1PpcIG4MB9=w$pT0#tqnc&!~^!(3dOkmPOWMz8&=@0$#&t* zPDzZbu@3fFd4>_)w8ay9o<_X~c>a_>$+)I7Ioh|dpE&$Ln{g^55hE8oUYyOiF%$lY zZ_i@fU;9_diZft`l(M3BCL;?<+XfBAd{2*=G3q&tq>3~D`GWD`Fr!O-3K=O=A7XeO zJUT{Y=IBU_#SdoLDi<@-mb3f5Lm}hp=2iAvP{4>e-{0pmuJABjR+Gy(1HNC)V5HFP zX~0|XwAN$xVG`C=FR)dt&t#lh{PgnQu%o>0#Ppvjj7YtZRydTxxLKxR+5VVc^>^HH zJFGL~n@jcn9JFd$h@=A_Q1YpK8~y32mhR%_35k| z_FLHd*otbLZ)bsfo<7zodz3WqeGdHSJ$|4;HY5Gx#umNEVIsMESCaq2@4w9Tx)6@h z>(S&jO89=mbN9XWuyejq#Tgy=Pdaw$P(eIJo7&TR|yy*j8Q4=OdXW<<3IqRP6ME^7gZHzVW(&ARVoas8? zqhF1zCUA^Sxe?Zi^Jsg99Be_KC(q~K4&W`%>%fih6$|e)11CsY*|!h_Mq>EiIRKAZ z)yZq{o|Rfn&(%}FPi?<%g#d@U`Zw+Uk;$_#3j5mnE(cF=A{iNZtSjQ{))Hg&>~O!? zjI*9BzxzD=7+ya-stov+>wQX25q*TQHabd6N-pz#o;f8ewiJnmET<%Y%bm?zF(1+U zcHL+E?y~JDyXn?ckk2VRJLg43a&|I0m-kTa)pePOxt^3eB31L@IdI$T=)0dLGr*@0 zn#N`RNy&lsq`CWnyH3-pOt;&B2ma?_)Nc;u7J6j)H*S>l2a{lb;1r@|!N@a~e=pGx zILP<&w!qbpnxiYgi@C-bJ$^W%URTLP1p<$EcJ?V!t__u2Jb>?q`#k@sY){$D4+F>b zJVd!q#l3IsIYdPj%C}RF?4e{huQz8?DMba%buYkE+1`)0+&+Z!haD162Yyw}%Z|0= z`{154V^@TM$NzUWN9GtK)sdpNgF-P%7iKwZX9D}_wdRNS(z+Qu;d4}!5&kuDt2dRB z&1k6K3qMpQXl+=wi@%3Z^J$>S1Nk><^A9j0s~Jse`S|e%13zW%Eg3uzdGTiqQj_OX zGeaL8^cADDbzjbQW`w7CRpiSq*);X(TdCAW9=PD&j=l)`Zqv72+f%L4_b&NTlIlhU z=GmjeYtVPQ1plEtXC)=}!M6=UkcUkoQgP6diUJ1=G?(?EqV1YJ%3pg?Zqic_uoL|J@x<&9%2o=>X zUfh3U0OhPM9Wc-Iqr|Jm?a4s&ql#~8>TQrmWL&3SY#%gq+->w}O;rdy&L`aRanTgS z)!uIKHD&09*7>!GPJF$Djy=99mP$k>-!WOY6}OTEERYr-ZuP*n5`J!XQSJRBqmV zjk-On`#kzO`b1tP4ghbgIo`DBS0d}Y7D{EDvt#8_3Lbe|DST4L&p&%0_y#;1+ei%t z1J4X*ZV2v)`C|WlRRyp|ZQ*+PY4PYwp6lp8f;~omHkIjNRO_d)%NXx{U7nWBj{^^E zI({G+cDOxjI{&{w-~unG4x{doUNcN7_nwj2S~6%v=%(Rb{^>M)_^cA? zUP)B`)5B|~wMn#Tq@LCzt7KZ&|5$qAl_c64Inm^%Z8CibR8ezCryBI?vm*aYdZOmt z#L7u2G|W=L{QdV7+E(e;tUfK1UXYpL^fEu4PRTG?Ws{de^}dw${m7E(o8tXpKR+bV zv6)(*kAz~M&)dRY>`b9{Z>P5g%cRn}8!6X{6;tVZsMAwNGpKfh2}xU$NyFn0uQf`_ zq;}heU7w|pL7QI6Cf`4oMC)=5n-T^lQ(J693efNVsuD(>jILoxi0uG9ZoGAzO!R zOQQl`ahCnHY`QaI_UhK3=%@TmcYJBWXs9?;b$LFu>k*jg{5_Xi@V85KdDNoe?|Vyc zRDk-LZ1kxCI?wN zJ;pzPb=`Lo-N@zBFF~I;N^p44@%g{)!YTK7bE~;gICPY~R*6giC8O^iy>=gc@GCyi zplh^woCc2N^7oJ6Sz_S&QHW6(r+DNj^h&5xvR54RTlJUq+VbGrs{5s9qAtdb743-y zz87xXWIKPcD zUX%pcm>fL{o=P24J#U5w?B(y%z;7gOoOa>T?)#K*$cvIiR7w;Hdq;y`K8@V85BpmL z4zjre-D{oI_t+*+H{6!_Ez@K{1w+dxe3B$8dMkf#9p~ zkE&Y(T_y9z5tU@Ph|R_54z)1FAsm3B~{;@iuiu|rdfX+dWPe5sWJM8^u~x= z;2(QgtEs+tAF2%HVh5dgOiOVO`nanWOA9lg3(XcNn`S`A3wfQ5c(3Iz%yz?Ha$}Yj z&0|s=&vRoa`FPxR<5-p|%GU%g~66>re{CSMV6~UJfBLv zAME>U-^XmK&26;5F{psrK|0pN)<4XccYCeu#603LZg z8TvGua%b~uA{t^TIqSL9vo?m3@}UQQd!cUB`THdJ)4d}Olgq#Q%Buq7VsjXDth;5=%0yvKbg$PIUcx$ zjI68sYCQ>j{!@2}-ps=v-@O__mRN?nA6DEjEV3%`s@u-3#CMZ~US~`L~g}Nzjfu)Q< zMGt%e-H4_tL>=q&9WgAT7;$Yk1VN+UvYR$r?kn(rewP0J9Qbur!R^*E#K)lC)M7IF zyz>XjovXnciqncu4Firh4XU)zK%H493^{XmKO-j-jvUEA-}%bT(K_@Hl`6dMRu+GP zdY}5^>$-(;^mId(PnOzA+O+7h&AZxUs$Y|*8uS=?@nG}Q$37XFtar7redZ{jY8!b&l8iFz8f8{(cj7e&YX60KVC2Uw^C| zcv(m-oS))6&4b%7OZnq`Ji+thU74YNn;Ey1*TdT>xqjs8=>uDUqw45j+!<%QDoV{4 z{lo8uUA0@cQ_izIWtxW%`Vz$<$@?QIxtgT6eODaScmH%R@X}FAZVXkN(PB$UWAFC? z)8_;K`2J@z<=!i8+|mob5B}@!^>@&vD@|VwS>#Q*!Re!K7^5$7)!m-nh&)Mpw*N?& z10_|e2H{&^htQ|8wFNwT!D-S`Q{ZLEU$(J_fw!3oXBuUI(?Ne09lVIKxyoc^lNWTi zW&TNj==6Qj@5-OU58LEQv~8f{tZhqQOhH~IUe5mX3C}?Z8LoSgpF*93L9v)$D`PXl z8u{DNsCoid;((ms`KB7G9aZX0wL*_h$p48?4kHp^xZ?j&$8a(dE#}zy}b^PmOIrJMpXRS-L zm`BOj+DU4sC*u5kpP#rBQ=4(`}%-O}DwI_Kh+{gECLooJ=8O=v}Ahc|X6u_UGJl&OUpsz1DZw zmx$$KBJHgxDKS5omTw4z;~RPGyC!g-&bcwO(-(LW4G-#EgMcHjp8w})FpxbeGI5<= zAbK6)giUO!5SKrW`KC72T3`dqjB?l@}l9k1=Dq{+`m;#(jk#Ot(ot0Eluc|-r17djThw5P;AY0=6=EiOV@y#W#r}PJbSl(oQUS0%< zvJ&J91;>CJ-QL#q_7D*D+;|CoDkUv<+i(2kTB4~!JG)7 zW^YgNyP$mVFkZf<>qs7iS$`gu{IeKR=dJBI^sN*c)%7!GxD)|juy#nPV=-(RcXR>Y zumooQ`e2gST?i`;G;K$XD1wwXNnzEkCD5^NKy&ouLeSNH)Y|Yl5BNSB?;7?BfvY%0 zW7Od?P~GZRnZ2?cMhr&d3px4&B9OMk6R8sbqLSU0tqP9mqFqS>9^>qXw zzAWuO%{m7l@Oo>OmjGtrRo$y1Ao8=fyfQ5YardXgX@3iW<1qTnHw6LEn-d&opDqNE z>!0)5?#00EU1I7gC<4xkYtG5|-7 zs{rn~uc`mYR{&AUvfK^$yp+UJk9U}_C(FiVj>Y@CmYB~VmB7s|+N{to1W};G(J^xc zz{p=u4qAR1m|@D^(zRK@O*~}3NSzPl_!_07vJt>Yj^bSt#Q|Awf4^Dn1lHMLKU31} zQuIxDj1sJ(>E;oXFprIME?_-gT9I#87)^=M562nP(<#vj)Q(fiq|C}ON~))dDOYmz z3eSH^DS7bg4LFohZozIXrTTIzN?#NiexsZ+Q8xSgV@oKBaXzY}Q%IT0&~1mu7EyAm z<)d0kCMBuWJ*$jQU_W14X4f5n{V_l1caAT9e;ZFiPZ@uAw>iJok`kWQhuuZNFint{UYh4%mLGrlJ_|LtVJqXQp5jlAcx8`mixf4#>7m$be9!+_7WW|ThxxNBL-2mWqCZ=<9RT9TCfWnvo2YB}+YaLu&B)un z2j7!UO*F;$#Vpe9!Z_}(jSb!gM8r1o93U~5GW{pvKDGYk);i((nS}}wS65RKo2Yp@ z(Ex~Pi9+@e%va4l({P_dl;lLuzWof>ZlF3nSYPM1JSz*nW zcFqH=YtzJ%mfnLH&!$ek-B#oSI=sXJ`@7sCb4+3!FpiQkEg2cWJzIIevE&Sh*V`;| z@j=|sb&y##s}95(!}gVUod-U!iK_xm(xt_9@fFb6Vr~7!wFsC}ww{wQ{_{MS8(1f& zJ5}00Fc@c#*2zw1D#0Il3MXvoPz7CkFu^kbCQx}J5=ZAV?PT!-1x^3NB9xb zs*__VS$t;El*`G815Y0G*=A7Y(Xh%V_Yp@jrVkAZ%BRFzDdV39$e)3xE8KOfsL21! zm#4d`Fz+l5)KVsB`%K-(IGR39jLE5>M9M^VVHx7cXQlbmZX>R2t8iPaT0of_tDg5i z6Huo9@t;q7@P3H2?BcLIO3DH~N)Mc&jOEZD&R>ctBNd&pzFtTftdbc<_IwjW4`dN=1YCR7T0Dlm)@|h_9PQCGEJ2 zy2DLx;`f=AlzZKGNy2!1ucPOMOf$y4{-SkPCC2&oY0LVt_`MGavbP8FDO3BX<%k>V znC-$#_dGC;XO|YfdX4jjl=XhC#QfWiTq-#q^Z8R}$%qq(GS(*!O;=FO|nr`IdeEn{S z<2cXqQqfM2Y)bUM?)%%3M2SYyGeKDf>Mgm;=W5PSa`|ZT76Iy^WltInrpHoJb*$b{ z6pDS|{m0Pa5VSh{3?5Z zhWXJNA@LJ&s^*70d9H!Kqr6VrOo=MnkK=*p)~fkGMg2@C2|>8|N2Y?@?)2Z&S#uQwbHR@@ixQ* zKP8)b_I)#H-Ts+~ivbJnl_Fp9O_Ce#aH+&m#&6^VbNmiXUbt%q>UTDgOOQX!cYL!z z9_AJMJH{iwUtARN&ku~3r;W-+ABdK9-@~=XfXQ<--M-5MxPQKRiqkRf_OcH%N8y;O zd2Z}PPvBoykl(!~7$o$Z@`LLT2lWm)N<9mq#FXQ^O%cbV6LQT)1+%<)bYwQ-X>SCs zFdTW|p-ys^A0@2H9EbOX&amOu7(k<3-6lkEEtuu2l5ug^r@w3)al#C_Y{556r|&WN;hg zmHaVtKAIzbOx|feeLs-ci@d+m$m^3!e0JDkUIV)~rF3C`ntiRkAA$PtX!Y<}9K`vp zqt!CpQAg(4Z`!C~M;Qgt8;iPwz(rLwB`Ofeqif?%?Ki>sLb~NvVx7nR8~49Bk9BKp zD}CyYH_*r1HQp_S{6h>(I4M?Hux#S?#3c30ai6thDd7Qy~?N8tOQFHsTpRHMt0J?$LYS0}+Vd zx<)J0YgvaS#F0R~ySa7s7?>{ghR-k1T*lxDXr z1)0Ft`DiTC%7EC!IA4R8IneRhbIRY&BCu<^t{r1k2HtJwHnaqmfhlvuqvu*V2v5x$ z8D3Edh4c38ciN7=@bq=~rC18W*A9s-8%kh=hoY0R5~x*tlz3%m2{>OBj8LCa1R3VrIpyU-7__J3E8xe}pyx}S%Ro8y-mX6MML!v? z?ai|S2oqSo@$)VQwY1AtssW|oqMI$L^gsyh*A@paQOJkImlw!sDHi~*qv%c_UkEjG zHF!HultcH~ggcvY9h}398|-3AV2PT_1`CH0kT9Hf>kYRUc=M+aK}|l8mmeP+?G=FB z@{ZTpQ9_W@VGU*(xCqsk%uy-_rg+|5sREqGhf}6Iz8tuHKj+O}gwKJ%iYlS+ef?xn zzh^lNbfy`7*&#rkpa1Emz5uwBloLWqN`QGiX>Rvo^l9HZ@)u;3g7{q5h(CIzz!|4{ zu1*7emw29!=kZby1)shlXhT1EfE)~zDgu$0Ow1pZVh|-3ebrf809^7{c}Et`DdeaY7j-2A`sy^+s>ErRfQlPa&`5wrT86X)8~$> z(BJ*exu5$y6S#xCj{dHLGt^*KE{HO%mh_lq1IZRfW(`OGhwK&c9DQHtl{asHrULW+ zaF=CCEDT5|i;B*N12L9bSs#h`;&EK!-rFNU=9Qdmw?Lh~s_OKt>4=AY*-sN{Qz-fS zX;09wPk}|Pld{-2lMV%XRQhL6Ciq>k5TWo+n@5QNgQv_9%+rSTzibCDy z({d|DAN9nQ;) zg{4c;_x$ijVnd%GXK-j)HjB%T2QH7?j<~jG9&a_P(^(&80Yr6`)Nv^@I*?)eZp#X7 z#OeQdj%Ci@dXvFV*vFAr@NB`i>>UiX98@10q&F(;?l@9z(M&CB* zN01NY6~uA^jKBT)_Z5GTx88M`JFBw!Sd9us3H7qis+|ewlN?v>cWyvmA@eYB)l0-t zqKW+Zr(s~`U|fi+-wPco^!|t6{a`eAKgxH+2JvL4AY#O<2E$`a>*K z>&-^}!ta>T)QaCZ_n}Bv&joR^;-3b+eIW7TN9N5i+<#r`O||`wct52hCKU51vbgVJ zx(efIJ}A9lIr<{|1>cfzf21cKTSjpom@)5uELKH6u#ng4WzP{=y|osIy=m0B+y1Cu z>@JU{$R937882kfe+wGbWM*Ps<*vr=eT)9lu42cgeTdJh0-5K|Y~Eh3@r_{h4S&gr zyp5<|g7ucVZNT?=ZrNAZa}0##(P}_Oc;CFRA9?hsdX7;b`a@QZ>_Q#FsSH2SkN#?~ zp)oH^%&)f-RsczE+BJ4L>L}6VYvG4bH<^Bq3F+ohiQlY_X7}SU>Ub#}59{Tqp%3em ze3!i)ePkUApzbixY*ZU=<_nDOw-L+Nr2=USK3{$ab*zz`WkSA;62xTBFwHgUGsb^Q_oxV62vjhTh8pk@1A7Vf%5O zRzce>lXUzpt3Ts`N&i0JdLaSGlpUe2>gXSxoBx&_#=2L1FyR*u>rb|+EM*<~<FA5t<62|X z2fR2-XhQ###u^Nq_xEJ?JL7O2(|NB}|H!9Y>7dKiUO3;Dm+wd9;`98-(5Q_#u2y%t zbO3#6$Bn<-TJ&{$t-{h9aGsCEz^n%K#_TUwX3C(Ci-?ldy@0;U>e!MuAMw3Y_otk# z!uVSw$6LO~_Zy=V7RFadxaUwt1DajMnBUT@VV$Z%${jqf!1W@^SBB%b%y7zp zHu_8%vg2V5`p<}`JtPdT<0a71Bi{dE&%@9+f6%_XF|q*tsinn)JdFEtilQT+A1$jH zxZ;8N$Y60Bed?mg=I$G-(Z8d;x38pxJ?2%%ygf`A8S0Kc`TJAOtZT>%!-B|^Rmd-A zY{pbbVm+vZv^u2S@ z%OD;h&faNkeB6Y%k(hA4?Ni);Iv)8m{pYReoMf_k;59J%3 z>&pPXcTe1~>JZ4#YL}MT6%CwfOEff5z!eJi_~)ho2UUw}WD4+Q1f#dEj{$M>r1ziJ zMgXVJ@Ij~%15AeNQ?4%R@4*9L#7%FJXLA%oiQBg1?<)~^{ggHB4x!%ec^uIsg*x1h zJxD>EnG>Me`!Evg_Ve`?t7HGew{h$_V-zK;Sc8BgnR;f+0QO(SX|p4qo|IP>aC(?b z5by#^x^Fu~0HZNtmDw#f;IcCCbO^NTsir$5qu*YXE7df|?|2 zTkLQ5pcNW^sOMR@nt=23{S7B6<8$7j`3pUf4_-{#v*|PXt-nbQ9g@iN#t-y+_1!7s z#V9Q_N8amgbVyo(JjKm<(je;y%>8M8R!co$U?_W_fOv~4_4RM$moFSG9a$p?bdk!J zUyVG^{7TfYFu}U`=ghd%xX)G>I~VLnoaWXQTMBnmlKymPKOymj&Lq@wFL)Uyub`Urb&Hxc7v_XqL) zirtJI`WP1<<*Y~_>yBf#;6Cz@YJpeH4D^3obGL`e?C+hmSqWT9?&N>gnr#F`@t0r1 z*o~-5KVDq3)&rQX_wN>r!Mr6nNbfsj1C4_?gg(qK@pa=P9}tz7XzCgSg7}nl&Fi1R zz+K%0j&EEcP%9;%Pv0IypV@r4!hllbg+&plUtHMp&wp^et-tMMk>_?a=H+a~eqm(4 zyd0WL$-3v^oL2NVFET$m???RAZ5XE;j`gG$|N57%L89H& z=LfJ)?H;B*QAIwhV9!~xo*jJ+4I>VruE}Xod5^kAG@x-kNgeec%F##Y*V-fU!nJXf zjWoJ*AM3iLeR#`VjH8JobhE>GVofS@vN7M!qpY^JCsIZ<6DDrbeO8!Z6w zOvVzHqg2$t||jY*zBCKqYPqECEuwp1yvG#^9=gGC!gM11UD3d z+?k`i9rftL#yxm6g#G{ScYoBV;pl_l$81s?B8k4YQ)y{UY)u6a1mfBEL!SO2~()5s zcM14J%Ev>}QQqIA87^TRTM*^~-rD^q~csov8W9FO|DH&kst z1OMt^)bT>QRja39U$yUywNXL5pZ|)}ZHM^3ae7&x2iB>#A4Z-*$uhCZ+?GsAULM|{ zpq7Q>r;6XAA}V74u9$&->}$=z%B>ZYt2i}BtXxBx!T%?!DR=Py6XfIaLk~h;;d`cn zQQj$W^#1?=0RR6?S$81T-50+aNK$BMC`m|)mXvayY@!!sMOJ1*ibPc3L@BaTM#^LF znHjl{(wll4G^KizG*n7kgx~q1pVvRvz27^|J?C@I`JDTZ4}o#loHcZtrOhw`_fZc(*p4O)fYDlUq@2XQ@!tg979RSksx_HPavZL zSMC3O5XhYGj}|J10AE_`f_8(GK;re>RU%FSu~}2|h8GB=d)m6KvWJ0Wi#KXDGeF7> zic}Mi1DPGV)3hlB$Oc)DDfN*+Li?P5wnqW!S~2FDa~P19>1XSuaQu7C%<)3F->90g zVv{3)+@Jqa;yRvN)ZkN_v<>ACC{^7WN10ZU`wJp6C^O$&XI@e!Wxi3H(5YFJbW{|M zev?L-k_8sNv8j~o@JZ{rokU4{obz9!{3($LNH{gk517ugy}8%U0WZ3}s&--_@J>o^ zpO9V-+^eQCcH>HccV8fSpGZ3J`Ho5uoaq5XM0|p2R}3Yo)`cDGqHsS);k=h2l`@mwqPC>6g4 z^i7(n7(hw);r4Tyew19^J$>a09Ix?bKK_G!;Tb)0mA;hNQ2UiTQ2wm3Nn-wNG`dQR%o6Lkl^hTl&cV|D_m)W64dvjvj%^gwuoIgsU7bgZa5 z5TZ5Jy=?;SyTfv$l@=w;nKkFnD4{$}lJ&Q>VBpYSkQ9zHlxHlRovwlH>%H}Jttla1F4Y=#loZJRWo5Jvh-%#A zIZ5`2L)D3L%6Km+ksv3&Wq6O&*(pufk9?w(l!yDMT&psw#Q6n*5^r1f!N47}!<&Us z{>F_Br}ygs3HzL2vDb%^Z7Fwjryr)|tvgSu!;2DC_ZKBX+fmP5&t9M03PfVYUt@NA zpgkV)%*Ubrn7WllNs>T#ndWv|R#0NDkd@W57lv@;PKn^oJ>6-jKeFrFk~vanAKe*G zAL2R2`_B8`#&bCbRrWk{0wVmafXrDTd3z55IOW1QO6oOS3I0o!W4Pr0F8 zw8Z5dQEx;K^)G^Uoi#Qj5cPiZ;Iod~C~qET5&uMNC*2FS>|^c!thiYg?J3idaD64> zgM>$0ypcfrc!)~8SEHoa&gZY$EZ~zn--D+EJ}gGRZhf%FRTlNv zy71!n1iZJDkc(j*;smuUUKxz|cOR_CF7>00O`GHm9(b_?CXoJ#C@v(@;hw2fW}4ORi(sC z$}5Lf+xUuitBc^Ugt~NwRu1q)pXxo9PR4!a)vOi7_#pKCn`k%2gA^8DG1&6detq*r zIihb&_ELs{+*h{^m3IKq`&^kd74^1SYFw{RASKTlW6mAKIL6DKDDx={?If3CXB|Pw zE++m{Yb<5HNQ-xE$2hScPgx) zg#Wz%#Mny8h<(jVn{t72#>@80zbm557?n4z@z`#))tyz6O_}%yYEMP-DJL{tuU4#x z@=k2b54I|$%;ifk^Sug`uEm=xJ!8$&pR4B{4nlS*xox5m_wQN>X?g8X_V-t zH#e!`y*6!(-m98J$#u(}{dW13RMkfbNas@Kf{n`RH@I%8CuhAy7G*5MBM+}hrOdho zo2#aADI-7bc{_E2D^#^z{SLn^1n4(pNSo@Vse>bp&m^|m>Qdb&Jm)q%CBXCc>$GuL^Pj9$kGOI|@c@yGoVsih>U!ltho^>boCEky&@ z-TCo$!p~&N_`B#c2`JxG?#>nO^C*uPUp;A!_9zg}nXm!(?Gj7u;gsWjH(lM-gL>Su z;*RJqwC~24^)IKP9W46;tc!5|RA-e2nOsW53|Cyh`;zsqIt4RNQ*uaR?wXc3%sa9> zb3S6+KrfK+!Z^dhbh_D#JG#)1G*_<)`iwZuy4vc{atz2%6fepj813?}efLAa ze&-9n?B+Ne-`kofnhxE2FwD&<0`3oMH50LNutRSW*SrY6SIV{HCzL}`UeAckDclLLj zC){BBsUQ1AJ@bS|<9DvhVV`487+;ij+%m^}cJJTT@u%W3uXUU*5k@=Q(boJs6>*vE zKJA_%;zEthhi54hcfP28H0skLMl8@QoieBXir6_FabWw?Tt*i4dQ(f(wBiWvA4)sN znNs35moN37?Wm`J;5sjzb;mUlq#hJK z7k?iEt$hl-eP?6AUdYL3>ZMb_xgdDeyfFyu^ZL$pHid#z-N~3m(MN$3K1bnX+;QO5 zzkb!tpHlf}xG~RYs0TNwy)YKp2 z8P{TT%+bxLzu1kV98F=!4mhuYE3P4M0OPVx(7iwl%3ze6bpvr|d_c4w z*CGE(xwYFv6ZzB5EAoQ2Xuopq&%c$alo2;XTR0TDo6qpME=Y!|IG2l$^z-4}{*?EZ zCze2Ssi|PQSSB3I5t>k6k_^p`6?YVtrNhIw4@i3Q8JKjGZ+(H|VUSn+j8qH#AS4r}e5Iwy5p3tUCKUDIK7HNmLwm3teb4L}upU{#$z?7w`>PjBK{LVVG zD{v$wE#_740Zv$8>*vk`!1??jylqx6aQ-M22NnxwYX{@U{;kPQAT|EtwrL5ZLgK0_7`U$ znRi4g3*3M)(j_ZHU4gW;cj?O^o{HFnW`=Q~5(6{hj%+t#nJ8Cx=;LU!b--E2@~a@=++Oa`d)*iK0v4=s^Fe*y zS>!!`)LyV>-AfYdkwHSDi*`m>>n^6u+*fiB)KQLBtwp!;k>9ko^lqAhekPU9eX<@~ zZos>sK0J&rE^H(3h>|gD z@0U9)2fpL-vbz}MZ&2v_E(&qk=XxuGA|6+7nJRu3>k_5z<#I}xr^9~u&Xp{npZmXkev0wC=ECk#oa~@`M}riI`5HDHjq`H23`gwL)2Y1 ze`G_Wmca$TSp~rLww9ijm<`+`HM0#*WI~t2kCM*PeDLgZalAMQ^WehA#iAjZF!5+a z$bzUms60Ep&rP)$UVQdH+y9{uA~$-=#13Qu_lELE{-zu#mg2woV{9JiU3<__P?`p_ z$Zm^5=~M{%X;x+YD-)JqJklJmkqNE(<73U5)4=dbm*|rDIbbh&ZQ^O2JP4l05~(aW zt(OvOqL>M?(!WEwOHv{3ADuV9C&xmow%xjfVlFfs`8Ii#RvOq0;vaddSdv;@e=11q z4?XsCRu*_Zp4;!RJ`>*dwwazT&w?%uz9)4d>7d7D2~-LcwXB$%za$HkE9Z3aNDf4X zZWA>z%mCi4Y$uYH0=)FCx0n4$ht}jz9?r)zfK&?)bnvHu)F-or;s@iQHB_nPWpEmp z#P-k6Hbi}1u=-xrk^)?0X9M9};Fc+m?@Y{qxvzbceqPT82Ss_|8_RRR!TOz4p+GKh zOzrs$r)NRyApgn)hYA^i58HBpD|i0F*q{txip8;RD+Er)#~X_!N-( zS3cD(2V;3H-rP-PAXTz((Y)_y$M!+O3`93y`9NVAaFONb#9jc-xSsKA9gBb`d3Dvh zw?!Z|(LTx!kpGyR_gnR$1X}MMdicBh0x(W_Dg%Wjz?~_)*YZWlFrO*}diM9!bBg(3 zzij&gsm=>PdhR|+3M~iwPT`H#?@%6Oi)vY=VBavWGODB)==)>M_Am0Fl~2F9;#3ik zbn$T+3CTdVrKNxIi2(-L(G(BlRcm9j^}Fz%(_eJ16GVO{wAlQ<{RtpP)u!p}j{-ia zTb9euVVv0TUL~u~2gsAlUrmcKPt`tHy?YhLtCq+^E|ajXa4X9GnuYmH8|lmi^lQ;@ zs~VF-0`Ub88h~vs zzk|omK=|{{F%X@1rO6EMGsx4>&x;5791wHC+~S~M7?A5amNZ~HT-Rfrt9)LtZ4KtR z#hd!eYA_GBq@@)9I7W%Ot=_R?c%EQ?MYJU5hcW(!Y0EKRN)6nUQpfTB4t}8;%$Jdl zRp}3~UYAdi?Fn$Ae3tJ+gUYc!8)bS{wdxS&KQ_*705Vy7Vt_E#$!Q+0c7FC)za{tz z_+lP@>Y`9T59MqvFYl`H24Z7d^{|g$KNrO~7M2*iwiD~?0>vgP7vx{QgLw=FT-(2%$n*fBD!6*{1I$l6 zbB%racwf&G;q6~AZY#ToJv0fX#5d1$e+I^VUdX5VJPXQa?5JPWYXe07(9iH0Sobyu zmHy4ex_?KF+ER1ms|KCgrIIM;hhGV=N_L~(2J)CxV?uRsVy#Iy#-?O^WCes1+N3x9)ksrm0mtKG2Mfn&xXH(6Yh=PB87rFl(60rA(M;wkVB^>3d$CiDv4OJ38=Fdg{@=dOu}%QD1?vU4lrLWz!!fQ$p$ z-M}wD=p*XeUZSX70qxGg>fpBv+F?qzayj1HZLz0co;xKPHmm$ygYdhFn3%gY;*PuH z#*~AIn@H!ndOI9{-(Nh*2<>FhX!jQRG4I(w2lgz-`zHur`#OD?-%4T2=HotfLJn9L zZIZ+L48Bt#UUXkafhxA;m!3r{;(jcTQ^0-^$q>dqVedU2`>efw)ehlH0Q-Ob>amdh z{GajaElNhB?0XCQ{)7F?>~}o(R?NfaqfqXFRX1a&;kXp;cOA!B-h+B2{69y}7KDKT z_PqD%Bl0%lx-YmtXQVnUia5;oc}hYtoy$D$ofCy?Ku7o+f9hK0hEia zFXj%PKZ=gbW5?P3YfvwIxbL#dPmWB2p?U1R%#;(fKeMTQ17O!}XQecH#GlIPbCg@cP>S-;ZI>k;eJg9-X&h^~K8Fj`MD_=VQwq ziX()q9*zte<2<&o zU4S@fpP>A8E#i{R3xNCn%kGPxx_}_S+QIwA~FI23YGpv`dwR{YV+gaFO%IY8Q_l~tE9kL&97>BGL*nP+_-dKFE zVf8hPvuCwKcSlh3m!+`rpucwjKNdfsV*wK7{ijz0nce4(V~|K0inN{Qvm8 zIo$uV4~v)H+94cG`OmyT`{8BP@e_+J_SezqX2mSYP?eKhT z#n?DAtXIUT{9t`G^7}*Uh7S9_UBGw$yVj#%Y%Ns-H=Wo5B;oB>6P*BHsspgXJOw0h z&y!l+bHH1w;(YDMO?#SsQ%hb8Na;g)7vvBv(07E*tBBGIapt4d8L>#36N3d zo<_;%_zy{$$lK;dwCdbA3QUrji^2OOU`DfbS{e}U^m+lGG+>z00ltR`z;LHXlw3Rw z16|H3g4t(*Sk>*)42uQgiF73r^DC!#!|6|$uhRC2mn}zrB*cSs1I$~=?7CoJP75jI z96Sw7fMAYJ;Thm0ZjVd;oCo%*kCZiE76VyyM*5dQ5geYlUnN%^`Lg+!;%ZJYNSU}< z{fsCEUeg}#v6c+r)CLKODB*o~w;yhhP6r~kWPbEpY;Vt~DZFtSdBxPPUYaaF(rJv- z$Mb)i!Y&2mZOqCvlfziY{r=fnwjOz!S8cQZ=hKupHai&hoTW^>&Z*EPSQoBjA0W%_Hf4;q`Y(E$j{E`D#-BwATZYEuQ$|%U+%sbqFfw%3} z*doel;GEx5i}GcusEYRCeBHKJ9X4gCuZLO3+)%E1TX}mmZ1d@Sf_C5t=FQsdbb)gC zCeK^{8ujJUEdPEb-gowsrLBsn-!)Wz-JxX4ypoBjos>e!mx{IP978F|3)4|A#5!ht z{K6yKQYmraF6}>Xh7yxyX(!qcKMu2OR=-ZfJm&Yt_-FzppQL;;8sjOG_V313o$;{F zV9V0*s6^nMu_&mx6$3o?^hpi#&jXJ$37I3-S@R>ss>?GW(*LkkvR)zhMvd!U5nYOP zpVxymx>yg2F6&*RlMRy`U4_m)DgwPQ=brg(#bD>{=T&Kr^{W2ivC7U|;IJ&iI0~S7 zf%$~XVL)^=tZ%0y-(}0oN{lZYqetRfbm>r>$NajIJUM8!BLS?9+gPZI)+rHl!yok88aj^-9&^!#*#VnbPP$U_Gwg)NT^7IrYDUwQYr7c z`}JO5|Lp6W`#yWGz1G^FVG}U&EIW999q_-N5$@0R1x|TaL}ke#Ag``}iITSkfl*)Q zW}VHzA=g*B3?u^g0L@%xwI9gN$8)Oh+5%}<$TeOTLWyF=^?%MgP@<{3+PQZhCF4JD zzhPqqgkz^OE=C_5$p^uHPWz~v1OwcUOWd=b zMF3G*df?)+Kp@>;dIj#A10gQsKSu1N#JlE}^?pxENPS1Us~RP?lF29hBPhv_{@tbf;b|}xz{(O*