From 589764dd653fda31f1aa85de3263fcc985ca18fe Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 25 Jul 2023 21:46:09 +0800 Subject: [PATCH 01/62] 1. add debug_app.cpp with my modified 2. ppo.py with clip output 3. raisim_gym_helper.py got a Logger using logging which could save your log in both .log and console 4. design my self Environment.hpp and could read configuration to simplify your training with less compilation --- examples/CMakeLists.txt | 3 +- examples/src/maps/anymals.cpp | 146 ++++++- raisimGymTorch/CMakeLists.txt | 2 + .../raisimGymTorch/algo/ppo/module.py | 2 + raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py | 1 + .../raisimGymTorch/env/debug_app.cpp | 78 +++- .../env/envs/rsg_anymal/Environment.hpp | 2 +- .../envs/rsg_anymal_modified/Environment.hpp | 379 ++++++++++++++++++ .../env/envs/rsg_anymal_modified/cfg.yaml | 32 ++ .../env/envs/rsg_anymal_modified/runner.py | 195 +++++++++ .../env/envs/rsg_anymal_modified/tester.py | 76 ++++ .../helper/raisim_gym_helper.py | 27 +- rsc/anymal_c/urdf/anymal.urdf | 16 +- 13 files changed, 927 insertions(+), 32 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml create mode 100755 raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/runner.py create mode 100755 raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/tester.py diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 2d578b77b..87dde6f72 100755 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -4,7 +4,7 @@ project(raisim_examples LANGUAGES CXX) #== # Dependencies #== - +#set(raisim /home/lr-2002/code/raisimLib/raisim/linux/lib/cmake/raisim/) find_package(raisim CONFIG REQUIRED) find_package(Eigen3 REQUIRED HINTS ${Eigen3_HINT}) @@ -77,6 +77,7 @@ create_executable(deletion src/server/deletion.cpp) create_executable(inverseDynamics src/server/inverseDynamics.cpp) create_executable(dzhanibekovEffect src/server/dzhanibekovEffect.cpp) create_executable(go1 src/server/go1.cpp) +create_executable(leg src/server/leg.cpp) # xml reader create_executable(xmlRader src/xml/xmlReader.cpp) diff --git a/examples/src/maps/anymals.cpp b/examples/src/maps/anymals.cpp index daddc496d..d4e48882e 100755 --- a/examples/src/maps/anymals.cpp +++ b/examples/src/maps/anymals.cpp @@ -2,6 +2,88 @@ // Inc. prior to usage. #include "raisim/RaisimServer.hpp" +#include +#include +#define PI 3.1415926 +int cnt1=0, cnt2=0; +void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +{ +// std::cout<< "size is "<< angle_list.size() << std::endl; + double base1= 0.4, base3=0.03; + double base2 = -2 * base1; + double ang = abs(sin( float(idx) / T * PI)) * rate; + double ang2 = ang * 1.2; + if (idx % int(T) == 1) cnt1++; + int idx_base = 0; +// std::cout<> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); + std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } + std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} int main(int argc, char* argv[]) { auto binaryPath = raisim::Path::setFromArgv(argv[0]); @@ -10,12 +92,11 @@ int main(int argc, char* argv[]) { /// create raisim world raisim::World world; - world.setTimeStep(0.001); + world.setTimeStep(0.01); /// create objects auto ground = world.addGround(0, "gnd"); ground->setAppearance("hidden"); - auto anymalB = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\anymal\\urdf\\anymal.urdf"); auto anymalC = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\anymal_c\\urdf\\anymal.urdf"); /// anymalC joint PD controller @@ -24,21 +105,33 @@ int main(int argc, char* argv[]) { jointVelocityTarget.setZero(); Eigen::VectorXd jointPgain(anymalC->getDOF()), jointDgain(anymalC->getDOF()); - jointPgain.tail(12).setConstant(100.0); - jointDgain.tail(12).setConstant(1.0); + jointPgain.tail(12).setConstant(200); + jointDgain.tail(12).setConstant(4); +// jointDgain[7] = 2; +// jointDgain[10] = 2; +// jointDgain[13] = 2; +// jointDgain[16] = 2; + +// std::vector footIndices_; +// +// footIndices_.push_back(anymalC->getFrameIdxByName("LF_SHANK")); +// footIndices_.push_back(anymalC->getFrameIdxByName("RF_SHANK")); +// footIndices_.push_back(anymalC->getFrameIdxByName("LH_SHANK")); +// footIndices_.push_back(anymalC->getFrameIdxByName("RH_SHANK")); + +// auto footframeindex = anymalC->getFrameIdxByName("foot") anymalC->setGeneralizedCoordinate(jointNominalConfig); anymalC->setGeneralizedForce(Eigen::VectorXd::Zero(anymalC->getDOF())); anymalC->setPdGains(jointPgain, jointDgain); - anymalC->setPdTarget(jointNominalConfig, jointVelocityTarget); anymalC->setName("anymalC"); - +// std::vector> foot_list; +// for(auto i=0; igetFramePosition(footIndices_[i], foot_list[i]); +// std::cout<<"posi " << foot_list[i] <setGeneralizedCoordinate(jointNominalConfig); - anymalB->setGeneralizedForce(Eigen::VectorXd::Zero(anymalB->getDOF())); - anymalB->setPdGains(jointPgain, jointDgain); - anymalB->setPdTarget(jointNominalConfig, jointVelocityTarget); - anymalB->setName("anymalB"); /// friction example. uncomment it to see the effect // anymalB->getCollisionBody("LF_FOOT/0").setMaterial("LF_FOOT"); @@ -53,23 +146,36 @@ int main(int argc, char* argv[]) { /// graphs std::vector jointNames = {"LF_HAA", "LF_HFE", "LF_KFE", "RF_HAA", "RF_HFE", "RF_KFE", "LH_HAA", "LH_HFE", "LH_KFE", "RH_HAA", "RH_HFE", "RH_KFE"}; - auto jcGraph = server.addTimeSeriesGraph("joint position", jointNames, "time", "position"); - auto jvGraph = server.addTimeSeriesGraph("joint velocity", jointNames, "time", "velocity"); - auto jfGraph = server.addTimeSeriesGraph("joint torque", jointNames, "time", "torque"); raisim::VecDyn jc(12), jv(12), jf(12); + Eigen::VectorXd angle_list(12); + Eigen::Vector3d pose(0, 0, 3); +// Eigen::Vector2d join; + auto join = anymalC->getJointLimits(); + Eigen::VectorXd limit_list; + Eigen::VectorXd gene_angle; + gene_angle.setZero(12); + map_from_origin_to_limit(join, limit_list, gene_angle); + std::cout<setBasePos(pose); + angle_generator(angle_list, i, 30.f, 0.3); + + jointNominalConfig.tail(12) = angle_list; if (i % 10 == 0) { - jc = anymalC->getGeneralizedCoordinate().e().tail(12); - jv = anymalC->getGeneralizedVelocity().e().tail(12); - jf = anymalC->getGeneralizedForce().e().tail(12); - jcGraph->addDataPoints(world.getWorldTime(), jc); - jvGraph->addDataPoints(world.getWorldTime(), jv); - jfGraph->addDataPoints(world.getWorldTime(), jf); + } + anymalC->setPdTarget(jointNominalConfig, jointVelocityTarget); +// anymalC->setBasePos_e(pose); +// anymalC->setGeneralizedCoordinate(jointNominalConfig); } server.killServer(); diff --git a/raisimGymTorch/CMakeLists.txt b/raisimGymTorch/CMakeLists.txt index cc212d42d..8c9901416 100755 --- a/raisimGymTorch/CMakeLists.txt +++ b/raisimGymTorch/CMakeLists.txt @@ -108,3 +108,5 @@ FOREACH(subdir ${SUBDIRS}) endif() endif() ENDFOREACH() +add_executable(t_sin ../examples/src/maps/t_sin.cpp) +target_include_directories(t_sin PUBLIC ${EIGEN3_INCLUDE_DIRS} ) diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/module.py b/raisimGymTorch/raisimGymTorch/algo/ppo/module.py index 2885f2d7a..6d931b4b5 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/module.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/module.py @@ -18,6 +18,8 @@ def __init__(self, architecture, distribution, device='cpu'): def sample(self, obs): self.action_mean = self.architecture.architecture(obs).cpu().numpy() actions, log_prob = self.distribution.sample(self.action_mean) + # actions = (actions - actions.min()) / (actions.max() - actions.min()) * np.pi + actions = np.clip(actions, -1, 1) return actions, log_prob def evaluate(self, obs, actions): diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py index 885f73e11..0cad97548 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py @@ -77,6 +77,7 @@ def act(self, actor_obs): self.actor_obs = actor_obs with torch.no_grad(): self.actions, self.actions_log_prob = self.actor.sample(torch.from_numpy(actor_obs).to(self.device)) + return self.actions def step(self, value_obs, rews, dones): diff --git a/raisimGymTorch/raisimGymTorch/env/debug_app.cpp b/raisimGymTorch/raisimGymTorch/env/debug_app.cpp index 88fd18fb1..58410fe12 100755 --- a/raisimGymTorch/raisimGymTorch/env/debug_app.cpp +++ b/raisimGymTorch/raisimGymTorch/env/debug_app.cpp @@ -9,6 +9,59 @@ int THREAD_COUNT = 1; using namespace raisim; +#define PI 3.1415926 +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.4, base2 = -0.8, base3=0.03; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(), 1); EigenBoolVec dones(config["num_envs"].template As(), 1); action.setZero(); +// for(auto i:action.rows()) + std::cout< ob_ref(observation), action_ref(action); Eigen::Ref reward_ref(reward); Eigen::Ref dones_ref(dones); +// std::cout<getGeneralizedForce().squaredNorm()); - rewards_.record("forwardVel", std::min(4.0, bodyLinearVel_[0])); + rewards_.record("forwardVel", -bodyLinearVel_[0]); return rewards_.sum(); } diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp new file mode 100644 index 000000000..b5c5cc0a9 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp @@ -0,0 +1,379 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +{ +// std::cout<< "size is "<< angle_list.size() << std::endl; + double base1= 0.4, base2 = -0.8, base3=0.0; + double ang = abs(sin( float(idx) / T * PI)) * rate; + + int idx_base = 0; +// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_ << 0, 0, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(200.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(4); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("LF_SHANK")); + footIndices_.insert(anymal_->getBodyIdx("RF_SHANK")); + footIndices_.insert(anymal_->getBodyIdx("LH_SHANK")); + footIndices_.insert(anymal_->getBodyIdx("RH_SHANK")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling + COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); + Eigen::VectorXd idx1(8), idx2(4); + idx1.setZero();idx2.setZero(); + idx1<<1, 2, 4, 5, 7,8,10,11; + idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); + Eigen::VectorXd ttmp =action.cast(); + map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + + angle_mulit(pTarget12_, idx1, action_std); + angle_mulit(pTarget12_, idx2, action_std); + + + angle_list_for_work = angle_list * for_work_rate; + + + + + pTarget12_ = angle_list_for_work + pTarget12_; +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } + for(int i=0; i<=1; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } + rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); +rewards_.record("Stable", 1 - rrr, false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); + + obDouble_ << double(COUNT)/schedule_T, + rot.e().row(2).transpose(), /// body orientation + bodyLinearVel_, bodyAngularVel_, /// body linear&angular velocity + gc_.tail(12); /// joint angles + gv_.tail(12); /// joint velocity + } + + void observe(Eigen::Ref ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + + /// if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) + { + return true; + } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml new file mode 100644 index 000000000..5f0f14b7b --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml @@ -0,0 +1,32 @@ +seed: 1 +record_video: False + +environment: + render: True +# just testing commenting + num_envs: 100 + eval_every_n: 40 + num_threads: 30 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 4.0 + action_std: 0.0035 + show_ref: False + angle_rate: 0.4 + stable: 5 + reference : 0 + schedule: 40 + for_work: 1 + float_base: False + learnning_rate: 5e-4 + reward: + forwardVel: + coeff: 0.3 + torque: + coeff: -4e-5 + Stable: + coeff: 0.9 + +architecture: + policy_net: [128, 128] + value_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/runner.py new file mode 100755 index 000000000..70f5637c0 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/runner.py @@ -0,0 +1,195 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg_anymal_modified import NormalSampler +from raisimGymTorch.env.bin.rsg_anymal_modified import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import os +import math +import time +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse + +# task specification +task_name = "anymal_locomotion" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=120) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight + +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +if mode =='train' or mode == 'retrain': + tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update + +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=4, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + learning_rate=cfg['environment']['learnning_rate'] + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +# if load_best == True: +# weight_path = "" +print = logger.info + +total_update = args.update +if mode =='train' or mode == 'retrain': + for update in range(total_update): + start = time.time() + env.reset() + reward_sum = 0 + done_sum = 0 + average_dones = 0. + + if update % cfg['environment']['eval_every_n'] == 0: + print("Visualizing and evaluating the current policy") + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + # we create another graph just to demonstrate the save/load method + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) + + env.turn_on_visualization() + env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') + + for step in range(n_steps): + with torch.no_grad(): + frame_start = time.time() + obs = env.observe(False) + # action = ppo.act(torch.from_numpy(obs).cpu()) + action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + # print(action.min()) + reward, dones = env.step(action.cpu().detach().numpy()) + reward_analyzer.add_reward_info(env.get_reward_info()) + frame_end = time.time() + wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) + if wait_time > 0.: + time.sleep(wait_time) + + env.stop_video_recording() + env.turn_off_visualization() + + reward_analyzer.analyze_and_plot(update) + env.reset() + env.save_scaling(saver.data_dir, str(update)) + + # actual training + for step in range(n_steps): + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + ppo.step(value_obs=obs, rews=reward, dones=dones) + done_sum = done_sum + np.sum(dones) + reward_sum = reward_sum + np.sum(reward) + # take st step to get value obs + obs = env.observe() + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 == 0, update=update) + average_ll_performance = reward_sum / total_steps + if average_ll_performance > biggest_reward: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + env.save_scaling(saver.data_dir, str(update)) + average_dones = done_sum / total_steps + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + # curriculum update. Implement it in Environment.hpp + env.curriculum_callback() + + end = time.time() + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) + print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) + print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) + print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) + * cfg['environment']['control_dt']))) + print('----------------------------------------------------\n') +else: + env.reset() + start = time.time() + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + for step in range(n_steps * 10): + time.sleep(0.01) + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + +print(f'biggest:{biggest_reward},rate = {biggest_iter}') \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/tester.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/tester.py new file mode 100755 index 000000000..bdea58d30 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/tester.py @@ -0,0 +1,76 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.bin import rsg_anymal +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +import raisimGymTorch.algo.ppo.module as ppo_module +import os +import math +import time +import torch +import argparse + + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-w', '--weight', help='trained weight path', type=str, default='') +args = parser.parse_args() + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +cfg['environment']['num_envs'] = 1 + +env = VecEnv(rsg_anymal.RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper)), cfg['environment']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts + +weight_path = args.weight +iteration_number = weight_path.rsplit('/', 1)[1].split('_', 1)[1].rsplit('.', 1)[0] +weight_dir = weight_path.rsplit('/', 1)[0] + '/' + +if weight_path == "": + print("Can't find trained weight, please provide a trained weight with --weight switch\n") +else: + print("Loaded weight from {}\n".format(weight_path)) + start = time.time() + env.reset() + reward_ll_sum = 0 + done_sum = 0 + average_dones = 0. + n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) + total_steps = n_steps * 1 + start_step_id = 0 + + print("Visualizing and evaluating the policy: ", weight_path) + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], torch.nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(weight_path)['actor_architecture_state_dict']) + + env.load_scaling(weight_dir, int(iteration_number)) + env.turn_on_visualization() + + # max_steps = 1000000 + max_steps = 1000 ## 10 secs + + for step in range(max_steps): + time.sleep(0.01) + obs = env.observe(False) + action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + reward_ll, dones = env.step(action_ll.cpu().detach().numpy()) + reward_ll_sum = reward_ll_sum + reward_ll[0] + if dones or step == max_steps - 1: + print('----------------------------------------------------') + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(reward_ll_sum / (step + 1 - start_step_id)))) + print('{:<40} {:>6}'.format("time elapsed [sec]: ", '{:6.4f}'.format((step + 1 - start_step_id) * 0.01))) + print('----------------------------------------------------\n') + start_step_id = step + 1 + reward_ll_sum = 0.0 + + env.turn_off_visualization() + env.reset() + print("Finished at the maximum visualization steps") diff --git a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py index bc65f3500..123cd1fca 100755 --- a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py +++ b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py @@ -3,7 +3,7 @@ import os import ntpath import torch - +import logging class ConfigurationSaver: def __init__(self, log_dir, save_items): @@ -58,3 +58,28 @@ def load_param(weight_path, env, actor, critic, optimizer, data_dir): actor.distribution.load_state_dict(checkpoint['actor_distribution_state_dict']) critic.architecture.load_state_dict(checkpoint['critic_architecture_state_dict']) optimizer.load_state_dict(checkpoint['optimizer_state_dict']) + +class RaisimLogger(): + def __init__(self, path): + self.logger = logging.getLogger(__file__) + self.logger.setLevel(logging.INFO) + self.fh = logging.FileHandler(path) + self.ch = logging.StreamHandler() + self.fh.setLevel(logging.INFO) + self.ch.setLevel(logging.INFO) + + self.formatter = logging.Formatter("%(asctime)s - %(name)s - %(levelname)s - %(message)s", + datefmt="%Y-%m-%d %H:%M:%S") + self.ch.setFormatter(self.formatter) + self.fh.setFormatter(self.formatter) + self.logger.addHandler(self.ch) + self.logger.addHandler(self.fh) + + def info(self, msg): + self.logger.info(msg) + def warning(self, msg): + self.logger.warning(msg) + def debug(self, msg): + self.logger.debug(msg) + def error(self, msg): + self.logger.error(msg) \ No newline at end of file diff --git a/rsc/anymal_c/urdf/anymal.urdf b/rsc/anymal_c/urdf/anymal.urdf index 230fb2bf3..58e8f74ac 100755 --- a/rsc/anymal_c/urdf/anymal.urdf +++ b/rsc/anymal_c/urdf/anymal.urdf @@ -689,7 +689,7 @@ - + @@ -765,7 +765,7 @@ - + @@ -933,7 +933,7 @@ - + @@ -1009,7 +1009,7 @@ - + @@ -1177,7 +1177,7 @@ - + @@ -1253,7 +1253,7 @@ - + @@ -1421,7 +1421,7 @@ - + @@ -1497,7 +1497,7 @@ - + From 346d58ec69cbfe5be4f4d581ace53953298b0bc9 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 25 Jul 2023 21:49:59 +0800 Subject: [PATCH 02/62] 1. add debug_app.cpp with my modified 2. ppo.py with clip output 3. raisim_gym_helper.py got a Logger using logging which could save your log in both .log and console 4. design my self Environment.hpp and could read configuration to simplify your training with less compilation --- .gitignore | 3 +- .../env/envs/rsg_leg/Environment.hpp | 159 ++++++++++++++++++ .../raisimGymTorch/env/envs/rsg_leg/cfg.yaml | 24 +++ .../raisimGymTorch/env/envs/rsg_leg/runner.py | 147 ++++++++++++++++ 4 files changed, 332 insertions(+), 1 deletion(-) create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/Environment.hpp create mode 100755 raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/cfg.yaml create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/runner.py diff --git a/.gitignore b/.gitignore index a88a8c81c..e10542adb 100755 --- a/.gitignore +++ b/.gitignore @@ -19,4 +19,5 @@ examples/cmake-build*/* */data/* **/activation.raisim data/* -**/.DS_Store \ No newline at end of file +**/.DS_Store +/raisimGymTorch/raisimGymTorch/algo/pre_sin.py diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/Environment.hpp new file mode 100644 index 000000000..1ed569acb --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/Environment.hpp @@ -0,0 +1,159 @@ +#pragma once +#include +#include +#include +#include "../../RaisimGymEnv.hpp" +#include +namespace raisim{ + +class ENVIRONMENT: public RaisimGymEnv{ +public: + explicit ENVIRONMENT(const std::string& resourceDir, const Yaml::Node& cfg, bool visualizable): + RaisimGymEnv(resourceDir, cfg), visualizable_(visualizable){ + world_ = std::make_unique(); + + leg_ = world_->addArticulatedSystem(resourceDir_ + "do_legs/do_legs.urdf") ; // + leg_->setName("leg"); + leg_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_ -> addGround(); + + gcDim_ = leg_ -> getGeneralizedCoordinateDim(); + gvDim_ = leg_ -> getDOF(); +// nJoints_ = gvDim_ - 6;// + nJoints_ = gcDim_; + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_);pTarget_.setZero(nJoints_); + no_collision_.push_back(1); + no_collision_.push_back(2); + no_collision_.push_back(3); +// no_collision_.push_back(); + + gc_init_ << 0, 0, 0, 0, 0; // + + + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(100.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(1); + leg_ ->setPdGains(jointPgain, jointDgain); + leg_ ->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + obDim_ = 10;// + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + + actionMean_ = gc_init_.tail(nJoints_); + double action_std; + READ_YAML(double, action_std, cfg_["action_std"]); + actionStd_.setConstant(action_std); + + rewards_.initializeFromConfigurationFile(cfg["reward"]); + + +// footIndices_.insert(leg_ ->getBodyIdx("shank")); // set for foot; +// footIndices_.insert(leg_ ->getBodyIdx("knee")); // set for foot; +// footIndices_.insert(leg_ ->getBodyIdx("thigh")); // set for foot; +// footIndices_.insert(leg_ ->getBodyIdx("body")); // set for foot; +// footIndices_.insert(leg_ ->getBodyIdx("lk5")); // set for foot; + + + if(visualizable_) + { + server_ = std::make_unique(world_.get()); + server_ ->launchServer(); + server_ ->focusOn(leg_); + } + } + + + + void init() final {} + + void reset() final { + leg_ ->setState(gc_init_, gv_init_); + updateObservation(); + } + + float step(const Eigen::Ref& action) final{ +// std::cout<< "action:\n" << action << std::endl; + pTarget12_ = action.cast (); // target for p ,12 is because of the 12 joints + pTarget12_ = pTarget12_.cwiseProduct(actionStd_); + pTarget12_ += actionMean_; + pTarget_.tail(nJoints_) = pTarget12_; +// pTarget_[1] = 0; +// std::cout<setPdTarget(pTarget_, vTarget_); + // note to excute the step command + // the pd is just the controller to fit the position to the robot + for(int i=0; i lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_ -> unlockVisualizationServerMutex(); + } + updateObservation(); + +// rewards_.record("torque", leg_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::min(3.0, bodyLinearVel_[0])); + rewards_.record("position", -bodyLinearPos_[1]); // +// std::cout<< "height : " << std::endl<< -bodyLinearPos_[1] << std::endl; + return rewards_.sum(); + } + + void updateObservation() { + leg_ ->getState(gc_, gv_); +// raisim::Vec<4> quat; +// raisim::Mat<3, 3> rot; +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// raisim::quatToRotMat(quat, rot); +// bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); +// bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout << "data: " << leg_ ->getGeneralizedVelocity().data() << std::endl; + + +// obDouble_ << gc_[2], // body height // 1 +// rot.e().row(2).transpose(), // body orientation // 3 +// gc_.tail(12), // joint angles // 12 +// bodyLinearVel_, bodyAngularVel_, // body vel // 6 +// gv_.tail(12); // 12 + bodyLinearVel_ = gv_; + bodyLinearPos_ = gc_; + obDouble_ << gc_.tail(5), gv_.tail(5); + } + + void observe(Eigen::Ref ob) final{ + ob = obDouble_.cast( ); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + for(auto& contact: leg_->getContacts()) + { + std::vector::iterator it = std::find(no_collision_.begin(), no_collision_.end(), contact.getlocalBodyIndex()); + if(it != no_collision_.end()) // if it != end ,means it was found + return true; + } + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() {}; + + +private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* leg_; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_, bodyLinearPos_; + std::set footIndices_; + std::vector no_collision_; + +}; + + +} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/cfg.yaml new file mode 100755 index 000000000..d8666d266 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/cfg.yaml @@ -0,0 +1,24 @@ +seed: 1 +record_video: yes + +environment: + render: True +# just testing commenting + num_envs: 100 + eval_every_n: 300 + num_threads: 30 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 4.0 + action_std: 0.3 + reward: + forwardVel: + coeff: 0.3 + torque: + coeff: -4e-5 + position: + coeff: 0.4 + +architecture: + policy_net: [128, 128] + value_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/runner.py new file mode 100644 index 000000000..1207ac1d3 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_leg/runner.py @@ -0,0 +1,147 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher +from raisimGymTorch.env.bin.rsg_leg import NormalSampler +from raisimGymTorch.env.bin.rsg_leg import RaisimGymEnv +import os +import math +import time +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse + +task_name = 'leg_locomotion' + +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train' ) +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +args = parser.parse_args() +mode = args.mode +weight_path = args.weight + +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + '/../../../../..' + +cfg = YAML().load(open(task_path + '/cfg.yaml', 'r')) + +env = VecEnv(RaisimGymEnv(home_path + '/rsc/', dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) + +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + + +saver = ConfigurationSaver(log_dir=home_path + '/raisimGymTorch/data/' + task_name, + save_items=[task_path+'/cfg.yaml', task_path+'/Environment.hpp']) +tensorboard_launcher(saver.data_dir + '/..') + + +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=4, + learning_rate=1e-2, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False) + +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + + +for update in range(10000): + start = time.time() + env.reset() + reward_ll_sum = 0 + done_sum = 0 + average_dones = 0 + + if update % cfg['environment']['eval_every_n'] == 0: + print('Visualizing and evaluating the current policy') + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'ppo_optimizer_state_dict': ppo.optimizer.state_dict() + }, saver.data_dir+'/full_'+ str(update)+'.pt') + + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(saver.data_dir+'/full_'+ str(update) + '.pt')['actor_architecture_state_dict']) + + env.turn_on_visualization() + env.start_video_recording(datetime.datetime.now().strftime('%Y-%m-%d-%H-%M-%S') + 'policy_' + str(update) + '.mp4') + + for step in range(n_steps * 2): + with torch.no_grad(): + frame_start = time.time() + obs = env.observe(False) + action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + reward_ll, dones =env.step(action_ll.cpu().detach().numpy()) + frame_end = time.time() + wait_time = cfg['environment']['control_dt'] - (frame_end - frame_start) + if wait_time> 0: + time.sleep(wait_time) + + env.stop_video_recording() + env.turn_off_visualization() + + env.reset() + env.save_scaling(saver.data_dir, str(update)) + + for step in range(n_steps): + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + ppo.step(value_obs=obs, rews=reward, dones=dones) + done_sum = done_sum + np.sum(dones) + reward_ll_sum = reward_ll_sum + np.sum(reward) + + obs = env.observe() + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 ==0, update=update) + average_ll_performance = reward_ll_sum / total_steps + average_dones = done_sum / total_steps + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(5) * 0.2).to(device)) # + + env.curriculum_callback() + + end = time.time() + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) + print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) + print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) + print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) + * cfg['environment']['control_dt']))) + print('----------------------------------------------------\n') From fd0703a9860cce07e0f4eb4523c6f46fa4cd808e Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 25 Jul 2023 21:51:24 +0800 Subject: [PATCH 03/62] 1. add debug_app.cpp with my modified 2. ppo.py with clip output 3. raisim_gym_helper.py got a Logger using logging which could save your log in both .log and console 4. design my self Environment.hpp and could read configuration to simplify your training with less compilation --- examples/src/server/leg.cpp | 73 +++++ rsc/do_legs/do_legs.urdf | 228 ++++++++++++++++ rsc/leg/a.urdf | 512 ++++++++++++++++++++++++++++++++++++ rsc/leg/leg.urdf | 131 +++++++++ rsc/leg/leg1.urdf | 224 ++++++++++++++++ rsc/leg/leg2.urdf | 128 +++++++++ 6 files changed, 1296 insertions(+) create mode 100644 examples/src/server/leg.cpp create mode 100644 rsc/do_legs/do_legs.urdf create mode 100644 rsc/leg/a.urdf create mode 100644 rsc/leg/leg.urdf create mode 100644 rsc/leg/leg1.urdf create mode 100644 rsc/leg/leg2.urdf diff --git a/examples/src/server/leg.cpp b/examples/src/server/leg.cpp new file mode 100644 index 000000000..d94ab7b6f --- /dev/null +++ b/examples/src/server/leg.cpp @@ -0,0 +1,73 @@ +// +// Created by lr-2002 on 23-7-14. +// +#include "raisim/World.hpp" +#include "raisim/RaisimServer.hpp" +float calculate_angle(float ang) +{ + return ang * 3.14 / 180; +} +void print_collision(raisim::Sphere* sphere) +{ + + auto& contacts = sphere->getContacts(); + for (auto i : contacts) + { + std::cout<< i.getPosition() << std::endl; + } +} +int main(int argc, char * argv[]) +{ + auto binaryPath = raisim::Path::setFromArgv(argv[0]); + raisim::World::setActivationKey(binaryPath.getDirectory() + "\\rsc\\activation.raisim"); + + // create raisim world + raisim::World world; + world.setTimeStep(0.01); + auto ground = world.addGround(); + + world.setMaterialPairProp("steel", "steel", 0.8, 0.95, 0.001); + // launch server + + raisim::RaisimServer server(&world); + server.launchServer(); + + auto sphere = world.addSphere(0.4, 0.3, "steel"); + sphere->setName("sphere"); + auto leg = world.addArticulatedSystem(binaryPath.getDirectory()+"\\rsc\\leg\\leg2.urdf"); + leg->setName("leg"); + +// Eigen::VectorXd gc(3); +// gc << 0, 0, 0; +// leg->setGeneralizedCoordinate(gc); + + +// Eigen::VectorXd gc(3); +// Eigen::VectorXd gv(3); +// gc << calculate_angle(-50), 0, calculate_angle(-50); +// gv << 0, -1, -1; +// sphere->setPosition(0, 0, 0.4); +// int cnt = 0; +// auto foot_index = leg->getBodyIdx("r_2"); + while(1) + { +// cnt ++ ; +// gc << calculate_angle(-50 + 0.8* cnt), 0, calculate_angle(-90); +// print_collision(sphere); +// std::cout<setGeneralizedCoordinate(gc); +// leg->setGeneralizedVelocity(gv); +// leg->setGeneralizedForce(gc); + server.integrateWorldThreadSafe(); + raisim::MSLEEP(10); +// for(auto& contact : leg->getContacts()) +// { +// if(contact.getPairContactIndexInPairObject() != raisim::BodyType::STATIC) +// { +// world.getObject(contact.getPairObjectIndex())->getContacts(); +// } +// } + } + + server.killServer(); +} \ No newline at end of file diff --git a/rsc/do_legs/do_legs.urdf b/rsc/do_legs/do_legs.urdf new file mode 100644 index 000000000..cdab0daf2 --- /dev/null +++ b/rsc/do_legs/do_legs.urdf @@ -0,0 +1,228 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + > + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/rsc/leg/a.urdf b/rsc/leg/a.urdf new file mode 100644 index 000000000..9f5b7d53f --- /dev/null +++ b/rsc/leg/a.urdf @@ -0,0 +1,512 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/rsc/leg/leg.urdf b/rsc/leg/leg.urdf new file mode 100644 index 000000000..a1fb77105 --- /dev/null +++ b/rsc/leg/leg.urdf @@ -0,0 +1,131 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/rsc/leg/leg1.urdf b/rsc/leg/leg1.urdf new file mode 100644 index 000000000..04a3cdc5b --- /dev/null +++ b/rsc/leg/leg1.urdf @@ -0,0 +1,224 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/rsc/leg/leg2.urdf b/rsc/leg/leg2.urdf new file mode 100644 index 000000000..5165e82c8 --- /dev/null +++ b/rsc/leg/leg2.urdf @@ -0,0 +1,128 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 3944d5c9129aea124c9febcf616cbf56218ef432 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 25 Jul 2023 22:48:08 +0800 Subject: [PATCH 04/62] write Readme_zh.md --- Readme_zh.md | 114 +++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 114 insertions(+) create mode 100644 Readme_zh.md diff --git a/Readme_zh.md b/Readme_zh.md new file mode 100644 index 000000000..d6d6bb73c --- /dev/null +++ b/Readme_zh.md @@ -0,0 +1,114 @@ +# Raisim 中文使用指南 + +## 写在前面 + +相信大家都是因为自己老师的要求,过来学习Raisim,或者之前也已经尝试过一些别的项目(issac,gazebo,webots)之类的。 + +首先,我想说一下,为什么要使用Raisim + +1. `C++` + `Python`,这个软件对`python`还是比较友好的,但是为了提高你的使用体验,你需要有一定的`C++`基础,尤其是强化学习部分,你需要自己动手修改`Environment.hpp` 如果不太理解`C++`的面对对象的概念,以及一些`STL`的基本结构(`iterator`之类的),使用起来会有一些难度 +2. `Linux, Win, Mac` 友好。目前为止我只尝试了`win` 和`linux`,这两个系统的支持度还都是挺好的,尤其是`linux`,对视频的录制很好用,不需要一直盯着屏幕。 +3. 强化学习很快,由于代码完全开放,相较于`Unity`而言,你的自由度更高,你可以很轻松的添加你自己的东西。 + +其次,我说一下本版本相较于作者的原版本的区别 + +1. 添加了更相信的`log`系统,在`gym`文件夹的`helper`里添加了`logging`系统,使用起来能够在对应的`saver.dir`中生成名为`train.log`的文件,方便后期查询自己的日志 +2. 训练过程中自动保存最优的模型,后期会修改把之前的弱鸡模型给删除 +3. 完善了`test`模块,在`gymtorch`文件夹中,你的`runner`可以直接通过运行`python yourfilepath(imply it use your path)/runner.py --mode test --weight yourweightpath`在`unity`等渲染引擎中展示你的模型 + +## 怎么使用 + +### 复制项目 + +1. `fork`本`repo`到你个人的`github`中(右上角有一个`fork`按钮) +2. 在你自己的`fork`版本中,选择`code`按钮,复制`https`链接 +3. 在你本地打开`powershell`(windows)或者是`base/zsh`(linux),然后`git clone your-repo-http`(不清楚的自行`google`) +4. 切换到你的目标位置,通常是`raisimLib` + +### 编译项目 + +编译是`C/C++`在执行之前都需要进行的事情,简单来说,就是把做饭需要的菜都放到桌子上,具体执行方式如下 + +#### 安装依赖 + +我下边只列出来你需要安装的软件,如果有不会的请自行`google` + +1. `cmake` +2. `Eigen` (`C++`需要用到) +3. 编译器 + 1. Linux: `gnu` + 2. Windows: `Visual Studio`(注意不要安装错误了,是紫色的VS,不是蓝色的VSC) + +#### 设置路径 + +##### Windows + +自行`google`: 如何将路径添加到环境变量 + +##### Linux + +自行`google`: 如何将路径添加到`Linux`路径 + +#### checklist(检查你需要添加的路径) + +1. `cmake`:添加的路径下需要有`cmake.exe`文件 + +2. `eigen`:添加的路径需要有`Dense.hpp`文件 +3. `WORKSPACE`:这个变量指向的是`RaisimLib`的位置,这个路径在windows中需要单独列出来,在环境变量中直接新建,而不是通过`path`建立 +4. `LOCAL_INSTALL`:这个变量指向的是你希望在那里部署你的库文件, 建议直接在`raisimLib`下新建文件夹,命名为`raisim_build`,然后指向这个位置即可 + +#### 开始部署/编译 + +1. 让你的终端切换到`raisimlib`文件夹 +2. 创建`build`文件夹,并切换进去 +3. 参考[官方文档](https://raisim.com/sections/Installation.html#building-raisim-examples-and-installing-raisimpy)的建议,运行对应的命令,如果你不想编译`python`,就把`-DRAISIM_PY=ON`删掉(他的`python`好像作者自己都不喜欢用) + +### 激活文件 + +1. [点这里申请你的激活文件](https://docs.google.com/forms/d/e/1FAIpQLScNL0vbZPDNS93L6Jv6fgR51WTsvXxfhnVOtKDVRdAmHIoG4w/viewform?usp=sf_link) + 1. 写自己的信息 + 2. 通过提供的`google drive`获取软件,读取你的机器码 + 3. 将机器码复制进去,然后申请`license`就可以了(他们会给你的邮箱发一个`activation.raisim`) +2. 在你的根目录(`linux`就是`~/`,`windows`是`c:users/xxx(你的账户)/`),创建一个文件夹,命名为`.raisim`,将`activation.raisim`复制进去即可。 + +### 运行例子 + +#### Linux + +生成的`example`就在你创建的`build`文件夹下,进去就可以找到类似`alingo`之类的二进制文件,你需要通过`chmod +X ./alingo` 运行即可 + +#### Windows + +如果你是通过VS建立的项目,这个路径通常在`RasimLib/raisim/win32/bin`里,会有一大堆的`exe`,点击运行即可 + + + + + +# `RaisimGymTorch` + +如果你是要学习`raisimgymmtorch`进行强化学习,那就需要理解以下几个基本概念 + +1. `setup.py`(`raisimlib/raisimgymtorch/`) 对所有的环境进行编译,生成在python中可以使用的库 +2. `Environment.hpp` 这个文件定义了你的机器人与环境作用的方式 + 1. 执行你的`action` + 2. 计算`reward` + 3. 更新`observation` +3. `runner.py` 这个文件是你的`python`的主框架 + 1. 记录`log` + 2. 更新`observation` + 3. 记录`state-action`对 + 4. `ppo`计算 + 5. 生成`action` + 6. 更新`model` +4. `cfg.yaml` 定义超参数 + 1. `num_envs`:子空间的数量(开多空间) + 2. `eval_per_iters`:执行多少个`iters`之后会记录并展示 + + + + + +## 欢迎PR + +有问题发`Issue`,觉得ok的话,点一个`star`,tks! \ No newline at end of file From 9462bb8db60d3d8c226de17b6bdbc70d88e42d3c Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 25 Jul 2023 22:54:03 +0800 Subject: [PATCH 05/62] write Readme_zh.md --- README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/README.md b/README.md index f6dc5e34c..7d40787c9 100755 --- a/README.md +++ b/README.md @@ -6,6 +6,9 @@ Click to watch the video Documentation available on the [RaiSim Tech website](http://raisim.com). +Click here to read chinese version [中文简体](./Readme_zh.md) + + ## New update! RaisimUnreal (Alpha version) is now released. You can get it [here](https://github.com/raisimTech/raisimLib/releases). From 98f6e76db4faa8537c44860b6845d37858da8596 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 25 Jul 2023 22:57:59 +0800 Subject: [PATCH 06/62] write Readme_zh.md --- Readme_zh.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Readme_zh.md b/Readme_zh.md index d6d6bb73c..8c078706d 100644 --- a/Readme_zh.md +++ b/Readme_zh.md @@ -12,9 +12,9 @@ 其次,我说一下本版本相较于作者的原版本的区别 -1. 添加了更相信的`log`系统,在`gym`文件夹的`helper`里添加了`logging`系统,使用起来能够在对应的`saver.dir`中生成名为`train.log`的文件,方便后期查询自己的日志 +1. 添加了更详细的`log`系统,在`gym`文件夹的`helper`里添加了`logging`系统,使用起来能够在对应的`saver.dir`中生成名为`train.log`的文件,方便后期查询自己的日志 2. 训练过程中自动保存最优的模型,后期会修改把之前的弱鸡模型给删除 -3. 完善了`test`模块,在`gymtorch`文件夹中,你的`runner`可以直接通过运行`python yourfilepath(imply it use your path)/runner.py --mode test --weight yourweightpath`在`unity`等渲染引擎中展示你的模型 +3. 完善了`runner.py --mode test`模块,在`gymtorch`文件夹中,你的`runner`可以直接通过运行`python yourfilepath(imply it use your path)/runner.py --mode test --weight yourweightpath`在`unity`等渲染引擎中展示你的模型 ## 怎么使用 From 2ae74b6dba31664e2514e6fac87fb1c2b02e94d8 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 1 Aug 2023 13:53:39 +0800 Subject: [PATCH 07/62] add rsg_go1 --- examples/src/server/go1.cpp | 84 +++- .../raisimGymTorch/env/auto_runner.py | 26 ++ .../envs/rsg_anymal_modified/Environment.hpp | 3 +- .../env/envs/rsg_go1/Environment.hpp | 433 ++++++++++++++++++ .../raisimGymTorch/env/envs/rsg_go1/cfg.yaml | 32 ++ .../raisimGymTorch/env/envs/rsg_go1/runner.py | 204 +++++++++ .../raisimGymTorch/env/envs/rsg_go1/tester.py | 76 +++ 7 files changed, 850 insertions(+), 8 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/env/auto_runner.py create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml create mode 100755 raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py create mode 100755 raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/tester.py diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index 2d5ebffa5..82374d562 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -3,41 +3,111 @@ #include "raisim/RaisimServer.hpp" #include "raisim/World.hpp" +#define PI 3.1415926 +void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +{ + // todo ang2, rate, ang +// std::cout<< "size is "<< angle_list.size() << std::endl; + double base1= 0.8, base3=0.0; + double base2 = -2 * base1; + double ang = -abs(sin( float(idx) / T * PI)) * rate; + double ang2 = -0.15 * ang; + double ang3 = ang2 * 1.2; + int idx_base = 0; +// std::cout<getGeneralizedCoordinateDim()), jointVelocityTarget(go1->getDOF()); - jointNominalConfig << 0, 0, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; + jointNominalConfig << 0, 0, 0.30, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; + +// jointNominalConfig.tail(12).setZero(); + Eigen::VectorXd tmp(12); + tmp.setZero(); + angle_generator(tmp, 0, 80.f); + jointNominalConfig.tail(12) = tmp; jointVelocityTarget.setZero(); Eigen::VectorXd jointPgain(go1->getDOF()), jointDgain(go1->getDOF()); - jointPgain.tail(12).setConstant(10.0); - jointDgain.tail(12).setConstant(0.1); + jointPgain.tail(12).setConstant(120.0); + jointDgain.tail(12).setConstant(3); go1->setGeneralizedCoordinate(jointNominalConfig); go1->setGeneralizedForce(Eigen::VectorXd::Zero(go1->getDOF())); go1->setPdGains(jointPgain, jointDgain); go1->setPdTarget(jointNominalConfig, jointVelocityTarget); go1->setName("go1"); - + std::cout<< go1->getGeneralizedCoordinate(); /// launch raisim server raisim::RaisimServer server(&world); server.focusOn(go1); server.launchServer(); + Eigen::Vector3d pos(0,0, 3); for (int i=0; i<2000000; i++) { - RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) + + RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) + +// sleep(1); + go1->setBasePos(pos); + angle_generator(tmp, i, 30.f, 0.6); +// double rrr = 0; +// for(int i=4; i<=6 ; i++) +// { +// rrr += abs(jointNominalConfig[i] - ) * stable_reward_rate ; +// } + jointNominalConfig.tail(12) = tmp; + go1->setPdTarget(jointNominalConfig, jointVelocityTarget); + + server.integrateWorldThreadSafe(); + } server.killServer(); diff --git a/raisimGymTorch/raisimGymTorch/env/auto_runner.py b/raisimGymTorch/raisimGymTorch/env/auto_runner.py new file mode 100644 index 000000000..aff020b07 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/auto_runner.py @@ -0,0 +1,26 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +import os + +# file = open('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml') +def change_data(path, flag, data): + y = YAML().load(open(path, 'r')) + for a,b in zip(flag, data): + y['environment'][a] = b + # wr = yaml.dump(y) + print(y) + with open(path, 'w') as f : + dump(y, f, Dumper=RoundTripDumper) + +test_list = [x/1000 for x in range(0,20,2)] +test_T = [x for x in range(30, 70, 10)] +# print(test_list) +length = 300 +for j in test_T: + for i in test_list: + change_data('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml',['action_std','schedule'], [i, j]) + if i == 0: + continue + else: + os.system(f'python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py -u {length} |grep biggest' ) + +# os.system('python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py -u 3 |grep biggest' ) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp index b5c5cc0a9..37e8cf921 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/Environment.hpp @@ -110,7 +110,7 @@ class ENVIRONMENT : public RaisimGymEnv { READ_YAML(bool, float_base, cfg_["float_base"]); READ_YAML(float,schedule_T, cfg_["schedule"]); /// add objects - anymal_ = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_ = world_->addArticulatedSystem(resourceDir_+"/go1/go1.urdf"); anymal_->setName("dog"); anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); world_->addGround(); @@ -293,6 +293,7 @@ class ENVIRONMENT : public RaisimGymEnv { // rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); // rewards_.record("forwardVel", std::mi); rewards_.record("Stable", 1 - rrr, false); +rewards_.record("forwardVel", bodyLinearVel_[0], false); gc_old = gc_.tail(12); ref_old = angle_list; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp new file mode 100644 index 000000000..81a9d7751 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp @@ -0,0 +1,433 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.82, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_<< 0, 0, 0.30, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; + +// jointNominalConfig.tail(12).setZero(); + Eigen::VectorXd tmp(12); + tmp.setZero(); + angle_generator(tmp, 0, 80.f); + gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(120.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(3); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling + COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); + Eigen::VectorXd idx1(8), idx2(4); + idx1.setZero();idx2.setZero(); + idx1<<1, 2, 4, 5, 7,8,10,11; + idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); + Eigen::VectorXd ttmp =action.cast(); + map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + + angle_mulit(pTarget12_, idx1, action_std); + angle_mulit(pTarget12_, idx2, action_std); + + + angle_list_for_work = angle_list * for_work_rate; + + + + + pTarget12_ = angle_list_for_work + pTarget12_; +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + +// / if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml new file mode 100644 index 000000000..32a0b24c9 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml @@ -0,0 +1,32 @@ +seed: 1 +record_video: false + +environment: + render: true +# just testing commenting + num_envs: 100 + eval_every_n: 100 + num_threads: 30 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 8.0 + action_std: 0.018 + show_ref: false + angle_rate: 0.3 + stable: 1 + reference: 0 + schedule: 60 + for_work: 1 + float_base: false + learnning_rate: 5e-4 + reward: + forwardVel: + coeff: 3 + torque: + coeff: -4e-5 + Stable: + coeff: 0.9 + +architecture: + policy_net: [128, 128] + value_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py new file mode 100755 index 000000000..7cf3010aa --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py @@ -0,0 +1,204 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg_go1 import NormalSampler +from raisimGymTorch.env.bin.rsg_go1 import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO + + +import os +import math +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse + + + +# task specification +task_name = "go1_locomotion" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=120) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +if mode =='train' or mode == 'retrain': + tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update + +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=4, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + learning_rate=cfg['environment']['learnning_rate'] + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +# if load_best == True: +# weight_path = "" +print = logger.info + +total_update = args.update +if mode =='train' or mode == 'retrain': + for update in range(total_update): + start = time.time() + env.reset() + reward_sum = 0 + done_sum = 0 + average_dones = 0. + + if update % cfg['environment']['eval_every_n'] == 0: + print("Visualizing and evaluating the current policy") + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + # we create another graph just to demonstrate the save/load method + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) + + env.turn_on_visualization() + env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') + + for step in range(n_steps): + with torch.no_grad(): + frame_start = time.time() + obs = env.observe(False) + + # action = ppo.act(torch.from_numpy(obs).cpu()) + action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + # print(action.min()) + reward, dones = env.step(action.cpu().detach().numpy()) + reward_analyzer.add_reward_info(env.get_reward_info()) + frame_end = time.time() + wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) + if wait_time > 0.: + time.sleep(wait_time) + + env.stop_video_recording() + env.turn_off_visualization() + + reward_analyzer.analyze_and_plot(update) + env.reset() + env.save_scaling(saver.data_dir, str(update)) + + # actual training + for step in range(n_steps): + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + ppo.step(value_obs=obs, rews=reward, dones=dones) + done_sum = done_sum + np.sum(dones) + reward_sum = reward_sum + np.sum(reward) + # take st step to get value obs + obs = env.observe() + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 == 0, update=update) + average_ll_performance = reward_sum / total_steps + if average_ll_performance > biggest_reward: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + env.save_scaling(saver.data_dir, str(update)) + average_dones = done_sum / total_steps + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + # curriculum update. Implement it in Environment.hpp + env.curriculum_callback() + + end = time.time() + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) + print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) + print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) + print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) + * cfg['environment']['control_dt']))) + print('----------------------------------------------------\n') +else: + env.reset() + start = time.time() + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + for step in range(n_steps * 10): + time.sleep(0.01) + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + +print(f'biggest:{biggest_reward},rate = {biggest_iter}') \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/tester.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/tester.py new file mode 100755 index 000000000..bdea58d30 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/tester.py @@ -0,0 +1,76 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.bin import rsg_anymal +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +import raisimGymTorch.algo.ppo.module as ppo_module +import os +import math +import time +import torch +import argparse + + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-w', '--weight', help='trained weight path', type=str, default='') +args = parser.parse_args() + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +cfg['environment']['num_envs'] = 1 + +env = VecEnv(rsg_anymal.RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper)), cfg['environment']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts + +weight_path = args.weight +iteration_number = weight_path.rsplit('/', 1)[1].split('_', 1)[1].rsplit('.', 1)[0] +weight_dir = weight_path.rsplit('/', 1)[0] + '/' + +if weight_path == "": + print("Can't find trained weight, please provide a trained weight with --weight switch\n") +else: + print("Loaded weight from {}\n".format(weight_path)) + start = time.time() + env.reset() + reward_ll_sum = 0 + done_sum = 0 + average_dones = 0. + n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) + total_steps = n_steps * 1 + start_step_id = 0 + + print("Visualizing and evaluating the policy: ", weight_path) + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], torch.nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(weight_path)['actor_architecture_state_dict']) + + env.load_scaling(weight_dir, int(iteration_number)) + env.turn_on_visualization() + + # max_steps = 1000000 + max_steps = 1000 ## 10 secs + + for step in range(max_steps): + time.sleep(0.01) + obs = env.observe(False) + action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + reward_ll, dones = env.step(action_ll.cpu().detach().numpy()) + reward_ll_sum = reward_ll_sum + reward_ll[0] + if dones or step == max_steps - 1: + print('----------------------------------------------------') + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(reward_ll_sum / (step + 1 - start_step_id)))) + print('{:<40} {:>6}'.format("time elapsed [sec]: ", '{:6.4f}'.format((step + 1 - start_step_id) * 0.01))) + print('----------------------------------------------------\n') + start_step_id = step + 1 + reward_ll_sum = 0.0 + + env.turn_off_visualization() + env.reset() + print("Finished at the maximum visualization steps") From 4836ff764c72e810a6f0270ed905a1f10fc56175 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 1 Aug 2023 13:56:16 +0800 Subject: [PATCH 08/62] add deploy part --- .gitignore | 1 + .../env/deploy/data/Environment.hpp | 387 ++++++++++++++++++ .../env/deploy/data/full_152.pt | Bin 0 -> 538687 bytes .../env/deploy/data/mean152.csv | 34 ++ .../raisimGymTorch/env/deploy/robot.py | 44 ++ .../env/envs/rsg_anymal_modified/cfg.yaml | 2 +- .../helper/raisim_gym_helper.py | 2 +- 7 files changed, 468 insertions(+), 2 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/data/Environment.hpp create mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/data/full_152.pt create mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/data/mean152.csv create mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/robot.py diff --git a/.gitignore b/.gitignore index e10542adb..f6ac31f3d 100755 --- a/.gitignore +++ b/.gitignore @@ -21,3 +21,4 @@ examples/cmake-build*/* data/* **/.DS_Store /raisimGymTorch/raisimGymTorch/algo/pre_sin.py +/raisimGymTorch/raisimGymTorch/env/deploy/data/ diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/data/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/deploy/data/Environment.hpp new file mode 100644 index 000000000..7e9f5b5c4 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/deploy/data/Environment.hpp @@ -0,0 +1,387 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +{ +// std::cout<< "size is "<< angle_list.size() << std::endl; + double base1= 0.82, base3=0.0; + double base2 = -2 * base1; + double ang = abs(sin( float(idx) / T * PI)) * rate; + + int idx_base = 0; +// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_<< 0, 0, 0.30, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; + +// jointNominalConfig.tail(12).setZero(); + Eigen::VectorXd tmp(12); + tmp.setZero(); + angle_generator(tmp, 0, 80.f); + gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(120.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(3); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling + COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); + Eigen::VectorXd idx1(8), idx2(4); + idx1.setZero();idx2.setZero(); + idx1<<1, 2, 4, 5, 7,8,10,11; + idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); + Eigen::VectorXd ttmp =action.cast(); + map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + + angle_mulit(pTarget12_, idx1, action_std); + angle_mulit(pTarget12_, idx2, action_std); + + + angle_list_for_work = angle_list * for_work_rate; + + + + + pTarget12_ = angle_list_for_work + pTarget12_; +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + +// / if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/data/full_152.pt b/raisimGymTorch/raisimGymTorch/env/deploy/data/full_152.pt new file mode 100644 index 0000000000000000000000000000000000000000..2b22c8b004218cc44b41a5a785441efd14dea49d GIT binary patch literal 538687 zcmaHS30zIx7k2Z2=24U>N-9k>+_QE_lcd}XA<|rk?(JqQqDiAjkxEFB5>iU{tZg1M zWG-VelQCrWo$CGm-}`!h@7M2VooBCo_OqY0?%wC@v(Mq}AuS^zp`ak~uRk>jHHpxe z1q=KwM_G*w4iE*HN6la0GEPZi=HLI~rQ!q<#=iPo^MD}HBB6hPFep4i6cQwg5r+6j zivmO;{=pGJB7tO3(4qwkIDf>Vh0(pdgux-gkl^uLO)r7eaK1p=*jKBI<8Q6aEzFmM zM1+Nl1TtOBLE+~9F`|eC(Y^eIA%QUw3xfScAq%6qE*D$%637}G`^s|!(cGB>=S1?=d)8(A#6Mhh(y# zPilCVDkYIXnJ-ZB)%drxz=(iofoeF{Z@64|53i*_EnLwfUL;WOrb`lNct|D*G<&GD zL;`KTK<1O|M;fPag#GVc~Q z@E?5Ef-|sQ9###6xetFNDjunoL54?ixV*2V_0`QQG_U-e>PbVO80>|*~D&;?_ z%q;|C;sj&=qta3^E>7U|AC*>u@o@s@|ERPUxWoxu|D)1I;1(xv@2-rA4*c6h3XX^t z2_pizA-`zh-zU<9?w~!oM{u+#STOM)nH(+f?8)S$zcT67l}YcOOimUF_~>vF9`qlK>pt> zi}(kby=o!e7J&X%Qf<=5m)W603HOmD5i##)mi?2>Qn0*-ZABNGWY;u{?NJxk!?;o;Sj88_|6AQ((`@xW z`K$zMI6g^{AfcNtNs!p3E~$qrStLl|3)XV;EcLI^k!IXAJkonc?!P8dMw}q?KL)jh zAS+I=?msFm1=(?e_5V?6CD;%r$oY>-Yr)1iLGFK4+6eOE1e>}myC#w*_iHSQ5=BHt zEDsU>eg15Y6XYBF%5v4+cPGJ?I6;B2heVv9(Abx|6>{E?C_&Lb^JXpB+LO0pE^ot! z_vCAvNU)tR*wKB-30WHDAFwz~Q1Z`qHiDghjs4Q@;m|eq%X-HCt{#%zB0)J{u*bI- z*YjT_{?P(K#XosQ2`c~M+5119sve$wJv{qGf&+X(b&Q8(oZz5w_#gU53u=1w*Zxia zA(5btFQ^ayL$j^maL<@)=AnqC?Y)>~R5>US2NcbQ6>;y-9+8q0<&GD`_CwkhP z6bVl81*c;?xTV6Ge@U|!ob8cz?r+l0iv*2)!G%AhSy>1!{xw@Kb@$UXA1?RIho+vs zu80Iz`GRYI=(DmET>q=#jsG>g+0*b=Ps3)BpoK5E9pfP#C%E&cNGmJB-5!zm{wDIi zNbrC!X#G>9wcue-F50@gN)kNk%EjZJZk~t)Px*ppf9kUlJnw1q;;%L@yV|_!Y11we zyygqu#CXWW3Euuo+9<)h9%=9YChdbr(7_jc{8QR!!Kbb?aJTKxUHx?5wmW;$@TI4( zuOh)WzTo?x`fLS1{%ZL1e+_^2H2mG&P$L;p{

w5#gz}u_3l+Lf`sdKJvKK0LdAn8$!d@Ke){-Rb%|R|-!am%wM~xDP zL_%fG@`Wm#{UaW03!!S4x0^_fLw^yebFhm@gFE&RX>v#;)Z#2(sLk0J54kv@4hQ}W z%i2dT?Og{8+8MZ$iZWK|sTs%}d(;f# zkVrU~vwYzY&i)yewa~E3+f6i-Lw^ws<6sw&5qIn%GUkv-IGnS5p$TVWJmlkqBRKG{ zuxx~;oVzD1GY2&c za^PP9+6u>T?w$b0a_DaXj^m0Vp%Z8M!tq@v{Sly@(7DUowd5DNaHv~RlF*fdUFmk? zjy-DJIV2KJ;4EM0!P!4!vlmY6@^%w>a_BFjNgV7V^5Tv?MBW?{2`6)wFXVGJ#zQeq z=)-|O!?LjuPT|}=VNK=G-@=;46-C17oaGCdW=XolY`xIxNEI& z7FXz=^+G=m^+=k{A(3znXZb>Z&i)abjg@e2m$!#4fP?>I3*-ttY(X6AVGHJvNEpId zzA%)tF&@3*gkc=`SAf>SaL(NmU<8N$7T`RtC=$-+EMK^w>!g4FZZONK4*V;u(ZX2H-4j+EhyE7UO0FmpuHr0T7~gf$A7R-FS9f{4)vV!A zmzu66qcDLh^dvfwLp_R;I3yA#bCxem;q0HG*$LNndArF{IrKlWG_KG?md>FbvJ4K1 zgqfV>3$r*I$AASwVHsC& zb<`T+5WLsmPWN&%kb7*67Vhfyw_oV`yXflpw)0YpcFKrk;cm{~{Y)3av6gq8M4Xpp zwOM31ba&db6XG8n5)`mZxQDCukmz1`21G`O2?K(K6`U*8w`&_GGGJ-XqPMc!)wL-S zx=0uj5EL%l%XubsFExV#qPPv3fWQSI!m94mx}JrDBSJ&DU73ZVi0+Dg-4$I6<JB-1?atYEmB39x@)X9&#S?9ts|c9=$wzd-Ms335ba? z_x6xicr<8&G3(jyZf7ngCBHK<5g+0!DF)!j8%q>-=Qtuz&(3n*A+Q=`w*w_U6C}s*#y5vS48#Tjr%T{da z(1h`s)?{wBI+-`zmBhG6P}X=m(_wTIo-R|NJK}<9fn^jbrBA@sW<@{-$isyWUGm_C z68$pdDchp{5vR|84=X-Tpz@v8sONo&`SfNyjY-s|+Epi*b8ZUsU}6nV%P<>uEi|A9 zU-IaZ$4zkfa3x+1x&o(NC294i1US9aj)}G{f$&`re;Au`?x1xh~j^kFyJUg$u>9vZ`k zefJ=M0mSTykmt9^YAjHr<$3rmdH7k(=ly}12i z1IMlO*2~L~yt{$jvqp{%Na%&XEzh&6Dn4wl3|et)CmMxZ?;1WbMi9S4W|y z$%uH~Ji_kZ>p`UMZDA@_>cZ49&rl-yDnyu-pt<8{sP7dB!5Nw0IO-1MYy03l{$sf2 zyN-^_``j@8a}~RiWWo9YUi6shO2~Qh3KoQ@F{fvnF*~nlvipqJvR9I5!?$5R zJ=h^Zc?TE6p*%(4=Mn1OZzXufHJjX-o`FLn9I527JFvUx0!$iI&GgzZjLiKUL02u%CuJph^gzBR9;%n2 z$_58v&Yfc1nWRO=@n*pB%cIG*R7IS4#fh58n$XOgjcmF}6Q-P&Ay)A>@cH~F%x5bZ z>LAWQ-DAN7#dfqdAsFf>?SUm5Rp9fpQi$ES6JPqIGV9GuNc0V9;v`8Zo|Yqzt1sg6 za-d^p6cgopW8my$4eB^G9bON#dje|>uYd|*KM(X+u_sguoxu?CD%8lXVOJ)F-d*jMH?DGg+ z&E7D}`f8Hq_89td%QTksJC6Cr_3RkiMC{zlG&n!9f7?c}#L*57zICv}pFi(X_%-&BLH!Q^LX=UWn%?5G( zbY&XoS;)?K|C}G< zrLlF?YETw>%)7;I@E^-=NQgSDVV(dYSp~7*=MBt!bse79-KU_|Pm$P7cf~1b_0T!0 z9Ztpd!_(_7v6+|Z8$M*DCnH35!;56sOh`m+E-1IcE}7+ zCIZvUli`Aq1h_bg$d=7Q2nwn|hbvk{_f0q+XI9XOg^!qiN>3ok4UrOS<#uw=a-H5IQx<;n^etS`oO&uTHF&KK>&eTi(rB79nzgIn@{ z!~KR7RP@hKpQ*%7sVtrfcFUHB;=Da|ROgq#Oe8XOcS)?dVm02$SJ) z0OQZsh-26JpvInw)K|k9sFEM%R9TQGlhW9`i{mj>{9YnW7x=zt*zagb)oPPjS0`EO*`5!9_czjc`FixS-XXX%RD-Br+=spO zI-p6@0;<+Y(~hO}@V43&WFCl_@mlLJ*?kKeWU~QA#0(-u%WmVD?ZJ3R=Pvwsau0Vk zOhy}-Ve}gwN8>$w{0R1VbY=bc{tAzv}c?F3`@Ap<`}FQqyAlxh8&I_!Ht1Kp0-kr##i zY1Z%iP*{#+PvKiU6)r_5eLuv!W}_H``L~#x-|yp&Q8qMQ?0}aHUcrdejqJq1H8A9p zIbE4&OhiMEV%yYxI8Z7Bii-|FXVN{!+g6rN+GYr46K?_kNeVrDC!1~KMG#BxDG1^W z_PXCgNK9Qy%(e#Lgw{gdkrNAW^WN#CvY-YRMfx*5`(ozyyRGaih3%j@*^1nJ;tn!V zyLkQAtCL5%>p*c{AU)oMcvjgBW*saAjuD5CP$A0cLve+3G7j@eV%-`wsL9!TyvLUg z3+p(9M2s?L4HGtAh@9+KQ>an|6-%E1R-Eo6YgIeoU5@t^sLxsivdqf4Y{-yw+2@4VTtNDDe$`4#Mw6!UgxeipaOtq@;+ zqDF+tgpQ6`2*KkMac-t14BAo&<0G@!pL0xTm~Xy#qlO>zdw~<2DXV9jD#wB^-38?b zGl)&vAaD!Jrdg|%s9*mwX!v#!KkIB~zx&ieU2`d0>{Cp1Co9uoGpyliPA-~f1kr1n z52ns3xb5shXrF2aH8Pr1ZN4RS8)${k?_9(w^R`2(?L9Oc`~-_BL(q3S z#7@5mC$mbKOKvb+NnY;?G}Un^6wyh|tIAieY?e zIvS2Cem%N8#ozkp9WEi9NV)}Z} zJtT6KSlG%(Gpn^wVz`67X;_3!I_(fxunc6LY=FkIEL1o$^m0rZQ=E7jh0|YR;KB}k z@|2doa6khW)U?8carb<0dz5&1vBTKKph+ut7FhxZT6=W5Vdhnysv2 z3ic$`+?-z zo0oVw{tQ@O^uP?8GSIn|4sQzL;ghTkXbOnx?B1>*%8jvS()0wS87gBTC46j6euOD$&judoGAu-;$ z6d&|Ko7tzuzofL-r;##P>s1ftd7fl<$Wo|p8$=#I^ukNYi%3X|B28pX$j2)#xHJW5 z0n8?b-xt6ytpFTqTMg5fyOK9~Dwwdd0g|mMnEtBnP;@&P!#9S(#!C;_h(rxC)6syq z#kr9e**bXp)&RP8u{ygI6(R1?AUbup71H!9)D0_uw3F5FdyP4HuXGE3Nk@W_+%Pif z+%1US@(?weLmkFdt%R9t`injAC1ch29<$c@15d+(rqK`J^?3lDF=7lEpRthoY4M2h zgZr%Frb+BP#dB~^xgU*EFeNbJ0uw_Eu;k1DYCgOWv|C+KMr#~#57`U@ntKz^*Eex6 z?*h)>r^re;%?4E~WxBkgo?W}_mpEUh9}R_CmiT+J!dYfS^j%CNo^6J2Zj&MW(@$*g zH2`$N){y|G08o5T$qtz-K}?+)Qa{L!1_fARzT0eaAUXqP|5hi;OFlzb-FVCsPl1}< zy+Lly5y)QdgdK?|ph0duUf`}z`upw3=0g)8a%{I_Z+7uS`LHvoiQz z`O4NdcEXFH^5ojW~dDaFH<<8x@^g#Pr}v@G_>(-&}P<{mu1Z6K-6X+pO%2E=2r5yU2F(pV#Du%GEe z6^(n*7dvE$-nie`ICC|&``-im&PTW`teUAXQX&hQsxZv&G0J~v0+G;}+?)^#!+(z> zah=|Dczi3P+?dT??SD#KVtbqQan(hIH!jS)L0hm!M_zn%-B9|n=rp5VI*z1Pn@|fq zAym1B!ILG!U|jMVye9h?l+1nDnP*raJ37JZeh2%bIh~kA7eDQIZWtU5jkApDM%&ZEYCgl}4`K$b(M-zZ#DHdPH|lT|;rHG`>tuA#v-n zu+Qk*cunamvyB)L3&-c|IMd^(7-K`rZV0h3K9)4@G$%F-V<1n#jMR~9tjcU7a2|1r zEX_L%`ZX!y5oS4T?9X)eq-H$b$vXlo7Yw6`b+?e{rNQHBCF*tZGOWnWgFbzw=sM%| zpjlplDeF||oPzUM?_p0nCJd&$e?LO@jNnns{iJ4$3s$#YnLR zL`Wr|&IoIwU(1cvAPZu0!4VFY*po@&V`yh_1hrOgVa%K>;Ax06Yy3$Owce%T(E2CP zl&-9vJZZDJ3Kt6c zP^&&0=&*tWG`maD!A76zCisxKv!;WF>2o-Goln<1xX9XlQYN>b-AB*iviN*KF{#SR zrDgBtq2YnYFyv%DYbNVVzo?#M=AHb>+`K0cKll<#XYA@v%}5Jl?zIi>D$BBGhDm^l z(4WqjeU^98?+BLc2&7u)OW^pVblUpa75j+2*m5To>N!(}BuXcMo+69(Njmi8fGs$; zSqvruM!HWidUWz5ya!*s86?8sBrtlW$r7_~Q!8kwe(BTfsbUD!gp)GNV3 zPg=}e&M-lL|0EEv3MH93pW(%s{`AV(D)2E}isS(mo0NI+6hhxP#7uO=U3+fgS9$oh2a zzrk-ieM#w@-MC=B5!#90Y+E0X^;cJ8 zFPZ+Bp%jU>L9^h&@_5N^-d88tJ8m&&9 zrfq`*OT{32xtMxtNzlc@Y$ESHf|`e3#(}F$c#Eo>asQKK*pxJsjCO7Y_ejc!zl6c2A{reRM$S3xI3poCR@lW`7)gzTYnLS#tm@u{$#q`C>Qt!TiLbgiYQ9k z3AedxeD%fn293t?^nj| zKK}4nMT-5>*@VTZV4>|p_DKw+IYV4&eY>l8u=RJyyQ+`LTz-1J8US)T`jRbL8_Cbe zG%(u{$)w%b2nzTLUQYXk8rS-ZOjwtP4?Z#^y^z6-yaN@CKdb1-|xc(C>KA~uHv)G+Wj zq|^^(+=R z=_4i^ZHLL9?j!S9nQ3p-XU&H6A~zCOK;V!}GAlb6QZl|^`Gy+i$$}*ExNjuRu+GO{ zc~0QJULO~kR>MM*^Ej?=D#`G1W3KNx53=h0=sFc=5*DjKpZq=n#hQ8KipeHasl0rfkOTO3UzJul{td z;asvWJ(d1)9|)}r4>3xCK6t#q1NxW`#^rA(601FuWKYNlV(YLEj;mj0;f#nS_g!iG z4rLO%GM;>>I6~_Tr0Lr)8Q?MCI;Mv0W$KR0lC9QB_PMbiz`{6)-W<4({hhHJu7)MC zd0syl_r!4CoR#tH=Zwiz!fF_~9B*x3a<~-d1ixY&gh361-UY+Kb16{nsSEZhdGx3H z7^?AmK29%Lhs16J`w{6f01 z-zeyB6iZ&HsZzN`&UnEt5!gd}aq<}(@-CnRocdgWDQBjj>74zzI%69B7~PMU*3ZV^ zBYo-Zl=W<{qfTIYL4yXpn?Q>PYvaYat>8)P*7C0h)JN8(W{eE`qPqMnhxa)8mlr$C0IIa_CyNY1@Gk0bZ{GGD?w#XoXVFzcp;F}2M8YU;mZ08?mQl%0MSA$496B1RgMQ*utTdl(KjF9?{cdm- z<)5mMuWEkeTk;R_nLrE7m?TF%GSZk}BxrR$1t*7-;#YP7R7*Y|o5xM3Wp7$B=KK+MTk0K1Yn7$>CE=JTm`(f5y2Ilw zb08LjH?w;shVb;}WMJo*Y4nzXG*n-|i&C?OWBf%+5_fzU1Nk2zMt&D#RXY>bSDptO zT{&_nLYld>-v@5pOJXc%o)*hrf5^Cny3h-@Qux5F6QU)!_mMlxAymztRpj;{FY@*2 z%ypk&qD>N2*DnCO{{Ha%tS0@HZNZGbDn&|!Y3={hjU#dHy!ob@wNpk_r?p=csNkMd6Rvxy#ItP!J zbu!~mBPfKpqvE&|tmWhq{8Ax-af$lu#>RMht?@FJewQItHQGe<%N+;p&*xccZ)A9S zoAJsD9Z2|o7ruC3f?L@Zb6hxp57oxuMD~6i)Sr?gn)eKFL@ygUeB3d1{MiSvE-V3tiheZ6 z_dYM~+;s`em+!}~EqZuw@@HP|&zCUjhb+A?P!%OT*U_84iTLYP6vWP!Ct`OQ^7Gzi zI2*rO9D8#s&MsR8_8V?tZFT{O>J{)@*$J?U&VhRe3)#$->&U+5Z`kH5gP~s*l9=V~ zuL_pgtyc-%bGjPixWcRULRJ45YT@)-a&e3M0$+Vn5+oY%Z51Hs8;{ z#|QFs=g$xlwBQ-z@PT{J9k>mij8&o&{dQtq%L#a%Q$Wpg9zyP+G<g4!X7cz0RAD#SdEL}b9E0%KawHt;$!ns~M@Xn&S0y3f<_lV;Ysctd#dwq%u_gy!MltYxr6Qy;eQBRD%PR@kSy?hw}{ue zr-1EkV~tL0xo-syhGWjPLtxmJ2O9=_#KD92vqd^u%reh1h?~W|bK@gE9JqkoFdL82 z`3m^{d>WN){{amKOQ=CqCOpkdL5s}_Os#nYMi;qbT!0w#Po0GK4dtYMjRbXkWdPpC zC~px@f$V)g780yONvy66uQZ|>%O~lQVqrK<_&ARY5jCPms1Z4SI!)Z6{u}QetHd`K zHOPF~AUdoxl)P$5g!su%F!IBB*s;cf4xVC0tu42q_e2vKcfJfhH4kCxb7qqlC+>jy z_8e%LIi4Li>^3||R3g=F32exy5lp4~DGc7Zp0!__M|+*0ObnG5lCbFI?6J$ma2t}z zbwwSfB*mIIE%znCTO5e$(pmI%P#y1@?`X!mMFbf)ge0WR7EdO|!7kHbBzV&|cI^2S z+CNi>O`fC3ln=R}-4EG*dJXJ8mujZ!+iD0qG8663%tgt}Dwcn%0KN&NiEws*COYesr{s60=ggAIBmBOCqv&gC!J}^f+ znK9a31wqaE&_4D9+KZKFMc_d=^In54F3e$Pja6YL{j{J*`e=~Bx15Qe^Er5^t$-a; zzBJup4J7SqWBR*wV3KG)^`=$C=9?QFbg}0)g!_Q-krMjzxSQy473$yQMGM=_nZ4$n z?56E{Ff|{UiasG&9OuZ4XtpB<$34M%jfG6LFqrHaok?>NuOm6^!|s?AAYOWT7n!_g z5B#!lqeu8|pyP52kDiol&WaM!m9}XT&9=ciK zowjihrtw*PU}i9Vo>m7+qZ%Ey?Z3@i>#!WR>Sn-=l68>ynZ?v3U;HpljZ%k=P&slV zYbNbY=O5pKm8$#2;rZ&cFSkCqk{INWw9S~zE%?CRH4G#zSs6IKl!ed5QB41OQ|z1& zLyo=rg$J4*@@D#lK%`n8t{T${L-SpkL$=)e>(K{c)0va_dBQ^R#z-L=>zfdt*M~^z z?M9w!?X-t~cKY@~c+jr55hJFyl!- z3yWEqduQ;L^>WB{OJRQr+|kBxI=#2;CfZb;72ocdPCxpyWSCA0Td~g>3uhbAHQC2e z=V~Kux*kYgsQ{jLl|e7=y}9ZbZE~iMC6m&*m<(O21twxK>I}(-&gwh%--^{}XiF@t zcYVY=v}QI6oNb9kO*N=D3n75pGrMsyn>@*OfU@(ElvukH38MroR!+xl`O~0<&xfh5 zZ{ZtHpAp{NfgXo8^1_|#(cxGIeQG}#ex4Xh6xJ%!*B=Wo?$t<;uT4Y0ay#Cw1&wS; z`9_kWJ03sv?N6_+EVh5R{|Rq{L2v4G7pSzPKl>)I4$tqfAxXzJ(q;P$A%5`$Y=2%1 zvCLu`XE~K*jT}Vg*YT*1r35W>HllO(mNNa!>}W)a4ZL6KNSd6U_fs|5q~7sx^LP@CN|0t{XMcwxwFzXhg()emeT{`G1K6jcBARa$O(OI)X@u*2 zkWo@2^r8wqd-xnYO7;Vl4govbNsBP~VWfVEG>+b&RX*rH)$i*Ar?hWkB)%2CdBG^_tlWEWU2>ugN$a}A=VDIw)m;4ekZNt5o ztM|9#vQLtjYTgGtMgl&1uSD$?R^w>( zh$`_*)fi^tfvKc3+?-7G?nO-dDbSg}zOyz%BJtT=Z&Y99K*K*p;8kx`lAEFr!>fOw z8h;e!_i(1 zF!Br7wi;K0phXmy4g@P=vG_@#uOq z9^TA#qBko=^uRe!+_x*0WJ~m=9^Z7R3eR4kfI zRE<}&4~A`G${&1!>z+f=e&Sjhni9Zl@6;zgihd;UcM@-Z@8{q*?><9$#u!l$#=L&% zK|MY>U{tXZhMd?)A1&PpuQi;>(OVDLqjyd+!V$ZvhvRFsof`?`W~DGnW3uu4M1T6R zMH;+ZP~7oiG=0vOBL|CSLfVv>5SkrHop?8yyN}v2^=LXR?!6xe?OxA(N@;F*YMKwS zrk9u%+MYzFO_2nt%fYxwxpe5ta-7{EM_T3Y;`E2-QD$9#bX+J!J{l^*I7eL^63)W# zRRy@o><)XXC=QFZtBLCpvhbQl67EyY$4yfG?6YMYU^;&Z`Z-+@xBK10P}$q!`Ml|L z?-UC>=BPv4GAcl7vMW(NrA54ZVSvj_}ASuMu>sm57Ma9x-c?2CHdOT{7D2uVZ`{u46Cr zG~kf!A$E=BRG4?&gS4JgwYNVWMyEf{yg9!~#;$bZr|f|B-;7^{hdu zI2Whd^Xb}M`lRIbcv?(1iK`s~U}whw@%Hp~?wcxeGQ+S9Z%)3BQ~RzYc@r`~)9nQY z+4d!`!VbakQL@DF>|~zKh_f(PeKhT7ndjiyvIloWO4DEcI_Gu2~;;;0WJYC@P;q z2hZLI{=IzZ$D;l;V4)nDzkC92c~Hl+Th3%3{b+&7H*DC3wh?$d$qa3B72#WlCT4F~ z2x}acP-nMy%#V66TD@ou#1Lt+oyleHM<~&Q>-WNmCFQhpk2z`HxD`I@<%z#PXoZV+ z-=OcJUwG!~EAUXU!?3Jx5c;7PJ@I8f8@+rx4JnhtXJ2&KElV zx^e4F=Ml`I!r^3kOer{8S<|gjap17(J##0a7cISYQS3DH1sDnYp%h;hV&9m-w>QZo zDO8J0EnH6Jc;?hMCW!`H8!`$>gXph`iu6mr^&qJe3kSC7lg79cOs2(7us5xPg&7HC zSaV-`cjhZNaxE8)`)tGt!6%Gpd5N*Rgd}-kU(z}+6bZl}D%ODi50%*9bzOF-6r1WBKp45@3fss8F}8gg?e z`EmXoo_ltdF*j(1uLgCH{7H)Coo#?C=cLfpX-k7{NjrPA;VCpuFd{!gDa3lzQY~#? z90@Kwr4^rch^w~B9@9HQKR z&!dj|d_c1hO!H*OcW&0t>n2ue=LP>J^y5FXHodAv+2 zHOCz0FWVv>wyqW>{j0_9Dw~=2w{~r{Zhdo4d-(yCl%h59{*3)K_ zR2bI4$M^TD=@|bCG*%VB$19)Ue8~p-X0s;uZA~M_xa>mV+6wlG>JIcfWyXC2`xOR8 z7BDXjpMcZdY0z2jOP;(NPx}PUg2Qh0!sGd18Fm|&O;A%^$GocXD#em z+044Ped8UTrblZZ|HfU9^YKpYDR$Gc9eBz33vpY_W%=?lF zJ2l^;+JYut{=9kE^1z+WtX<9YO0c4-R|nD?_S2Y4;#Sl-)t4SD(}gqNWJo$}z^Rfh zWZvf)V0FhEG}K0uF_CH{D_EYqC&QTn%>q1mTnY;A+<@ZXDb%}TF!NK-n{M^m$Nu!* z2q#{yqEqwaY4!s@dLeo<&Asy#uDJB2>+Emi9sj9x?|@-cB`@yqgTvaW^XD$w(YVZHxNSkvq8Sv(i*lF0v&C zF=OF@(G|Rg@7ZdtxwvJ2Pid-%m)TOx>%WhO6NY%x zIyP=Z=Kvy+;`DP!H5vpH5DU2&YSr0q$M;8;9{$;Jkx1NCO8D@6T7* zAJ&E-IsE|6{vD4&RI~~+}l;@!8!S8<);7}&%OeMfm`v}22*?@rB8KqX48FX3>m(0GsHGc zCle>hkp2}-XmK(LYL=eFNSi0nye*2guKNHVa~@;g;o5Ze`#{)lo=fcAmN}G`hS4EW zGhj`dn9S$bGPGncG5EBaobg-)Dv3^zdwVT8aXN}s7|y+`;MKyW{f=}O?+J!ltOkYX zA7Xa#H)e2PJq${C2hl3SNq_ZD&~8eGVWW-k+eu40;&>uE_)IjSC(4Gl-YcHkH1TyhKmbJc1CJm-uPF zJG1{Zt~?Y#%Z|OmcAAfj;aPgC|%qx)I81Sl-v`eQ3g>DRlGHNLcVJ9*$Wa zVVXOq(6Q6!(+ZRI%(u>R7$3x~O%jrE+R|S1@jO#_T~xqmB?fwuy0!sGYYxZ^!0E}M=g>~-m=&`6r{{UO%YguwpY zKBQW*FFn)JipO5pFjm>;!LTlhT=n&Ep!YxZxpN7WETnZ8abvo22Q1Sr=i|v#BIoNu3nmT7g}cdmGA7Dv~la zsx*m&N-9IBRK`Nc7(z;>v+wQfouUCzQe;T;T$%@!de8Uw*Snte{+@T8=Q(SgwfwP{ z^Eub`xvu-Z#zQW&yUa+I%wd9F+K}@#g}K-L9;95m0eNCq9&zl;9`aobLk1?q5=CQq z!Z}A@VodKb)9YD4jCl4jhT)}5c+W1PxbQonwO*1TqE7Q7PS)5hCAG+r$G4dEi?fI^ z;c$lMv?-*5wv^pKQy|l^)S7&i1neq}1m4@Xh3vugH+fxegfogqeOUC!g^hREMcn(Q zz?$}j6YpgYv$b|Nhz_GKO!E&@cIoR9W^1glF1$RLHL^2dZ~xpUIG0gD%5=9fGfr>j z-I?}@P;fLPt`FoA>aUlw*&oj{ijTJQ%r=UVdu|0V{k2nxYQuSU-whLpW5U_64c}K0 zj`lZse+L7J)>`1j3iIa`sutwVW(BtMhqPexx*T+V*{GDWY@_I6K zy(g=;`6MGRGod+VLosW+Xcx1Y*hz+LcO=Ec#{?h5#+WxTp^T-*VP@j~b@^~V&$2j(b z?g(%0pny^S@P!f2t|spM+s2wmh%hZ8Zr?5Rx!aV~{`8Y^ zP~SpibQ!X~DHGVvrjNwU?r~!JQ;gM*e`Y7=pG9|yvg>G^~?o{5dkknlTF~J zu@)ObiMc@psk7uV5t76sO%Dw>2TZEuB^duD{@mMc_p@pnaV|uI6zls#|wPy^v~xPoa}B5V_#Kbx)pp4hx+$6WSE)=wtK z_bh8yTq?-jby$$z^Gn!%;7;bq2C^B{Y$ju3k6qg1=Y*y*L+Hhx=gm2zN$STYF_qmm z#O}Xuc(ZEAoQOy*O^l5^TfZ3y~NGSF9lZ~zhI7MiIJR@%0$Y}J%sT+dm^CA zle}zJ$@XL~W=fu>G3K4(tldjF_SoYjB7dP_5K0E(!kDa=Be;D#hrKd;*zT6z zspeDP5HlL7NQ%d(v(XnPkXQ2!iJadu?8Aq`-b7ZDPzT(G|bWGcf{$1M`pr{u|zsh5cBas`6du14hFTuX9#W;(gwd@8eVR+j)CrVBV$5xmt~mNNAv zSBZfSapY!+@5D&{6W-l}Spw~!!Worqae{~=(-NkgfukMji5rg#QBw^EKguy>4j zd?=n-`P-a*otVX}*|mb)-Z`DO&@!LZ467iY7VT%Ao0|!1?HkEh-6^a?RR$xm|0>b+ zV^CnxbdC^T*Uu6FC2N>2oIfsE$=d%sPq^xp5xS%5Y~hl#Jj>4| zgjH&-z*Q!fsZ@3#vTA=4+vDyCvL3${JomICjf+oSP+Ga zR}xF^yCGVNB*Tl^<+O4D3KwT^NF2rnwVFzqr{!Nk%I6MDRxBI0WH@xlb!p>g1l?f?n(vPVFOjT*BGHuKr+y9(s}wFQD# zUw<;MW31S98U;#NbN_#>$U= z67a^G3CD%^3H3MbyxqOp4EXslX)j#JYZq{qotw$~IwzLLe0yl;+)1!(-5KVkMP?0u!Z@!_dDSdy)13~J7hNh8|csj>4HxRRWchQwZ{LSn5T zmKb-7q@&%{S;Bt_`R02wGg#BdtURVe2AuCDwiq=L!F%KhO1z5Ec=3`b@$@5$#be08 zEp=pAae~0wC5L#HQ^}Zn+OrbJd>OyJ6@*iE1i6?kCO1&F!3Jn9 zWf+M*p8D*`cGquhC*Drqz#A@EMcP^w6CCTO%_r|nVVxAr$evkQJXfSo_NA{Ty^uFi z)zHL@a_5rkI%^r{MbhkgzqPEL{6aSHlQN;dVm`@+)i&2FCXg9IS)>tXQgnKx8R=Oj_f>U#SeyY3>5YaJe6Z# z)aMapyT+T#l@bN*?a!D${lV~ae7+&W+h7L|9 z+i1;F_UeRG*v@7XgSo_askyAj>pbGdeR0-oW53{qx;#5|gdjU&kFm4c*0JsB4&-7^ zHaYE11#wpXCX=S9E>JWvZuSVcW4HcOEQ>795Q6R3cxRj)gni~lM77Kn=54wL;k-$U zlx}DgsEp6x6^$=uu=6}-Q@!wP9$CyVlZ1H~muc+DtFmNFc|CjIVT8Gma8_`#B!PV? zdEf3oi$&Z6y<5fR3-^);-~ZiWk$L}Rv52*cll}j7vB>{x$H;&8=Z{yi>@V8@VnUW2 zskWCPLXWwU@ivbcg}ZNwf|mlqH?tC=jDwg_F(bC;t_?#dAtG1m1o7+TL*`zfCadtL zp1A8elf}P2BCMN9Mt#zH#vomh5EQGCze{_WAHsh+XR0sn>h770W?e4x_~sMhOWH49 z_rc}l+}QcVud>rj*ySSvu?uI3BH>ODcKH zxB{te-b@q`CwS}T&t?o2t}%Z+wHTh4GWqAe4{z5GK9VgtVn5;kWS!Q*;;?=%(nhxegITf_XW! zmr`Q2(t?=CxjN*Bc~Q))e?`OIS<;Gm1f@F!|aS7J`aRMVZ-Bg%&GA68yGnp-mHwp6{1a+HpW|qCT@BR6aV3#`Mkh;V*gqDBYgkg`KKc0^k4ZW+-yVsFA2C#t%FYSDkQ#$ zg)rZ0mJ?~Koygenhs;VxC*pweX5n3k;@KE(AlgdQ$jkdA$aI-KD-C6&5^r_E8YWgW6Y^E&HV`sqJI{H(v_3B(A=12!&twEBGO%@Ds;TeOSJxX+S z`w)*>YZ-G(VL5baFZ21yTjHzEN?xd?BiY#RN2>oBAq*SZ1&5ZYk#~B8b>FfF%!IKO zyep13iJ{KdM8UUQLXdNwk$-oADB8T1d^hrpxM=J^;$=YkI6ooyyR67Z%a1X8S7q}2 zou`vCCzTTSdkzzakQKv7FA`LAW$@C>mXh}kU)$ZCm(9$0l}QA&8L*ieSBWr-qr|~7 zGtwYCmeC!SW@Z-cBytL!$QaF6g0VLj3H$A;OzjB|;r^Uh=EBl4!YH?%N9mg|Zy*#c&OxK1!%g?H=YzT_vz$>e(}aq>?2IVK`&6IrEJXg8C z+&j^Ztr0uUWVh8y){H}bh`K`9?N1~XI zoXC}DLdf|!imcrE#cZzs2xD_MM!1W~kW{RfCFi|zWdHRhu-2QDnP#~?Y-ztSYh{y3 z)@2`LYTfn8@rldWp&ync_q{!7v}6t0pA<)A?pQ~ftiC76mWgBi@2?lm-+v~DCRLGM zb{EOrf=bruy)8L;K!;oyxr=n+6p<^faWc4TBdKsJj)X5B%)Aedthg{HNEZ#>;!Zl59Ml(eYP!>C26fh(#1xbePW)-W(3Y8L)v#R zwsjU{!~SyeLUTDe&$pBuzU4{=Nb<=2Np+;fk$6Jsw=8S&(v*CCYZkdt>HyhX#w8Et zEF>dB&ockHN^5yF2>ZbxX;hce z_8*3+p{Jn#T>*Ukoq_Z(OW|?NZD_`LHhg#_L*LA~h6W5{VOoA3689>B&{K&>C`OT9 zy%|$s*03=Z(o@6r|9p~4_nivaiW{lgjmJQ7VmbHo0E1SChoVL2ETA@i026MaqVT;A zn9f8o6w)aLwJ#n~R~LSyECwZ^L;i6Sb2$K;cgvU(354)rYuDd!_TD+V^xkeB}#(ar?Q}^npMXe0X&O9XidM zR!V*f3gt(TyxR(V2OCR^io@=gGX7UJ2_3h23Lk6+_&;@S!9Ynor2LEr)ck$J5b-TPe^#_!wPtLr_077hX(DM29yorKgpB z!I~!JLH?o=^iq2{^u&ar*W0#(+_H^m^-phbYUqb~GI!CF(}l2> zHy4$p6{0_{lcDiOBQjXL2x2xCifk`@buK)cy$*E*eB>Ibd_XTW)X0bn&nf?X2UBMZNSy ztv;^EpW6q=!dUcUhAO{s{u$sZx1iU36y$51$2O%mh>W8~Jr!b-PNQO#``Flu8uWTY zH)JUsM72i@@XnGztmCl){XIs8eh}&haZ}P@*7`^^zB?XvDjq@-8{*+%^C>j$5{LHu z3k479^-VMVIq<{CM`Rq-w?giokDAE8Kb8CYjvHzmm;vU2frz^?6W+Xdh#g(92Ay#f zpzFyCv5n7cVUibyt_ft|@hGCaq#Lm`Njvl`=oV%8JrnyJTb#J(DPJrDiS1MUO7;|xY zz>UqNDW%)jsMuKuQ!O|Ff^j{#6gx!84a@~q^KdjIy8+&Q6GvY!1)zCdtKhPBI7$st z1nV7f~Mf}yJ?M>nOlJF?wEERQi3#3Iz;jh0L;tw4w zK%?LwqQ|XqTf_OZ%jK!~SjKncvv(Rj4WES92b$9HV;$g|pf0jr@{>D3^1*v_WyAnq zIIe}1-+qJk7$45;Z{K0frf_P@XB_>z(*u15T|kSU2kR$UXx2In{OGzb$l%vyNX&nZ z4z7ER{@$yA-GKsBwLAwhl9!2$!)?nH%-8QNru*0yx>eHvt-`3f-Hp&MUknbrpQ1R=X z2FjD)1NVO)#U4(pLN6|)ff{a&_f|#2oSCnw8n;(4*?K;`YPlsoKeq>Mm^zK#>}rBP z+Ws3=JEnrfiUGc;@_1I^Pos+Cc%D}(of?nf>nktP6AOxADLO-I?Q}<{R4nnBy36SG z0MMiBeCP!y9PsXdEczz34e#`sNB?!m!_Nc-<4>O((*_G$T*8<=3nSAH3554%dAb2dl_(1$<=G0>BWB857CQVdOWlHdmY&P9WsHK4zz0tHh?uw)ehf0x`dSg>0W$Z5;Ds|BmE z5xLXI{nS;Fc{+U8o11Rqi^?Kmp(RlfVM^(6)UTJjHA52Q+@koy9fvV%7e7G7kFklm z(r{Nt3SC;f3zDuFBXj!!j8m`>Jvyw1o<2*%mgRq?9!{45a`8`*{n(Dp1-Rj(8FYx{ zDcr?JotiulhaY{KkG|v`hlFtr=&BunyjmsP_JuEgNZkf+8kmGW}F?am_(-4~5iC zD!m0$yeEl|KA6H+LLcG01(!N>pbbepmcbh@XyHpQ;+nXw}JbFe$$d$@+z8-I79()Lw;V`kIJr zFMWUh!A9qNYJeXEx4j#%z=&`dj1`WquFnN}^+qHqHbI5>l5mz#wA~59P;Hn+GO!h%vwAToo*CIgNv-u zi9PvPUfL+Nu|Wm9zxx|E`DHVee?1FbtDS-pmcPMX{mMam-%zmWd_EG!G%z7D9R~4J z=uLAb%q}-WI#C>v`JtzL7Pn2&pd#Le;1PW~xKH;H7`);Dr_CtPQ_CoGWsDqz&Q(OO{*F;Hn-WFFao)lMwrM^_3vVmpD{^L|-bNMt(!mp;?ZCtJ zePfW|h&+8BcgCOA@xkHyXUu-|CI3)u4+PICM7PG{VMatVirrL!vbBT2A|@K0$XkM4 zZpsl^FTqI_xc4SAxb6GXJw}L1$q~bchb53{B?jJC_3&L?^YOgMU*Py@ z2rYY^fFGY3OW&_rjBEGKqiqa)=$ET;{70%6y=;#he(qm764j4AL`Pt1kv#ghn+rBx z?o5xn0F>03*LR3`pRHPYiu>x-?D`Br}U99nu9wsDQInGJX}<@L7RUB zBld1Eq_(P|AkGX}{zO(}9IyEY;qLF%)UE+@2r7uhI&|wWpLafxCE&t@(1YlJl{5Of zW-}aGx)gF2zT{80Z^J6S=3@#k4NMj zHV|4z^68=L+PKY%JbIT7A5Uk4=|@R#@etA;PB`Y#U(TGPL+4J$S1s_tYj%6mj=LlA zHB0=Hf1HT7XmLe8=lUf6Ab*o*kc!FDdqOP0P;ojP z>t=;6osgr?#S}m}^91|o_#D;UYDB*a45%Bl6F>CE5Gp?X4D{~u(d|TlpI&^p_o52D z)S#hx$8~d2`T^_7dBRcgdyGZ5=-$&_16oE}w(8Hy6`ZH@NVl8pEF%M$qY( za5_v|lJ*K|0p7#|baC4PJT}0H{&!#tez;~K9>!6oFZ`Z}pFY-w%HM4fSuZo3G_Ye< zRVZAnl3Sn9he{sZg-?zzQC64{{=#K5+)0(9H#s}g7d<{=8H+B$=lFW`&o2Sya{SQy z8eixiVbSw5!DyL05B`PZU@`l5fK)govONAws^v~sZ$`*}GJcEwPEE6a05=nL5#2Wj zR+gRN8u_b3{T>hC;vJCrw-kQgFGY5B;<)F)4>bCy2Q)(3(Z<{t=ygQ{oOc~US9H$7 zXNzQ!aX2|Xfv;zb(2uN4=uy7Nk2z8RDOJslYn!-OUgij85abFvqjRt+ow2Ze{y*%p z&OM4qJPD3ht5DU9Bv|xQ9U05+M^UGCf_KnyGA&D#SGp1w+j&K8I8(lk^Zoe6#G=Ah(?1Qgnt0q%L9_`f!t#w_M}i7b!! zi7`k~I~qd%DN}iOO5x~?81(ULBt&o@qgA_Q(NT#`aHnMOfJ^_V?U7YzG&UDJMmHhr z4~Ag3Mg=WUtOOUQxv<>+Gv(&$OC4RY1C0oZM7Ecuf3@-26&~Dw%PE+fW(ViXPr?Ix z1xmJD8|IPIuzBuT$g{u{2HV8&==Wc+Wzlu~U-H=s8XS*#2@calJ-s%buSAn zE?dKm@iA(NsV7LBPeb8{Qo!UI4~32$Le_K=#8$|lkoy;~vWP^H_0sSs3F6j8qrc^y zFg+oXYDqc)wH9TR;r{v1Lk;r(`d;8(e`*aszNbU-vx6Xrk3z~by5NQkA7wV?K(|o= zTEdi|Undjb^y*A>qd692x?DxJ+kc~S_*l$p+TM2~-mLus9bUT;|9gHS|IaRW{6K*; z?6~NS2KRX3wf5IQLwgk7MczeGoaOkui0{btRvmO4UP1RqDbTk(Q^D-kb@cFUAH08z zM8?r6e;s=`nuiWYU4l_lK%b7?guAhE{4^g=;MK0BFlis`m%tT1ruajIRWCO33sJ45 z$6-!cDzc2)1pRGhXiil$`e)$=6W>Il_6-lP?c+R=_45457JS$Dcu7)L+k#OAN3;avBp+l22 z@pQRj^ya%NeLYeWKP{t22aQ-`!!DOZmd9Pc7m)jW9*FVkf&4W9=KhbdBm-9{P!s0s zFIOW^pO?tfsT9`vYT&-l2dOEF;V^6VckXzPIGy)M5|{8A!x~Zqs4`O?KRq^piVn3? zi*j#>jALqPKR4o-B+9Mb$*uA=L*s|1!`asu+Umav8pW<*iU~I8#+#F<2U07&}WtWW9X5(1YhHHzOl{GOpB{ z2lM5;@s)clp=R_QJn5@Pmpl#7leA@cpi~4twzL5rc6gyV+t%SuDo5x#?s{A=T!Z%V z44^lduD}~KR?+vrw?pT8J(2Tt3JiJ$96`;TCEWE$l4nYnSOp2~Ug(m8F zfVmiL({&5(O@5Aw+Fzm^>uRunF@&ljX!!joOJuzyXuIPv(UWMRZa<#(a*)#g>W^=G zA;EV|md4+EaM9uC>eRF=I{4om4!AMX0j~L_C~4Vp+~nv+x-HoOua;1xH+RmX^>@y~ z)g5@Wi|s8~_R36T9OOPHVkv$<=^fQS+YN6o<{?e3eQ--j1vp(6kR$j5Gc4us#Sce-+;90A4Cs_V3H&3jPDi=@1|tgYV3t_HDFG_!=1s!j@&~2VL9>3oQJF6wk zDfC^X?!`sY8b9ARZ7URR$vNQ!^1&^XpX?^6zA*_IwyMIJ2N%(y$?mAZQ5w`3Nmy>2 z&-ER$5&3-iD8Yx4MkloH9S;g_{GhPle2CRMM0LkqfX@r;`LmX-N9U!Asq4W$pc|1?Ow=ARJqHVfAlQenH$sD=4|+0M~C=qphKR zP_G(@X6UFuqiYW`rDGBI9ff`1a8b;AYdHOBy2y6xo$Nr{Z%{>@{&m!^%Du?(X9xCT z$~I6t_yi1@2I{5lJ=ETO0%Vgd(cr^X$Zf+`nA5TVsSjpDpk_Go;a|dL=GnlZy+P=5 z+)i+}NJSgdH;F6{%N12{MtT_a1u&TT>8EJu{Z|On)<$*tp*Zi;25{RFOP}cdO6C7e z!o>KA@TLq$yFcJiy<`Hla+*E%RpuS)5;k$`yP0517HohM!kn2^gQLju$dr4GeK42_ zNslH`8!Bc&7E?hj+joLH3L~EypZe-%y-af4QmM4k#-m9L$5<(P8;kxVXFWWGN@lS>Vt zcC!n#jO!z}6Jr>Db1JIoo(2<|e39AGY3PpEWLTg!%AM^zhUwhV7g;X~h0?I+?++<%qdi6&Wf3kiFw)~R>J|Scpc(eMD zzIqng=qd+$tX1&Uu03$-GYPWM-zde&GI%yEP4Ae~0x8`UNLO$hB_25k1>JX%{+8|F zovJ6YUYLJhxc|!1`8GxSxVFdJ`Pwn3`Id|OIF?`hn@ZjH@mDJ3abEY%;cL7%=3Y#d z!&X02q$s@)+~}$0jTJ}kHm)xE$k){`Zpw?4;Lj=I^53{BVRvUw5E)0n%@5EnYYs6v zxo}eQ2Ryqihuq6bunjW{F=2WG9h*v_N4_f1iUSa(50p=&&MPuqDWIgEXM%O2bE*_9MEQVJtk!&sJ?J8;-4kO^XdUiuix zF5n~oCG`+d+XlzoZcw&W?ohASiCHf=iq>Q#LHN-+Y~I&Z=s?C{xW4%q;_GQ3S(kE= z`5}3<7(c(-pH2?0#;@YRs44#xj(2WHbsMMRtyB&c>{^6{bS}cfV%OjeF*xp$I+K3Z zUWk`WOQXGbTkwZplWDc5F?8h8#rVgcK{UO?3BT7UFLFMJV|WOPYU?Ny?GkXk)QBwz zPKN@OKzO@J8c+RJh@2d!(^k@Yu)jnMFI(<}MG3!u^5Yp$-Pw(1F1!x?lbR_P*>k8Y zsU7&~QRsfySH9&tZ;|EEMl#si!Izlvjr9%v4z<{P11*kK{zLxsMrS@vfSSR0j>El1s(Pa`tUv2V$(&NbBsc4ceD3dR z>%tU|S5VJZdVFCzHHD&G`#l)lU!1+DkRBRb~evv$Vwk0$xS_|^-c7YX!2-)XqKhp@*_QjWf{XBw^+ zYDCYnD&&qRwTrA5Mf>ykIn5$u8oUhOxby+``I04GQlJVM!af5h>%FM&GmlDdG{Gx8 z?C=YQ)!2y{o3R?@+$**jDCl`3SYrDhtIzpH4z##d|*QVb#x}V z9#qYq^J`w6MpcvRp#60-`dj2gT~L={@aKFuppt;z$@IcC;u!O?xE?}Ruw_)|e8WiU%jrEpIr&h1D z6% zFCk)T9U3@09{eobTd1}>&Q|$o> z_|9t;q1!_YWfF1V8m^1b&Ck@Ow4c~Sou|+dcb@9>az|rwE8va7Bvje118>t*(V9(D zV0599@J=d@t}QXfUY8o8+G-z>^)i&0g_r-5Lu#L<;|FOU2s6~cho>rG>NCW^{;D^1 zO{s-?qpOC0{-%vzdwdK_F!|0Eu5kj%aw~cQR|l7p+<{KT%hKxEnz*#A8f`~Rhs~85 zBI5{=>4sxv-jJ~IB0Q1&1WKn>xUYqMTP;IZVLbB#T6WTh-m|(DwoSIgx9zz|X__8^ z-$)wEt`eiijpXnJQ=Q?&*~{olxiUVc_Xz1d)T+d2nZ2O*h(9?Sxl^wn&jC-T0!+O=I zy5b6$9ZUa9CHo)2~!vP(qQS{_V3SEv0q-@1~2n*n;0F*pVgg zx!d?&So_&wEK1NoaWMmw&>4qKDinu7?=HS-j}PYat%EbP_%?O_^Fz$T#s@1XJx7(> zy~Vy``VZ!M%A-g153wiy(=h!+fAC)# z2zh-CP$YH&%&b$;+(&;Pz5XLQDb)%GzX*_XNH^*VtN>r}TWES_3DnIEL!$bz#7AoQ z5!rkcJbD_GWsK2D8)>}pKqD3QcnW?l?SRF4{;R>IcDuIT$iBbZH7BHvHdg|m4ft(vL#OMO;HrTaz&@}W zu1#n}4)qv*l|f$j9SQ#0GJCGIbOdY#9WDxzmxt!DEn`bA>9HoP*STt6<^0#jxsH z0E$v;2F*Q3(cNM*q}kRXvOK;SO5y7#rGm-Wc}nTS1&Fz4igYsmV%^o>DBgWPs(q0^ z>i6u#4Emm7db4#Jpaw)fAbpn$7(wj2DWf zqv3*iFd9~9fd%XSVDsf#P@dyEWK%GNWi4L>AHsNO-V{aHnI?t)&69@v2ZPXzlZt50 z%=eg9%Un#yQxPV-6FvWtJ6{HW7fzME3(7dG+yYwX z7e3PhdYiStWI{S+Z}1+>?E8duh)T$vNFlHLSJ9oDr@=8b54jy5!D=Ub7Wuy3Iz11T z%4|bZlwBcDMjK_(y%6*C4)v~XI*z8jp+c^z(PDX(C_1bWI@fqY$+#qv35bWYlUh)` zT?14o>_9iw%F#vd3vf_R4!!WZhrJUE7TJG@je5~<1MG2Ls~f%K`(IdMpGo^~PlwAP z>*>5ZZ~2W)!hQAM%lRRTb!c5of!PMN`^sFyDTq@lT{}Qf6Q}`Fa z+22TI-z|}Ox@OiYYEHT9<}E!6Th7ScWTqv5klV8I7Z^dxjEvRi8oOB>dpClAaa&`wcg|FQMAIb|_n4l+M4 z3!zu0pnE!(F~buN&~k$^VN7!Y{wTyi(YqtUUyv~6UszBC+25}r%gO9Kk){W1?84lD}DXO|L z2Me6lj-B(?LZ|CxVAO33_x*>r)O=ZK_^l_4$Th*#>3=FB^Mg0E1Fv~F4RyOt#Czr( z1(j*i_>#Y_c-!(>c*}D;`gN!V{X;4dcQ(_(qozBcl&iPkxkCs%-a3v_QhH%Q>2L_T zW0$Ya!PUVS7OeC@H=LrOHDU_)z?~nIdrdobHFp{|Qx8$w+-_l2DLfS4ua2DBPlzm! z3-UZXH+>q-)CS=)0nX^&rG)LxPO$Acg7cwwz6Z6%S9AFQyVYClKe zN{cA0=cEe$aXbr+OL=0;p3lc`o)5>r+WdyYeq7TI1_aM_?XIs?! z^2YS$$jjjU#2Eh;r%ta>o{5{?UWsC+7KyBvr^&5YUn-Y2tcwRDb6fh4lNDa|U?M%y z{WSigdI)}3@1$#|%hJb=PJ&Gi9DIt2E&aRK7@uMvj^vhm!xHP=^qP>%$fi9+3rW@r6-= zbfHfXzOA1^Mygr(wTc|9<(C&;x9~DLljeZ+==tH6$Cu)HCNlWBwpVCp+6g>ZJ(0ds zyd1A(=g`xl1L+&?T$~Xsr?>6?2MiK@4*34LNNlS3drD%DIG0{M6>WQG3aQ~*=>DWb zU^!ZkjpzyclH^aKybGtXMw1D!OZE$OxC>$Sm#$u6gItz-T!2e1#s3-O@srGZgU#?-iisjME#c29Ox& z!HoJ0^n#|TUn&`(>=lh9%rubYkPGzQibJv$l_0*)7|0F6XGMI?q^`mhVjFE4u^3J> z>*(=RC!F4V8_7JoioY0t2^ov?>CzfMB*>3FJ7fgCoi3XUw~=2XQ(uNhT935_`}shROX3fh&_LquOEAZs<;1w1$tkhCR-oQ+i+sM67F~yZC`&VWaF`NSd3pt5v!#GDZXL9JI zOPr|}W^iPyia76PsBvbhF65L)v~Zj)oH@H)c5`ZC<2hr>J)9x6a?aqMcuq)uEk`C| zKc{zQ7-!rym9uEs5svYs{UY0|i^h76YFZ^{mqH^4lVUk_qyISW76&g$lu*uhu2bAb$%3gYjPvE ztwF%m-TsTKcJ2b#cybc=r`r&BMbT026PMN8j}t4o`|)P3=BEac|#o-f0oMG}3=bA?WXWzz9 z&bQG@PRZ5H93~@_qgHc_leg$J=O#Z(WO>}xc*%(x&*w}S*~qDT+Q^wKKFEnxzsoVT zi|5AFj&pjC%;(w&D{;q@TsVYD3a3J*n&am?pX2`0m(#l1j+5`Qmh<4S5=Yu{8z*AY z63%ds52t7A6_Ig_8|ZO0@Fec%#3NjvzfoM18-3i?1LK^O$Nk*;ZHb&=ZXoyH@FT9_ z3~lb3j6%LWr!FyV2R4 zi7V!FstZ?hRHP?yYSNlGnUmx>8?Q8Sq@ovdhGy;K$aN)iPBu>D#OOV>wY~G*HZpG= zM`Fz!4)IEYqi>|ck@S+|e75*un|4N#!TEIjGTW>}m9|4qY1=>C zG24Zn#kM~RT{$hwM{M<_hizp??%Mv-v#{M?zRcF&b){|W!T{SDq>k;7z}EK51TWjB zn+CRLKKt3~Hp{y|BI3y^&*@ zV9i^S8dRiFNi--8Dh<*k-+BLj-&)^V=Y7vwXPqDC&$afx?mh4OrVMuO zrQ|MNrVi)CQj>o~QX7xXr^;4UP|3BA_?CymAA3A|eE}Hs&V%}914s=|h6<@znDZ4e zUi>r6-6M^+WdFgSVm!FCPlN|vN}!%v2F<;tP)(;nkNGa(-dqWPL=M9qy;$B>jsgVi z2;^HH$&I^!b@zsbob}X82M=({{Qy&YIsm(jFsOYG%s-n4#$oFCX7e+u-kpYlq;S|` ztO^fKnu9}zGsw+x1!tOu^~)WhVM-O%^F<9Zbyo6?LtqXUj2GI2p^hs2o{n%!_6T?? zyo6br()csu4-_2KrqyVN^p6 z%mgOEG2G8Lj=L()Vb+IA=yr^Q8G@(bQKAX9t(=4oW4;*C)eBK?I-r#C$5&&~fU9Gn ziz$L7Uv_}&?|gW0DH}fPrNGQ>xsa;2AH;Ocf%Ogn4X;|hajZ3GD2~4YY~lG>&Lvm4 zSegbgJ~Lo(dmab}N<*fzI%Frtz`clDlw*81RqXzh`aV=ag$`9xV0oT8!?{IOyx>ww za~i4W`}vfxY$GLRb(?RV9#)|s_u2&564gi*We5Tr{+XhC+@OCb9eCSTz=qrb);AB< z6xLC5dK#%6_BSYR3pM!QBm%7i>hR><6YAKFPU^R=EeQ4fq`vyLQMW%|;Ty+;H~x@O ztOt^!5};xDi*gKgg{`;pp)RToG8PHrgga{JD3%YOEnVRAzE9NFkCS1e?p#uTi*CTrTyZqfcmQqR%i(6#W7y?X3yzId zeB%%(;Ps0e)$xSCHNMx-z>wu0`1|TZaHv0ssU-xL1^M6we=jT!{samJqp*b*#9sRq zm=b1;Dt}~<8?B3vPf4Npdl8)LIvE92gz)bXVZQy`w?!{u9a#s0(?vkkcLz-Q6a_;8 zr4Sb^j+edPLA03#Iy_ZJSEJ3))nf>?kLE#8k1>1=i-*$C74Yi#M3~%e0uu#yfYVfe zU^aZF3nOVriHZoC^Z}!kEs<$0KVxV9Azc zxNd6%CX8>yrZ82^^cw?Q;E#IU!|>*7H$0M(M#+*@_(p0a-}3meCJ9%0ZO6%08?eo5 zG5$Js4s}dqaLtYb_~s~$lg!fbIeQCLCclKUN*bu(rj6a;hx>oZW82(eh)#3Bkg~V1 zcflA0+V#L14+(VYn7}uV5s4`n@Wlw%TKeOd;&ja0d=wX#+<{Bun=r4h8DwoV@yvu6 z)J+mXy;>bCeQ$`-fvGr{?uTDDO+)tW3iMQ+fe&mY(e0!qE^Rl&S+RP224{ly!IibX(4SukvGT>#K^bAF7raBszMBF|yglGk;!o=2Rx8laCvg6K zHB3J42VW(%K*8rQ{2DQXvq@qww*+BTqXYarV8b_#-{d8JGnT}Y{h^q(xemCZTujTG z4J(X}LGc-12$FDs#S3&XMoAU@JS>p4pNYz+F5}puwHWC<5l?2G#7!^kvCu&f7ySa9 zUT=##Y-jMz53_}{pt#N+*2(XtF4?@JZVWrZk`5s_FnS7>yqXIFACJN&t$Mg+bcnkD z@+lSe>jy=}pQ0Y!eoQ$jKc|9YtEfMI<<$2>BNV;z7Z@pAr z(}Xt{YruP?6HcDE2)daf=uOpAn$9)QLeGH2m|*DJH4jpJr$NEf+(Ldog_KcnK>M9)ga^ zChQc_Lo#lK-WqZ^c_a=zk0^tc2Y^cNQn-~J2SZi+V2h3!Xih~~V4VVUIqq=glOmXh zE$3S=QcKUl?QRZ?oO6bA(o%5qQyLTx-ltv^c*3tbYpC~(g|>h3urv1;C3oZ{WqkY)gj62E%okhKi~3*Tb7SD*A8KJp=a?Z)v8qv{a@|iU{EUM>mu5L#gtat1GiLd0gt0s~<&5QlPR8<8#4$^$6PGNH zYu8ww7(HwmF#De+zjX)ahoRVWstrw7JU~+Z1HDxAtkPGX#W~MJt>!!Bp^j=Hj<*iu zx>!HlblM9qehtPQ(JOFpy({|50M4(Ez&6#{__t3JKbmOady0cro*{he<=%mEsJL(g zEaTq7{(bvlR+un$?=^*3HyW)^K7gUs_u$dpLP&Gn4I51i!J%ItOjo^vV=vCY%cf}f z_&W%MAsKGnT?*YXhrsrj0mP{~^Q{+4r!z1u|2jOL_6cUGB!j1sBTh}a1WS@^vA@0- z#23ARMb+A}A+1athl?kI zE0YEpsmmdAnlD&=41gbB7r=wH`$5@rKe#XCg5{UZAgpEw`;;qT=B*WQ!GPxzYhvML zRtlW?!+-wLB>EM$UC)ARmgVqjI1Y+t$YKAHa!Pt@5Gt;RAYk+z-~OfhVL49i&%#KhBj~@U z5HBZ7TX~*7i_dpjTHT%Gg0g+(XrU5jrF4D^VxfSQ#x-fHKOeNM60WwRzgr<5`K)R6 zWM>tcERVzM7Uxlf60thGeFEQoD5~cp%&3`xO}Puus?-**CgV@Xe2? zq6BbwXbJ0oPNB~AQXur+1KN%mLQQrW(2q4?+WUJT)~<>Zcb}&&7HGo!?kRAz>>3rD zqyuf~>M*=f0dVVE$}49kOqLRWwTmB65$Tio#$lrAi+%xOct!ax%%ko?%939&ZEFUs za}_}UF*&>(mXCh3E}+V%JWz5F#jU&Lv1N-a%72%~NYhvFn)?ZQTW>(PkPI#g{R?KE zAAs}oAKy6KoMcgV>i~eT5}NgjVONb7?){~XrgslvU;IY&SiTc4t{jDmj&fM0R1IY* zo#3u>6YeJGK*oklc&2d*BzDC@q+KOM879HO6Z!CEV3cnh$ChZo>sQ^>;xj)f*CV;q z%3u#TeYT2v@=+50KIo-ZSihluhs(j|;%n5}gfEoG9YM&>TMkK=Wxz$?0X1`%BODC= zMZxN7s?5BfGMx99YF{eFH;$QoF6duB36r0ipk6w!mJpDDcC#AcP<;{#v}Z%HF;5p% zI^K>K;8or&QN@5DyLT%tSDb^>^|kPgn-4Z>Ova}f6YxhH2Y+mHLZg)w-~MHCe<5`^ zO9!-iz2N6DW7wdz7F2|5EoWS4rL5yTsA&SLDS0Cw>L)LcDtc*6MV`{9?C*|IpCV6F zZ%S8COL#TImsbx{Gp)_2Q0oH9+j16lTT-2G`yu%PQK91m{7&BrGt8^t*os{EII|zV z(Al`p))7a`qp-I{1+B`@!maw<5WXoLROk@U`Bee(y!^{&l^+aG@`upRZBQ=~3s*RH zkO5tM>t(C+eLVU=5~WmT;^q10LE7X1&U~2y4=onsK-gti%&S{zYHh?cQ*m?G>QmWeLm@r7E&}WoFa*_ z)hE%%9dOqbH7jxRRCM&dfFpmpaoPtzl*$)H@9$Emov{xkN;0wa_bybR&2egrE3dy8 zgVC!ZP%%IW&-3bj{Ki3^J7lmtp#)5q8$yrJMbO{07ksN1L*m?bFf;5bDBJ>UzV3{@ z+x+0q9#>GEItP6B5K!2B7`AyNz#!KO?sORgtyB!3k8Omn(UWkpVZqeIj&)RZkrX8pFHik>tH3u;Xa2LbYHp7}5xZRMwE7O;q=l{0E7qgP zwow$(PRH;)NmzOKJqmwI#X7l}czW0b<$c7hPUB*EPYLj3?gTpovqSs_>0t@her(R=0(Si^bq#Gzokq zn?U&1Mrwb$Al#n+gZi-l8}&lq5%ojr2bGl|3}(T9sbQWSk8@OnNs!Z6=@*(5X<-6mBrq*Ki_K6wkfr=jH1CeDk!haRnZk zbq%)S1jq>C)wnkdf$y5%p#CEVh5BqUJ2MJrrO!rBnU%2PRukNae+GdX$6^1XA{ew| z;GSk2e9+zs`LjMi+KyE)^YlJ2w;Jag$LZruSmS7fWvPqMZ-)Rn^i<%^Dd{lZRS&gg zEw<^XQXa7S|!BfRm-83XJ9)7mxo z=7$!XgQ~VjFl5c3Bw`CV`ZfS(HVZC+7HGKR4J`cf1?~qaVYhcY3{3Qci3irfy_KtB zzEKjq{Js}{`Y(pxa{^%2g)NYJZz-5adBVS!{MW}~68C}CIT85tR0|dyd_*biPKP_4 zrzm2h4;votqYQSRq4M3sU`)4((u*mkoQ{=HntHOZE_sL==K1>d?}jLMZY%Y0$?a_g~Ch9;<>8I-Igdu*56vQp;q#hhDqmFO4;F}*K$p=BgD;Nx( zo5OuWNl3}40l(^daM5%Qw%%63u4FM>arFg+NQS}fse{z~RyEk!XAjx>;UHhX1TH_4 zhGW-f!_0R}pvv6}otWZgHh4s;;c}@Io*#Hl72G@xFZKXf@a#s?L<5wvON6zKD`Bw30hF#hflDbj zKzLdf%zIxBsZUZta?*ZS&~OS&f6s>GA{V~pabs{Z4E-vA^GnAq1+rp+^Pw7)dM?A! z=b1RHR}J3j!k9%i(0OXQ+Ga@Mu zsH=1DP){50Q{SvdsG|#BP=6L*qrNgnsVD!$p#FO=b!E{Js!jS1-{)oR!G2IPzXke& zLvXAp9S)XAV))hdVEk4Vj}FRX%tc8QyigD8E(Am5V_pp|Q5cd2Fuo1(lF&Nc~X(4lBx_FGC-fWhcVs-eySek%ZYN zmq6*~A+RtuhdF~QV5T>3hHPLe_?!Kq#03Pw$v6-?%Tz$cafphNQ3S(N_TVG$$v2Mj z7iws^wE+YlYCsEH4j-#BVL+@FxGlk$c3%@;H;3c?>5k}OLBSsV0=Q$yh41=tU?IC2 ziURh*@9ga`{z4VH+Nxm7f%#D37YaN2I{3yh@A58u{@@cl^?nKJaZS)1=!ny@H^LT! zFkF7-Al&!p0QVe!tSmbV(wGTnsSI$Kczx+Qwl__cX7NY%}6*%xW1$|~HqF{j_{+8H`;{q}$ z?)3wD(uDDryboq{Zs%Jbg9XQtr4Ws4eDSEbI2uG8#jNlwFuJx6SDlo>LeV9dRI&-* zh(84jyDGTZ&FiCWHpSmV6Yy5lEx4q`t6yn$1C{m?id@FwtlJq_=*xeeJ)^A|kG~AT z#=j)W>VBGcb9RDyp@Q!G@VBP}Cd;D%%LED9YhH#|JQ4 z{|TCEZ$sfcHQw%syTKI<1$$_i;ANR!;_l6D1&fdk^?{?}R%i z%;1!6B-H=ozu(ZLRsp?V%ONN<5&FjpVQiZ)QvS0*;<-Ft?{@jL7}c@S)zmEpwOM!s=qPmsoq z0o&k0-!_rxiBvGJ8 zgKr$}WyWyp&l^fQcL6opbcUJ}@QJGZIRn}gG9iPPypL*n!a|iy2#r2ZrF2Mw?NfE2 z_bS595@EPai9`IXacWShmG_?E3FSvPHSBNmpX^QMCA%Z`n18eY!>!r zgn(3eIv735hQYm>D4X8^+LI0f_jL~#nPkD;rKxbZzY+}ZXT!q(qVBNKtr3EFY53m33qR^FK-RJtS6hZ* z=9mGh569t-GZq+eQ378*4n%=J0XVS5mGAf?+Cm1+w)DfLsN?Wh{W^@@s{r#Sj_6*- zV(Q{6C~&0*4ej)JZ>y$5!|OvZoOBs}avNavwf#_BQ4aewBjMVRE6fS}1X&CM6sKwYeE!YOjo!Ec8)a!4;HM=0UK( zKS)~*Kx%q54Aurf)LGulc;qH{F%Se+b-6G*-3-*b2;VqX#MVId(;x_3Y7OxRmIA)# z-Cc%RRNM27qgkl}25L@2mT(;S1f2lEQ--)XCm%8z%+YnV9xRQ|hP)SgIBCsV zc# zJ>@Lyc&CdwFEl`Oy#ShDnFI1m4#I3tF_buT1Y$xcv*!W1&IZ`CmD zOw+|hr5#{ylLRSu4#7l?_fWR&3AoCZf|BHUpa;vLqqqnpF4yq*yA=xGp5zZ$cDzj-%^KcPZ~E>W{RouIdWl#>5`j@mXs4svatQ_kj@RFk;?#C^U^ zDTdec9iQ$Nlz~07W#PweS&#_RfaFV&P&_mXmIa1@UIGn{8~4Kc_Z6@%?guq6>6 z*TJB81WeVmgyGl1uyM&|sQIA;-@V7E`Cql5Pi8JidhOs_9y7WpTJ1d}YL$0L+3I!= zuV+~5ZZ%=MJt_y8TU`%ahK<*b328+&xr}9d+k1n4@Sle&7Z6POrp}fnJns zJBvb@+4#$=6Hm1_VW0FFzU^tqkrv8hIhXQ!Q9vDlI!fQq1vEFNfNSAJ_>q(a6)Ms2 z{Ml+q5$dJ%p6#Rl%(+CB@4G^6{nby2+CQY)l1iv|=~tbW2@vP0kBgw5tdHOk9K+ z1}A%OttVmXnluPbTMKXB1VaPw+%`Qmdw8_{Hij*&!=b^ucrEt?dgvGPEsrJB{-Ky=Dvn59o)YMA2Yf}Zneyg#$M*~G) zb;3juWz2H@0868r!EpQ&T)kESGu!yDe{^Y7g0|2XICZlEf;7eO{PJ+zD5Q(pOdjqL zsf6(rVpy`OhPMk-3Psl~u)5X>ZRMxn@)tdjB+vm4KdkV^#2etZ@H}igbr)XzHN`g! z|NZQXjniSfoe!9?sbCzl5Oh0_!PLZA@X0A3^tQx7rCkwZ=$FFYVi7oWLlWSsIP8%X zg)4fWsq|TW6y5TY`YQH-(%(5oO*i~brE|Yi?aiZn+x6t~`|wv(4Zr8wVDU}`OiWh& zPfr0UTb=R-*6UTFB8 z!Q10YgTyCge4pFrl{cvOUcT@*Y!R6Ft_K&(GjRFKE9&w^e+U=bPVIl*O0~&*gBRga z3mQkM5biLQd$y7q=FK>)bquA1=RT&EyTwq-Kju&>>LJvS)fGx&OE2H@uyCG)%M=g6 zxrZ^Z{7($D=EU&&Y;CYH(h;|ORY8|mMwpP~iXt+3U>&g*(nS)WgJ;9`8*m{rH5cms zhC)tPH2i*1067u+AY`vCY;iixw>*5BO^uW& zNoq-EH>DMIo_aJ~Nj+$Cgm=YCAjocouGYP9y@j`*E3g5IVy8jyeJ=cV_JMvIad7H& zgPh@=uz1ZrzHwY<7Xb6#2$J`RQO(9;&@h+`O&3*Rh3ySU{V*90MDxycM=eYX?xV!! zNdi+X2bKBPD7Wp?V9?6~>XzQ8R)xyKyABS#%zi>ug+8H7cPR6XY2g_`Ymh!$0!iO=ut+llH1?l>>6R5>vr7&yEExoLQ#I^*(+knr zH4wKa5AHbKhS}e1Am||fadP54f8-jKL*UP1D79z+VU_m~;~NMKf$}I{k^|d6h9m~I%wGnEaz4EI3S~%Mr3ND@_drVcAVds0 zLV*Bp)-v25)WvmR;WlrG+^xae6F1`<$A9i085Z4s|G&C_1pfE?M+5{kX8#9+=9RBp z5nj*cKVNTmVcw5~#Q)pEkr$u^R&H6hF36m+FbxaY9AavYa~y317XQ~DmFRoc%f6a7 zoJqb~-+B0x_4f@L4KuzLH4-r`tNe|ojf#`it&L|LYE;O5VZBEyv9U^7qiOYkM`K5V zXJhS-rHx#lDr+OoW*eI&0yci#m#n|sU2olxW@r=U^Rcn-you$B!gKZW{>oTiE6%c6 z^}w|uoSd*KJ~YS1%PXgGGpEwJR=2Iuea~f^Ejp*I4Nvgi9I%PCiEVmd_2|S#>pp|t zM(6Wy8{^!lri4pZ8YAxt+5F?AS+5YyXk=!^Hhgd_vewX+vpHB8VO2AB-ugnGgiW9N`@ZfA4&R7#`s zKRc_;3qw}R{8O!+AB9?5K96tAOsQ|QyZgi{&0M+3cAiC}2=A_S`n-|NpE|3CsZAC( zGk=d*O9^M&+!biCJ{8kxWqE#*P2|KBn?H_8Hh~>7HlMO5Sf5+q&}jYko0WFJ8k<$k zymzG1~Dylr+2t!OBGI^8jE0J zD}Gw9E(x`A+kdsua%Y6~^v1@EnIXA09+%fyYbW^IJRJFDeffmF4NNVxd9M}TNRDo7 zQV5f53d*-^2w>uE`tFG~*8QH^bnBx{Q|n#PCJzxitA(d|cPhp`wf<-^+&C|Cn$3T> zx4TPrjero3ZM^UQk9&^)H}|amcmCgtz5#2?Yr$yM8+Hm|&U#EL1M*J0+&Nv1SXIuww4zIVhQyqTaS_oNgnc&XbiN5$a6em2s1*OZ~F!##= z47(JET@Ib>boO`#4;_MK$QeulRpxh1)1gyjb3C{RsLRE216{4Du`X!|&K2u-z$xr|Ic|P9Kl>{uVE2EW z0gE|~w*L!+_i>V}sgexiSt>!kOxsQdBkwcPO*%|!pa8>)yyrN@*>ew$UA7HQHD%}Q ziX|~!`JCqXcINQCb1dDiO3%KQ#!kwNW2z!=Fq)Ue=^zKFk)vOC;MON0_VJy{8lSmoXrgiBO zMr6WM#_slYPSo%RV$}^KY3CSck;-{i=$0P)dRUA!wwN%Hszc4?LODbdHV{t>dAfe^ zJ*S)!rHy7}Fnj0A(*;Z2=_Oi@^q0sm?vQdFb7PtX+fsa$yGhl(dCsza+m1$$oO^#f>9ZT;nF-BT*}lSEOy%VV%{P@ySPbYUn)`Ig!E^TP{h`lHkAf`g z=_SMt^v+-{`WKTY6ZVsElO>F0iZaW6Q9+uX$&&|$Kby7vfO~Z3eMJv-~}b#77d zel{vCi>!Lx#6*6(OU_I+VShg~VQWeq**kl}IDgm(wrcfjMyRifc`2vFy8jcPl{`wB z?-|J)E%9*TzKNomD`-ZH{23&NOGQr)4v>GJTBSwIl4sZM(?m+cV8(bJ7|A zTW;*$2oZL6mNU}8zzX-MaE}H!=WMa z-F_Qs8Q912d?$0{%MLd8O&;l+ai3Xim_=VQ_(2}!b(8u~OSZy)7c;Y_hDi@sV^fvm z83|1r`oZoKjKK6yjM1}b=EkKQZti^r`s@5tHr+o0S=HII7`282WY?Z$%suN~+c!=c z{+6RGF8#nB^7LBV?Fdag6`<8>cXBp^Uvx4y$!6x-L_yjz@+jZkDm zhgDdUI(PD9Jh*2x0`KU zAxqDwwqacYjp%!I56BwMQ?6mfEJ5h~kf4AMH zRI`k1gN5uww=nv>Q!ZI|UWZxm;2NjRA(dQL+D9%dJ;OY{Y{=bOEKU^mzUS7eTxjMN zE+H49?~|(Hwe&O<3rDyLJWou1yn6v$v%!NKez9{Ii za~5}VlKM9@UDIsYh&{6OvM)>6BU?H2V~JD}^~~EAo+OchUAoMqo>N?70}1wK`*JdM zX0Yuvi$O9FI+6ZZHI4PNzQ_poE3;*n^O=CU0NUhfG0AN_&SW1v$xY9zBArIUEPL}W zIlfDtu6eLSv+J+u56 z_Y!9%qvv~ut0B_O84RwmaSMLf9P+%D1fM@iBK%KqTFirqL61FiE{;pCtZpQ|i-x)H z*=fw7!4kIJ$Bs?ssC60Z!|DU!=MM~oXuOWZM{G5m;W zS7~9M3P%w={dh*J>NW9xv5tNVJ)C@D2l}mOJabQd1KG4>HocUi&1OvSC9Sdz8~B|NM?45&OsgR=9clLO(r3iw!+Da?RLA)+xQ?#5^oz0h@w++6FO?H@dYH+blflHa?I(91 z9%OAljuH1)ZyDKfdwNIAUZQm_i(dRMk`7*^&n!>uVA68V5I>IpnIpE7Knk!ugT0l$lfgoY@vKnf6>YPE=`G_H4*B znr-^U)v!9rOg)pwoS%1yan3iQBZAk{c;W}sXp%rPMX#6-y>`sXRauNku`TmNwVqsC z5lxDYU*tYMAjyXJE@9_fwxi$9p3e$yv}Mm#KPPw0yO_v_$#lO#2)S^ukL-KnLT?)1 zN0fDI*=fxIjLE1L8x+7L>G8HiH?fvTW-q6?kxPmFdl|NTzX!8&JeNJMd4RmR;>_8c zXG{-qr_-x_6xkZJmCUEJ?#vIC7u@&9(zVW88R0;dsS}9d_QrBa(l|>5y|$AhjeCjA zup}*8+Dck%uadkYBb+aL#+XhkXJ(JxLh>Zomz@7=$}M@goZe#lk@W66M*?h17-_?L zCa*bbX26 z1G10Fkf$@97Qc^4zM)Jn${r;L7Yq>D3pT`OrzjmRq(P$O?U>KglKFfMN82-v ztM*_X>7Q;)x9vz^|8zBSkE9ooy1s?1-%2NX^7fhZ>8%GzYSD34bTP|pu8JV}W{KRk zT?^^4l?rrJfeka*f$V6j6!X_RfmLZ&qz`{fX2k7E>DZBv#93X7TwAY9r&X4dFVYJc z_jjUf$WaA)!P)y{`I8AOr}H@}ZmuA4C(DRJR1*8-qYzoLT$BCe=1(i%5Tp&(?`PjL z(@EEJ723GZh<+^CLTcNL*>Lk@Vlq{l-I@|j?x$T~{I~Rwp(E#*QygAg=Qp2-A9&3% z>&YN*8Yx!OPlb;DaDlY;>d^}pd}X$InA!SCJz|or@|o|;ZjwW6Ka+W)gAhq!*3|SQ z9lCQJ16SJ_#dH3|Ao3wM>*iJR^3)i)lQO_@z3_w4vJt0eSEn-Z*JW7Vb?oF^jXfin z+D{&&`VhzFEcWgybGG%vN+#~hFEUx!jkOMRC3APqWKV99Cvr#ck<<4B$dUbOY;Kko z?Vsw*207+1?MI8rvVK`ky9vV;?wm(=rpGY%6!)?O0xrVSwacekbTu=Oi4x-D_K~;JsI?! z(06jUYu%N&Lu-+~pZ<{>a=U>v3yIUd&V)0f&S4ji7tm9MC5ZIOt+bEW4RSg%knr}u z$X-Kx5>oVtxojat9}jY6zYFgnsUljeqrzDxys(S>O)TTaf2`v|ToN~4W*(VkG>aXa zkj|;TsL4omq>_D`elqg4@43@@0-5;V6&z9RE>2gaH@BZVn?C$InDh947}0AgC84|+ zEOhToGUy=By6B#vR|gc(KCZxU%XV_=SmX{!a8EIo!fv*!*`>ntPpb577-KFhOTinPc- z_oWLvC*Tz>Nvwa`P+P znI%U~kfI-o^rTW#R;chQ$G9?&cpb8269(Ti^~n?2N6(is{l-}&zBrk=y>co&t0;@f zJFtRVm*>r_{56NhW!Jc>1?kLe(;J*!KAjw@Q<2cCbh%QIUzro7Pnb1hMa)(C5F#*7 zhhF)?fV~&j&M}iPqYX@Q*qyNv4ENO;+lBpKInv*raZi_<(&BrI7~z^f%)rup^oPI; z%v|jW+~Wp`#ISS{(YYE+By{V@4u>RGG-M^2wyuTAh(1Vs)P?AElk}J_7iqR(=}E>+ zO_$dATgi#Mt;2B_lcKMm*hgBwXD|oFc@HT@xR4L8PLqtL1xGp1~J6fH5Qh4{|B z%Fq)M$c42zT*2s-q^IH}VS5=;ST>jL8mM6=-mGALwTF`6@hs*7r+^W-TEehKub2s! zbBLksC30$A6XT{aM%zEy##*d>&Xt*B%#OzFC(E3tvn{^`d3n|WqQte}4s=g!%H8V5 zyu4b>K6Vu596cC9YyD~9MpzYc@Aj&*uc8eYw{MEejb%X^X>*_6!l9P{gP&GDt8{U@rWWlaakU%@v4L@zW17GN~|M|ld3ts zp)=^aHy#p!`ER*#>sHX=XB4=D)?>}ePO+TMovF-V+$38nD2&*p`{*v=8zSEtenFoaU$aizn8nuB4FxJeaQ$A$GPmXB5I?vHG8snT9nM|e?);9ffF6E5)Eug)& z2oXKw@1!Jyv0bkxNXy9;5@n0Ytj*#n%u()f=6Gu@Gyb%k5ie=wNDLljOh3+LzRul8 zuDOWQ$AT9!_cj_ZRZ&9>qi)YCnADIJHl}pN$YmnGD1w|_>%<=8=#!Q|apZT5E=fC5 zLtmINMkeI{V#J&C$sAAH@l@|87uR2HmN!Jn3zqkre*IJauhPw(`{EuxY5q7Mnly3L_M&B~esT^K%CXC=XOY_`nasB!C+5t`Nc#H^iJ6=nlmBC@gB?6#XKbeLxVXF*as`9BPtcOX@N7{={AN(u>yWRwvS_q=aOQKXDy zR8&NJ7x_sN5mH2ns3;kc6>-n|rJ+cPG(_4ON_)@W{qO#H?!D)n@B2K@=XuM`UsK@Y zy&Pyh;d0j5^4X2CWO}j)%};kG{2l`mIL(e<}tr}TW53|E?)B9wzUKYNX?`4|>2f;UIJ7>RV2Yg(kfNg>o@Z-4*Rz;b! z+v^s?zftx$M0D?cJE{StS!1zRO_Ei0PNfG2Euhc*ELrG<@%A?>g??kqY4fJ*)J+4h ztbaJ}2(X|9no>08kplAHPqVz=H^6zU7VeF&pnVxv;OogxWcy??mVW!oHygQOL+V|s zIh-;aCf1bLMwZtmBu}dI0g?~D{1L{9sVs}jmvpc)NPT6gCFboA5DMx<4lRY zbRLD}d8g=w=Q3K`tqv|HAJ7}65T?HHJABG^WBTIvdGwNCBR}b(`1Q%S<4Qbr#>IoH z;Wx_6`NN;n$)ryU|G>e{2`E*N%GO^l;V#Ft@DfLEz<-7FY2g?bw&7w3`>U5huI2-r zU7!bggr|_zW@+}OzJ_l9UFi^Oc7;~;=6E~Y85W0n!GdS{{9I>Q?){#r5D~tX zZce@frQZsu&L|G`=5EFODW+Iit;4cT)9|87|DcAN+f={29#>`@I-V6_iwZ$?$8(k*|v^kwtOCG z>^uz9`n9mlZxK^Dc7Q6bPo}&DMoh9#n>9FTz;1bQc;z~uQ=4au84Fve?9x{_SG5SF zTMxmEbOoqnkWU+r->YDPsLdC76C{8m&#XK-)VySW__@1@ew;srCRI@zKS@j&}S;^I!a# zXf1X~^eP>DCjj2c5;WGorp-$|@cNnS6s@)c9+anmg_Im;GVcdpC4CCkjOpi9y2j9+ zHPg}T##`tuTfzAMqS%y9eM+BH$G;dil?}KKaJ2tA?0QuSmf|VAPT_fY$^FfK6r&&Hz*IrY6KS(ZVQ@UCv!3T zXW_Ot(%7YA$EGB1#?Hj!f_u8YY`dl+tJ}xukj6p2_k6RU-+LT0pCL}8|Kzc%9sx5i z+XFu*%d_=;tC^36Ej+Ef!;KufAB4ZJQ|}ksw!Lo%y2uN#Yl|1W z|5pXSqZ)D4i(z0hVLg*L?Zp}oxl?+T9cRInP^IQ_yf1Igb+_ zmaON0{woEwGj^yv*@zDK568SYGblN*iaVMf&w@=hFz>0se9g?!w0~YG7h+^d&tX55 z?Tp6}PF4KlXScv*&U`NHVv%rZUKGeG{@@RokKo=naI|*DOmy>%A&Kw`idQaa@J^jZ z*H%}7=V&Whb#XFlE(bwme=wf$Gs8=DOX%EN0l#76Z0K(I2r3>EF><*&SBF;g#Bv-v zX}bkAzf?kg?`?WmrH%(`%;`$BE*3=J=Z0TvrxALFY}iUe{AaS4%}N}>);^1`U#;?) zWSKHvKPB04Xx$aw;Bgt9?mZ|xp<#n1twEUnrQueiXuvT3I z|4K+gz=iP`_4hB=HE)+tK3EY3E-K*t8Xx}j)l0Nhqa7cX&*gG#1*|1v0-GkjkJO$O z(dHg4W@s`Q4ckP&Lu3a`ee+5vEPn#Q=U;*W7s4NI^rek$UEK7_QktTBg_oKAlCvxi zL@6I*8fCqd?hL%-brwzGYBNN6(fJ`*=48M%MlM9sLwdhS*S4?Ig%tw+~a|`?ymRa%ioe0oJTXCNV;r{l2Tl?M_;PJ8wLN(p!h| zpe2Ip4@K^Nr3zZe-X=erB9seG!>x<7*jkyPI7(HV&aD)3c}Jp9-jJueSNDQS^f}Jh zCZC0-{-BvZ<6+!wSK-n-(|8YicdoIvnujoDQWQ7kz1y zt3Uf9(w4(UedAR8Q?cj34mxRD&&!HA;njo7;8EKt3KhnYtEDfklB=Olp$*hL&x_Hl z@z^kUkH2a25(eGV8k`r3ytO`4INy4Qf4E@`pOv?j$!pa^q;3$l20DRnSqF7aJiv*o z1(B_%63cnt4Z(R+NNhDOv!LGZQZTEZ zmJbPaEifW>J?qYJW53(dDffvOE=b;p6SBfs@9X6x{d7KyQX32Vr2bKx{|RB1?Rc0u z{u1pgFQVsV#_%Iu3S(Xyvf0Ou^EJ`?;mxICY|++!xOM#-)xXGr7hR%zL_Y)1QWMCl zxs&I9X*SkaOepIq#Db_IQd3>S+MkZ*)<1G&CwD!D`mQc=5ISkL}tRua=rPy{xf+{6HQLc0)zw^trhcMf&P3n$E*waj4hwe z`G;8J?6JD^%|oBw$)4gz-O^!VIa!b~{5$6{=P~CpUlw*Ydb6l`&xBTI{&Dgbh^#$J zXze={xO#RPoE=ljlk+>?#7m6*e38Z9Yd_2h7Zt*TnZA^#kik~!{t=$t7{tV)hcism zVx{2?P~?9WS}UuB_xHwtjL$oq(VmTQCX)QiL!u1SB?_er?a|q^iGS|C3$Jk*{J2#y zykS}&otYZ$kf5YR(}(Tg2lGpy?nf){>3A6BeS(1Qm&1ZR3)rdd4(P3$BYfkROtwps zSYzFACJ-}47xP0bqQ3?H4D90+8`asLWYK#xegP@Yyv8|r&Vq~QM^MADYN(&Pilkx^ zxjc_l=VmXFZM8cH_MO1rc%7&``5|m}6qR&1#JQpN~dIdG4 zCo4_p>xdE-!>|uWdRGLSO?R@d%1_QCL|f=K%PG@ zld5^T@PR-U_k84Flcz0ZmMRiI<}*KX&RTT*Aj2NYc5|OEiDrhsZ)qF2!>JX@Y+>4Y zh&F2DrHY-I*F_)hSixkxls+FCV*DxkZI3WyXE*8BtRmM#P5jqu8)#Qm05*Qmz-mi1 z3{%U8%%DYz?1$<_$xu`^nOV7a`fi8 z!~QFV_1mf|IpO`y%y)VVO;MF%-&>xMTIy@z{abrz>PJ1+w#|rF>z~K&+$)1u#^<@6 zA;;j^b`D&07&Ug)@vNnX6fN zU$vmTM-P7W$ze_FAqu}Q5A*)rBPSbQydGr9?q0LOQiltI(NC^I=8AH%RM%teucVQG z=ZhD|o#R!6DQIr)BrJR!2F;CIA*E<3JrO@D>?b>xGg6dOKfDVg=J=D^+5brHg$o{i zdJ@(d>yqceB$6BAi_J4{2+ypr$FZ+h(uTe+a5U6sx#z^0!>!SLX4@&wuOyb6y+f5% zU8=z1qd!3-wU8?p&Deu~_tE2(cBp^;H^n{a;4j@VfMa7+(Zc=_$VDRW9v6u23tsS! zldRc~=`ol%(U`fMwWXrWX4bfI3Wa@0pwr(?n6xb#^ zJy)3Vu#&suv5-oC+~uDP8%K$?FCo5Mhvlw&OAg`(m~!MMa%p-3zqVU)S4x*rcWW3- zw%!HuJG1$qL}hj(@CmW6-LUe>4cK$VpD(W(js8ia*eKl*%*%T?F8whVl+P>T{%PiT z@^lBScy)<1kE-Fl{xx8j^P3F+zM?xZ&%o@9F6-5?WJ|x7^TQoq@!U8?JQ2Q_D#WyD z`HJZ<>QON6nTU2b=ZGdK(@0pFKK6f1Ta29hM$ zqNT~uXIxwBhazAsra)4gfE``_mhlPVJu25Z<2p++;T%xuS#IQ~n6gaSL zUdFsLU4>3T7MZ%k@V&hn5?yw!*kB%V=Zx_6;G8{e2SAxMu z6C7ev29am&Nikv^ecPf6+&@RUKl3yw$u*JY+Hwd|xtO19GveM``T9dBa&}LJ4A2vC%8f`l7!(!C|TH@P@ zCJ&Qw$hTXNgZZGGz6%^j|K<$sY|&mmfz$eG#}?kVVskv5sQgYd_|4~#+v>zrj`-3g z)mz*|H8&QbCC`$5Mzh!hT6myd7JDOIaY*KGVf8tAG@&i9;EEGFdAgG7ujWD8ukY~R zz9715qsUtKeWBqIBeCq~Ag85Y2#@UJ_%XV&s5WOD8*6FJx;2NuoUijREuCQ~heH}i%Grq3LY{iKT#g?eZu zK9OBsmqV>DR@2_{k<4q=78=%g5`;;Hv``>VU5_U6n+>nf=d)f6w7x;z9$nhq_n0q@ z{J<~iZxnL1$lM|?fu721O1hndYxevHM`o2$_VmrLO3suv?6zR5r>fv7Z$F%WFpI`3 z>CuCFJ?_bBaa`4Xj>~W}#9u$}3f359awlBQLZ{nyx;Rb_>*s32keX|xQCh)A2iem+ z_YAmkPM_6?t%WZdDXi6W9Qb5v;J#~VY)M5Wot=FhF0b=srF-+3cXu%ya#W>@=_66) z_9yrAM9@^1P*`2KDSO>J$O5z;08O2We^14aNyjsmgzVFg$IPo~}B&jWv1UH=Op{hTgMyn2?g4>Dg^OhMf zP<@9>-gXa~n*?nCtkaO@I-V>f17N1oU5IR5%~>fTKKz?Qu{CqRqA#Daj!NKsYgLf? zp(oH0aa@0YwNO=v0p8GaWIxikvfATXY*S(ctl8f|j@Lxm{CX^m*Xg56*JNnTX?srK zy^nOgJ)o>K`)UQYL@OV|Mmw-&uLfw2 zLN)x4Xmfo#Pt3JM=dVIuFp?MT~#y`jNY5 zxdaD{dxTrN#F=N#SS-HQ2TF~**xfrv_~ph%tbN%U(k!l|BpG#-pCkv;+k^O7Ss(ZZ zB!-g%#PILqG*s3r6?iG%;eQl-hph8GaFWXcdF9c#E~bqSNsi#WBd^;plPLxBfK-~d za3Sj*rH4;!rm|&KQcHfPm7)G(c|J#dc7))jci{?$}w6@KVFtUJR}ZY6(8n(S9poC z>>V zcKDTc2zoaF87brV4bo`WU_sM+C$K3g z3qZVKIOSW6V!qwSQ0CGx{GdGnjqg`-QT#--zpe>ubUomz)M(V3@|2qyG@9+)Vvc5U z3s`FYdhpQn2F1x1to?oj&Y6+{kK}aFVzCP@GXDwtf>h9c$7%SKDNgG*l|ZOgKd7s! zGS`JGVW~*7%XdW6gT5wi>%(j^)Cht@rC0ex-5FRnNzvi=###8qR|Tg&-vlR=ykN+X z*HqmkVk%lE2|Y?L!_-5PFnfU#rVhBWDX2xuyG-DM@k^R@Z4CQ3<}@UYbYvfAGKe2x z&!Ue$qnW2-QE|H_OX||6nK9E?%ffB+QROmMdo2YnUkk&qE1rD(mLNQ?c$+F3o!G-4 zF|3q;;>D!+Fi7s?O! zKuX6dNRLTpw$H2JLy9g)J=lSdSBT+eei^K~&_a(_k4Lx9X{b~4ne$n+1K+K@Ocf*a z*`BrvPRDL9$dBBBS~YWpO?)ez=6Zycw!@h7!po#k7|J@HZpP7v4Me`|9HzO?0#81A z4Vw(B1nF;m@$-M$Ot0M(HDi{rO%LW%&cv7W__hrmE|wyJrwk`1VrQ;Cz0Pg%3K79#tNJ+fTX7jqyOeYe$!`rn?qLY>`onQ`(ekWFVLgzmRr!`C`Xp&deZ!bN24x5x3(2JDCsblCUrJ;LnGhYzDwA>bu1hD zxLrWYj`OT07$@(G;U4Wz=OZ=4X>hF!K4=o4_{ea0340;=han!gD$R6n6q9%Hh=wUk zH*w?jvq53jEf^Un@@c*w;r|?(%DHbaWR13MG`)2U7uYe23oi`9FuftPWAGMlCiQ`v z{k)c>WBR!=EOX#=dSGsVxdS3<7(W}KbfMGv*rv1nldG`j1sd-6%FJT#JZ56ZC* zVs}KI$rZSDJC%ASufS{FuV65JJ#;wEM6sHW@L_Qv^`x%DCs#B1)lWm%!nyO&f5I3V zv$YjGa;jZ1>!nS`|3NLOf#Pc?PxVGrC?AYDunA-<< z>zFE)`=*fHjvg3qeg;CVIbI)_`PyGzyC zCm`LHgSC$y3HYG(81du~ziH__N*85DJz9ahSywWJzAmCk@sSvOzJMmoPo|C-8yc3f zgx5SQ;(%ifS%jGZyO}YA&9^*+X8(1VGyFc!Z2ujF6`0?278}H^bdF2 z>qyB7 zwU1MBVY9!wk$a&%Kj}z~pvNae282jpT?Ia>4W!$1(?E2aHzpS5Z7sI zSQaW`2+OBJ?+h`_OVMU4hrR>*d0QxE_ce-mug@;E9uws_0@`wR9G*AQVre-uL34&1 zn^B&?&&pU1-wi@p-qlCk(xWf=F|#GmsrL}QsoO2$1*VhG`xR{8`4M(>T?d_=`{C+( zA*md{OwZTrqo1=2&eYaH18Ft<6p+LeRIK5GD9gNjX%ipVVFNXjqQPK~2^Tc4aq__)&jSRrTU8 z)oy3|o?hkiGhai@)GBI|d^OP#9C4^qCF*pzGf zPigTV7xbI77ssD9rf*iOK}|I0eYU$tpAJOPlCLYtWR$GP{~CaFOr}f2n|VijJDRXT zn-bdEVaty)8vQ1L4*4s>=T=#`+-%F*M2x6W&J|LWIYdJybivt?yZKZ8-^sFg3I6uK zEjV%fCW-Z(1>0+TFfC~zC#w?%bqgnvhgr2?vy-||R_r||`)Lllvfhn8y-o)Dbr_$n z3c~_}J9PQMZlUhGXE1e?IN~E;i0iuoW=5Z=YUm8%4_=)8_dEi_bo=Tnzi7bwq!uny z_=GQ?|AX`Q*CC1K;rLhu@y$6`_HaZz=K3q*qy4$?{OSe_|IZb?ha3^8&*}vU>nW5o z$qU-22hipyW4u&wi$_sDthDzVO>Wa-wQVbDSeXP}iV_ zY)kc~<0cni(DWLe`q4)&YbMZ%!Y86<>kZj8=L=K5tl(!}T?)(YU#FDypUL&cc){p| zPs~t+EBd;*?u;K~qBj@Yi+|IJcyA0^DuaJxZ<252 zU10(0!YA8CPWzeyjw@~h8;L~}JN$_{1^DH`fB4No z9)5Su7coMfY=+q@*kz%Ck;bWT{fH~F#}k=K-xEmhz6}}0(ikvR8?INZrQa2$kepG< zg`8-m07H&-rEutQ#T1=q#NhGy4q&5O$jyB&PHU(Dc$sl{wO$_GijIlyo#`UhdJ`0i zG+)`UV(@!l4LiSn8VxqYuG@r^g#{HKB!R<%OV$KBW%ip)U2 zhbo-~aHXz=|CAAo1A;axv+IG$2OseYKg=oXPzHIw&}KGT8k~3k6uLF)BD^t`!7aQj zm~4E=oxfGdc|7<=ynPptfd^hrkLTYdiP5A3UA%#tHP&%cxR51s80@#PVcPdWR&i`E z+DtQ`>H-;%PT9kcNt{fVHfmzb&1TTvwuvH2PLSVw8&+Z9f5*q6BO}p%8|J`GRMz6D4bv)37LA_8?kPpff%PA|(RJVdNuz+zla&T&vEC zeA39jyB6kDCxWMl%UamE4Y~41{MON@Ma=0`Fv=Q<`GHRC(7C7J?Kp%i3t;_a9$8UxL7uyney?6~h`f85LtXiNd zdN13jp5h>kN)gN`)52|gq7hEdfE}lQlT}@-sCTrVn{The#+F#XD_aBXnXwc8H046` z(gfjhligu@yhCx^zZU9a68;6Y&o|Z+-JJO{;Q4L`TfiA6;$J| zBrPaTa)9No(k%6&2g*o2q3xLmu=3hEe7r1}wSN-exec14Jj0rOSy4u1DnStbQU8woXjWusN5bDfprrLIZP`^tsdt?O|~<}ew2uU@`?uF`<4@X_lqA`ZirjgpM<^d z`Uus|LP4_=TVtX~9v{|lA#xoM@^l);-%({srHe`B$5(!PwFxucFqTz`?sM(^qnX0u z=}>t30u1R|M;ZD$czN)fV9B=Mz}pQ+?|1d|RctnM-uQ*=jz&TD^RYM~*&1qxs z?_fb|O!3m4dJ0xrOfz4X!mZab>?rMMn5bAuM#)PV`d5SWKrZqD3H;usi@bK%Qa1eV z3kq1Y70(c|QulM-(i(VtbPI%A&!&?Hb_(xIO#p?? zhftY&m9wc*q3#oIeDK#ud_T94N|wvRmD@i7&VQlt6U112W-o-TbHKfUB~70u0d2oOH8ET{pAbZDD ziaFwp=aQ!o_dtr?s)j+ymhEsXXDjQk9Y?eGX2O{g6Ii@yAq!0}0x7?tENX)hoM^rV zkJA1SKWqset^EvkLu@eo%qsl*y_Q@X}2MX|4lM#F6 zv>uA@NwK@j;)TnMb?}5}^=65S7`}fihyQ)hV?_ZiV0Yp;HLqOBYl?arCu|!5D%)U_ znHF1DxD&#cX<|>`A6{~J6FWrLnlc&fCfYEz?i5rgAK(`Lm(D%3jiCKW)>x1;9h~0ag4LI^@ROV5@`2}8t^N*>2oVog{!JT=)PoY}h! zuFP8@csoa&uiX6+{%L)taCVo=yneIcnCR2s&m$1N&X_iZI1+yMgiMREOun~>|Is%Y zpPssE@1OXd6r%I^Y>PrXueJ-z-fU;h2W4^cm?nPqdKnQL7EE(5CSqY@Dx~)%f|=@S zm_9m)Emh@M;~i;~KPsxO^*LhGocj>>WtJ#ITntOat@vLDi|CWJ5lmjwND>Wg5dFlL zIZKSDGhc?V&f6JGb5}lSiJhb2%?I)1Zy&s9o=vSkU(%9dS2o9O315CgoHpr6G8t!8 zP>fFD54%j{B{!_Va2FF?5c-JA(j1LJ+Q2pqm0^b@OtE2~KmKYsN~b<*V6BM(DVJQQ zN9D3iZz`f`-!I-**M%**Z$w6e{xBy>p2o$vqD84O&ea%AP6eM~@>Ny*{%;>F?9Zf_ zOT9E~&k{~I@j2&Z{0S1&6u~5BJAS(RoMJz`1*_@@qMS<#Z>h%Mmi|TPl3|E$C+4!Z zhh-T5@)OOQFb>uX48aEF5K5PQ01G3|P{y(i7$o;VsPQJ1Zs-&_Y-=hPZVY2YBo-2QRAPS z>tbS4#96VjI2!)_k8ayPVzcJ7gVt1YI@+nn+`6s`=J=(v8uMHzkbMVx?~didN~?q) z_K2|n;RT`bC^LGYE%H#NG5+8@33f%(7`JB!fjsr=}m!N*l!Qnul zHF)~yv;REjusQ_^wz6d&n-lpT|NFKb-R;^!uXKV zA6(pb6;>)Bva(A6CDHT0fBqv{@=DB{wi?!&!bV;Hxw zkqlq22{x6yh)3Jp(8CV(T0C-I@zedOEF4J^igXGti33rjE*1?rHf?IH_U;!-TqwAGCn? zMLk?fxC<6Yj^N*XSzN#RM+OyUoTjC*)-WJH3|ybfp?6#@oLTbOA-+%wZJiD9@n{K5 z{{01R{6MTRccvjPACSy;b*jic$=6p*#}C`ISZC!T_~ZN-=E?O54aM`}&w{-|;o=a% zHPiW^tuPes-g3k%g;StdZz;MBoS^NapTUQbt8vtlW`36+U`TujhU)C1oIhhL=oi{HsAHnun@i?KRixybCpzm9gn2CWHwrzgS%V&ItN28w7 zj?T9fyxE@Je)AB%fA~Yr1*RBe9gVLBmpVLg?}FUi# zhJYV?ASinSo%1=%6h6h#;$AEKvMe9Yi+JtoIoEiV#j%uAVTpd1 z1uRJVAe(-u8@#oZv1QLk^7A!kWABZ{1@%wCGqixS)Q-m88*X!@${ILcdOE&Htl^ZD zv+2D<8aLh`2HYBE)69Fd&Ui;#c5Pu_~4oR`DMM#!N0T#bIw!I#;yj8r>cIMo(^N;OXdiD1GIQmnSc0 zod!ebWa@R0av8}a@(#kz=t=BGWG$Q+v4Ty?6vGE4rL^~bJ^%i58T~hT4F20z2pdm+ zq2*hiQ&Zu62vgb%J_ErNsbC31zx<$vs~d%P>O}1B#uB>o{tRlxUE?FIZ$i$peA=4B zV8f@ip!d)lui9_H|M-XXYrzs^oc=cDZyskUrn>j6Ir5bFPIjK;leXVIJeg^?9H1_s)+FvSgEyho`p3$ z*V#rf<4!|K+9CQ~?nyq;<jNdjdm-jM~kODzC!-5|1{iqOo6RXU&;>jeW6OvjjXMxmQUX? z4nrOpqf@r%Xw#|0JsyVm=Rg8}xi*&>-3rHhBXcRm!I-(%7Jz7I=kDK+0_&NE0@-^+ zUw0j*Cz~Z%YVJ&?HO_|eD@1~EXe^`a#_X5MLw;3)5ngOoWc3&3V9NVdEb?JG85+ir zT7NRfZ4cljAMV7LHz1nq3z;Ex<2g~J*p6u5cNpA=I%p*mp~eEpt_ z;?o;2gvB#eBXREAoAD@XSqd-j?&T&QPhnegrZSJxG7$fq&9$Udz_=6sY+1KC+FZRw ziwjct^;67Qbe9hPw9JLUp}Sy|!EW4o)SC+#VoGQCI%BE+3LM~HP~~SyG>))>yk|ND zA}%-iT_KIiiRUM+JV1fLjWk*z6n_`@(d`qTXm6M|mW+G@)^o?;w>Oa>CRV|(zMTwB z?y@3}G7AFI)mVqH5j@VmgvMcUIOd)nK5Geu7Z3VH9CJHt4jRIeX5RtBrFGQ*$qUEk z@1fIGzxm@?kLlr+X|!aRx4_B&m~c}6a+(zQlx$UJ;?3HZ!hJ{b;B1WnI=>`dIx7=@ zez?h3tJPA#*R|MPF%PTuMU!rIEr}i3#!L@sf^>lkiyxm%3Df^^R-KlVen1EN6Atqe zADw}32acnDz5?FV--#99PEotM8P^bK$oEO?fp?$oQv4MeHs9;KeRtqfXc`f~&$Kxz zXmI@sYc9I7?3G(E(M{AvpWX+`y*8Aq^8;^{?}m2;7vZ4fLx&43N8#>u6?SU&PO>el zfUF7oNdEj2dR&%6CU1X%XY4r4t_#9fd^RY3en3wXj&g_w@ z&f5?^{;D(QwtO2^JKf|qPn19j!z=K`G>i-IS{7hWqETp-~h(( zAw}8v>p~i>b<$?JZbKkqvjX$9+r?gKO#uB{MHJ9UFnW0dm28dUvp&bt-_C8Ke$_Gv z85hHrW&Na_r3(a>a=Ict@t#J0`M_s1H28$G{!l+Thi@zMrN{#{Z0p`C z;j{@#q!nKa{yzEqqn*~gZtXoXIDCw2f1A$-4Nepc^OR>jr>)sLGe34BFa_q6$YOZZ zG)(xmh+S>-fou8VBF>_f%r?}M%7{x~@oov&=3k))MYpK^SO9nT&>D7mLlw9(;MAkbiy#^86HdBQD(T#Bm!(Gg}N$`UYhHW z#wTeJU-6WWTAf02)6-ygS_hO|KEqpxJ>gb-_s6P7^2{c?hf5P4q!$aKY53`0kuGc} zXx=F>Fux0-1>Q8R-HZRavjvKOJSCYa3|-1Bz(QJr?a1fxJy*!YsRx!v>;XrS9$q)N z5WJJyV2CL5t~%CCBhBxL`Z=cfE5@1~Zt|m$lNOkBa1Hz%ep{4J>%x;!E-*S#$d?|J zVWS)*QRYev&UW5}?cKIaGG#cvU1iOGUzr1oyOj7>=O4pFqhJU)9V-ZybAU{%SM)6- zM8qD7qwq#HIP8*Uk|GZ8d8;gQ_s^jHk4MAw&MwZRAqUj9X2R!dE7+yANCyw)=Rff=g}#-LijT`7QbJw zr0rtYDd@ym+T9e6(vzde)a;tTRdYM-EECPmY&Fg+dm#wP`T(mse^K%=DfT|zl2)&c zrW+p*@NpvpN#f9QG+G}-H}_s8jg?=x@8hP?kE}FUzvm10Ze%j~1!>T*$OK+@v_Ee2 zIf5Q>Gda1v?cAV?3Y#sjf@c)NNWWtQi&`PUJKhZ9-<zE!aV(HjEHkI{D zFJQxKP70Pik>#RXXR(SyLr~D>MO>;S{XW)2Bi5Ut)n*Ui<&#AU&>G5LBx2qRaq_TT z&d!Yr=GLDzhN#BB4N-sUs6t|B!*V-+=IoctJcf3_w2m5xWg(1vnhX7P?Of}_UBY~Q zNfsBohp%4nP}F1KIV){n%K2=7ww5YfPwZweWkNpLV>7pI)pTyK?Fsd@1yZHNaeS-! zl!S7Hf-lo-*d3dRtb>WO^o9(khGJ}@=vpspJ%Lq@2BMCj0d^i}r$;y@_EZf@{9YeQLx}XsE@e_ zn~NE2+h&3Be=<0iYMxz5l%mm9VmP+_9@X0TW6t|M6uY59_&hvQxI;!BrIZa&plHH2 zO@2jpMc33e_JsgVTd42tWKh_*l0KeS=j>Nq5&0gD*t**n7ReqEnw_=6(EBw6(;3Na zk)t}zi7RQo?v9~jp!lQ1{4iwo1OyFehouPu4XXwDklf27~d%VRjj#-bt#%(Ziq|}ieoVP;)Nr~9I1rzQGoBABszpeMc zZ23#j{P4{|8-;?9Gk@UE#1%BsB@^~9si2Kf`{~&;dGzTCfixL+VS0N#S)P)@M`s+E zkC7GxY9(=T8lvZ8*C5Tz6p)c*CUo}J(Q0`s_EPx}ZzlPZg5K)DBk34^ZnKL>KRx75 z`go&%+9XzXb12)QkFacw9rmr=PoZM#*z5;ds5-8VrZm6hN)?Q0m4vV%=1MBn-m*cj zBvm%;dlKB!t`K#eU&2CdLkJz2M=@H@xC!UeX?=Si&C>z=FU6dl{qTscPP!pnDB3j; z@qUoh#D}xF6_#-D%uTA*DdML!J%UAp3kY-?2aVis4>x zxW^h5OaLZ^&xW~KJGskla(LnIrUp`J6)}k0s3dU#CfyKm=kE{mbFZ9e$psW=`iKTRN64MH@scWu@v9$}heK{QE?5Rj7p5GlsEEqCTvSvI2Wr^97O`WFcO* zgVGjs(oPFQHokQPWkrg-vy!d+#t3uvL~Jtt8Fr7;3S7tUZna=?BPYU&XU*^@B@i|g zae^5`ec8ux1ko=?u5xu>&b@X(~|FrnZDxPO+xj)z^`#N+A0XqkSr)?CcO_+}7d zBozwAu+8C%*z|aPl6Ll`v)Kr}e~eLjLIF96&7%qtqdcKU9+!UH{@6e+ z$>zy`^^=L1z48>b-HmNnQ*a+tF`SRp96>8ri}nN{;+$DA_+g-oW)^s`ycrzptG-FE z71|(noEo>O+z9T7-Z$SpEooQ%Je0d!z<=M84GayyVy-HBtk-7)H;z+>$tKdcQ;q#g z(#d0z1ZTo;HF-j(6bp}&R4M4dpFTQ9lY6P4-C_)*wd(#d@tdIa*s=h50p z;wbMQOI5K*iyOr7P?0-tq&JU+_N2j%&^`G6^CRdPQ37A96RAU#*@XS7qbC0|u+K1z zbd&oy!M-H;JM|#E-v}gY^ABR`>R_^XJa=r|Sa>n!EZ>utg_FwTG1F5OpQKG7OVc5o zn%{d!J6w#XRI{O31Y(*_OOVAc&ai`|Q@u?!#f7y|n(3P+kC+w)^W{L9i+S~-n z4PD26)~7>QXbf&xp&{7l{hac2*O6zLD)WCb7D^UrpxYB=m=J#hF58Rvs>>=&?@S_Y zkIn<1&R4u@oh$CUt;9aa#IP`iZ2zeDT)W&xh@77w=nX0d2Vb@r*Fj9z=}0-x*141JWjvht^3mzo2|JBW|}8%**N zH${v|9IHMc%3ObJ;3cL%g(#K(aN*lP_Hq3cF6eSM zDRm@!GgTUNPARdt75`C?`3k0a<_6~*n@J{)bJ<44i}1*80H#Gpqt>;BR2&!vc^E+l zHN$aezCk;J89wPnq`^s267IF#TMhjSf zkY%e4)-kU^CAP%Cg}XmOL3m3_7aoIeLlz6b;9xK4k1}Pk%Wa_f?p5K-H9|hhNr(M@ zbAcO7Nu?zv5%Bl*W^%O~B`hqkr9V^kF+px7D^tql9orYNq9gNYzjbX_z9?kD}c&->pdEwFY~b!l*Df368z$2kX5b z$$qBjf7!3b{^%HB(YNJn(}jaDwP8AQ4$0vZ z!TQ!`QQA98IK+=fd(#i}$sk9x(=MD225PchNkL4!cQ~`inhLk?WRm9PlWcdgCac^3 zOK^9wGsZ{Nl9Tvzp?YjKg?{}8c1LpQUUe+I6<5WKc zxNovWFef(#|DKO!UD{jt*$b?gw}L!dBFX`Vd_BnB$am$|S_h%g=uu2JNDF(+h=uuX zM+wv8AZ?IHS|T0Oy*UB4=$k@^q5%7YcY|$GhDa;Szy}(u@oefHFimNP2i~LDukowd z8Rcx2c|e^>ez7K@Z9KSeBf0ZY@yw=fFZ;Jw8YG3r-0MZBNm9cGhHm!6>b3WTrqa1| z=gUmq^7$>e{_Z5)F&?0mHrGJoe~QjD9LukZ;wXhgNo5{GiHs$ld+!QGR8o;j14$Z` z647ML6e2>2C^AI@DV}?uiUz5qlr;QHlcG5d8q|BgAANDTc$~A(+H3vRXMMD>m0)Jq zifN4P0j@7#7fpW~iA}@2x$HJ4nAEP0nW~F$#79X|H#rI`U5gBrI7z3zCnRsvf$evUrtrf^pgt< zxvd*YV1~ePs@6JAi%%=z&Dz0iS4b0mm^U6ueh(FS83S(nZ!M@Ux<-nE?{A>vWZdOj z!Y!H;0!1HN_?8D&F!9R)PP1|0MiIt^q>IeCh6-Rl4`egc| zZ9w|I1M!#Bb5Q!)4xhfxroY#&^CMOkP|+eI&S*sdi)69T@pTB^2V;^eFmHC`-IBxXz+(mDGIhk4?bhR9gV0{r2Rkr$Y|yRF8ad+{1U2x z7ta-fet{&eKD?EW-FuIpw+vYE`*N~19)Xd@-t?az2X~L_;+#DUo*E8h?_cKe1yT~| z7;%w38Ro_!RK}zJa*k8IE6Wx{xq97o;Q0>kdELdUCeY~uzUW_;QY zPYV94xaHn#n^y?yT4=y}6h3kLGNahe!}a`%rN;Q8X(0@~Qbd*F3|f^rn0@3;Sj-_U zCSSc-Jd3-{r!P*Uu%#{B)H_cG?u$ra;5hnkau(n8)exp0%@JQrJqpkKq_Ovw z1j~5+33duQ#3QSBq1!PZG~Vk1fqN@Sdw)G;Udw@((Uo+hNeWiaHNwqv4#4Bh-#Pn| zL`Y(axX`%2KFmvs1RtVEP0fZs5|zUm2CI^4(gW^DQVu?p;6ZVSBC1Q3P+fR5Ow<^O zx4&GYqOK6Qwk3xa?sUO}{wB1|%UQHZDTYl~F-8ZO;mqBBA7y76WB3+pZcBO?(@wWw z?KZ_wTBgpnk4~Whd8a8*u8cCnvnYPrV|p<26O0wlqul0=7%<2!{RgK$1-4`}u*qJY|TThq=a}rp)?smv*@TXr7F7hv)mvggv z8^C7AWH#(`6$_`G;QnkjZ=yFGX{JASDNl={-708m+I#NQhdgfG@dt2iXeheO`o`;Z zD`WMak!W)^5l7mpVS!o)=&#ph*>j&kQpa)Ftv;6BP4y+M?3rw5c|1&gEn;QA9a*Yq z9|dM#qFq|c_^(q}GpG4y;WuYZldCv-VtN=>%E_Q}$s02EOX1d~=&{Nt)42n>icDq5 z0h&3~S!}mMlMPFojT3}cii&%?A?39V_qzngW_KF2{v*EbK)&q`sZpJvbcl^Nb zQM4jZ7v39RFlwqWICYcw$8#}jR5V#iltNIWHB+iG z!V`5#l;fmGs{e^;$*qf!)}9LnAvV-J%a>pMnPA!RU}_6(ga^0>_WUqnH3KT)!c=+g z#A_?|_w0Vot=nAC_LI@b<|E%$w;D?O0>rnUETm5p)7iS3dgwXO4%*!T5NIjIo_-Z` z3kqLTc+w!8v$&A$`DxC6yBT0Zi#l!nwVRrxPf>eeB>pwTWUMGziR{$;{*MPSz^utEK)gIWq?%dgc9qDxCFj z%n?mkj7@N>;u<}97=&+pH}kzI9TakC2iu(23AY87bNQLiaCTw|c%?evwS>{E5(Wbd zkin~EaoFd2jwGD!(YDHH_*gXosv_#?^Z;R>tbGQ;9ZcBz@5NxXMwZJhuY{iyXX4n+ zA#8fsci8?lMr2q$h{d>OkWJ$P5X*0XeuKO4`Jxd9ZZTyGHLP$$qABdUIF#)M12(;~ zhi1Giq|~W~sCK~(J$^od`Hwv)`@|}Wo^g*RU7Sdxeag5>o%8f>Zzq=()kUM!$3aB6 zAM<-Kk|gqvh)XV|vTJu7aqc(4?-vwMe@*2A<;b1{#~~50)q*`HKUlBDMG|;D_ z`IP1Sglc!$vzL|o*%`SNutQ+;s1_vfSF`0X?6j`H#TE3D0gKT$-4%AcT1vsbduf=y z7b%wCqH&9~(LQuNhBba7$>p~>{d?wY-mMaTi{5NJ_$mX9^tX^`h(42B-%K;!-saX< zzlN17@7kXKFM@PmInhSvTG()G0l8k9KpN-m*}dCxY(iHyzl}f5?J*8O^Qp1y_2CFQ z>ol329^j0%FJI7${~Dm#@dQ6y_7GJ+%_p0s^&;omGEyA0i{BzX3AOqonf26ZEO*!u zX!^R9W_2!RUdx_=`OJ8f_WVgFj-DkA+Yz|!%04i7zn2z`{RGp(7o*DQ!PH)JmNpKY zO~-dF;$KgZ6pss6r{+XQ`20A5%ns>cOUqgQUGZr;p`?pkk`_(BwS=Xu(`QSM#)1EC zA9i`wSgfp>C-(R3qBY^2^eje+=>|u$)~+1x&}wTuYaz!@TzUajD`dDlCueMYWs1)a z5VhAm;7^LTV)zsVA=7O~tG~!#_Pvwbwu~iUwlbD0^xMsic(#Ea1-)lt<6VM}{SbSg zkwLpU>*@M9RjiGX7}BL3(SNxzJepgC8x5q}=MNjU-iLwhRUGeVgYP0vL*PvfR-o{Qj#@wCYE^E5hPob{EGwnXO;73l zsk7YH$&ySj*qY`)_q7WfYJ+vz#o|Yi9UxU#Od-;%#LLsJv2o!SXw7Xm2wJ1c?%Id4 zv5J$#5w^KB@aYu%>Lk25bT_fxhrPjKf*696?YOIpzHm=;f7%87cbfnDNE*dcdPGJ_ zQ{ido46t7&0lms=*&<3JmEX>6Y@9iaUUr>cK5l_svo_%Y$zJa3L^=F)vClFdVVY(jPz3J`JvHl!qDNMfii5>l4N|PP>ROyZ}2NMCo>7l zhwwaKh3$5Bgde*?F-q#MD5hH%k{Y8$$`>}XhKy+1KJySf&^kc8g(Pd)Da^QiPlnTs zXK&%5brDTGu@b8XJFwa#1>AG%ncUZb?$CAg6~ryp;oisXMbXH+(3tc`bWvZ&ZuZ=b zxFmi(|KIp35q=#>&owOAiqsJ}=8rYoe5MS31tmgV{a_TMCi^=-nBHWL#*%j7e$bvz zdzWvd!l5nVb(Rfy_}OKckRipS*PfzM4<-EA7$j&{({aF2VK0|B4g18M(2-FB`N{2~ z{WBMn^|8qMnry(j1a-DPdo z7xGKO``NUgbpSGXx+;^O$l18%e`xa4Dft3KUzd}n!+A|k{;i;u}9#8r`;abZ#z#2Ij zc)IB#75;e(H7c|5OP&gB&KUyT>LW4X!cO$QYf(SpMVv^@_B#LiNIMsFDTfrkOrgZn z-?*f8v)O?a59nv|R+`4;(DhnZ2wmI5JL~6Tc}EyGZdWl?iss;9A9bA2>kd{$yRmIv z3V3hq;*LQioGbDJFNsQ=SelDw$I1mgI36;*^I%-f7~Cc5hL1N#vyGh-m`srq6=dAE zE&t+53d_xKA{DUV+;U0i560_0Vf8=qUpG^TGll+pePnk6Q({=kjZG^sYQ}sjlP1 zuN2^q)I->|sfrtVZy2QiDC4zbN3%xzy)bwEcB(6~g`mlMvFp!rfnh!jlfMxRm@phF zJH*&wYDrn_4nI0bmBnd3fdy7W(eZl{xk$NEy4zUXeIkY%uDpWX$ya2rHKyW??F#&f z2O1D7A3$pVQgDd31y*+41&3pjbnHe6L~YCA&D#3t+xDL@d&53%RRX|dc8Ty;G}vs2 zCHIlT;mDmb93D4oUgsK418v8v|I9#tK&6Cgvihxv=dX z*4(|;a$3Hjo6=>pQR3Z1cGggq@1jDwKJOfrJx=1^S(nn8p(DuGv>nW6T%$1^E-=qx zA4;S)ahF~{2UQn6?!0L=e61;_Z%>@j;dCRv-ennh|J}=+TE+aeapy@k#)a9r?}dV* zU|w171vkUx1bKd|rK#DU`B@mw2PWL1H$yJ*ni@m#!o=m=2Ei{qETgRiCj}2}) zHq|bFm(&AbjQO+v2?6Z%h5a}(ViP}D+Z2X3?_rn2q?lghcHZ#V3Ru^1 z4YGT)@Y#`jT-d}6(x1JXG7g*K%hwtdJm4re76@njhJ&mm%|Q6xL(pH*7{}io$HujU z)3m8J7_2o!=m@w351y|e@7bd{E7ce>yJE|X|0#3D8#SnC;wTt7`?~1p{3Lwxbq_2a z-UyGqW7&=ni?@~Htib(67 zAn}$Ix75LchRp4uO$V|BA6+C&5jfa3Goo0=munDaC-@@&^wT6d2XUhmm@_nUMVDQ{ zze)J|=*x9WTLLEl;|( z&J|`lN}^kdABMd+BCd9|hk%SiQKNzj>v3@6s#B-KuiELXrh60`A9+Xf_nn1~kBsuR z&BvG5Iw1e23TB&+udjR|=AC+k^Q?6t7CDwf)M;gAH75tI%avfu@k4w}y1)!SAjz`+ zeCO9x3HRPyb>7P906*d9A-d@?g7pe#hWZnKntCV!!*6Ax&V?axJaZ-%ykCc(q>fYn z;<;p`q)nEK-q8hPUv_YjD?j70Bi!m958d*c*x^&d;OJ^otT>hn3Aqa)-SRnHN$nKH zxta4F&z3-IQnGknum@d~apc0ijM=(4;jR2ngH+FtVJDx>BhPUW`2E*-YW=v7T%W|@ zf%+l*;S_yLxc>x}UtJ-7_r;9eVgG^WQa7CQRgZ1DR=`fKUq-5vjzIl_`*>n=CaIk5 zquTrw>YCC5N!whgSwVty&$~14&9ZpsTOei`3}q?VvGj7o5WK0;!ZnV6KwuREa4!ky z*>t`lel>PiU*YFWZH7~m+qp=svtYlyI#^lm&QFHvAgqV?c%xSl}qEUd2;x}M+>l?5E) zGx>RVL2D{#M-;$?8>d;bqXN@kZo!64n8bEjH9-5AdOG)XF!SccGW{-snvlO#lJUb-Ki zo2x{o_KBeBC**tPHo;p#s~j*#@GweVpz0!3ypWd4KN};@e#8!h*Mh%rqwE7NwO|T* z-3q77VKdp#dw;;)pcMjhWMGq|4>j0%!~LQFy6U0M#Rm_<)WbgX>6e&(+>R4p**THo zcK_xc7A|EwpQO{)#Veu0)ff8z<%(YP$Z!vOCUQNqgxj2;wI9dG(l6`ScjK)Ekk#WH=uedhIXnB6PL>fYy$OoYwt_ zXxL8vPh1LhtmQ&_cCmL1Q{fn)E`@VQ%NIB!`tp@y>>!%onQp2quW3z$lNVVxd!}7 z#S1hzg;D5Ud%RpG1tm{A=_(|HXyteqzAF}U)N|ncoNd%~XfMUx2^ajYQtU#@YSgIT zB0gYsgg!hPDzLW>QpybzrWH7e)~pYPww00eRsAC0y|e+s{pPcj7B%ROnofi2a%k%P zpZsMLV+_zs=cG>0WkUz3k)v4zJ`Ck}{4RJRg9^k3Cm)dC2|=SvxkYzR{efqe0d#5G zQ}TNA0<7m5b4G7N*|OQ56xCkO3E?ni_Gk>6skPC-6n_dY@*~~U$Dm^3gZmq%^S4f> zvxK14kY*H0IkS*n-BzFWg&n*hqi&Yiry=Z>dUs>Hp`g*D604GY&()08!Nx6d zG<&!*n^?MpUGR+~-=<)UIW?XQnlge7Yxf6PzLcJ%3}^al%Y z%0{uk)mdQb_C{#yb>}*A4cG^>1iMosGpXcWAo?n*VZM)^NJ4wAxY^eMD%^h1zF$k& z)$K#Lk?S@vPI#XxeZEU(1})?^QWk_w~O2|Fw^TezrT1}+W<#O=Zve^V=$ejm1@RZio< zkUNEo@3w(S^CN*x?}Cj5GpQYA7Jx zo%eF`HT$Bw7ipxpOr)wD$)Go-LGl#onDYglBVyu z`P{RwZSY9ai85jfm`-jlteAI)_jR}DciNU3x9og4=@7K~trzV(T} zzfa~@mcN22342(7uRYYsYM_VR6}~H|6AVMgk@wzuHt3Wd?z%#@!!GvFpJ(^Qvt_Px zYRP4ESIU%rd;BHiKLeSDQH6N%;&fc(nNB|IE%C{nr_}qjmiupHEIk^bM@H4o@b!=@ zGhTX&(uKG0mXk~I@_uBBE4A>Zjy<#cn;oe#Dm$I(OEF$G4cDoB3a^ETe1F16H)R4GlBoFjbWaH*r+oZ zFrTx46u%y_d$N{Udac6k{ZGldwGhipYe?#g1=Pw8!e}2ww##)S?cSNjUt2bbT&4~Z zefjcI96vEuyxu_y;uIFJeu@3Gb>4oEdAhLPw#AY~R9K>);QP01G-RXRN;BJG9Br?8 zD{u^LncC`akom5RjI|cBt?L{3gCzy5EKik_FqdQYe~USt-wNDlw?yi{BV<oSea zf4D>Nj0W|cgX;~sY|_O+cr!?fUGW%8d!5JOiaGHRS=~)VGP z)2DI?{2_ER7?`VKNAE3i^Y5aRzzTj()@xdODjC1P3j6)3dQIKG<=C5=exY+8)44p|v&s$BlJ}FQ7aK9t=N|lrGr#F~N*o{g$(&ty;RZWRgITsXk!q7A zA)ee}m9{gtV}K-UcsU)Xcx5rw{U(^K8O7%HRnx2o#<*jj0+UTlgaO9yfcM-$iAunf zw;bhsEMoavlJXP~HxfHC1_K)|%o4_@;JtAMDINE98i$ArtVsh^+tl2)Fp58bGcy1@Xk&9xFOZ_<6 z$ar$}v4zT|JbFH|!nwQtqy6gYU=X_vtOY;Yd{ra%;MEowlyZ=Mw4UJ}<`;od^;Wui z)rVy}W{Y;(B!cs)kt8=Po+_tp$Ds1tbiw>9)T`8j^9Fxxe4WO!J{z$y{`qXtmnpF7 z1yR4F9pw5v4Hz8X2KHid}oMJE8bC2N<1B{oWmNjo$%Pv z>*W7s1P*^Lf=gota7ug(Azz9>dgth zpv#=uSgZz#_ts3S?-m_tk;j&;Mr@Ey6Zd!QH1;gK28vV0=_Nok%nx7sFMA7$OA|( z$0VKAY+b}gn(mn>y5Sf^m7g`i?1C(t+%Ir^SrO=t+{c?LnXt0@PH<~lgDLN-=(fdO zx~gF%P#zA`q*NO`$_Y$`Xn71&Oygcj3p$wcK&+j%5)J=Fuw~AHuyA${d`x^vM=q6u zLGM30d8(B&4jCfuEtTUsjsBxG!-R}agFll??}JUv$M}e;S$y=gWcn@49a?id___*Z zXaXhFb^pbW*`)_nKW~7feFocNev*H&!H)^xa?Yt=OtVUhIQhO%&gCTIbPnd?qA60i zY2ajN3Y239#|#FKyVp3)a$A-scuI@UP2wy9BjE5;IjEa5lCjDqDt;>GJ`puMXFn>0Fw8HYa|0<&fy|6Rr=CMs@cj?w^?eP;Gfl+@j5w& zQFQkaWuAEjrrnv4`L70#W==Wl+4_e9yry!7Ugv1Di8Ct{M}m8h2oAoCzyqWH@YTZ( zbL$ts<-Bk?&01E(UDMQIt3qbdCFLsG;`5KcU2z9wPRXP0_g9da7>L0)|D)F`Y0Ulk zdwStrOVOqM(Ban4Jy2{AeUp*GafAI~$nk%mwe1YO*Eg{v6@|eUF2+vNgPChz!%6GZxcb9zmzl zc^cbOAmpC9!719CYS+x=7Oc6{G{ss2chAkju)HC( zyY(w9*)4SO{u0;c zbhhM%%o)MIF^>b^Dxp*6$UY2Jw8qLW$D!ohF>cnVesDNfiFfKg2xp-a1x_e|u(TNZ z7?=Y&uVdf>#n3Vx7xa9b!D&x>367C%G-G!g|LUVXJGXHuJCk9`B7HPiOznGmY@ANh zZVNi#o+B`+d@}y|7ENQnH1TTxNmBdC`QYMY%NnF-aem6>{EtiH@J_fXXerc^pJ6nb zjxVBj2g-Qg73$o>2NpPEtr{9KO`LI>ht$=p@xt*QTCho*l8?&6jO9IC^?$OUyQ_#> z5^7Dw8??FEMT@yBs}AEwT`^5dSD|716v6tpFn`Ya4l9x4J4Y;`Nv?auzKtxToWi)}e)jF>H=lOPvd0wAgjDs3z^TRz-s9p*js)OJWN(` zlAggBVy*~IvT5KSa1fjx^}^sjp_})$6@IH-0&Nz3U>|ju#V(S-^~UF5@`$OVXrvE5 z^AA&~qzta%r@-A!3qf*yllXbudw#s;FgPD)%544#y5rY1_-%zWXE!H8^r0=wZobBG zk*}afxEgsf70H=kI4L~3A{fgTc}t*k@2&3!TT3aXr<3cRIIXLSEf#9YV~78k_xj>Q^SxSWnIA5 z93RKp+e*3Uu2xbO`tlYC{^}(i&nf)OZJvUUL%^aa{?VgXd~fF`8e$s-$MWJKIH_3V zd&VA*W{kx_mZj9xwTHSkm@_qJCoV(2f!6fe;<(eQP&lVh{O7zAnk|fDttXd(Rn-o9 zTl^O+{>9O-q_g6Xx;W^+B8i7>iqNF30km}v@h{S{`E<_l@EVPKbgy&w3sb^aELBktAlZM66|LEW~|J# zf!U_6e6helFtJ&LogR`HGhdk*{xxOaS`BGmza#B<(@3qhXTVOFy@Cu7`}<1Z$&Q;) z-*b-J+n0oy(zj{Mtg3oaYJw$yg)DA^G(OdR#b+P*kG6O3AO{gL7jYv0-widUmtlyW zAw{-UYlg5NF{Lm&y@H#q{F~;fo`A-Wqao(3m;zO-VA@GptX>`oTlEfzbDXv@RoMl+ zbb}f650Yaw)3!ju&HzaB4`56FCc`M*AuQ3p5z|~EAj~BZPW1Z09?2x~y3Nr>^RIlV z;XJ(TeuPV2dzjpkBgGoq?(z-GrqMK&1N5KrdkVXMogbe5p39q>KyyOBgS*!ReDt{x z9yKXYk5~d5PV~ULg;ywnyTHrl7%>;WD_ql=g&4AJ8hnz@fQ>;_G{tc^>VKI)@ZgE$i>v$FDw?0yTdW*kyrRp}1NJ)JA1N z!#G!bWaSLTU7PqK_KWYY@mY00gcrITTG zh!#yt8j0zyLvXQ7r>MKQj=L2s&%&%`a=`-=(6B@c?&=(d#+$o^Zsf;Y-_>iPgsY2D zNsp)20heKK{Q%~FdJK}LlEP501{`1?sxHp!I#9)!;-}}_~;V$(L>Y$R$LVUS#0*)3KwAvf% zh_ial2R`cH54M|8kG(8@wC^DYpEQ!bT@Gm@JgE#i;F88Llu$Qd6-kGnZpdiLj0i;^ z4K0=tC5H*UhAb?04oe=A%+wy;rnk)luvfdAkNl!fqgAf(rOpd!)r`sTPO864xViX44?JSvVJBSsT^( zg}}-$A)Kqx$AUi0QeBvrd>D_vY!ZCQWQVpZ8kHXXUGPpOcS3s%sA~{s` zizP;M(}RI=VERFtuwWh^{bM0+lwzQtoDce~&KPqoLiE(EoQuj+LkXiHWTWLx1|!yR zzmBA`hTapntQ0NfOluakjCrlw7+KqTN*r8$bjvj?4@6*Up<%8F}3H0ZIi`Iu8-)ahS2?c zZXcPP@8?0+92W-#vpSC&xT2Lp-;WsKhDj*;6%)^{u507fTHR@3jV^`H7MM4Qxva}d z&`NF&!1KJo!!hKT+Sz*~J$xTsnS75Qq8bQ$|HPw@(K(RWFoVLS=K$KwgL&00ylDIY z*gII@q>EB%Lfv)vAZU$0oQmP<%nX=yN>V(@XFXcV&Sb^g#Uy`m0v64-r;(3_azA}e z+V-i3!}w+f3D0s_?1h8yHFYz-etZokTC3UJDm%tK%ezV&s@`&4?+n4as0X5sOyVC^ z&4GoR6(H}1F&8&F7c%n}ir4?0O66u6uxrjmZs!3ZJJ>Om?G$!bhbJ~rUioWa3>zdxhx->JcX2nWr4{oyCIl|oNw9I!97=8o#p${S z`T4)i*^GS-Y<9~9(Ch0Z$D@|4IbM?;f2RrYql7GAf2+vH&JIVsI7zZRGFa-GLHyN!zcQu6?IH}pBpP#a7KjxWT~A#OOgXg>|~QRmK}0{j|a&pT|s z2kYXz>F1Lj6u&?R71p?u_JgxrgkJ@0Js3jm4&(TFH)<(u>lic%h{s>1B@oU{M9o8w zp?Ab2dbL#Oy?B8vti@Dh-{r}!4NZWzi9O=%O`-H*(^qlst2pjuv>N0k+F;p;A26w_ z4yJC7!wG$cc=mcMy_R=m-wZ3@*idy$`#hBO4N0d*`{b}wC!X2p8)3ewDSK0Omjax0 z>DB(p*z>EHib{}uwaQ>mW%CDzyStP>GSyD{>r$6i;C5zMC3aDVR6_?pQ91rRZ zgl5fXs2lm2G>ijj+oUx1{P`%HB4pIYpLcsrE6+QCCW|v1Ww42J=I#y5pi-UDm^Vd-$((D2?w~yw zW_X3$*KWigS?~v@ydRFeWw+@1L?6)(eO1&kie`zTH(-_Y1^RV*Iy3q}_2C zoR9cO$Qre4{)1gs>)6``PeJ0QCK#rB;s~w^B1%idzf5IC@fOq3($$&GJ#h>^)lXtc z;z_*m({kv^Imw?mAVjQ3Rn=>(aG`Cc0@CA>5<7V1N2CJ+{nXYTc&f^-%?j9Fk#f;bIKBw5Oge1mTQ4P8*DZ z*uF8Um|Haj(pt;m{;*rHMoUDKXA1ea#`SQ;{jHG0ngVaf0QR*_#iNyLX!@@xZj-I6 z`1q;ccIT^yqRZw1%nm_5+-{Z6nyhf!!M{<3=m#?@dK{hfukapG%;~E#x z?{ggIP7=8D%`{9qEYI`9r(=FoD_ojcf~1o`1^tCM`qpn+nz=>%SuO<)%RfTn1Z~(H z-v;+et(eu><6<-Gf1F%ZqkKNXxH}w`zk5U!mR@q3=bFB0(01j zzG3+1`7!$Tekn6q9}B+6chfojWn#UDv+(!%ZBXj1%Z{)A2*rafFx*8RS8FiwiKyXh zL)l1lm>+{pUj{HU19vWMc?6TTm?2)^u@z@`8*z%>LZ9ohN|>=ikCksrVrT4ZNz&5+ zwk=!F47YWIVuw5?T$RH?76N-gu^wtC%x8wJU+d?7(ZlyMwU}JkP&Que6->P8$c}5q zvBg2AC>=Y1-SYPln6C^14|}2IIt#YDAr&Q6ieS&?D|CQ!=KpSN2AlU|a7lI!{;*D~ z&yTib;kmlx1dg!pnKsIPyhM>Z+}KysZNhyL3;uIuA>CjEWD9>c`@3#<^$9>@g7EvU z`V33nZK7k-hEiqs6-bYZ;qKNt@E1?-t6$dK0K?0aC~2}i+27HI{bLiTJ!Ux=nM{N9 z9)WkZ>K!~9Fo65|Ef97(74lQXzv?9`_Tn?OE1>zs@c&(~4D^WOY$Tci~ z{SR`Dk!P#ps$jBDG2d-bM*oeU&z^_hB!fr?)}|o%RqwnMJMp^(v7l{poJ+lCi$6=0**BM&Fvju<4U&~Wr)7Wnnpck?-0&b| z9RJ5RUmC!^j2y$(w4S4lA&KzlQ!1b1xq!AUj%C|IMq$b315hN4FGqssax22xL9OWw z8@DPBvfp;<=j3hef3i1He<|2Bb~jW_D9&6~WsKIH@Wxc>aWZtH3zhIZ#sc=ei~9 z*&>Zjq3Zbi&VKIT855>#FoY!-3iJe(1&Cb#g;o+l zc+NHY)Duk8bjxARjFBk6`XDJXRi?Pt3V%w*!j{NmU|MB?|HT!;%#9A@KVk;+Od|xGA^yfJgm44ziqLyNGq6L>yy%OHY9|E_PitI<_1Qzi_LL{qY#xxCHLA>N? z(M5}~?2n=&ITs6h-_tUNrVg6N3 z_FVji>Kejuy^SJs5Ab69uMQGdoPPq-JFEGXr>C=R>o#L~o-01x-pZ%ys$tW@cG~^o zBI!58VzC z=40n<=qwt_Hnf=Wxwdo3dwM#*=v^K6MRzN1X)dPTBul7h&0j?wGF0PaFT z7FC=ZggIZvVvV3F^}R1dy;o{%RH77HI53ROwzS65TYEvuW*zi@e+yUN?1NMdTlTic z2}i)!`l*QnK}pC5kJ+L{LHft&xV;Unw;WARqpC!EpUs2HnCd)D~;ssmq4(78nyd& zlb5~)w%x7e^%@en1i6iLGPjfze`}KBi2$;eIY!2rsu0y<>B*>g!3s2KIY*o9K(u>d2F+h~m$n$h&>pKa)>f*+ZY^%)_x}0>vs?MY>u6lN#<@2ZbIPOiHq;EDcBm?QK(%=M6A zM_LYY_S=8l&VqdXx0LoS6x-V-LBpjA zZbZj2R`|>sZC2{CzirXbT5rHl2qBS0bUrPaC1S>9OJI4II$mtEVb>+q*x#h1*bvyV;^|&<9TEQXhPO`jiY}?}3p{EIx{{h8KsQ)2HYJZj``+a;#r(PC3G^<}1iBY? zi&o9E;`Exw;Bop%lbbTY$=C#L^pApsNjo_e?KIwEy$^SBZZ=n>a)`J3BXDu^{=#49 z{Z!~;!akQR$7#(E`9H(7*!8pHQ1W~q*oEuk$*o~5dC5JP|09jxY_^*M(k{``%Sm9> z-OPtv6Ff_aW+IJ9KT(s*R&HbXZtRNUaCvM#7d&b?jhJ2zCfmX>|KI?8vh*k=&S>HM zee+P>(t)=V&NYV*QUJLjTh z@IXP35%{79;K6YTrgB{gT_dNkyjw@|%dOeIextOA15TLpw?z9T^63NsBgpR z5dVZ4mhPYvXSWdU_TeIz&c>}PH1N1fBbPKum`O@ZWgnwOENH1dq;2sctx6L%;Ab)! z9hG6_qnzkhLnLOut0%vnTj2J392(o0u$yf`lrZBGE}jvHo-!MlufWecGWi-mXQC#X zJTwiC)(X3l7kQjf;BEetlPS|{y~Fi;UxBvOXVB}qDV01u2rnl}q5fuNthl2D-SPW5 zw~kbpVv_;*)(}58e5S5^Wi))8!n+jO;_N<6;QrZ@XwnBzs7ZqBD=o21zZ`!3up~z{ zPa&_g2*MxMBR}^emv-hjtQi{(yB%9-x^EPWNDpFjHjMyd{vYHictE%AG-lqG%x1bj z=0hC}fIbdJ=@)y*)FuF}4o*VXH4MDvmEq76ElzsSG!p3-2|4Llpp$B-?yiQwM&pZ~ zPyBx?8#&{t@i-#QW(Gq-p=h5AoAqriS2Ok#{sNS=rKH7BjWOIH&@nrEo1+7 zh|n?dJ;V&Eq@fe6@#@hza5*lJB1FeQY2*f8$#o;WoG_c!88|RKnJ^qyB*U!Fv_a;; z8SpvH1f}v4Vd}UOXmnK*AD?i6C1HcP(9u3ZPaq7tZpTuFPd1bs(W10wfp_MqN%v-@ z!1haTsj@?k3XbeT-`Os_sM~}8@4{;?xgY_wSrr}LoXHjLG{ibzT{bdMoed9oMdibj z*rZ$qHoj~)O&hFOsiG#!4>;$I8B&^L@Mt?5oP7&S$GCF-Z7)eKIhj^IHzxIWhj0~d z#@2cq=EqFu_@Y-W;Al`ljr)u!@cTpV*Ppq(PWwU1z3#=FypM7t&+X&7@+a_zK82!b zSttB`c!Qg4(gAnotD3|kvvK@oZrFllupdwSzI8D4SY^q&@qcdgw5y}t2y zBu5!vFI`Gyhc&rh8FM+cXW4x7@k4Op!Wg`9g>j8jvZ?IrMRJU^f?}gTR8_uHZqdme>8H+H=k@VOBByv^c_6?48LbR#~yZuLjVu?X6sgVI?Uv zShA;42e_nt3t@&#BIRZkRo+&;!k0oM$*%Tgk_#`x&*9y_O~++AGpS`t zH-t5gMDLbdn!GiK_8nY+!@BIDX~RHKb<_)(>oJoq+E1Wu53}+6f-jUZZxrt<-0{bx zYvYbxd7wGz3;&+eL}QsU@y4+p{NG+3au=L6)2^3@0{`$ZK zM~6UfwKY3j?!Yb?&*i_{=Ly`hbQU!57xXxmQiz-aiqeE{&Y96vZkCGUs*wU#p=~Kce+@bRj<}6vmyCe$kp#@$v;^YYInWD*-Nxh?;?k~9C zw!s3&V>EbxARes4JYghoPF>0j#Je<9a<@iHM z0=MhdT6lH*1UIw?c#1m@QnLbS@CH59bQsI4sjb8l3cqR89|La5sSS9LY}huTzY(4A z4rZl#ARAyoRbdC=>kUZ=2{LADRy-5u50Ya4!rpVzEkeiV{AJP=W^8I}YH5t&VD_=j zLU0JGK&;?{)onNhPu(2xPP@RNpJ+|>smipe?h4$-CtO<6EZD7^fsUs;Xjkqy+Ve<) zg+$3>w9S&fq4lKH#ep2PiZp3Ea}4c#_74(X%S z(R0K@NceFCGJdI}{HK4A(GlZ9QOLo-w;ETI8{)BQ@$BmP%tHB53^TbV8}9aRst z!_=6Im7xVY@%7g*wq!#gD4&^3CK1D_L0?^P@IHYo&4c7yJdKiX%_n6o2~eV;P(AlN zj7*PV`uq2Tz4ttLz3vfR@5~Z8HB82-HBqeNj3s`Q*aS8+XY+=Vi3|(RQFPH{zHgfh z>D@|!U9B%jY3l%b>Yu{j@Egvo6kkKbmwawL?4vW%(|EgOa=0_8nl2u?M!zM3Q0>iO zXsJGn3oWMOFOzqo#_@9KvBeKNQu`~@KNnHOnu{>`=Nxt^Mqm`!KjnujM2h>_EcX7<6{6q5u9x zQ~wNo#%GIA%kwE2sV^Y47vuTzkmGRN`V3#jOX7u}^Fh6{k}prYOeOoInS-$@7&Bx1 z;r$4<{kZ`P<9p!#er^1EU6Gaf2pyGmO$_)iNA zGEv1H0x$7S=R8g#{|HO|+fC{F6u~Fmp3RPbLMF<&6z(O%a&M1h>+Qz7-m`J#Yo{NA zH=|{EpOR_ZWEUYbK71yoN|v)r+V-5=KO_E7<0-H{xR}D~jPUB?-~2(NMsgo1jY;Ka zIE(7jqD2npIng#HQdoISyl=P+TkjuCx+z;lrP97^_q;d28>-=k9}`hmAVc>~G{Qpf zR56xmvReYPBgkS3T+98*OUQ5GAI%En4bG>rKa09Wjb2V*KFJw0g?4tBRRp=_D^b`U zNs{g97q98EB9rD!Hq9!V23-9Qt|(uDrOkz);gl!1tfJ^Ym2F(WTY~o^q}f#`b7&u9 zhhsZ_kw)2glsGNS9^3cP7}pDxZbRZ&50<0EBO{RTILIP06nU%mgM6&p6b&+O;uo#F%V6i57CN`>v7P>2wufUnH|WK5c;>akaymQ z`YOKAfa(HZ|L*Ze1{Xl{k}jba!qaL~8+@1lReV@ZowKJaXk>Vap5}h#daJgIrmc~zHj~<`pJD7I1^irHDpv38v@5=#_F)(gPDdW zJswf z&sS)pW}uL9pGKo{Zi3+pM_hi~0KL+dBmBM&M@Mu~UC3EpZ{sA=-L48pJdVQqAKp+a zaISaf__Fv2Rdjkl-0}Y$S(Bv}9lCM_j2hO$00&JRXQGBDmIQGJ{O*#Lj|}VFY(&$4 z4Pthew(x$F-Fc-yw;=my5)N1p0usvVka+$W_-xcvZEaqe2B$kYJOP*yZsMQmdbcYdpHVzNR$d(nKYcv+(Eo^4DQR! zf+~kXF8fCm{&{T!<1b0Di8<>hXR)?1Cph^3NH#o>mSj{0Hu5K{-5F zCx=bfrXtj6<{KmMh~4<~0A8age`z)f68ODWL_N1dEjKhdKE#MIbA5(w)7q?^8Qz+3vyY9lbEbD3u@l zIv;ig4&;wT_mikgVA(skGZW`Kbi#fR**y#3*4?qjh37O#?P3CxA3TA1N{$w|w27iU zSGPm`jA}BTV~!VFxKeWiJg2<}zMs_PRSMRyMb=XAAb2Ud4L8RzJI=#f zrEk={*bxrAS7b8=Hc(ueE^39o0>{EGf%$$HZNhc&)5tEG_U$AeuzfbH^O?m8<~h@g z>JYFWZ3iX3vuMk>o!}K*5Bp}#U}Lg9+50`R+}A`CzHG^U63s2={w3Ft@^mvYTXCD) z{d7GG-7}t>F>f_#2KF2gSgr_B|lqBgq?7FJfL_*WleFR*BZvc$9mK4dx7lw3!&HRVZ)AJi-1vI zGueJ+LzKzdk51{!*r)XhSQ&1OStWi#H(3d{m>v^3&)&&Gb1Vp!pXH|KbF8>=2CpmJ zcVxaPVp85__N2IxH}zkF?Xm|eFDhQ8q8%M#S?keIzb*_Dhh)IvSubg8slf55FvATY z2Fxhi6vuul78N@$Ae%osxQmA?p%G^>X~%LpzODiOz4<1#)!9qamuwb~)s$upjp_@kI6%Jt4z+LEfID@iGf6=)b!BLuhonDOsa@<%2Yo1JILvOF( zC;8{_?=PO^jP)1t?qeb;{iZo9)t5(@cL5$X^pM-9_b|hu*>&#sY`knI>^hAG;`pjI zQ0hDa&(o#h;iuua$m$Y|8S4V(OI7g9OMOZ<75ps&Oo4n$V9hO0g!yqWY+npc^cjsq z){kZOzkYBaXND`@y`%Qh`Rwqg=log6Qf9lp6bglJ3~ou~RW@3(AFm4Vw=i?NGQ$(D zwQYhs6)E()=dh@H_Xwy_`XTgf@9-w9}J3LkW?^&h7XO!XR#81Uwt6#H`K+ zu=;nu`MfJJw0eqw@YQXnZ{g>_3w>dJg8_cC7z*pyW;nOv4>kWy;WW$(_`a{lsY`k! z4*oj_gQU!HcU3%kK3u|DI#&^hK0;B@0y6HfhtHm&Y@$mHw426|ZPFR|b6E~1{m$og z`-Zco7s)&f>j5p13YzRPqb8*?2)f+L`!&wu7H5ZWii@gY@OX0!o4kg#W!{0osS|1K ziVirq`vi0aOJmA-A57nWl+_3wn2S?ZuxH2K(aWX|n7@4@^Pl#IH?ox!&Vpt1ELn$H zoNXbG0p7fFQY*U>wvm3SO$3V{lW_Xuei+{E!aXoe7I*xPB`2JW%6bND3*^J|=3**$ z@P)l~bzE3qE-ld4N4IZkuHHxqvuo5?={#r{XI-!gK4o|EV%dl zf!f}!Y}cbST07?;cj4hM{Oz2FJ+t=1)_x^+XLAz$+WJyFdTs`olq|w=_jmEy9%?YJ z)c_Npo#XG;da}wCUAA#}GC!>S5NVy%g|FM($!e3p^oI4|>UY@n_fFS-2RCvr!e`RBld>#-W;oyK_6_>Nl|irn;pHeFBYJad3~znAkE`GD z8ScppWgcI{#c}JrS!%}{a{hRf)P@o*AGHELojeL!J}cq&Faq3iB0o4VOstk>ZP5lb>CX`ql}eL4ke?4(#puL+OnmpPXu<= zRJbDFz-=gh&09pKGqaMd+@JbDbSU^L{PLyZz%XI=;+Bm^zm4ZYPAz2jc6h*)+5K?O zv<}8M428>eLr|;x2Ayp*#bT{4c$<<>Z=~gMs_#a&Xv%)b-u$3aZ^3&gesG1(tcakM z{xWPq%V1Kwmklak(&)%mDP8#TcK8FMhi5@amMzO^G{S3j`_XG`D;RE#qQLfj!Wr8b zHhk+94;HdI8@ohkT(_TOzFy~b-smu+lIwIxj!?nl4Oz|}hLuXPya5h^U4_%hWpyZp zyDt@(J2&~-k-)-TgsjB+XcC_@0gwD|e8v?EVMjUxx{Y?y<0;R{|4Swn^k%_=jsU7TB^kd%1%yOR>1~oLK9+2Of@&2c>Pk?Dh;xY+b^`^T}sH z@sB^$H>i`zN;Prb1wH1s{*uV-{8@rVe@NUMjC)SK5$|sfrg{F}pgH>ujnBGG^QCmz z^l&R~W8V+Zu56=((8pY(@eF~5xD97roEYt4ePWg3*q3?+|fWMFetiG*&1nzR$bXBIa?Ob>c+FaQdQP@)&#ANG?7+C zi;&45hNegL_{zvWO1Xc$a{mBpO8NB-mfyE#pR-Fy>BJ~{Jogb)Js5#6zM5mf;Zqct zsD}3a@8OwKUz-h9P#8fzUfY@8pz zxpOnzUEvJhQ*vSHIs^x7nN>Qc6g~@qsgH7E6%l*Jsez#ehkZE*e4htuW2T4xFC;OJ+iUt{) zAHR)sr$2`Z6(gqJqXJ3y-->&u%b`o;Sx{(9gp~sSd6JGa>))!uLaIO0sYB%yyiN*! zkL#fi+k?<&S_CcoIvpPern8Jod*M>QEIzE;#=b1p!cB=s(KyKmXY+!EX%l_^T|A9}8^D2{Sq<_ny)u zc3`b*Kkd$W%NsQefy;?auzq3*Upe6dYuH=>MRPXMIcsGcJ%2vTj#x`(s*_1xyHAwZ zv4q>~paWa#ed+J%ISeGfQJ8i*U4CxF`@XuxdG?%#i67_D$NCZ%omMM0vR)T147*6n zwD)jxgc)Ip|9JSXcNm<;B$Brg32b74W%o^it(Ce2#X@y^!s)ZZ@2kTU$6w$xJXF|~ z(Si6r%NE@P_LlDW$#hdi7rRzTGrbMvqW({hxdAN;;n{?XBtGfLUpq7b^n+XAxX)1v zC|v>rZff9A#YEaNe=#jxc^o9u)N!O%D&!3<0L=`6(R5$n0emi?WhbI>|Bq8}Z)+r+ zKC+E;LY&FqSOLp1S%FLS4noJUGMatRQ~gZa9YUS;@*5O zyO%@ecS=uX(&Ohk0Mx0^9G3j^IpioD}bNGJ&5h^gIA}% z^JbQxMOS~E!-p|asPz35H0mCOllOl@nt?Z0t+fMo?w4hmN4@Ao;68De&Lnnx$4h|; z`dBX@P2nKF*DM2QZY@3bvx69?2i_mRr7(0+fyc&Zm z+mBO6t~n^#48oV+74X-@bXIUW7Q2(4Q&*NEJuiFW>inNJrx{rfA4h264WVmXvE2{q zjs2MO4R_Q}oXeNaNQc9&1KEh$32a#83g-2_LbPLNA7{M=@kx9HOxZJ&%|Z_re5064 z2>8cybuoeyT!BsGF2e@%Ci=e2nbn#*;ODF~oEZ|v<*dC4i!A*>|NCsz9heKz&%>bi zjtN|OK9Wf`u3*OVRq)cygS1e&fRDQ$$5O6;;%X0VfyTvdf(#i#AVC~o^;8JTv(ewAi7Kapia^)Znmdj?k^8i!tr_j+3?k^8Ul7R=U85qI@lv6WL| zp{XL4cUBoddW%0$*W@ZLHE$M9m>$4MJsAgEG==VD(nZog90>(31~}(*A2+2{U@C`7 zqw$s({A&#ltXCQrQgwciSOKFkt0PjT`UwA@X12v)we$v(x?7~ zz}isJ9iiXi+x`?LOqz?^9>~y=)rTm!?-ta{e&zIIU-GSKN$Ak>ftwm$CH~Qu#~0l# zpQ=IwNfo_+a83ieC! zfT}B$v{VT1@Ft4HO8iGKH_aLajAU{#gPqgX=lh zXUpM{zb`!w9RzlM#dOXwpB{c(1UsY$;o-4qs24OCE64jWc18*<=ltdOt#@U%eR(vi zC!=zP#eO)hv>tX=Wr9ZH6d0be1~N}*(vU)Zk^X<bS z)YxVCOLzz4LT`NBX@(kH3e^VMpj1mG#Q*B&Oh*+#fZ&mvB5?Tc+l*QEt~Mpm>rf{{AF-sjVP3Zga+Kk_Ol^$cX=& z(@*+OUr}joIv00#H7~6qP4D8DgUt?WT3jyALMRzkn*;cFMUt4cr<-n`=z-JQd!gc6 zA9OFYW)=SNq$f2;$d3(Tcl8`_r`lz*?8v8ni!zuHYlJTwhcchhQ8eyqHV$?EO|zPv zn3{EzIP6<99FWZ9C$+3*ZgCyZJ=KHOetkmGFVt{moiE$m9O_L2`8$-y`EM=;#vhM7<;1Y!^mL*BqwhEvel1`SbaNpp$fAvm|>H zng>DarjW`ZdAj?i5XPVRNE@~d!5x2!&YfK1!g^UtKxLX}`Ef-_q%I+H&^sBiC(MMlzy3%tnR> zH+BKy-TJ80C7(|IZKt?xLa+AqEqXG>h$TvNb1xQ|!>k2$^gzlBYVBvTShYR0R_7SZ znkUbEw-|%7-+O578H~f{H33?xFk8VNR;sp`BAQ3BP{;w%GU3dBO@UoGR7xiY4M*Ls z`ONmh6Fzj=DX#H_4z`O9;Kr$=xTWuvaX@GwsR>?%qN0^de&2Z#$;4yi%kPjo#{}9M z^x(VQ5R4S197$lFuS>(8Eww!2!uMd~%oHIEZ}#Eh=YewG8F{xQ6} z<0)G1k_mP~PxANr!(2v_5h=g?0?rTjvOzV@7*={&96BQq#%u{d59^!4Z?ce{%k_%q zFBRr?GnCoSae|xP=_qJS62qFeqJ8-CwN9=VJoXBlEXvUH)R53O{?A?4B%ybUn?>Y%+NkKZE@gBrW4J#F2EXBC! zNTCYD@vk?%B)=WwS(H(vD5y{l zp7k6PU0oRgZI8}X*3ImqpHBv{DL&q~(W;e}`3&OD=2t=CjQyPAm{Lx*W5OS1Hie~PY$J~cw!DW1exKwo#%|ErB zv)5~&<*Rj=^OzwlPhN1_G#ZobU_s)1U@fNJ9m-0d?P1A99M(+U0iGYdNp|dch+B}$ znGO6VnssFzD7_qsb0qCp=<9{>w{3 zX=COnL$Tr+o@R~?$Jm4K`A-*0DPi73=+JouFNbbpQRbtu?^rUQKggUKM*u3m&xOF; zR=CnyO**~9(4>C|CWt05gD-k;ccvs?Uf<1qoA{JT35C}7#>b>H?lYvN{uO`9c?QqT z8U4It&A)#aPh*31>GpmH95|(uf0t^40s&V0dVFn3MELD!d3_ve4G<;-Kq zwalbxw1d|1+EldR2+hz|#ny<;T*cX&u5;sD*iTUai+WP%I(BXo%-=8%7mkY|`wUAm z%zOxiHi?_z)hK?+&2*z9{UQvz7a|{1POaDbiJA zSFDphhVcR~n2CJ!9eMs*h~D&1@!hSC!T%25`sIlflVI z4O4>j*!<+Zob;+h;hZ^$ncw^Z(hFj7i~T!zIbR7PCY}+w{k3HC_SmyD?h2?8XnrqVNl6X>{@S5YpSP`ak-1Y!|4|niv3}XsVzuO|G*FWQ4hPm zOK~=`&uBow5b@ID-LO6Kkl3@-3qzinaS6O|wi)ph_L@Y|MJs)(x_t*mt_q+ZZ6}3$ z>nL2+Hh}*bT|h(qyrEA<8`_2LNN2Y!elI)Wib8K8Z^3;Y7pt+E`e~vwKRwv*>Ds7K zDhUhccGB0)K49AT6b?U6fajjJq|$FI@Oh$Xw6qzB43<--k{Tpm@`JE!?7+~a*VPK>`m6Pv(!m*;QH2J6%#@L*o3ZK8=dP)b|)@0((*bVq~ z+j~eZHe?rtnTXC^JLdB{3ce{ugX^__{L3+`=%3(n@T}XzYVWPa?OFn-xyX{-%LcPw zi7&Yrx=Q@M@6a4@nevTivMGg@Y`93+&Hc=Q^@eh+=7B70S#F6oLdWc!$x*O46+!K7 zy>R^G1@70li`#K51B-Fv>yNbcb2+@z z@M59j76=nkk%dR|X!>nE*k$okWbduaf}IA_b)nn*ciAJ5sq3L?+Y6wQ^OQ^l=iDvh z{d8vBV%$Ab4P*3;*@I~_u=t*kjmtd_hwq!>Lm``7mJth)<@sc`Zl`!&?LS%;HA*OR zt>8ya(FBFx!}0E|Ac*KprHL;#u@ZFy^!suVHU>!37u8a}Y064wH#;7p?g@RFE3vGW zjR((N!)a}Q0E~*-PO}zS3OR@2I8NdL1mD=gwQ27K??G*(6%tNMJ<2diZxT~@Yk@PVD!-j=`SIuaaKYAfMwrx~p__R(wq}>B=O1=Wq+1=0_ z&S6XKG}qRKAns?#RA65^U{Lie9#o9+W&ccm?Ozr2>e>#`m%3fmDB#!!txoXVx)_!zpXbhz z3y$5ho}r>7yRvCBZ+AfxI;LHQB!%tVht&ae!^D@mW*!qc4agRU;kQbg>&meF>3#U{ zqEp-`?&gXi6?A&1V%0h&`YD^nqD0%7^P34w_1_)xx9Q-xK4-jo!3C?PkEF_JS?u36 zq1%@|p6!*A$lLfyUnkooE$*YWS6cxL=={M)C<@_h37hOAb;>i9!)y#9o@NOr=N z84g$~bmJcHFlW;xjaWcuCaC{*fWmAS@Kc_OwQ1E{!N@SOsPSM^b5sR3k_UA*1vB@x z8PIm@1RuToHKfei&)1C_%H~YE#hGtUC%Z*Mv3!Fq8VR#6x9~QhLEHr+pG}9|#e+Q%;DQc|h!xV@+(hm1_%aGuN z6Ad3%=6bhJhK7EVrIr(U828tiPd`SGdb>&-R@=kv{Im%7H9O*bFMsCQUnl-@7SSkt zJKp?HolRUUuqjHDH98)8ezoyp+Yo) zA<9b%&wjPS6bl9X8|8sze-}~m^`$T>zK0C2Dv7hb{-Xr{qrj@1G2-R`(ieJFQECI& z`wPM@NyC_#xxYgS% zN!RQ&%XfbTZ7Nm#nhCq$PR;}B*c}O{%$Kt_exGPzQv_O$JB5-firC6w!Fct70h_nF zg6^(6%nkpsf#w!oA^F8^aQn2GxNbof>D2d#=2}RwmmeBM3X*;7ZeB9%rnmf{jpt}h znhc&aF$8{Y2}IkJ@irBfXN-v@A2D*Fj94@3{!eS(v00UO>lgUt?}Pa zS<@E@GPu-D-s%FAVr4D=_s3yA;QA0;TO{yUqBhg!Ey3tE#hpE!sDvR_=6EBqkhpKM z5Lm5Bm8D-Oe!c;G<4%chJ?rM4?Jb8YMJMu=)ZoQu+hEJeo4kJAACQg8gq{#H)^yer z@9o;lF1N)*f|^PSX_1!_i~2JLk5UE= z)f8NYLXYg=l&Q>Gu0=e%Rd8O!oq*o()%2-lGAq1ml0ULke`u9PelzN?SnXK6T^`s?vs zC4O)=Z8B=eh*- z?t~W2DZC`F1)sc&=-Fg7b|d3BEz8_Xi}%U0?DaAz&n*5&yb-(BK1e*aItRjB4tIH=47!wF2Yu`SV}UyUc@YT4uovf9{0zPLBK2)lXF= z_FP5Vaq69Ph%T=`3a;xi!Qk#e_IRrm3x9JNvTr2vX&Qp3PFoJIT6~0!(xGCrj7|KC z;Y97I#huU#qUZtJ*e-tqbiK3~hxg8cptW~7=}jZBTqOqIpfpa=xg^YLFLJ-eXSpam zyh-l6s$uexR+{xb0$e0N@mF(Chz|KqVD-22;b--7Y(9N~?CK?1-n0+g;+aXXp-F|+ z2veLlze{+f+M#UG?A56GSBab+sxg-vv?m79 zf2mu=d3Rn?)rHYQ&gwVOsst#otAjbk_N;1pKiDTUz(BM0lsn&=sTBT!hPUoK+dK>% z%7(D)!;@g>rKjX;-$?OWe^th=u|mnd^Yk&azEbVgM4Y`?i>@E&rwC6IHm$B64m@rr z>D`)`IA|H^y&XdfHa0+DeI71bbZNjHVWFT-I%A_DtJ=c|9B>bd3_I z#UO)!Aw7;o?T=vz9one#>MB{Lc~RW7FQo1`kA+{o&#kTN2K{P)xLJ?a(V8xyGvk*D(z~s3 z-MdQa55B-1Xf$JL;}yBT{cEW(YcwXRM)C3LXT_GbjI`o)giiTuer$s$tGdrKi=eC2 zxw8O#vb*^?R>SzU1qztaB5*2P17PC9nYg}D@E$8{glpL^=y^yDG>X#U>k|`T3(WCM z)i!n~x9xJOe;FwKtAW^EI{ZV)GnCN$8*;xWqI1eEl8B9^+!?9x;WZSA9K$-eX=CHJq!fk$od!Qy9KR%BuF}7o6e{`XE??4u+Ist9= z9HZ&Z4dP?>38E+H!LTDg`NP9ukF#r8DpVW+4( zxS7g^{^7$eZ^7WF)lfd~69o(BvsY1m(4MHpd`BmdoZ>$5^^iUg9XJgo@1IcbuS~Jk zhS^Z`;UO=%_!nfWX7I~>c=(=I2%F2>;7XN*coAe0{>}PqEg8ccMP*jmria%9 z%i&GhRIrk7z~Mdd6tZADdL^C^#}|)g&AvfsRP2Hi-87i--IGuxqs0apEM!?{?3ntB z6wZI85=*rC0Ries1oIgSS%KD<~opF#JK5dXJHH*h~lmhV0!o) zCFnlpZlsI?IX4&B=3UFBBn-sS zPbyq}fR9%U@D*JM`seszHJt{THOSb{%dqVuLJZA+_9>8C22nk zV3|z|F}5z4RXi7Z*s6$HCW`EhodS&XFQ&vp2XSFjFg{E$!n`0UR{dryb-jt?UHrXR zyRegNKj($XPbFEA%{7=XHu2gN1{g}_~tCts%S^x|GbQ-K)C)1V_$>68{n_u~86HE(HrYS}X zKt*_`o+wJ8B}Tj9?-N~eexSk6bDoUmQc|cOxtGee@mzLNJ{5C{{7fk!gZg$Go@#Uu zvO@xQCQTJ%C(MK|{)4de+9sjv`+!%?DWZ`A`@PXgntj-M7BpW@K(px+IQ=7H;p8+K zU+uNW5Nt-$xpgRFWrFtqG|I2~$b0+MOP68(pti&EW#LyWZFQM;SEIt)C2L?WPMQbz;z=bM( zE?U(Imak(JI&T)PGYx{B4tgYAeve#qYXxpnBD1LXh4GjF!x2+T>GYnb)RZ|2SDw=5 zcV~9+UgL%PO4CBRyi8Nb7VhKj?HVcUhhO8**-xqNuscrJyoWYkT*}K2R7X)*8+81B z4*Bw0;?v6`_z617@N1bOJG}cUZ8Y+~y$ zOjsky%vX$}9p_I~PT(Dx{=vbRHNu=;*pFm!2NP-UdZFKU-UaoaSipOQk+?snk0N!$ zE0@Vs&@u5l5-%Eq74rv^%tRd=mKRNxin_G4bsqDaYlMfc@8;Gl*au54#?!yp)fl`t zjpQE%G96h9+~PT$b!+R8#qzH((yB;cuP?)Evn%=D)xtA@^s zU`8`Sz1=go1*Z$4~j;}Vt{BQ zTkM|)ADcH)BwtW@=l)X8TdxT`rw}(X^es(#@Bq}))}hLrMKthVFPW#?vVB^)+{6z^UoI3Kot|I3mXk zzX~3SXQf*~ZQ6Ov?b=39ind}|g$JuYo6KwOR3gs>lc4(EEWR^s4ohthU}6zc%>ka< zXd2As?>P?+E8mNUd2WXOYn@=O$e6s48F{t(F5G#t*EM{XohT+ShJ2^y)4fkx_~~y1 z(~BMqn;pF|V9PKrt@IAv`)dV%RhF>Rv)!OeI+M*htj=q;+u#!CRJPbsRV>QZ!?8Pt zuo|-iJXbAu ziR*sdOY1KkBE9%q_(|3YV%Ls^*|B{UnqwVU(XP2{g1aHPH=QMig{z@|(lc&-(m#IV z!uzD%oXpRRyC)tv;3CyDy`c^9X3X)Iz!<5n5XU$uft|WMUXzG~fahM=l)i{JoqY%& z)yKf1V|rNsVHA{IO2Fe|o#;;DIHqiF2*q;C#9DK&!?^#EcBbJ}ym22FvdfkwOR{9i zk}PNLVeY$xN=aH2{fo4xM5(l>>``RRP9l*+a?Y89xhIm8BvO)S)uNqBwCI`V?eq4T z>pIuD&a1hubI#2CmhboT-Jy>*WvQSKQ#nm~wFcVYbgY4xE&+WM!{HI+kHYl-GS-Q{ zF#WU=t2JX5EW6>0W}VK#Q41>YygeE0fbCLb?M2o5Y>`4E{+Vp-`DJ9qg4wJxMsUw* z3Onwog9dkwG8@|BFqQiX&&|67ca^s>DIp2?&H*FVH)A_mc5E|cDHnr(abAP^wJ)LV zSKBxt@Z0`7Qm- z&?Cqe%ACY$VTQ)A6? z*CM<9N>s5$I^I9tLbWR^V1LDLFwflz)-5tXQNaaJxTJ;I-tx5}*0+qYW@obZ%#N}r z)iscGggGmnx19O#{L+~?FYp2vPyIDrSgL^Hn|X0jX(8&?I*ML(A; zg+I4;aop8w@a$G)#$ww|=B2MW8{d5gi`u&z>|DCw{>s0&|FZ-$xyl&7v6$pEG_;z1 z!RVkJ-$K~k+Z{?wJDXDhO;=;Ri$f z<)E2e8$2XFhFecV%5zj5EgAfZ=iA@KlihWZ?%h3HhM6ieXV8dsKN`V?H~)tZy{?Co z+)81>1s~Y9RKP6Own2gILpUM*Dl;=X23FE*&_c;$?4oSC;lrm~R{geogSQ4iwo0F{ zl3fA56)wm6*}TO$E&JiNp+vUwxt^1+fYTYiJAy3D2ch&K1@>H=J(|uLeVP-GV3mVY z;J=cu@OOwc`_(rc-XC^zYWRMTn`Qro@lR~9b*vxdsv(1RxyCZFX<5+dr3aq+^ zR0gfgnTAGANg^NjQ}{2mhb~g<;6_I~^tt6&gD_w{`aCuX<+Hn~fxTRgREaNhlGER0 zDMsNRhpmvgdmhU0=6Id&LZD`UD(n@gVB1J(E^qlBZ0QJO{af5%AH50cMtO2satX}A zJP&Ag-VFNcNieZ8*^EO@iqnuLWL5l)uokz~-`QhJG4na5%zu-qV1p4{z9QDiv|A2J zXaK5_zYtw~!Jt`-t??)CdORk377{C7!!xFzVUWQFc+&GBwCp`Y!Y6o?J`2CgC!ixob#UEjZ+wX!rQqZH zOsky>m&dq=ePg)+4e9kcJyvi*<%(w**=`#)_j3>Y^{SUC436it$$P0H{R% z1^kn2T$%;8wM&AA1Ls*!J5_c~&}_Km{Y-S~cM7YPO|YL1Z$Ju!HEUYKv12GpJVUMw z8OrLRQo$0G{y`b5a7?m2R3Vh>vP9hYz^Pm1D^BG4qrR2f;cs<-b%z%~a$Exi&)p2a zU%r7(Y2LtH)E#Qi+8yxM>>51c#$$IJjfE$rzd#u->-s;A`}mYt%6Wc0ncCEgu*Mcr z<*1VNFVlu+y=0)yITh?tp^WY)pMqmL2FN;4jV<5ug)&~>1f^`0*=o6P{5Yf>Mqg7w zou(909uI*qxx%`96PAjvs+*vf}XTaXR|D38xbBBh(kD*RV zHnWdE8D?<1!!`GQ)D!cH;QOym4RfswIfnE$eBj3SXrV4^^?L?lt`;D->fdl-O)e}C3`EtOMsnvWN!)+#9PYfvu^h58 zn2w0+xIJ?&ezABfG@9ds%~@TXV0;fs$#%l3Yq?bNqiojBQ4jyUIT!8Ho{NojQn97k zVH~HN2ZgFxuNeg@@tGt0sNRa*8Y+)2w*R7%-X4K){u%g7fFq_VY0QVHM6~eeYn0eWI}a zlUi6ZXBmo^VTX^euSBm7>7fCYHmZ!va+!5jo6S8r$V9lRunsr$v2(yDI28C0AD@t7 z!)()$jr&YC>ijyq_x)aMUik!`YdC^OIZyl*St+#U-x2gG;4JjDbjHoGV{pryA{ey1 z7)!V6<3p|@e88N0#XBWzwS~*%D%gb$y!skSSD!^&=3HiESD!>)&XRD6ml|y4 zeZw`D2<3$@#x17N4cqt^m^5`CYWlzLxahMyWq)=h604sI6=$a4BUKf6uf-5t(sU6j z|KqXuerdzL#gmcTw+cKfIuEN05Q3^ZsM0l;aq7r-_&YieChgG2j~{xVM=QQj+9x|; z=raeb-K5J(o$_a8b%m5fVmz{m?}CrSmoq^pSiE$BGn<o^3lX;mU%4&@QzS+KeSZ zmCi`2)K17mD6c^Cx7(tx(^BAhC1dvKlL#oE`jwiRr-|?HiDV{USj@b8ui@ltZjQ9` z&Dc55T+nLGUdpbmnqsW?aO{eEFvMXWT)tWX=WzARVGCc_qVWd35f^7&8l6$4#2PHy zwuky@vjJI`@$eoW79P5`3a{&FbNtxki?ZB3@D%$5{NeM1h8?Ct9A|V8nm+l3|5M^q zvFDnwPGFGJVE;@MQ5J{u-&J7u^R}?iew5LT4nR9>_rmuFc!=2Yo4OEq3WYg8gI@7J zsd>Lm(e?vJVa!KG{I2;T4&0UHq^R)<$E|!{N4`IdU(arayX_~THB!S=*NitXOwO9U zno^C0%fw*3jVzK)6+lU4Sp-C1n2VcTVV1QubTxPh6W*qwq+KEG^Cc2&jLRt8a6bs$ z^)Y2DPD;V^CP7HX#UG>$5%|_B85CB25*Mz13D+hDvWfd*DBGtIsDIoH?Rc&Qg(o-< z8t2avo?@Wg=ny<}tOn}b7=g3%O_|AeoqS51r;J6oH!!Mh# zqt1o!zLo}i(aeyQyl?_XDmLTyd&F4h3l&t%i4JDV?~8a%&mvqf5sCFz_T!Dd#%Slk zG-TG*jZ5EfYzNDI@cEz#T0|?eRo6YB)2R^X{dzWAdV|~fX1|7h38v`Z+yBr}OtPD& zlu`a+!T7UYG)nvL2y2?;hy35RK$lNkHV%TFmUBZKR%m5^(2jRWJJydYaBJ4Ozgi}7P#8D@b zsDuF>Hg%gOu2Pr=6{m9^^hz3*E>>lC`}~KLPFtcYi%y`dzs~sg(oUSS+Z2NKYU*I~ zWvl~a*h{NT*yW|W*>&?LW1;K}w0|fJ#c!}_j)>PPFD*fCE<K;u^A>&{b%rxosj?FDFX0alk7B7gOYqw_{Wxnl3D=7)W5Xxj!~do` zFuNCC!3$!H;82q#S05EX(_wAY?==HO?g+&4(;}IzFXzMa+rn{G9LH`lyacBX$RhRI z*I@F`8vN&~CYDajb2{GdhhEuDXC>dh!c7;sy|;cHwY7(ZwYhKc6S4I$xm=I^@s-m= zZg68(nXBTiADVb%({6P7ur_OEEX^$Pjb`neo8W;??}nbvFl@F>7VRi|3RCB=bPBr_ zM|D2oQ}+mWv~j5%nz0n3%Rbd;m(C@W`LNN+nq%$rpPJ+32Tf4x@*+0uegZ{KQb9d( zE0N6Ta_Zu!7`$<`9CgUwV2%%yaOsv9<{7tFC|xpyS6p*MHvT72pr8v+4gZQOzUg3T z&i9*8^9oPpW{4qfT5N;Y0cL{Z^E=2bK)wkin!R&3`e{UCO?M%ToVd=Md6et)^$dmX z&3cISPkS(zlA7?C*c%vsMinMa1fkX)hHQA^Q+(^3H#XVtgnSneC?Vi5d^ur(hNe2g zy{W(PzG-SG!r~F92bN~j)%iH!#s>DK`FcDxNt;S{Q-y2a<-j=JV@g`g1;L%%tkt-M zG1In!Z8yH*WVLfp!$Sw38ob7&-Z_PzzHx<*{kx&__jdU2!y@!#MFRR;z%hY!!yvk} zk5%&d(qK4Aja64IVBVLC!Mxu8$i2UymaK_n1C?sGn`{KuMXnu7v zYX0GZJ}PoEE<1oPEjx=pxI3e1&XE|smPdPgUPJdAU2sQlFLb=3$$rh$fkZaP?ea87 z<+YVf8p_n+E>1!3tim z2}XC`U8X#`7DVx`#gKivMj1H>ap?-aAr^fB25m;47)z99^mM@zI(X2+C zJaC$Mz-btzwI-q5iQ8~R#a&!fV}Ld&rQzgX8OY`7DeSx44qddEie_Gv!{+1aYtb|&1;V~ed$w8}q3ze!qDs}0`nw7GC^(%v zcP__Z9RkSVl@HRq-2yXL5vvY$~#^i zZAqut=1@&U3E@OK6G8|K#!>$P1j*b{Rp|*xFsJ}acx!DrVC`o!jnd&7l&@l*0 zUfj)Uh7NG``)OwJ@FRF?jU)2AH3 z@v!zHWcjfdXYRE{KaUDw!eBgeOs$=XmdJ&3H(i6@z0Sic^Tm;WO+GHV8;^RnUvzr> zL#bPyuM@t>i*EfodK7iJI4aAkd|ORc#JXE z6(3Q(%P~A5u859DcEKMOx@hOZNGkNmR(5cQKU-z{3nm6RqDKV|tj*>&82xlTJM-07 zYE!!!ycT$y3ePJ+E5EG5)^a@dNtXo9yl#U}E)T?InkTqidw`>zc0)Or19hiHPQsIl zuFS4CHP9mQ5UXCsV}&szIOk;f;{MWAY;bxC*ZUraVSZImyz@3J`F;k5#>C-e++2R+@PAH;U*y>K zpnAr%rUUcrwsZQ@GA1ji2DQnSY7|;_UsE z?2Pd+wqrvAH0%AslthcOm(}Lr)NdzYZ+AA7jm?CSdZ|u*pEq(Vt-9aoNRLuBBWEKi(ZatkZ&w?})YnM38T1}Jz%3w*HTHvD;q z51$`k(9Ks6btPf^dif;enNtb1ABeG)x1wNii!v^f<1Vb}QkXYYKpFO=!TK%lsqQ^X z*za3cp@mER@mqs=@bur!>~?Dn2E^yUyBwR}YT9(T;Zg+d%$mtM%hOPc^Q=^rzsFT# zX7KUFb0{%*DZX6Mg6G<{!)`5QM9n5q?1f^c)**_0bBD#r2ZYdWn-D%ep@=+y4%)I` z4|N~4g^kgji1z&mqx*Yt(z{lCxkMiM{($&fTsYf=2H=UpRJi(*HnuPo;KIo}aOS@` zjI_&MRBqeDl&n3B9&3HZUB(IMzN;9kc+|V$Q-D6QeQ1IM{m#SNE?;4P#(C&+R0$=1 zbbw~7l5qHym++HyJdD)%4?+9uaI7<(i7MZU+$=}os<A?=4HE!^>>gb{i4Glh?HaiX~# z)2e?D$K)P?gIa2^ae6j3393N1j&5bTMKhp}&;xFFZekv9D}gm#e<@YM7cQ-DWy;S$ zb|T~)%Jz1JZ%(g51*tYn!0h8pulhGlIBdDFrx{Tkc$N)3pk2a3O)9Jkt|9iL~i zC4J}7`~6z%fLf&}ib_Xi(Yx@8mVHd;6*bmziVah1_TKSc0jKpcEP_{46`;WheQIQ( z9iqQqKu!ansoI4yY>%LO$X0yTEe6xiR4yB{Q=g({QT^k7}~#1@Vfx&3o}a=;?!^~V;Dg6GtJsfA7-+NID3lhusf z%Qng+!5jB&o{a)Cn&9$3sqmC$8Em^+32z+MMnkDRRPO3m+>TF-m2r_koqx{3Uja0A zbJtol?mPs)2YI3&y-QKKVK2mwIG?cN0PJ4d20ffk!C{A~=xW|w-n&uko|{bWW&zrPVyIZxdc1!3eOR#5j_F$_ zhpT4(!9eQ(eArxzn@*f&(w=jBWDPO2`H&vW{m%L1H%KCb*gRJ0=34ecT?ba4y#V91 z>Z-%TuGvhBkp?SfS&Xg(XrTLVPe8w63FPy5F^t>LMvWih@)Vwlp;WvarEg!tuI=D- zlSU4>sk0jk#Hz82{TWo=D2J9^Yl2(r^U$R)G^6O|2s4jPLGKR6!IF#`m>Wc62ZxvN z-1Ika=-*2Gs3Hn|Us4Rmif6MeJEWmr>qaD9Tu2r8?q(By`oTX^C9u%*Dg%;Fu)UuW z;O>Z6_SQjJd{g&0RDG__RwW9zP z$We|v7qC%Vb}g?)9wh8@t{2o;eSoBa4b+~wpB?eD&E9Dl5a5=>N(M35gk zr^nS(A@lGJzZ$sIC>t{i;$Xw{L~M`&&`uS9qyA0IVOs@G)088S&&v}0(nEz! z3;5Q6hK;F>@42~EttZo)cn|hA7BS907E>Leimc1!Q#jGl&aP3t?mGv=pbLu>N{xuD?EvMptljU&Tx(pZ>kO#9s5N@3Aj)IFL zQOoV)Y}wx~>Xg15n^jOwwJJ5h_3^q#5Wex$fu&RJSOcVq=dbRhBG;})`Tb#N_P=Vj>ZdfK-5pTf_+GrR zERz!NGD3dADd<5c##PT)rzL0lv6@CC9&G91X4(Sy_q-GC$+U)rOd)zNb_WK{7ROiD zr7#hr1UENGVGk-4GJ2hfrfgYb5$2ZU1hF4b0u){aF zTI5D9yZ*Hww)*#&*>QB(>7Qf_<02D;bspVi@^$7>MVT+4>n=-_UKEX`H6?M}_E@b2oRO-8JPvT#XgpiI ze;@%i@9k!8GDhh6LW_q}U(Vf8#zoDVF4RW+1{21#hWg zl;*vrvX-916AVCN?KFNHJ`-=|*i7gCKBWS8OvWjhaqymf23#loy8dcR1+~XegN27{ zp_j54>;IoCTXAGQd?jm#5}H%s>nJ5w{)IGqrc#kjn&*L*ubsv|Jf8|ldJ!yD3_x)M zisx z6TpnJaAZGsI+JB?h@tsW_V@T(#(Sv~`?vZ#r8kttD144>Fr2j&rZgnskayzf$#r#3 zXSNaz*Un()(G$$4dhxpCyHk-M$O6j?q}Z$tats^@Ky9bm8xE|y2!-3`Q-)!?p!A9w zsGp;XM|W1?>oA`o8YJ0TZF4k7iNZs^v)Lofu5gij3+&4~0sF^yA?n&2tP{GBd9y|z z#TE#d%fq8itacb~v7N!JHC4a^@myxjD|0xI8M*c>~24 zI|KRm58+U8DLkdw1rnOctm+ptbeWuj#<@I1*((r@+7&beaNSx0aRuxh{;4r(|SQlO~youF_WGJ^uoXvW43>O@$#~03i z#vVD&to=M+cJ9f?80c!Eha<8qz4iqaZ7G42V_x9p6=$)}qc7NNx<1|$lEg@wA7}GD zoLO0=8}Mb~ChXWPq)JccakX(Y_5E!rHruiXUKqF!Q@G4)&s`31*J4@p%!GAXuDXCq zL^-e~^d77nUCxYN&Ou`r0^qAV^-jaW5VXd2jM1O&!OrP^g5$pHP_O^$qW$*k@U=^O za5#C7+B>fvKCN2|UrG$%(}zYWciRwTLn~n&t-lnJum!IxLuXjW?MxRabVh|9o~qtr&Z} z(SbGkJP*BhctpK0yNa8>$x{!t5>a2C8>{2`hE35uMSY(V2pwe_8R=pXUU+;3mU2sj z3V))Y{LMnBC?uJG8(m?v^hNwW=O{|HufQ#wxY*a_1loAd7F}PILFKm&LHVVR;H*dY zVar`59O2IC1dXGi<6AMd%5^uE`jEl?(X?hYCAfUEgbHlME@9zF1Ps09$F|o_;D{OT z;jQ`hIQHoXcJ=s&|CL{deTr}4>52q6G1-Ok7wl(h{0yMvE(2=5|59%L+6(sts6ct* zHZ~Ec!nT=DDECe;%0_J#`n}7M4docli#|x=&E=dAJ+;=UV~z{1^4kT8un$}|;b=p`A2-|87r`}OBhfBw3nB^jrojOit~BJwtD-;x6jk2Q0-Z@I{_ zVhZ~}-x)2i*iJ3!Fh&EZb5TvmeXP}F&Q4h)&gr8&8Ka_BY^JsZ>+$N~6!*jMn_@o7 zyv(N>>#o5eHVqYh-^+Fm`ol13Z)DnboLQIG4!0X+ix$^p;;Hc~sQj|mc<}Zk==o(8 zTic_Ij%*Z1{R5m=d@3K(k7hjwmJeyr5 zmW+abQtXO-7AOUnQ-0y$RL3rLM91wwnav((`p+mz6g-X7z#qp0l@H;!l~hCRuE&hr z@&LGn>uJ1}NXzt8UY8RSnqGTev%b0~|=7u&jj*Dn7#4z{y52kZ-& zZELe&J`!8||2m$;JmEi3aps%XCE9KM_MJajb)TT>j;8(M0hZ6tyUdSFe9o`lbHO&C zFi-HIHIpAK`o~w;r6FkA7R2u#br8%K4hg2r;R&X^X84X0#{~w5f7N#F9OT=e0O6Ct ziQ1a?A%d}~S^Vv1dHl1#E(oT7h!CtBvlnE36$)nkS0=b0Ho~86mMG9le#f7@KAUeY zY~X8?GXy6-K|%dt-CDH0M4&iHO8CU?693@zbG04?iv`-N9BLf}pZH5$Jp_6ahJsC< zLcVO?TEW^E68t}R&+&7Ot_qwY4TXY(s|59~0fMPpE$q}5{^CCzP!>EtY$=F~qy*bd z(gfXlZi4dlF8udzCkZNcOcCgBIW9PIKBbm^I7RSo{6j6h?jC=O!5YCjrw4p8GKoJa z#8^<|5LfH3@q};MxPm`k*TG-3-HV^DAIqO+TU?v!Y%g&1R1&Nw69i))rt$|asqym^ zBKQY;Kk$R5{Hfj3S}K?qQ7?GCaDpEdksw$aC?TlroF@2Kwu8U0udGIKV}oGcd`3`O zeT9E(??ZluceFq!!cZ`{KSNM6Ws2?b@w0-~h$({ZNy6G`gGU6Fr=RiZ0tGcwX(P>R#HuOsqIks~ z!Hkq^0>Rf!wMF~XMPELj7A;gY7VVr~!;8KG=@i{`Fv)m1{XQg`c2N;`klI#7UmQ>s zHeQOQpEM6U_}P>6{ySUf{IyQ>;f?Kti_$&b3wZ}oLt`U-X|t+GX2~o%KU+e?-z_W5 z-?Bj%LWYP$URy0Jf}ygPW7dTw(LxJ~1!T?e4wXEnVh?lxWew}6;w zH=WL}E+>2ho}yo_Ux-7Q<#a=DguO3VLyL!9B6b_Tp`|Wm(%0I~0l)5GQQNu-kOemi z%3Wzeb;vs5z$GbCzI+X#IvNfV&X<7DyhTJ>O`728a4T@Q{)(s#^%TSy7}I&nNTJHA z$)X9<8sN<|3g)#I(pA0%!qLH-v@+U9Cpe`D+w2(uc&-3uy}CsocwH!rN`FZ2>&&Iy z^ykyloOMNN+apBz6VmjK<{-K{I0ytv@af>zr*!<-G9f?QmA`7=N>F>@n_&CO_q5sC zIC^!oqsVuY81a|)pCCRQ3h&=+0xoSMMEZwc^j1GLQV?*CKD&Gkc-9prpe3f!rwdg0 z6|a;;tqxsah0hz_tHvl%^x+X;Kr9nEUG@c)D|6^QD@EW%cciE@JAt>)S`%ozqUnmJ z9MRl=r-7tdCVhQl88~eoA-X6XOl};yL^qU-&{je#qGsCySrOKZBfH0r+&H2PCqe zfx|y5^7w=aX!z;{KKY#hOE3QevYmIp#uQ6Y)$E;QXZkMkqKRVNjEG-E{6SOljX|y` z=C3lS`z=NqJ=G*f>NLQ$q_^PkA8Qb+upjI&9Rt@^HluT=}Imzw`>MFF3F;wH^fO{#!8ah zIHyke-D5Cgs}A{C-i{#sc7WKKcZiMI=fOuuOEaIKS6=7wvC9#>2p!X~| zE$I20Bp6J1e^p*ppDwL$rpt_?=qpjq^yV%7LYZ?LiK5Fvf?t-4h1+kgaj5e$puNAI zr9V!3Db&f!bhyx~EjSdXNq^qBOsEPtRnq!yhl0Z8^iFyXt+X_dJ~w%@@a&}oL14>G zL5!QEP;32M+J%3V)<1ZjpHQ=dPIi(6*&CAuAJ_e`Q%aE_er>NJCR`QhX>K<3pu{a+ z+!syZ4t^GIO}!qybl+9Na*H%AyY!T8rrwayV11_0Y@|SV>_Di{QtA=0r1Sw@x)u}H z_VfA84@w2c+GT~_mE%N)gujqXWr#-(FNsD~NKe}=DF~5}1aYltgucv6L0rB-_&4UY zVE<7)dS>twqSi)RFfRT}7*bs(2;G}2SaLp8nD??q;BTQJxHlX`M6edZ*ojFFPySm% z&l;!|)Lwcg+;135%S(Nyy%L3j=F8s%7B`L%=eH}->@sJePGq34G_*_rrlt^+pGFEC z?`qQ#C-w__6&&b-1!sBha@Gh+tfd@&kNzdhjf{!i?c+j+jV55rg%qJt?;PTsVv67` z78g2x%oVH_ETxk!N&&lmFTz(Ri}r8P1XZeu^b7ID#3NKKynW&Ys2C5d_0l~fx))^t zf`h~y;-008Yy()JT9C?{?wU%Roj;ZE*)~h$Ij&4B)sA*>HFx8YW<&PF`76QG8?(rf zW0j!OwSq9HDIykEnu=a&Kj1A_P6UoQX@aQbD~J!hnc&1lY0!RMg0}jl57NzxiI;xi zAetDab*o%~%hFNe;!#cBfi?5NHG5T%-qA^D@Dh2i{L+bLdmqxZ;3N1~B<`@}NHw@n za8TskRZHyrm&5-#FH}@qltyn}5J%*ixPVnFe1ZJDlRzZbM$fjan*@CUu7$j%Q<0QQ$mLgNYiiZ~02%T*5kDSZp}h{~=OvMItEUj>ey#5#od!Oy$QPA5_K9TPREyZ$O3^E&QPHh&D6(QN5l0Gk z0h!o^_pGs_0WFN7T^pOE($NTC3zViyuDfM~*mG@ge5)Pb{VAWY%NPMF5o<-aZXNR!gRv; zLJN_;W1DC=ArWXv#f!XR3-3J#Si5siWAMA+5qw4crd zv0=^&V7}%n9hRj79=uo&B982V+aZL-O7|d!K2%N-||J+T`&nG+t`vlF8QQ&gCbcER7e#^Ynrri z19VwDm~!_tXi}*Mp1$g2%!e)_ykakJ&eY@J@VtXy<;n?Ac&3xSRN@4Vo9q+Htjh#v zWTt|8m4k$j^<1zy=OM6ooJi;T!=qG2Z@Q(?Y!^S{h(NQ7q|th zlicHxu!)i*wq6JUlv`m}~fJjfRn86du}9Qax{I~dyvMSjl)iNE_-0y-&ERO+uswp}<)9DjBIB-}X4vwr!62tJ)f zqd1h3#XzwHpA@+~N8Ol#j%TPWoK{x;iPMgNmn!yWO_H z)Uy?+<_wDZJ}8ou;cC&kr%y#jv&6|17gwIv-G0%B;awuBK^<4PfH; zB2l+QiD20+72ta9Bxtz1mQa6SN+z7#&WjAZPB=br5JhcmAmaGx#GzXo$o-lE5O?!7 z-Kpq7esWR-M|Ns}?cGWssKidxcT|$By=_IV*OvmrJxavLOa-#`zy#4!vXSKYK>+Po zOFsBe1Wre9Bc^;%C84~YXmN@QnV7zXti3Y1P68h#cRsKdU5YrvGvxZBpZiMe9$1co za;a+~={xS^uJkqJhs}3IQI*_#_e&!Br3(3$nMQuh3I!eU8MK?DA~`+GguHsJgg4hx zhcp0%;D}-?kO)!(s>WL6e}8hoEMYTH|As-2b0e@YHzOZ7G?UNHO(VqvTfqUrEYf&Y zFE8oLNl=y|=Xkk)lra5bO};oW3<63hu&H_zIdR#VTo^C};%$;iNw*nforV^ z_9+}hZnz3gPEQ916TX5E1$+>-HURt;yFvC{xJh=(i;;``Ux1Is&%k4yYGC$m9vFPi z2f^X5fQj}la8opej4x;h=;#ly^{*?r^_8R}|86;GP`L-P<)0BVD=We48%886xti?n z*C4-L(IJ11?I$^f4&j|U1RNTRf#>U|;G>ojsABQAoUYeMFvG=i6yT$^{1ygz3qnS0!U@VQ8mdo>He$}bJ%@4#eo(UuaB>Xkue zeE3a_tz1Z0w3A?+WhGb~s6;N@rz$ek6nEs6Z6RC7o`F67dE`L*A27v4mmD&fM@ETt z(H>W>ih_=u1&98$@bvCJ6_uP_LFTne(^pe4@P_tus%{uK^Ntq2T6x!@?anXaqVGbH zrQ~05Pw_PwHp_=xl(TOY zSs7C$YG|ksMSm(Kg~$Cwy0RBU6Dzq|>EB15xUoA}J4YU@Q}_v_-qWI!XQqn0H(P=m zlNv$BE)Srq;X{78znb?c(1tKLm?3(8crN(Q$D0sb*-yUB{|Igzp9LN`?IojQ%*Y|7 z&%{&n55x!0NV>!21aQoVBCE`#fztiwbnwqW(poH6XuIJ6`J=K6xP3|@Kl;ojYjsVD zNZOf%7cYof_X^0BEAz>AqcM?EP#!5|dQ9}udnd2p-yyK(!c5VBY5l-*#dT5TGlsm_ zUP%5iv8dBOah3dMw;IHb@JLPHGvL}bS>ZCvDB}GA2uwq#(P@v3c%zIB7iV;c3zAKD*eb?vaTP{ZfAkX(s)5;y9QXZKo!)ikp+65=0bW3E3`Z@9WWoN z9BwoY5kdKjz||w#VA1|l!V8(=1et{Dr*w=QwGH=;?KYxVM$ z{a$6ivtWb}3rHYV$SwxQzlnn$emRKA_9EUjE)%RDe@7&*Ri};CF9SPXtP{EGRqXm6+1J5_k@8^eq|d76UhSW$C^NOOC66XtK@we z&k_VJxa)AniU&fiDg;L6UBsZgA_!6u5^YEB*gqVr2IofQfVdY;JdRKTH&yQP%6`lS zt5-Y%-_=xj83!K`ZJPPu^2%nx?azA%G;<&y%08+8b^ z6~RRFjdw)!k6!+|pLYlWx(pWUN`gjuQfc3*a#PT1q#Mc5FP%SbBI>QRY!>n#XQ|>mQHC=@$&izZQa5>3aRINa${=3WF z_qqvPBUdn7GlhuvOCZvdwZIs^mN-8(lsGW!0+2Wx4fwPqNEj^wfg}0EJM#%%^|BG7 z->60qntTiB+ARjxc1{9^9_ACzLe0VD!}p1tRTscgw;Q~Tw|){QJ89mf5Nl%faSu@6 zQ$TF}lnQ384*{z}2+;0+0gTm25Z438cq#5mL`RDTvE$t|Ae=-yoT{w^#>;| zY1SuVvQ8F|F>(NUdJ%;4D^2=MydlsxRtAGR>x6E!5wSX~g|3{EB2bDyOZFfzqxSU}0rGajnl0WX1FnUGvPrrP5h+9DX6(@*|gcYo81V zPYa?etBgK*Z6>egb{3!>Hqn35q(lZ?(qxcWEWOPpp66wG0^EEd1oM?k=%dS)2pcA~ z^6ZvP7CxQW;vllQ4RT&FAZAp7aJ^+f?_bqJ?4Gubu56UB&wO=)=(=znbnwH#>LYsK zBKnW`R29nq1S#Uv<22y7LX5uhmmvCwdq8%=Qt)rqUt0LG9%R@(1wAr`!l=0hgyX%p z!ta;ri1L|v#Ln-L^jK2A@TKNtP%&>ch}pp>uIgIxvP+fd`$!!4udoLxKaTJc7#rT7 zxtT!Wc`9J*Qv{>gRzOC|lz7~c&Kv9K;qF5}g!NTvfUGyAg@x(#LTeZBwb`BS+p0=m zldYr|=4CnDU7!R8qGk&xBN2f$+jw*SUIxpIWWc=YXF$@|0t^~<3NQD_3e`)Sgd0D! z(QiBYX}2LmaAri4jLEu7H?KZUbdbFS?|T6F+~`27ynhZRjm8R&J+TrE?oJ11_g@9Q zW`QCnNgXn=e-hZ}&_?Ta;iwcxU zlQ>Hz{O>l4nScB%A?i>tBFc*@a|&_czkw{cUh8MvDx+ewse!eiFP{2gsR% zC8T1c4q3IS0Vppp<@%-nVdy;Lv3kQeZf0dA3CSu%QFzXM-83jl329HIT}El|i0mjU z$}SS3|s?4%{yO4=kP8visk{?EJf?z}jkbIyJJ#`j8Kjl-<{3WLtW=Du!AaPle0>+=%*;)%2U*Xy~y#M88-cfCusW>CF2|)S+uWX=ko< zowXkEk1U{a`xB^Z%2o1bcOK<7Y}~~X(wDD7vZW}x>prws zd;JkE?zF@DxNYReg&0^`@`)_>e91n}S;H)&RV}^qx?A;)O zsBLcWc$b3E80(1fZRd#jyk9IaK~|U;^aYG}n_yz{PWJF`JpaeRjKfGPvhcnZ6OP{_ zey5IuiBp*PSxr4x>Q_t@%UsB&G;8jbOe=|*qzKnn6p{4@esZ~L6CkHh7fv|n;IIf6 zm|nI3<*b`YXl4UBdu%sWz1OD~pN=E-mE~mjo^;r09)mS;B`_;w8fZkQ@JjawfM4eT zTp8CTQd%-fH06~eY}Z5ld}=;>!Og@Im+VN6j4QX|pAx4Z`;ND?I|>z^1iS_x#JaK{ z%+qrp%UGKYeIKTx(xgb<@W2z%n&h*j?oK@!?!6Ar&U(fxaI>Llojm$19>WDskcIY| zzl=TDK~h%kWz#gIV9%vbWX|MD^4>@nMg^L4FAaASO^J6g(jt+Wj!PkreTL&}R!!d7 zy&^v=rSlz$I&VQP3^pKM zW1PA19l7Mtf*+z@Wi|5Hp+eMf!V3%sctH9WHR9_#0$Y=^xL?+D$X??R@xPAOZ1TpZ z+=EZ!$iZ|mi!<6SQh6*QRs4D~y-1ru*?*#SIo71`b{qF~uPLT@5pLk1P|o{PEi+JG zMbzi1qFi+?={;UZyiOe>#=XU;+V+Xf|5MJxotdaHnd0!*J7L`A{pj>}FS~zJk(;oz zpIa?AoeMBsMh5;<$4Aw=&~Yi1tJjs~W^Jq{hVe(Z3I4yitp$yi(J#{{n%|Ja5EZInX6=Z_QRS6 zQL>CQ#2slQj=7WZsHZdWzTM9m+qUuJN(#A^BXm$FWh8g=ur3ZCQ$f1#9fhkP4bu0` z!TVkkOz0|QRTt#QU#oO->HI(LcIsnNK3}2SOuCX}V*p9c9|}*$s<79a9q`TFYb;pB znHVM+lc?_wpnK^u_X{797Xx2&&$Bd$NpB8+Lv{jF5IkY{oEu!;?Fde0at+ye$rOfp zq;ucox>;Y9Jhy8Y&x{&-`1X<-{z;9y_;9-lsUNP3+gB#=fngk2j%j4u@1?=(`U;|3 zc#B&;Z!jczS%7iKR^DKFG}AaAO@>TfEn2fS(NfE@`u00|BzcjwD0)w&vO-s zv{o#8ZA@8}_!ex9`N9UNO6Gx%Yvi<~A>Z%b%DIg!h6`$kxPklj!Z3OS9F4q*rNtWP zl*xdF^>T1&ae#fD`)giq!vnF3LMr>n<%5H@7A#8lVV`b(6NjA-X8nfh%yoqa*Qr;^ z$!>LlmN*yoB z3U@Z?fdk0sY~~t1-{QkPl_A$yl{x;}1^wRYaA%M;9+Q%y0hyQBo%N>hX`(%w(wzn? zCpL0h91e(=s?7$EwnMO|K#k3|Z-Bz=W8|T0FdRrb$(@{Z71YlrlY#e!fJ**MIDg%O zlQK_*4_4uH$&g6!sE-6w+3&ErbtdWQ_9U^nVv3amh&z2u&5L)ZFhKwB9L$S?>|nPkjpmX1S3!X$|CKkt4hxPyre9M!_*zDSGQu0T-#1 zM5e79Pn&d-h=0lxGW>i4aVtE;y*sD_{L7!D?SU;k)>4MHkweK*8AkXOev&!&1S!OR z&rpW*jA~%bd!z)_|0>11N=P(T4s+SX-?Hhvz&ZOSij|%0UWr zDbGjz6IlBBJS_Ct32heTnD=NH4Dgr@A5_1PLwYfoUU&;{{P&R0ct4sR zH&n+vxti!4-we)29HCf~qW8rJcDrIU#C0a|`z}1>-{dH=^?~JlTbl^%pN;42KG?(l z7$aKVtwesmW_Z(NIy~}@Az7ty#5pelXTC`x(-bE0-iA7OWz%PMoudI+Ikbz|@5~~n%Un61T02pu&Nwo$aR#5WClycMOe0OFBC)dV6jXW+ zAnspxW61(l+M2A*t{FZc&7t36;)_&ldiVu;zo!zTg~_5%oz?JIR~;`5o5^)XA7QNC zA8ZDELyPAt+49I6_&IC{n`tsck|SA07IkUxL)(6XMcQGgx^NV~2hGG+ni?d+{}Y(` z$zxG%FgDbT<)>(v3;JOUY}#`$dB+W$8fZvM$J&9-@(%Vg{VX&lpFk^}gP{FusGymY z3Ef^2pT&J6oJt!=4ZP-i+#u{^>OKGscE?2;j%}Rn_{|dhEpd$v2RfLu+CPIFK zr{L-3jXlq1&|%p_gyA~ZaQlEm%2n9UtI z4=##qgjs%aLaV7YmDN=dpH5gRKuQbwXo$ohcptf)Wg^T=>muTuMi$&tfxqr8!G%8G zVEp+4K`lc-OXCjGJZ=?OO{v2TNoWkK7o7k;P$nlFvmKmuFmyoenh3zeeQMwxE}%m8h_$l{xasI4;jzNFLkCzK41W z*-?*3>w)29a%VYCa2`i((?$zx<9dm>QjKnGcM~SJD${ylC3kl-<)b>jvwt#LLg@5* z(TCX6*rsy>yhmgU@fw9QYHV@6|tgOs#HDp2*mw5iH^y+!rqnH zxZX*RYHgb%Jo=G`OFmklht@jU^m{wzTR*~3$7_Jr>&aMok?`i@T6)p>oqb*C04mI} z!n^Vt>EF$foU~IVf2@BF{2TTKUnXy)?>r40%&vsc1r^u9?D+)h?&XNAx`*6X7dfoh z_G4hR3DvjAgcC1kpyD$>D0_JXe&oM}e(44nd3ZCm z2v^<@}&!lsW-8ai~M-RD*uV`v7d0XFp1!w+zE)@fR`bq~2XZ8mX?S%Y42@1ZIBEeYtXr0Wu* zsQUG8*zR0RjWt%$0m_Lr? z!=oDo)Z=a-O*Tp(Bl4us=o#?_mk)l@sB<)5>^jN-&!? zEg9*Kx-o|1MA0l$xcyf569S(FFB+O5qfCcx{Frwx##=YGKQZ^x|zMzD2{C5cQ zQ3ZZ;F6=Wq!$eUt@bE#vMHduFXjlW9z6^t_5`YXR|B?CM0r9FxRZQ^7#jI^#*nWvt zuw8cn9?52;Z=?cVja6sQOV*Iu#nYjE+eXY^Th20^FMyxV0aRFCk10;6kf0O|2Rx5) z4!)Ws?XN9g-HWXKb%ZFq)(?NJcVY|ubcp`U9%B9R0y{PIp%}wMSlr=PMA`KmdETPW zwO)y3Vajf>ZKo#4%znyr`!=xJEDqbBALgzm4g1%S?vBzxzSp;r0RUc~*ep za~D|lL>4SHPNsIb!7kh7C$!OIO0TzF%ObBSX8rs-bo5QMi1_ z1037ppk>28&<{wV>j(Rid%tAq*yt3PWEx5ata<|hTGI57dn&k(vZBLE9>L=Y7r?x8 z4m|WWBEf@vNx=9yu(jw0w9Fj}qdmTHC3i>A&h4A&q{2{$5kKJ`8qc8Vs;aQ!$5G;w zoC|j{2ht7K1Ish(Wgz}3t%F5%-{9oh3m~M`gK}CC%$!#Wr!^|LcSTNcQz{dx73`_J$0V}7-wV>E z$I!o5!(r#6V{qndqy07e5!7TuyCkP~S^Olo8TO}@z~$5+>b6>g9^N#DZgnxD^-=@D zMc$NT8w7B*^?Hynu#RkgM4(UusX@bT=pFJ8cD&G|Ve}~s&Nl>;JY_-QO9s>V_M7-{ zk+}AtFJ5TSg*+uo)Hyhp{hpJ^gc({)!+j3UjWT5w|9aS8kJrp;+(&j^y#X^uXbX=g zNC{QNi*Ts+XJ*1b^3lcC$`6CWowE(O|17 zd#&QluWWltxYs&JHZ115vb}J}m?Ye1kbuq#9qfqV2aNi91{Y1{dAZoL+^PaETwC0Z zv9ks;MUcjib5e1myB&_rCKx*0n0?qWQkXkq6aI~zDOPq1#4+zSkoY6&LU4k-V5eeB zP?GIjYZ5>zSJ@N=9`J1PhNuXl)r3P-)ViRvz+X|NR6PaIbJBpjMknuq^Dia z;AWpZnCm(h7UuSHxj(g7i1b)IpAiXX$Rwiva~@cH6hQ4`1}N2Sz>1YwwEv!;_>|6B z-l6CvyC|~{Gz+dlfV~MAIXV1R&Z&z z3M?8R@jPlfMFxAevw5#)qw&(OWT#YtU25bh;NpIev70MkirYCb(zd06W8a9whsyH1 z7QQ1DEzuYxR-!U18~EE358&k`!|0FX5Zom3Bef*jq0vuiN}c;)QjiK~=}`cADVK55 zft|GLr~%zPw}?%e{~gM%kHP_m{rHDnS4pZ_Fj{E#lc3o5%x7l^-I_I-cIWB~F)@C$ zVcj6mQwf8Xi)$nh8!yiFdm@wV(4&@LiedLIYc$kdO5^wF!88|%J|A_JzxL0Urj@C| zrrD#R-7XBgEDiaM&O52zVg-k@p@H<~k$yOPVLz{4Vvo`(QfhSme~YL=w<~?QZZCXV-32{HKVXf$1vRny0=3~i zq?l84*gLVCc8PkqAy*CP#Xe)26gnDqIorYPNFMYCj;01Skx+GN5%J?x!)0)MHhS`&^ z(LqFQ`AhzT)b;Y0?_`PJ6=$x0WRPfT{4((h>rX6QZw0d{`^J_p8ivaaJGd~-Y-W=X zEuNVEjCgF#wKp%Dz*K(*VCGSKHq1+x*lS#77VG0!b?i0KgfD^ zZYJ!+!asaQ_AmZs-A>VK{z|#ZoI(7%H&0lT;Wc~h_78lrr?#kb!(irH7AsD^WCmR4 zIx@L=AD59on8lpXWX-3(iSM^6L({M?tifa%Ieb2rm>pSXXXsbXRK2o@+|>l$>e6O@ z#}#9!E6c@4xobr?j41E*QHe|Tir@m)7_$|N0(k{*U(!^5jF_}c#Zn={K4(oexo#}Q z57u-LT`GRUzdf$bEqffvnws8_-w|)b3dt|{OUBd0p)*Ev`H#McaJD}`?$1CG{rZA< zIf}Vu=e~+=^m&q9G@2_LDu>onjLEAr8EBfO$fq5+$??}J`Cpqs(M3pZ4Jws-3o|`2;a`b)n_;4$K&@-32bN>V< zOfn=N`mM#?!zb{&3t~mF!_xT3#zgW)tA;&1JCuEpwu6*O^4K~ihin~@!`qjQ6ncA= zMKz5#xP2!l2pL~3&}zOXQ5-czINTb;T~M#T93`=Lu3+-06xTFYa-( z%nSspTR#QagssB&1FCpwvlgv9PuxOqSeGniG!b?s3Xy29VFS>C3CGpGo2*Nhf&>K>!hX}5|`B?TC= zxfrFY3%DcSn(*r!J7G%8S>eOc{lXBlAKZ_LhlQ4R-?^#NZXq{UAOCip!419^Z1;c_ zg6a8T+rt=hupw!2)c*#h4CS3P@S zZ7vvuW}@edL_zz4j(FUOG}hKyL83o53on!4Ps1vtGSY>n z+5@EN_7h=_OAY=JT!g3d57IRXUMLlR4ZV{-Ltfu$_IvRdL8;n@o_jf$^?mDvksfN; zl%P%nb{MmFYUkPa+cjiqZ55uIvWoiuk#jH_dWfp0KZd6ACK!LOiCxW<1#I|9Pkvg! z-tQbsZ5piULuJW)|4IcnT$o80E2`3UH)qokSt<~aJBDuj=0ay))`GepJrJEN1gbZ-K>Q7$KZYw& z<1$ZL(`AIHzS7iL<}FbZsU~h z0S?F4pQqsvER6rsLFMMff#qX~9@n;>PH~mzg$Mswd!ISYpQ%Wx_i+q$Iz-!_Tqj!u zpwAKyv!eM&sCQ=p>D|2zYIiXZP3&NqOG4>$GcsEJE1oLFE-J1>ROr#~jr(Z_jeykj9X9CDEMSRbZ$P8L99l^QiW zBu)FpT9lE&r{4!4Ze9dur$Fgrhvy7}7E==uV(KP&|dMD4Jn+le-hsD{+~ z-Sn-#F&(3B}j|@ zc#2=Ft%BPpi(x{*BzmjzB>0a_qqj9}af#IqQ1~U|V6SM;91pAk%Mdv_CC`!=1XaOj z?|E?im^Hnrm&gx0Im7;v`~+CO)s+rTm!kVtl+&$}zNFmmE9Aw?Eh3%0eITy9L`*dw z(%+G3^lq*uwFtRF;|({_nJr@Ql35Ss6=lRiZaWQH^?@1;3xUV+)5znz7MeCG4vZ~t z&|aOFV6)&66}v~%Nn{gQcJ?gYY^nhVhZ#9casEm(UQ~l#ioApH#ubg07LX3-WSH5g zf(3CS=!9P)ES&A?AT>sym(14T-V;Blx2rF;Gucm{#+<^_Cp7s7SK|3OnU#3*>OHnT zcZ+yKw~26Lv;(i{@&gw+FXjeR-omT>o46pac=pTVDNESAkNdng51ZO92wZy`%J&n@ zv-*Q>cgKhVHLBVA6OBTCf2*j=yarF^?7^b6kr?XfFK#@NjoS}r;<_Kxg%1nVuywnt zpnvxa2IR|Ns(BQeCb z*qygGSjo4i{Ju|8II*vgb(J2+MK^dRc6aAeGD28q^*wy8`Hz_$@)i>HGsS!Cby%e1 zK=$8#cWl|L#A1E?g^c=UG)&EA3#$BuoA2FFVe2B)_iJa`=fl}TX*2xo6CxxTUSzTQ z*ElubaN*H0ZFcw493iwZ3eywz3H>j%gji)~c2;(hup?wA>pWg02*ME|)BXluxAufk zWe_Dg_(+O9PMLreO>4RIf>bzhz&2A0z+d)k*4r)=#ecV+jk!%V`hhOQyV`M(*|j{AoHFD8Ls3~*P6m4*LYk} z9LYtyiOHq7IcV+kisVctkQaKJSk7-HbDWewu1k-rX=#v|I}{$R08+c`0NaS0m+()3_Cn2p%=> zA}Rx)lN@IO!;9m|sb6NGa&128m~oNh31KAoZ5UbZFai&T2V(u_MsDBSRPt0q2R`0^ zOmD%RIGq4>9=90NYwJIrAT#%+&|r-TgJ96|{SZI#!?>VFCPi27EZXkavvnRgyX*J)lhq7HkQdO#IKKH zm}HkB4vJj?gK|dDWAiRS{+M#EvfG$*`4BAXu9qV@n?0y`=VjKg${O}ody+}99VBu0 zP1L-e1yQR2dUuS2==L=7+RYtY@*-hO(lOEH-}XdyU?3QpZiLZ>^Wd7)WL&V?mgaN6 zz;K3!aNxmw5|x$<^Fjo4d+tlj-x-p*x0B%f2Fb#5t0l1B=N{oMm;ff|a<4oR>D^_q zVD3Hxl7|PNi=<<-Slb2MgDT;PdI|Uso`YNFM8XHf4)*QcJJxPKjD@|jf&JYl?XT3% zg`$DQm>lz%D7_TJiY5>mKWURM%G;r*PDE;c^^sQ!`sBKe3p5W%#bw94(ZTYqsImSO z9L@=Y_|4sLtI&>Kh4Hv#S9Q|B#}Iql++R;suaxEajH(ng!+I#js*W8uxbeJ(&CS z3|{Opqn3ZosF8mfbBLHk?e^#4Ns_^-<8(4)(N9#A)yC#0*_>qEF)i>&1vNc0fp<}) zP1O#t#={9-db$g`fv-uCN-!j@&=h|AOS+Js?!p<>V4*^~ovg1NDroGvL3)yIv%=y& zvN6Yvbn`dZu0>OztK=hwn95cRAF*73>4R|H$r7v;YlHGFHN4pJNNBpPL7w{p+PTRK z!pSsj`Y8)h_lF9dDhZe-zekW!8p}S+8z-F2szK!qnf=Eq++*%8_qgvCLF0BA>1gODQs&H z*zhE%@Rh7%Ds#Itkl1N(L?h{N4KcGeAC84o#zwmR9 z1G}$rNZ2oT0mk#a!jP^z!oa~pCB1-~LP70PSUOLSji|~*?~VoFXK)wa$;QHRS*eO1 zyGG%NjSc;2+9@dQzs?kgEf>a242FM8Zi=OQN^$G_LaxH8R-8RK9rs>34pGBLl5wl` zxEqfzan1VrcqGx6_=g9JvxBdQ_Gw1)gUqUk!#HW0S~?dlf9dAG&qnh2ZUh!vZQ&;L zc))kRD)EXiL$UIJ>EviZD#?y-<=YBv$>{eZIQ6BYVe`QE?7Qi8GOFMM88Oe4NHys| z;JrNJS9OXERqo)rl8=&NV?&x&m<-qYBl*9V;$e0BNp!MX!2675<&A>??2)RWO5P&tFDA8iZ8hBW7@eXqs`Iy{S)rUj%^V2>;f03dqsTKK8!d&3B5=Q z_CU=1agt04g8@^Fq1SDR{k<*|nADbl53DH|wxq&#pFu+QmHiMo9`OFGN#Y)pY_c<^ zOk6wF2%guKqvZ$(IN$RX{OvpNVtfl!M>yf=ruop3=P$^QvS&X=>q7bpQ(@w|6zo?C z1@l=8h54C}*@(T0LW1ZFA4RMMce!V5`vP0se|jV81W2=DAxN0z`&S5m4Vq$-qq zsS6%{$CzbA5T@o1s#q><%O2$T3bVJ&5PH7H;R^l*?$uZfsiSe zCVYyUEoe_&jzR7fg3N`5ghiI4g|{<0ov*~8p&=Mn6e5@<$-~6X>#U}zM+mtsgJb-f z*@@ax+|g~oWgR|*cQ>73`}>9qi+VdqQ7&V9OU+RxRz)~`R(3|L(!-0S5hM$l*^X#0QK`xRX-n z#q&~Mvi7t(7g~ThTX65vQ>yjUPq-tegz+M2`{$uB6^&nYVxuFDDk z#&(hA_4_dY<7>Ps_nhB%`Ul_qxdRtmOvmpVA8<}fK(tzRF|nQIMtWnDP;J^`zNhFo zd06_#eqXo}f8%-=iBaS^pPy^E9-Yy6?RbpXI&Gck^SdBerM-fgg>YCpCleCpzvZSy zu4exf2a&rEmmxEpPsG;CNMTecIXU=>STDYsP0x8Q&fgXe%0CFqC>;rtx4DP{Pp;vt zPLz_B1LBdDK4G%QZj*~{V}x0~x5(G^w&+-pz>RcqAag4ZT-4w+VDrH`ys|kEhs4~3 zvV-kdQtAZeQQnw(!wlNv#5gVaHb_0V%E`_ffU6P-Jt}U1CF@V2XKg(kR|&`Z(TT7- z{1Wp^FNfyDHux5|1x9(B(Ljk#V1Gnku({ZQeGj78_HRir*&u=s8(d7>zQ5z^XAOn8 z@RiJM;%*$@V~vaIHqfmnR^o!I1?<<=4sy9z63^8-jQ;!YGMG0FiUy~%rGp}HL!cdM zn*}hL3=7y>vsdW)YmetD+~|}E6EGg_aFXOcl{?lFh1F@Wc=H~d@+O#U^wmcvi*)?i zlZ}nb-hy05tS~?9GCL#}Plg4D!~Uasc-hnxD~}EpDo$R<@1tyJshNgQ`*kW9PdyA> z>D%DqnP22h$xRl#zZCx+eF=D2pOj162rq8!ry+gTWZ??N9ye{`o~0~dr6tCk`iVIF z%5_7GB^s!uc24bmCb9bj~%!i+$s8 zu+C>(ZXYJf$l~!@{UADEvb*5Ebfl1>R3z!Qstff~Za`(sMiM?%7UfNhY4wWbU|c^( z^u9|~F!vcK{H6z~g#9g)z3=DR0%Gyhl14^e8k46>;YiL-$#3(pA>buaD{PbI6&FNvM}=Ev&6^!n&$q{3dB0Ju@Zw%%35w z&pugb92~)WM1`Wqf1AjgkxA@~XC8{v_o0Uh;Na{F_gB&Yw>58k$9)kUo>;n5YB&EKwOJz*r`2b?4^GOQTw8d&F#53g^t4Pd<%Ra z$<$f-w2R-*z0dahNHYBEIbrs@7`)n9hXX@h$O4)BEM)y|e0VJwGoEe1wRY)vy81t6 zy5=ldw(JnE-)4eEEd_XToefC6Qpe{>ab!lwC{|)O0u<|{ZezpMFd!O9l)K$4jkPyCIRMIUhf;TNoESQ#I*RlU@8iZiipQ85WUFh;0w--f-*N0U(HJj@>$iU1v;?N!E-P4YglsIn3b zj^|*TZ6{2<=7{(1G(h9c6}aZkMEb7F3JV^r$J&J%Jik~)*g4jU4*GJI`b+$*@1vyY zb?HO!?%6>w^&iH*Tc4*fLvFKKr>9UV>E_<0t}x|KKaLP&Xp5#io$jy<)_-;hGBF zbI*t#^}bG4D5QW}K{SkCnhx0A4A$=o*}${MsPPjw>KJG&ghj@Jcc+9~u=*vtJ7_*R z)no;0|F(fwBnMi4n$$8g3ryaefkobzjUXi^chhS$ z*}R6Xn|=v5nOoA?ZA0O8%@Y_pSc;CkIgLCGGNO*fS24Ss(VG%IbEe&4n93q(^z}v9 z)2z);AL~**k`jm+`-G+NF&M`arZ1!;B7&0(t7pgrRL3e*U zN9o#ebirat)+T&D9G8Deh7XP+4J}!;vt~3?dGrswQVeL%`Mq%PlpHRq*QPF2mmvGS zEM0ZDn$*Z@(ErvxgP;5LNI*ssJX1XnH|xdV`}P2Q*Y!j`ZkOI0ml@|84F@wy9I&uzsaY8z2G_&EvOaRKt}gP}gdirQ|U zKxT$z@qsbJFlCe)pC1#rtG1a>58I1ck#SZ6A6j)P^pX`pWU1=CsRiD=sanpzmrU=zMo` zu8)P#Ca)1_)0n||4RQt3rQ7lRUO&j47Qx2qHdE(WL3GplpBVlooo*PE4NpGF)BWR3 zaC~*3=+v=4>_oK%-n|_zc07HA`7Y9AH|E^utJn21tz9AZ^QyD4V#+gq;L)t|h>5T5 zJLf8MjeCmmX}UTNx(cZObQT8o4dR2k)sc2cJmD{;_#x6xq}rE{W}!|vOD&MKUF_sz z6@4-L))2hVCylSn&$5jVC*xYRT&DaxpWl{e&s_i3vsU-T7!{~3<|2|rH|MTEw{<6R z?_F8$%keFI(#Pu<82+5^_go}$ki2^_n2dw-cZ>L3FJ4K#o@v?Gu&V>InfU!H%=zPq ztHbP=)bt6WJi7<%eyu7#!#4JN;4P-;or@jC`B=F?8q@lNSaX)9XnVV!SYb{QdR%+V z_?;5}?es~!IQtbU+%e_Wh9AS|(MQp_Cr%Wd9LM)rplHmRx9oi78#aFIhw{Jc4%>C) z7BFdx^X%}!b~ZPV<9Dw)EizqrgN<%^%QRZ8#r78(SVZgt=JPfTqqbEt6}k%FeA~=& z?S1*4u1a=!#9aQ(qyU7hWcza?|AlOe_q{=~OeC5dd`{4EbOAILSDbd)#xykx(Q4H6Xgcd(Wv zT`cKD5FXSI#{KC#_{rW8+~TcL!uJ`aY>i$z;?*TW%Q`8+*|nZ^zq*XccSX$O_&K~S z>EX_J!tluhWx-)t39_Fa!t49&#K!Z(uog(xP(!_yjTX?_eF2aB|c|mRVM5aABoC_6XvDRIcZB27#A#GW# zLX+@L3Ma98oj*defl$_ZK$yHGp6Sf_z^3p1hGOYE?2_ypTwfl=ww|$KA5PcvcLLm* z{BB^Y8-@uUHAUDJ>%skee~Q`lp2AfI8eHQ~Rm@*?i{+h&XCeE{grb{-z|K{8`n0lO zw)-eny--8?<0q#opT$PYstYq*cZsCtMzfdea)qb16};N$&z$lTAXAf5x$gJQ;(r5P z@-$Xe$X)F%7(BnjB|3iKXANFXJ{@Xisw>smEh|SfTp5g)SrhMTt;e~a*2HfzBiP*K z%gNKn_tGA(3bpTlvKWcCwr9sAAy8=uzT7xnxVC*91{ygq zxyvrXn&WxQ_W1`<{puXnd3%P?H|PqxF|C@dTz?kdYD?q3y^pZ0NS!^CODs1{b`s1p zZ(+j8T5iM$GodL-1;=ho68==blHdXraSCt7Lfa(YuCl2R*z9 z%I5Q$+enUNF8&m?82CIYWG(ti{@C0k$5!j{emkn*wBAIn?_T=t1Yj7-Pl z2Cwmgw}*IwY!L2t)L{RXr!c|S1Ha766g2YGgxKmdTrzGVxc`X25ffxtYF8+po?n7h z3j#3P^$RY`S7O_GrMb*pTQ=7z1-Dw=WfwH2vV-3iLg}nJ+}tFf4lg;cd8pdyQSH zyAC_!e-r$U{3b*1gtBDgctPuZEc@>M9HvbCCCL-!pv84X+&ttg_BZW^(IaOQqYsPN z^V5DX=5r?eNsPlc>-E7$YXyFioeG7oTX4v>As{o^3>Gh&d$Dup6Bz7Qh%dCE|Dzqwy}XI#8b9DR1xPjyOw5vWIt6Tga~yL}1Kmg}guRk<5M&b2-c}B?_f@mA z8{#o0q6M?h7c*&Bf~Cs=n_i8<^vTC?^~NV8tPzAR%^w(*`wy1AHN(ab6P&2+1fsbo zn6XbHYuq*;7b|Ju(K9ztY^X0mEl|4P+ z>+H}W{SQCQcntc8tJu_`3nke#g41~GA{H!xVLO)CvHTE`o>KVYU*n+ddLv^^Pjdbb$UDojVZy1T3sT%O(DY4 z_x#8|)1juk4i-!-5ufxp4_|$zkY(#Lz+}WWkyW7{E!g7A4Lacs*GBAwfeIt)LKhyf{Iz&l29YWrm5$F2MBU8oCA)z!Cy6rMx z`~8{pxRff*4-SI>DRo*=WdsxSj9_%XHFOpjL*qt88X+qtnpf7*oqM)YtMr@X>wRa4 ziw}jdizb&x-L-)ch7&>WyD8Z0)`sC{22jP4&*bHcV-WH}!j>CbMI+QICA?I5S|k-z z{^p7!m>E2SDHEh<=Coc=*H41(ahHhx* zB)TJ;z#y)fctHSnx5ff8z88u65-F&xyG1NN>A|6zE>iF1P8Rx&CkZEC!Ac7k_}1l2 ze`IKo1pgA^ZxYA-&bEY69kPJD3=8aFMsopAZ_YtOz?4D3O_jsO&y(AW!r+`sPId$dcS|<6}UFvG1 z1d>~8LEV1)l^0SvAMGbf$jP{Y7oi!)I~r-nJFsjX$`rVx9}gXQYNCTwiUmux-sZlG z6UBnhm(C-nfj+Apb;mdsVLMg$Y>`#_&v9xzsDf9en!-DneTLfYDlORW6NWlJR#N_> zGHCvc2`cTrozmd+PwxH z&T*%HhiD|&bkQPkFoHVyRTqU+9k7}(i{QEbJ%u)zi&KZ@ z&)|(GMxdK?8pY3RWUii^ZspsO!|P6LqNm<+3e?)%M!VJQ z4+p58VjeY@&E?f(DDmyRG^ssidnxDjQq0)9Md(^Jg*NM6r`jNtT7D=QxmaA|`L7%% zZ&z%o3sQ1~>cuSadV+Bm6#%OPo{!-vGc1vSbbeC9=pAp z5<5Ih7JW}*ga1=t&2pr;*xamUX&*!aw;zWbe-Ibb%uJpj(5xJB0ge)$s(J* zMA%rH-TCzlquKL=`IG$|)fdE&Ve9EwK1+xF`{x5mPIMzzg|*pP-ml2xkwBtem5H(2 zJoJdNB6914*mdS|I9;QkXQgJuqR2&fWtA+O+M`cm7W%R!Vp8m8uLI2OerZ;u)ehoK z!r5#2yIA$~B_Pf0Vh4StV4Y~8VE%3q!u#e!xvoAz#D;cqd&0%+A{iblVNe1xn?qPe z;W?gE_=w#3-3cKk-|_R6u{e2(4S?HA@-aD(?7yxHuevspkwa6F)so3r)Vi7k_N^dV zoA(pb!;4A2y*8=WQ2?jBbo6?E89cC-hbz;X$j7C1NNsr_Hi+?J9ZMr|rM4MS`q2Yg zGNVYVOq&hLI)bEZ=V8t3N@QD+1beey3T+%PC80eLq%TSqbw$fUuSNXT;%DiyP##Y@9uS zA9%$Sh792kK^f?IBgH0f%|@JW6>n${Ao62#Kxk76Ils@J7%99!cYZ5@{kH#L;ZP}a zZ(0QJ&E)sw@a%NR_nZq0zrQBYTb!^($SD4?u9<1(?qFibY;r91FZM|Jg2yFN(EKKj z#W#66>u~rZEL)9P683Ev$8@e@p8 zIC^?*AqlYN(X?k0jBcXYKVN!K`nOE*S|39uT4OOZs*?Gh$6$D5J*9(ILGK@Lcynwi zH2Ym9>l;qc)7$mH@IM-vP2Eoxaf~dJ8(M&Nc7o`e^I-g6A8C*`q5C6mVms$UWE&vj zDEF6{vB&}feN#a+zn%E<{vtn%*|dUe5S#z|FtQQa4i{Typs(+)A#da3R9aX(>{M?j z7hP1?nq^$QAnOZ`O$*@6;c8f(s?OZM@DoQlnG*Tm2#n3HQj_Ue5d1p|OWPwMvn2+) z6z;+jdn2+a^Dgzf?+!{W<9h2}W!f`&I}Q%x-tS@&`qj8Bd%?sSnBhF+t8pLYO>cy1 z@%2>Qf?`;CT#0Sjy@>vsuTKANlps|@vh?1@Qj(z8BiP&Dig>p<*6*t6WXaGSD&>zF z?Z&?XLt2~IFf~28`(GiN%HIKnN+-!CeJ#S@XpWcHRFTf7l5A^~5*b#N;`;nq`(i@Ql=J0_9V)U#ySvkGE#%bS4oF>-xU8EePw3prM*le;sGS-M%6irUqJbMX+n z;ba5W@4i3^6Me{$3&NyqwKebB?2XSd+^*7MY&+eIIB#4- zhNXX!jMayzmP0kHaFz)hukxDsNiJje=M8e1I4O3~^htDWP72w3TN}|)MsRtWBs<$Z zjBH5046Zk_h)KXIZr(SO-2bD7W-d=6*0_L#@0v%PEC-2IJs+x0>eJ>6yTN5w0z9eJ zAr($i(66jUQcJ%Jq-_UrhKL3rNjZADu>&xTmTZ?wFu3fT0$(2rlj+iRMB{lSh|h3G zY0eU)c&jRWc(Vc;D-)1^(OpXSWEK{R3!vv*b%*>*^6V9%ELgL#8s(NA!4tPLaq-<6 zaw1Izjy1ibF54^v97y1L=t+3kSxw?I0_gaSGI+gW5jIdXB9ANVpgOD!8fgjohj9+r zs7kPf-d?nIQ8wOXc8pBDY)C>Tn(#;aG?2da5%$THklOVjcz?%XT7hrHy1LzCcI9MI zZ+=8l(Y^X;W}6drP%ajhWEYcj?gM1zykvA?{~2^IGasYb z+jeujz(#l<;|P4&mv|f*gW?}=PHSa~BvWf4(NYm6J@$a9f3#rKb|uvR%tO0n)=*xP z9x$_?Jf=FsmUBGELZla|3eq<$XydU6G?M88h7s4X;SCqu>Mgu>kjuEAaJGbJ8Gh)~;0r3< z))VDg+`(1*v?;q$bvp7t1tP1?aUJiwf-zqQ5_?@BWaSii)b5VINBcnSp)44k7scI4 zR)L~#JS?mXgV)(6)Y{_tND#P_Vxt-6T|x|(i(L<5ciI`{q(NlYDG6tbZz*MO zP1JLBEv#eTBdnK9*}a_tzY5PnhczEbH?*O+p<=u^+7trUE>z8?CwLkH;&X=N&E8jPu@hI6Y62O>p61doCB*rzk$7~ zb3sgfGIU+iK%Y)gI8Vw1szNB#?Jfi7U%rA@YR=@ZsuWEwp2yN80o-nhVKFrcxUQKb z@UZJ<`cDL*7xRq;ih6o@A2&A$GL+|)i=?5Qd9u{k1Hz;$cZ9dB%Yw=pUqgM4F5r8a z-J%Y2nZgABeyfzhqiF5^3e-Ps3Vv@l9e=m{huVZbSiBxpLzylAkZ@uVHP`zTGghU~ zyM`yDOV9OC$AmHd{%#J4rt4z`EicMpVhCLpF<@Ns$C;nYqM3oKu_)2A0hA6#p*amF zc=J8?z`4XvIKZ3Rt*cxpFe$Xc799(z;iI`I>TEf>cg_NiF%xLv%gLxH$p(g`2rjT_ z6ihik$1;!ebvzOZhad4A=VhJ&s(e|59m_O8Pr(~^6l-Ah{p)zIz54|%q3UQ}%n2w~ zzQQb-E5O%7%RpOb3iY42Fb-L91GC9xf`&FJX6d;is=t1aI_2lZzxJe0;*XI&nDbT7+87l$muq zjd?AvdZ@Lw(NwScPTof9Cbc{>pO;=>1Tx`4JXr_e;t`r~4K0U?&xNR2bPmNHPDf`g zPc!RZEQW2}HR%2J7kG;8Y4r5qHpZqvp80ZVGCH&9ByasXMUW^=#ZsrG;pqYvHlE4B z<10g;Dm}23f55Zw{EVU= zrNQc1w&*d+g6CzoU>O?VZFQ(Y`*wGu1v}COLIb_XzpDa*!z5u|rzS-1I}aVX=cu%< z^JvORX*yfD7p_SsfziMnICcHA;QOm8RPpi*s1>V0tKn>zVcZLQCT&8!x`rsvDW6(r zq62WG7IbqxP*d|RIMBG9`lh1~8i8&w;igMf<`{rQfDY(wZf2wkCQxGFbrdctgL=G_ zAS-)@KsH7n9an!;$H}w{Wwu1b6~TaNym7 zufH9VB%eP|bdkVeSf6hw zGLzr0bcKJ$Y#%>Qa+J>-nk=|GswEh|;wvB_ii}pPd0m_C2L7uP7x>FY_VLRMd;~A7 zP6+J(X$byR=m;uKg$X`Ne5iZ#$5kLyb(e3sD2rd0`KQjTdzWC2?Kr>spOV#{o*M!W zGgjbu`I$vi=iS=&(-$tK^fuN7-obUc-Y@tMUk>9oivKE}X+3y>Xs@z`nOGM#w=> z67;C z&3+yw@GjXSNJ%=vKV!H-pj?|Mm{t`mxV|`0P^#a~*AxCGID2TZz_g;Xc5KvEP~ALF z@clxQU`c#}!0KNp|Jti)L9EXJzyEGQU3;hlzxMiiLAuUbf!6(XR^r@uCMCU0aLXu8 z(5lZDv@dVv%a-U1R9(Cwr*8@5=AL~2Nb!Tnbbh{1pW3@aC?GA&8hG!7(jVYa$^Ptya4&DLr zaH{kRnE1S*^W{07{MAyhioHM`Dm?~v3Iz};kfi_3{sW6e?ts7PQ@DF@0>wx)0sY(! z-f;@^=(jIW6ps(F-L+^*;Z8tXv}xfFJE1v92U3Dtq3g*ON@a%$w2TX=&rPYIS9~44 z%h88LN@={Sd%wU3UkvtL=Cu9aSd^h!N2zlB7crT0U_4z0b(R{@rYGI#Q!*YPyil8- z)D#SAdCkyUdm5#6EkKU_&p}HwhCUIJiWn~oFg9L5M{CAH6vsF*SUnfr3H7Bv5YBnV z9;RjmPNPN3R>3r<7}|Bi4m!-M4)mYI(4T*=paL@^kwsx1YP}^uOE1Yle#{jrq~abu zx9%QvtXl-Pe=nl7)>OlpDOIrQbRiiPR)CpI0LKf;q2`T7QQ|3$@a2FRw-Y3XCbb#i z@wM;J_Avq3W?D}zXqrxq_}60p{8(`QlSGvfn@Eu#5)tH(p(xSXKT2X2PbQ{c7LwZL zNBEWNbfPG9f=qQ4pg(m_NJ*j$yYGE6NO#=Asts1igf9wNUK}jwo-Wxo@gLqgDn}yy zZV|s(l9Y~|93Fp?No+cJ>`>n}vR4lizsd>Z(CbPJ^eni4&x=^wZ6izGZKJx>+DP6u zHE^6J4jr=|;i&Oia^|EXRJN!Q{e7`8dde9s^z|oZ3%K3Y#;@qWyC3+-;mte)F6Sk; z=mNecF_UOXL_&*8FvzaT#i|<(xPH!%YAXgx3(lXH<*DhKY2lJ z=y#KsPh812xooobL?TJ}U`{=1{*0{*uOo3kE_e0pJ_#*eiD%W#f-P|iNZ5iH^lI@7 zlDP2~BR46O`1=;($wCuM|E_qFdOZo8dfQ0C{XfK`@DsXYD#!X2X9AZ(ql}K_;~bB8 zuwCmxJ_Rm;xM&sjy~GJ3i>2wX*azgRDI(5sYsm(KM})b5ka0-=%N&i+;v6F4MECb@ zW{k^|u6-Pg_v|rbWvwWxp?reOem}&NY<0x*H5#$|t__UwR$=zW(YtJZtT|i!pEkMm z=q^zxDPvM^^T>zr_pJ3}F=}{O9}zi{LB70OMtUCXVm|kNB?pxX$)~qUWL_=jR zD=k+^?BFf#THr-AO?yc_dPrQtYKc_BGhF&e=<*NY3bx?SY{uaMnUmcEI#E_L};R2wDCj^V`+gzpDyKn}P1-O@3jdIx>r>xa_1PDwE0A$Mac{ z-3e^xZ8vs?$qHQHHjlj*EW+QBgGq2f4h%OD%x9ky zJcvKYsxkM!ooBNqDdD>rD_I+@cv9R@!Ww?_W7V&U<9@#&*7J-Fc313SG*H+|4?4tsCjHQR3mI3+*~LND*amuS zr!ld-YQ}Pd9kOa94DEA@gU2f_p)857s73w*F7t5&v!x|yLtQo=Yq2MDM-%D%RlA6R z>uVgfbselpsexwu8mymsgsjh#1zQJge43<_o$4wi$jX9DnwAX*&#hqR)vJ;t)iJce zhX%at{UWSTCrVpq|D!yHIM)x?TmJO^&1+k=pKSN!_Ky745pv}>%+X9{VYVD;nsNdQ z>Ih`qbRo5Y^99q3gxJwTZDeoie)^iw3t~7@3DnItIJa~Y7$=4^Eth=3$HR~)X3eH| zyy3X*ewieW%YY>$Ccx^hW7w&08s77M7;BaFG1ncU$!!^$e)o7Sebw_CBO04XZ2h+o z-Pq^kZDt2GHq8u_&6?o%9}iNsPaOZ(pG|6&ACNiI3wR?=JBX>^3*J|o05@?BGj)X; zGL^8TXLB>$oSEgQRMeSXef&8YHnpccZGA}$|15sfp+WsHyh$jCV|qSaC10=m(nq=c zwVXB0E;_14?|p{Y7qUup;DUFQ($`r6>Z?2-8T1;_d2fsuzS2IZc~67m zlP{=vPY)6bu7SD=2QVeZAT;d&jAK1;6x$8*>_wFQxCS-nYeE>;9|(W0Msots;K_mA zpgDOQDizGhCc`N7+dKdcx!%BLnZodRoMQra9ff$m9;B@{3#M>B+01V&x?zf-k!M18 zZ}A3MTP^S<5Am|qlfhj{5+WkE!r<$LaCWH-oDS)R8+LCP4T&PAUO5kmj@d(@&m6?x zBn9y@qU5h`AKI08160m#CaZ&@QPDgnXdkseiepbu=cO2=IGKhW>-+KZF%@#`*(ZwZ zP=K>%7J%VrKgfwzL$S^4m_G$g0&3h0o_GtPsRtwAAYBLb{f_Ye*|C1lUIR%v0Nf^E(U1jm?%h@w?m70S`jGjL zwMZyT1e~@X#jOIzE#qHxI53_LI;E~4us??BwD z6-d+kJ*swzBEoiM&@@MlZYmN3vk%|+bK}my6~S`kI6jXa_+0Q>XSBKps}Wa46;z&r7H9yAWUWei21Lx+SWdtXnS9_|RF zpKr2ecfZ?6S*aB4GP&8f*xEk5_$=!e`E_f}QmO z(D^S76|_ea%`Iop$;aX7@~OG(@Do{*z;PTrc2*K(Jj&>1&p^#?^&oxXF!oTmNR8Dd zp<-qQ6I`~BO#b;3TE3l!tiuyj1#_6V?6!p5j7eyC`gSCITNDH{)Npn{1C;sQM@Pk? ziO0}PvbS+5qoMZ^MuO%duhM8zv$7j*PiqI+fBtN57Yp@@kD=Z15%rjV63u*J$;6TG z$V=3LNGr*+JC=T}pBAa)%iu{#6 z310QDK>1Y>Zck8R|K8&Eh-1ScT)l%i{$?`_4(Wgzvy;TPb1aIVi)hJiJz|^r32aTX z0TtW?wUq|cwDO&_U0MXlm$pJMyad?_6L?wAIg}SZr4JR!(QHi@I$FGo9w;y%dwuFa zr`pC^>dq6iQ__%5&kV+!g1(^wE~oxtmNETLRfv|3I7=5-gwlN@Z{TCVR=RgXGb9bi z!?M|@;P99{-8WB%)<46dqnB!EC)aNJ_fQ=8+Qvd3Pl!H<B_^M~kLbROG?E_X_ko9-`}0^yq$yrlYyr zuCt}%%&c3zu-o@FIJvsgCr3g_w$fKH$_}I+t8kvKJau{xTMJ7*d87FW?a-V4oEm^! zC|zU;Ev*eO5Wu3LtN{44HxE5qI+J#uJp$opBI${|40M8>1Zd?X_>cb@CJwbByMF~V z6`VsKR$TzMoKxsyf0N<7zS=3%DrYyM=-UCb`;=6OX(*yae2QqLbz$(HcbESB=o5AnDnVXr`;g#y zKPs+#10C(lN&4)+wBL@YG!CQSPgNMb|Bxd6^WkLr_suYvcYC3rx;z6;h=jq4;ptdz z*cPVN>_>Xx5{&y+4e+98Y+_8x;K;D#HI_B3v=D9Y&u zhaLZc=+Rh4#_I}0Z);)lUSPDV+6Vj=P7_S|t4{6c>|ktrr0XnZRx+Voe4f#Yf1KyG6lzWpu>N)E3=%C{78C9@OM78c{;XrcU$pbRD!6;ChLWWj%=(Fs)SETNFw0$tmiW&T-9XZ`r};Eo z95RN!bs8|m$L~;T_jCpB<8vr6(QR;WWGctSGlEkRVGwiWC`jLrfv0Yfy!BywKzPeN zyjt`bO5SD(Z<}u5NzQk0z_yF%;lf_L?cnwvdk{0a&#bgBM`t(nqmZvcaAx2uvh>fuv6UAgSpF_Zv7SV7PA7%_ zD}vddjW9Kpb3^QjwhAsd0wL0$shrd)U=t({`Bz%e!Eiq+Slp6U**pV8HfEuV9`~`Y zs0CP5xWiwrKEoLZ3hEqD!m78ht?@o8&1|dF++fJmcb-9XO%2TE`f3_o!Qbw#1&ymR z^wZA?B>$2#EVEw&OFg`)e_hS!W{^H5d}0!8|GWz4Rhp3tKlQR8s;u<*D zM8L}B*I)tc!a`2Y)YmdVknT)m$Lg63tCuLiLYJCErV(zy484G9hnB*(RRpp6l`)^$5^k{2P@OdE-; zTO7WS&0v}R4CmY}7pzvR!6hm&Abzz~U^n&~cL`EK20s&2dCi3#t%s;vuV%s<-z1*x z%{)r-LKWrjG>uui>nxmnVM2duyaj9KX@TeMZ;0XU;654$A$CHOws<#QcV)FNNNUG` z0f>OLayio*ln5&QMY@*0cj zsxXniJW!3e8(fMSKsRn&g;Y5)hLZYeHT?cPPInc8+4T%Bskj34$9%!YeKL1PT@8n& z893TI8RS>_QqMlMQD4uz;r*zTp*R1h&nQJ6VFGN1z)n?(@=nTzp$#LbJ8cSGEw~M5 z&C0E!4iGjscw#b}bey;$P{|SY(hc3uq&r$Lsb}CkyJDDW>jwhdXoFM$>OXwRTNd_~6 z(X|mnvSTa(-Y@-%SBO}U)Y^1romB_9-1-^CIz0g24UeeQ`qzm0brXfG=%jRKKgP>? zpTViX4E+21eo*|DjIzILQFU|6$V`(c^x)kL&_V_z^+r1t&Fe&kM(OZzfJFg!?<4=6 z_j&Js{h^HH=D}nW&a>dD45tI{@af~<$pzUhNG$v=&*()cnRu9uq&nWCRkE?jd{7ML zHE)1-KkF#Nk%cJIM;(k^3}JS(CwI0SfxTfo(sC{Zu|CE?adp7JGmPer6bNLwW9&s> zI<|ZgOO{)2;TMUxLgLbGXoZe6mwSjLla;Qcp#G^)?4iY~sMnxve|ylgF)?%ndXPaf z=Qg9>Qd1rDNb=H$oky)iP0b3re;J@gyj zx4;ymhiIsDCFsQ6MW3JlM*{Wp(3Tu$>Rq)tb0T6USe#gmyx22j%Oh#{&*LO%REdYz zmhY(b-ri)@n(x%5Bzg4bwh=s+NhS+QVqvem4?N1smh^pm{SMcG=9vIHe9`cWz`JS``VjJn<;??E4ys?qbLQc!;I67*z#1fG8&N3iDRAQU*iqweV}L4qyS(6ihhmga<@IJKLc z?^OZbEXzdOkDL_mT?x0pjG(|BXRvF>Ot`)-6Fm;T zjcS`V<8Ku*Fz?-LI5OoawOFPGMQv;ZC;vU5P-w+CDNln=`EDemMNv1LW`VcK2wH;D zkmojz6|X%9+g{72%FE}%w(9Bd+vXsg+&B$X$}d6HTxk$nm5JJ4aNl(HC_El5q%@x2Bu&nz zQE5d!befluPv0lemxJ`7=a)TH>-1Cc>=uX@S^#%tSs2tyJKAPVNvQUkURMNPz9HblT^*8=V>ZfqLTeg4;83BHyOT zU<*|pSZ)>!3r_(xYFGei$3^HvA$qX#umHvjjp!32S@bTAN9ec*mpQ6*VvhRtqq`xJ zbVkxt+9kFHIDsJ2y&D7MeGFOk;0c=Ku^tNTy20zf8?xTK53cg836vZo8O`tEf%Zvs z=|m(^GdYbT%o?b<>Qi9f9WB^C>IWB}_h9+z5vs=Z9hwEv5T`B;XI87zQ{L$y@g=X& ziPc;2az9yc%-fHSxvr*{hCSi<(mhtiLd)odU7pZaS&ue`Ye8|n3pw}2m@c@YPtT9D zh1zGGXzj1(TpzRu%KF#S&*~$<+GIYR zkJkORfLL66Kn-3LfuD8#)Km3d_^x-GB&E90A(Q9R72`)pukJkhgSsDFxcw9M_lCi` zkLPjPu}ZXxRR+&*5Ae4}9=>zh1oq?~#i~MX@V&kiPg3KL`!h-bEOo$naYFuZ+{O!xRoLLX@(e~iHqq6jO{TFbD;~DP! z_W)^`)xy*Uu4XLrr#^XxqV+y`P@KmTY`CBTC*@~BZj%z2Jt{yeyWMGu-39M%UqvhZ z3b6P+O;{-#1*N<4Kri|*yozn*-lJ#G9k3BCtIOc?4#qNDeukjFu2i_>eF8G%Ph<0j zWl+Lu(Q`#3iP6(#@aX(;kS=nea?}%0P~3Ok9(4+akEvrTBQ0W4{Em0vhdHEiF2Lrh zbf`0nrA|8P<0Y>j3i@iKposFM0+YfaBRmQ=ZP^W#>6<~a=KzGgU4WReI_mcKTPRnt z1)paIz~^eHRgR?`F^~KV>IdFoc|TuJ&4@!Ab5r0(UoMEQa^u-e%7K6l9G~K&1zqRT z17A(nz?;xMh_DR6pW5GB-Syspjw~=F279kF8SZb8g6mQ`r#=-lp30GnB7M*;90%Wx zbiwYn5QLPkVbZmvxz&jpGUo#<{EHtI^tpzSE=^*L zR+Ka8ldBl_W&hBeL>+jfxf~^ywWD8A6@m>8VJN7g-D+xV6uMq7#k6f0MOSXyfN*3i zb>GGnFVJI3SCYWA~#*>vF26Q3GYJ&Jt{FPA!o-BKYuNfOl*DC&7K*9<)co-72>- zl8HR}i`sVsQ!T0+sGYG9X!^(jvv)x}`g}VY{W|alnO|;3 z`ds!ZMD0~Jyn$u#8Iq3K^%@T1P} z24&v`@TOD>w;rV7vCeL^N+=9PR`FOnjmcgE1yb@fF4$!{Y0d^WWvDTs7` z=_E%#ejw+}HgN7W2Z-KR%{DLaVP|i2qOD!x$*Ggo1pmdLVPl2os+J*tomz4DrL zbdYa%b4gI&RigXK1m2zc%r21RX6&i9B=kuxOg(agnD*@=${9}V%ctsWr0+P)`INvO zx|j-%Z9ZUjp#{DECrE9cXKi= z;`xtcado$|v>2N!uFJMaXJhE8TWnHgJ(=Sa*~0-;ju%*UKWG@(E^^k|L=s$;Ry`{qevG8De?f*h*IEK2^Ro z5&z9}#GbqCuwJ+=7PdBo6t^SPZ}I|Rxp|ibE$maQcBdL4?QfC zVvHK9r~>Cr)ZPmdbu}5Dj8UHeT0D1(AT<7(V6XQ-tK|;<_^0ASW^eEle8)UY z(AB8I?5bA5X)Q9iwyT&)kJTj-_mlBUnyZU{&n8Qgo}$M))>AX)+u$w38E9nnMSR1l z1+Ov6WaQ-q0~w_Pu6-lh&a zZEr*^#yX_)i9FizTv{;0bO94GzgFO|nJ@|cYtY}{*C?Na31(3k%dhwz!JGMDI_`0* z!eg?DpM^#XroT|N7lUsYw}#-+2zKde8HoFj5fJY!CB)6+)yg0}4;F z;4|ly6lrJhhhPjg_aum5=X-qWqd5KQ!y00(Aq~$yCD1!sU!a1$Qy@(ylT>>Dhutez z(MKPrQyQx{AA$Q17_^h1B~GXz$1PE?hVy;u>0dF|F zg&(nnHw(j<;|Ej7c%Uk6&DJyg*4<3cE(vtEC>t&Rdl%ilp`7;-nEZu#fJ!0N|%xLO!F994%|Rd?V| zTn^4M8bw0l4BD|O4P;%FATsJOiVeyW7+YO{y@N#nONEKf=pNW?l)>>hmFU*3d06COw*|Z6Z#~2^NmNs3}1rw(Phk}*kb6LAB%_d`e1=;B6D?1 zGF5oG9r0FQrr^wZW_E)x)h<8_zNuQtn3(YqCC4-p!uRgUyxZ5evrh4<9n z*NXH^rW^;M9NK!$Hd;I8HG2DeJ1xGf2X~n@QRn+qK(9lRoVmCP!a)gN*(RWudYRJS ziguE?!h`hNmBrvu_!LNkF7QQ*kso10}-R=z}joh-69F#tB9o?4Wh z0bfq1AUmaA%|1WP5NXbk!z8xOgBM z20fv+$7q1LO3y1ruwz1YZt|HY|bPgBs9Fcs<4^}++aB>1pO zTj0?a0HLDR;FI|m_6=6UwZRz3$+!$N!=|7mV=Q(1=_$&I`%RyQE+D0uuBbk9EqyO< z7c?F5fQl*>blctGrFag?`>&LeT)Ge3KL4vLZkq*#JLKuGaW7C?vJ8;f8Aw>62A2La z!Fy{V7)j;9n$NYMH7NyNxZDI`k$E6CS&`mg_`|YduR3gVo#ux#^JuBVLJE6(z3nCNWVM~Gy$W3#HfBMJ4bMaba zH?tAR_u11QP7Og|DFwF%F3*jLY`0XzMGtRGN`qLloH~mBrOdK<4nuhp=*HJ@sHMLo| z3y%2Qg7R^Dw8`!|$~bC)bXWfel`7Y%hK16wvEw)_Q;9&w7f7LrC7~L|>Pf70C zmbdiugG=Pd$fI0|-Cj~!(=3*($|qsp^XS7!c|3AxUxmbRO-wQMfi=S(FMFW|a6IMOVsjh2$%Wxh1j9_IcL$-$^`v0>3S96QsQE04~S-otrhWKRiGqcEeySW}<7 z`!|^sUbsWF6>2M9s@X7l!)<8qnj>WB!W~?KQa>~8_BnBfbRKyYxsc=$BAyv;0ZZ-| zFw5XP$(F1TW7rgu9<2zwA9d1}D@B|PSxlbyexifsgH)lmhOAcX;zZLM$+3S8v|IWR z^fu%QvGiJ6=;1}re_Vi`2}ePUDbRjz7MwN;Aq|)22~MtCrB{+H$;NecP(Ra{e$Lwm zLq@C>{HK|ugEhs`%`CjUDGmI}4ALL1!=#-zhcRDAL+-L4j9>d^^*5tx7hJ*Z?EPb<$liW?aGw3;1+%Bh*LfF@>?E#CB&Qc`iOp zHq2Hb3)3XocdM7cH?bVldll2)`S~QsOOTW-bA(3T97-k6lis0wfFET~r!dyk%|(Oe z82n)hD(#5c&lVD~{|B|J1EG%;4o<#F7@n^Rmz><;T+1pZAa4?xr8|_F8#NT>FU_Gb zv!3 zOUOg=+d!^l*?iLLUM!jy7)8gAtpk@yO5z_i7WjH#H+;V_5}n5Df!m<){kK+yZ|bIC znpSJ2xrIP6r-~2nmBTcLB-nTR7UNNW2J9?<(m4_S;^z8C%)>2qSpG$q-b~K7Ixo0# z$^rpSl`llABQX%^YYtNs(#gDwLMCEM37sZqMIHaS!@l!PWU-Plp1pEGa4?FkTQzgR zqHKU}821yz-OXIG#&ISyR00NX2#$35V_;Vv!WR0sfNRzXqNJMz1?r2$+RMAi>JTye zFsxg=e}4+BFA5DV!WlY1+>S;- z*OUynDDZ5DPwnJhe>u$B+bm|6_DsTAnsdN>FNNsGn)vjdBow7ghc9m~z;#y*Sah)x z4rsfBhv+=CZEpm_wbktSpBLfu!~*y`u8VH35+1LVkk)f@1Rzein`{3cP30%O-;18PRp6Yq-wP`<{8yb>9J-=0#^ zb0GvSH2G8S3VrDik!sMW1FLfXps|K}#*zW9m!=7HKj&X9Yp>@Rzi2a=mHQO!u$Q7em?VSQQ;xmBS5*<#utP$3=$gywx zpNY4xcLgo4+mKj&AABV!V*$2nOxRq*om`LsUUKQQ7wv%*M*_dr=A&9tvgO^+ofo#@);Zy({qX zqdB?mwFoAEKS>gXz6G*hia)F{iT8BcM%J8Yg4ZJo1eTZuyRW<4DjM^P$_iLWJ<49+{DdwFiDN%Ben*3{ zD`H2BdwDcKH>^?nI%-y~una7)g% z`p}P~1@^_;3MSmaLg=ZFhJ}sk+>zi;MpD>a+VtpvbBZCHou>o!Dp$yn0R>WfLmiGb z^36CAybc*iN+ku*kvkJ2w=aeG{Pk2bU5Rluen6EY3K?<12C`q;9P*l`(vMH&iP^Um(0O7c zl(8?FWl4oh{oo#MptuG$3l&x`J2FI!hDZz2JO5I#On;4yQQ9 zhCgUz#Mg-A`JYlero0}Cf%ZxGW~LEttxMw5y#K3MwPOOm?zkBLlo;TTjcK%FpBn#A z;L$${AI|T;9ERiSAK}A?&3N#NA6;~;mhNp$$G$y(F)Mcodi&)uM-(0Tg**ItxqVLD zZe3-je(P%9UN4hsRvi&lx|bu77{llIwKDQE-0;?r`8X;WaPYqk7!rN?OTX%yd|>A=fPIfx6*TrvFbM0)n+Pg-du$4fdSBJcB) zCNIs_zZ%ft;13-ALxJ}W|<9V@zGw=BA4}Es&Bq!1hrB-lJZ2bAPIAZ8w9H(`ir|Y)i@CRvlV1V%Z zedYK=ZtKxT=?JXxw8yBBf3(W=G4tn55{^$VLsoSPsa!M?b!Q!8R0<`r|6U&1tuP8P z#|is_U(q9BFnt1H>V(if(u?PvBv`Wfndk35oYr=|Gh&$@ctBj9NdFUdNH-TVoHM znjHdTwvGUaZ?(8nN`XivhY|N~z+t{uIh!nX)N(3ij%2Q7Hsr*R?oWq^DDoPq=}tnU z#of^O=Ztk_xhhAND_iBla(C4ugt)f zc7eI@>kU~hC%7CLB~VgJ6_-9eP8(Z|1vX_3*%g#1ikp^2K39zf(??pcQ&$?U50*h+ z_b1xF=A!t~^I^=cu}87@O$3-+ImcZuj7ORE&7|dXJkGF_B$LjMWrBw2(Sr&W5Mz6- z!a%8kG*mr7rz_!b@M;LKCl_I%*KENrwHX!vNs1cvB#E3wI_lh%!eIyR(cDiqLiSTy z@LP@M+y3N$+V<15N%|Q1w4o5*k@tds#sG#czX$(W)ssf6EYfq$3;xtxWyIzgFib~| z^S1AVrUXqU>xd26mt{qIj=W(G&Km%qQM&96!#{BLuh5MNLo(cE3=Dj*g3B6#?4yZ3 z%;#k_aA9mD41H<=onIvcSHf>NlO7H#%jH>%d46!#;5_))Ed{H$>fCL;XfoU`1s=s$ z!~33BBq1*5Hj=&`2M{K3G1?9!aW_fY=|~U zCb)w3-tlCTTs~0?&VqOL8Q>R{Pin^GK=-Se>{d4&5}khx+InkY{bOCuX?+s8^E{Xv z=bZ@kYrDxN3xSRE$c}UFI1bmdgziaO2gEKu$|UUlE7p>0CQFSEL-|%ormdtLhJL>X z>0eKP{hgCgvmya*wI@M(;c(`v`!8aywwG-EF^g@N8O|tt?q)u{n8>;bbGgvKBhXcM zkQDn^vhI0*V7#U|*Co*cSHio9g4_=F<7G4UAb$lmZm?vnwmnP)uD=3 zqbM@d{5#nm_#f;2-vgjE!(h0oi0ueF4HA~q!O51vI2H2brTg1Q+gJj*4pK^yl)kAeC57R|u@XQ$ijy#TA?y zbBl@Z-9;rXX3|A^x-@NYCpUQS1i9^ygi5EcGgo8WC%`08Jp&m&O z7@CX9kDL-KDH?EpKb)n1tG&np=}73;sjWDkxJ|rpp9j-9FO&Ay2o<|zT@rYOA({Mq zk#Fngih+BF=r#X#M($=O-TZ1H7bX3ho)B_RFMV>wbXzLT_~!x|ZMW#NXWyA^3l74x zxBjRcvlCKs)9L;8N;)>)zG6$HCI&pv6K&GCPH%<1CiBOXV!G)FOq`WNm7RamGp<+3 znK}QMHk(DX+BXE=y3Zi0PbgK~?TP@WkQz8*+{hKW<&v7BN36lZ=`_c!8>|eJAwI<(ioRDfuHHl0nw@npxbYjD zHN6MXde`CnV^!Au*;u%r=nPM$rGQoMb#RSrf}=9;>G)sqY;EZlwyXUPp0#uZ?;EX9 zXdi?jg{Hvko&)Klk0C{PZzqkEU<3Qz;eJm%{D|v^vA1urxB8`7_i?=-cXv8IGmM4t zh3&A@aun-pD$9QCTMNB8L)jVX&NODD4>c+s26-Dl!W>DK zg9~~T#$B>a0QByQ zG@Oqyi}+#U-M0RsDWAf~^8@7-nc*Xum|{;-8}P{5e%-Q){l6;7iI6!&YP&F--s#Bv z+%-|0{F@TDHCDv!dR@g62DnSBNb46U*Jmy2!BzXO`k&&Al!#vMnnXM0AF-=>S zk}qE2%o1sL=KPH&QFm+$srHs73*O9TGS?TADb7d^emus|<@1>1Kld?DHrFr-lcj~O z^GA_?uN1Shu8qm9SwZwKK4Sjs(qLpB4rhwjog;_0tt0F<7sfdxfIQy!A8Ck;C1;QC zAWgf*kUpnl)(?+;VoG{8iwEX(kP*Y;h^yau=8||JlcPVM8Gj;`(VjDntaOrP)C;Sb zr+-z&=PhrSmz!;5zPc%s0NPd&=`I9Cx#UYk^(NU+XS6+9Ay$rU=g)vY@v8FKK1 zNGu!kg^bQzz_?mzlB|WAOqX#w$sO)*J@@nyFuqbPKH;(uZ~b^q9%gnhBYdYJcdHOC z*y=LelWwBc!izGFs-Vv_U8ar=6rVORtJvJ~n+uYNAw9}MrkDfJR{zSyREbHR?M&3} z{3LqJM#3}M;)?a2=Qzo9AF|9Zg>(g<;NA~eMQp>}nUuetFr+n$S~LpWpRDT)=~pJU z5nW{ArAuUbQ8799`aBb;6GK)s*sweG62a8xGI#H57JMumi;LTLipNxfp~;T4dd$WCcHOWfS)j5$oFRA zHbuebxpFQF6)Vzs`j)l7*(h{0{AOB*O6q|EdkG;Wr z=MwSF=O^H}%QD!a^#FDr+5=K{x5Tq!=YX-UDZaXu4$ebPgTdRInA(v7E2j^|uhRys zQ^=l$F5HQ+&Y8lTR-XNGAPMh#eTI%7`P6cp3*6CLOY(ZBW7nNj4AXH$ z+X!_$tn&#MzqvxhCLd|C=oroW@{!6uT|^A3o>RX2EwvczW9n~Rz=Jb#=>B<+p^-gL z#AmP2%}WIqw~;e`8va<|r{%!uj1}~f-C622R>;-3F`^X~F4$@#LnepE3S9R#YB8Wm zUitUZIpdEDUc*oMzNHA&bIgL87z zu~GLIN&4}HI_7%e-8T+EUj{}V@GSQQ9v(A|T3_by+>>K?AaOPJ!XQRB zAWpnkLzii7Ala5Th-%;m@?Vn^c|D>9hd(dC%4G-1d1_4Ih}RGeIz0_A5%lhXYLs9iLUt7u@!_w8EXKfeooKdW#rzqr8A_0RFj)#Fg! zdJgx8^9<#I@LSSR93Vj^Eb+!wg`=@`_eD}yHJwkr{D{PR%3x%kI=u0Zg@3V!tydpc zMaj~sus=Z+yjTsKX8Q;vZe|eIZ|i}(=)uI#4S*HGx9gZu8mYW-pLpM_O;SH&nKpt|8yN+W``XA}=Mn7Q8)2ZwWs`#HLehK4m_8{z1G^j* zS(&hFq**u%z~oZM7zRUbXIU$>3Lb=_aRH!;b%s(ZaEhvF!n?fN&Hy_px>xa5sH#od@hPAsC z$aXJ!j(?vZcx;Z~nvL9$vvq(CPqRR-Y8>cj=Yj1vEB1@LB?L8>fq1$;d%FDwD<@M5 zgBQ)%rOhIgb4`JV?f+n%{}eW&Mv3k6mnS`MN3*{Khab+B#}At(3Hua9cFC_YG&|N0 zo1I$G?+H&$Z|Jjg4$1Rs*DcU(o(Alx|I66zjsm^=(}WCh5j+h&i`PDgF<|OTvLYDa z@YX08Vq(W$-TRcu-LQoWMEs`S>RUi^#v@|YvV&du!JOR}z6Cs;m#`PF!;=%=!9^tOUzT+Mz(JoL|qds<#kGi|c4C`%iS3Yx^N$GtIQwkKWDc$>~&)J)$5 zuEl?^M&m+(9bTHg4ma)kMlWUBaaCVitksmS)6UhsbYs+P;rDWAvFHMJ8y%$IyL?f` zV;6n*@2d6lx?9-)Fq(EshtP!!m*Oh_iCAj?f!b8x;YweR!VS-)=>11aL^58L^z$Y| zX2IQ5`iyMkJQJO9qDu-^it9P)2&AdS3RyCQ zd)yd_(ajTSaqeU~K3+`UhL+RjPFnG)x`(Q#%5d=kHR6Rgr1_VPw>eKUfe-VaCjN1~ zO804ur7KliY0-6K`ss}o{wg%VhZ0g4L$6}j!C4ryHjEk=P|mMOQQU*Y93NgRjxY{E zEj9?Zc^|Qk8+xm(v`U6^zI{tPxMm4wb{*)!6)W*xw=}&(-L3mhBv4VD2CXT)P4nN~ zqY|c*#QpeMC^WTU^J(-4w z>btB@%6_nxpZ~Vvd{ii2JYhqfdrHKvLWk={VT(9hdLo**3;*MH715i&+i*?VM{4@T zlv`%L7Y7+_ZhD*?udt&|>=!%@hrV1;(P5+x^GsAo*otm0bX6aTIXV*@?zeKsPOAXF zx|SSl9U$8)iz+0fTfj4;gqZw(NwO|Wg0grNSuivLW}j1IueUCOmjNHhYwaYsz1yZ@ zzRWW+b>#t8`BfXk%_xKg@yE%v?T1O_+5{N)DHcx5S_9h)D&a|2=>(O+ z-SX)EaCq*pkX({{NltZN0m(X+eUTFd`(GwPS5cGo&ZWa)a+AP4nC=JqVQV1j|GNhv zL$UdsD*2G`g0MoyaYRfs?7dH!ef1!`nOvADvD&aZs*8k!z@AYO80#oE>IR_~{Jve@$c7ds&dN#X_g%j2a9^3i%%A zE1-A$CM^DH0S`NKVePolQ1_oAoczF%?=fZ&ZBO8H_a@SOH;k;P%YfpDpJaVj z5tOM{Gvd5Ua8cI^8b(}T@+^--v11(3csBqql-|OJ=`)}wM2@|ov4PuRqr~hF+eDHc zA7$+O^g;6J1;NP*?8d|?@FypZusy|aY|(G@sXq%`R}|D4lYX|(=w)`X+=Jg`(1(~`4On7hv8b2saTpZghZ9slQSy1IKO!* zUY5Q}WX;;C`x$wRwI78O4DQhN^g2^OcMM&k)4Am-UKnD09`@eR;mb3w<6ADTqViEG_IuhvmvaL1 z$fkgb1ZU;8y-`F|qDMDQ|A`u5ai}9Plzlhj8-^;o(AF6O7sBSE(EERg#$Ln82s1;h zE?46xnwH|KB2DW?!IAeP>Mc>wDnJ>P;?Akd(UE8Q4O*UHv?&CFv?s#O z_)lb%NC)T7dQE0{{-Aey?LdhegQsQ)Y!ahxvi@QWnNT*HzY(nf8Y&YY>|_}p9+1W6 zuU|=Lu)u97YvwL?HZW&`Z<8HS@5#Du1NfpGhfl1B!`EG>=!&vc{LS|abriD7_hR4R zIhR;&;Af)13-A)o{3_;Bh7?q7D-t~~mu6ZOq;T=wJn)J*0f9Rfz|LzYur%Z&aoN#F zzM2-2pnesQEnv}ojVZKOhto~=&A3BG7fY(okWtH)0k`oWVYA!O&LRqIr8mHx#c}-n z&czUw9R=rw_vFTm8uIP6I{9_^0(n_>24~4y@s@R8#Sg+q!C7Nt=(*<%_TzqW2^VCr z`qniXq^1TJiiVR|x&rK9o`9vPR?uQMNJLI~Bu-t7KjY?+nO_f(srL79YRY-Ic6h0f z8!_a^O%8yl=UTi=t}0lZsNlqY)p+`3Cutro`F~^?1g`4F%aNClxOKqI)wPAEd z=?GF4{GEpPB;jod3C8!3HFL4Ln6?bZR&W4&;3)H}Iu?zN=<)~mG}7|oXJoOe z4>rExMHi%$an0l@c;u@D#_TGhY32T?D@r2&MV#Z*9^b@!NppB^Ss3=)#^IRdmqat} z8sOncAXYuCiJGm!IObP`;MX`#Uw)ZLeT4U+L^8pRrFm$PpaM<)#f;L}Ep)TMb-H`R zi?G5StV8N0(-y0P(P8TJ?#mIVwm*SJTfCrWo95GCJ2yJ(aG1!2562fbhvUR=C1~s` zLoe6*)5y2hR3*|Hci4@m|AkbcO6zAlEAao9ZrY8S9%&+je?BBr9BG;HiPTuJTmlXM1_eGqoS%S+JZmp;CocAp!WpNys}yXj;z#If=JaK;8h zv^b^9ho~#l(LR>cO8FaiKs233Pwt`KDXY1NTriS>X1*y%-#9jZLb(RQH+| zTYS%miB<5SJ8Vca$8D| z8S-~HJ7m-$_W2>f@w&YNe3?anhfb0$b6bc*-x_w29xL7**9YG}4r6z&wTJA&ekOO? z9jHBj3idwkg@<|iq(A*FSmb7aa!fplRfq<)FPorPI~8JCHAqO|$bU*HtkXF+*6{LT z(S<{`Fmb;p7$0+hn@l|uyCd)7)5S5cPxTF{w7CefXAtgwuZ0k}LndCh$kvTbCKhVL zL8(od3mAF;Jo?_kM^#f+cWpc9-cjH>WVf;fp$|F!j66IYI*F7{5tEX!)8Nl8O}2d1 zJv!;qGlsJ}%9?)4x8CfaK$`zZLdaH0(iQcEc=kAxJ2yCpb#A0B3)YFwPP|P{ihSU? zzZSf!?h)9k8pKEKGox%Viki+F4YP+=Fr3~Wh*#VRYkGwJ+tZ<}0Mubko|-|?fjOjk zdLi*!TTJL>BldS-Dp^uCok@D67GtZj4gxuCnnEZAII}Z9G%KHZM$KeI+e$h`~ zj6K2{ggde$?kY0Xf{%I1lcC(lvmMNvy`#Y~eLgeALwGq{=%cRBQrYGSGg;ZQ)>t`h zJ6qAX3>Mkmhx?7kanq~^VDpb52^Gi0ftDKV)z%v@xF8>gDHMW@eK^`nCBcFGV4;7R z4Udg#1zxX^i}kc(J2m#;&T}rj>yy(Mv3!tzj|Qf_Q?T-9-lFBT```DYK32SA7MwBIV_923{qx_Q097z zP82dE1_lkN$bEp~vm~yhY zC3mc#dQn1$cUv=^u;MQEwyThj--NlsZzqs{|A3xw*QK!!JF%lG01F>pr+b%O7Cf&e z7&Sb2_N_dB)gYHCy*)~BvnlY318OY&ejDdqF+i!tt@Ovnv$$6O zHaF}-4Q|mI!X7$p$LGx*&3|lI0;6?|`5D>>SM#njv&|*2eA`%d!_ZV>P{UQM%G_kN|KE5 zJz6I9lJlQ34S#oN@`lkoDw`nwsojPd*A7sh!Bi~uc*f;8rO{AT31lB8&?$EZXoXrJ zu5|OoF2&T}tBD;DT#95PVZnK#-zw>46lvb|ydL{Ke z5{4d)Cvc05I{hanMN=y0ko0Zlm@n{N=H;KKss(M-tLEj8maWx%rxAm7LN(p&%`m| z8vLKDt?1tL8RHGF;+Q`ZaQ?YX_}_|&yk@^Qj9EV%{tcOizPlYDq~{ZaB*|mDo8VGX ze?iBNv4M?8{-TAXBP^#wz*oAFd8Kj#8dWs;OC`2^hP)a-#peeK}5Q`HmpauWo)NXHUsq4qOG`KYZ$71J^BmRuyrysb?`Cd}yZ?sjz?sqZFt=KsF&gcnj zK}va(0n)T0f&XdF;f97KY+mI=zGB2&yf&bZi6h7IpWMS?_wo^-*cXi_gc;^&y)U3w z)Qvsvs&MGUMKlmN2agX5PP?lkp=-GnXk3mFZ=Tf+XV+QqaTD`-k6K$kWpp71UKx)@ zcOoe!^0djRgx{QyM@EfQ;D6u$jg7+&VzF)<_MW2wdr&OkDHo21W~ParVe>-b|(*pShgD<{O(}gTocn_HIFJp2bI4>+z|% z6Cr;>C~u`a0*vz+77djx3vIM zjptGGi-cFxoXQ^`auc~#rHPc-g$Jd&yr#*IJP+?c_ ziwC2j^q(O=req4ft2E_Tg&6XMIZwEp$(DRm&tq_Zd4b=c5zlY8KmXtZrBdzXGc1HybG;+eyjdaw9tIKmt87G>my%eO~0MQDfb9NskGCoR6p5;xXu9 zJX%ZV;FW2+xM=%dln$1PSKT^Paky!nXi26E76gC8zel_1eaorj_2W>CkXedPuPx*< z2E)nIBdXM7@+7=QX=m8S2g{C+Ch zq9BcnT2n-u4?4r^b1TSxuL`awdpN3|DyPq+tl~OA)v5dyeR&eJP)jt`BiH)elZYu7H~Q0{EA{m6-OuEf?;9mlu^Df8i+8*6^5JOk>^S4xPkLD=(#M{a;$@6ew11Xqxo!(x@`ctj4m>CiwDx3Dyq0oX6Vma(k#Ld9d3}DwpfpvonJrrPM4m<^ zUt_K(w{Yh#YcsDBW-)Ee3N&W6pUA()h;DD3M1^`BmdjVuo*j29_ARR78Z{$f(ULUG z8m)%D%YsO=*+P2NT|k6Mc( zuAq`1Re00#denV#kpJou$*nDtr!N;I()m-qq4W}-s;9;BISz#Xu73-^{Y&H%UrF+b zmkO}4)DwGWd?#PE5^zEsr8< zP_o`k$p0kLXaBC#a}Ik5YyAYHlT_HTpGw#n`MPYj>@0|kuYjHhDfEq21o;>Gi1kvB zrqeG-vtAqagS(J+goe86L(ioAMh2l~UkeIE4pkei(j#2#jbAhRH8m;J^$QVUH+y4XpRW zTeD)YyZu<`f4pa94SL{H-ygX9%?Z`UWDBgupWs0W`|6oG`R?#UEY??BX3V#fPydwqCI&9#7>fcj_ew(+U%|=L>8Xdv=bNDygvc=E})=YJMRbl3ULb_alqhcr}K-dMzEU z`%h-w&6?oRlF?*Eg*IfjJ>rrNhJn?SNY?3B13AE_p?#YRTj@RrMILim?Ujx&CDWW$ zd^nt)bKaDA&YQ%(y^xHaU$R(^k7g||9Ofd=rLq$@=VPB;4RaBVpm5F|ymgDf17%9* zZmnb|sEAnEIf8e0Z7`ep-+l13?1kSdN^GJsj{&Mvspq^5n7*|OOC6Jrp}ITPQw#n*%Acl@WpMM?WNX|?@wAH^G1zvMPLTZsO9juh z^ssEutvL$A=NyMwtEZuK!B_Uuof7zxIu7=1O2(IMm5`Sza0_ZivGtpVu&i1&I=1g* zx3=D(n{9ij=*U}ImG+m6v!4YcMn8dl9^a9~IDx~*PA5Wj79F8Ler6f%a{k|MRj~?x)IgG3gFA_Iz~fI zgVlXvz{1sA(3>XB*8UN?Md?6q_dj43z7qIIPp{zJ*l1QU{xNrWy&^BcEN5l>zvIfT zZt!26KpqMAjASo;_L+7x)83-V>iVnkr>wGBgY*Ne$1oAsyEcS%Tlhe@4=0N*uBjn$ zF^0UtYe`HxXDLq6DP?!;(Pcwx4)Yh+9cB;u?uVO$DUdr`fo*GuX7a!FVtUPQ5-hOW z4lVkQHJe&sX>1({Y%3K9fD=J`J6v_6gIumD5ycK5^E^0>ar+Sk$^i~+&_Dy!C0!tN z(+e`|Rs#N>znN_DJPcB4Vd8|=UHf1axpR59B z{;quAcGDU|e%TBwR@wF-{+SyC2jrqfS)M{4 zWWz(Q{c{|RFSEu2EhEwAL3qW6fl4ZESz$GG>2tdLdD9g2S@qOwPcL0?NSIf?nSp!0 z$BJT4%F|<4Pcbvh9$P<$PxO<@Fp=fUHqQC76xKJ6r+?<1;eNSq6ea7vvkw36htEfa zFm6YeadoQ|@XO^3v`BrAbzbjRG1+HLV|><$3+uE*kWHEQ)3U@8K_xWM;*qt5fc&`@ zyb0ZOR4Xn=30b$RhPZb!%ay*6qu#nwBsV&biya!nd3--;-TqQd^iD<+Wu-JkH}eE8 zQFLMXZx57+h&0l$^TU}jxxc(7lWLvS(^2N`_h>1JYLlL zOHRB@HAi%GnmMlg_n=~jgR#|^)FR4$3Kl(mKL*`@xNwL0d~0P(SA0J~0>A!dt*l*B zs7HW*`E2ue3|I9NeV-V@?LVYc@wagbe@sgsa{BB=-^yQOgMt#X@OS_OOt#`*h?K&}17 zxJ33g+6}zKp+ey5in61)U-cuu+&7muTz>|hjr)Z=Zv4Z5+B?=yQeV^3cS@-7bQpi+ zg%5UV=?T7fDSqB-Sw6b=3D)h_sJt@Jg4>#J;z@@QaHyjeYeHx9hx|hMRzsE#zx;>3 zG>YS0*R5sNz6Gju;0gVFzY@RS%Rr+O?!2*%6Bu_*##d*m`Q;}Y;j1=_c)t*XH5j@l zcnNy#>Y)-(dcL*evR_wAN(+&2ZE%y=a+KGh(|~9ZOcA- zBOs8EDKX_uj@9Ckzn=VBbzMGTnlW~)>Y~}!lE}UYK+EO~-bCgjom^-Oel(r`V^K#= zZrH+axRi}D|Hbekodx_rt|iT~T)}$_976Ko6+iH?fOpj~!@SWYeCe+V5c?*FlNwx# zZ<+*O$niWJ>66KH<^SU~ZDaVXvDctsLj|w=a2Q`1Y{37VO2J$^9TS5ku{Zx43A0h= zJ=iw%3K+&(3GX`1h$Hamq7@!HX@rW^;pjBv0={c^#<-~iX#H^s)L(aF=jsby+FL(} zYt>^ug?$Z@JY_#@lyugh|d$&2+(lxS7~q@{-!FP9alzb=mR3U8q$Oj@PgFvCEX4dC&KN zhJCVl!^51g7oUkv{`$=L`Ga4Z)UON;?nyAPaA`PTSru>CUqvnwcY1TkWXYYMNN(x1WC_+esl0--%?|EP5yr}yb zt0<`oYiez}FQsr_jj$;YuvNY_><`EFS)fu`b}_p20Zko}&cw+xY-K zY@kPNnoJ<)rSfs8DZ)X8!cru=e)@izG)w(J zmMV!-i#VUiy(fz(VUJ4c@%Jw{)iIf(1RlV*S?$>OeE?3bwV;c~Pf;&HJ9WNBz_b_i zWtM(Vrk0&e!~0L1p{Dz1V$+l7shL_!s8qXH^1to~s-&ig9B_F{-FetTeY_=L8Ezb) zp4cs6d3yvsOAF1gc%~@3p!g9s@u*_1rs`VCdMu;X=$J8TH_Ir$)5|CYBLk{;b0#Ua zE}vaJc$U$w`o@H9xXu2!oymr$Ct{(nK(>n}@x!eiEVB*a^UHU!!ad=vP014`@tqW3 z<$M&;YhghJhBlD7R}{$JBsu(UWEZpA)PSvT5vDHL4KeLz17y9e3u$w~lw82d@P~UV zYBd)LmNma-#$T)t?|Wn?wyQ?`E1I~p^Ol5 zn$Lgr%?Br1G%=KO8oO0Vk#}+=nklJ^Bd%Qo_)J71zGF5*?#(j7yrWOZiKrRWGo3r+ z_s%5z;+-VvvS1vo@Zi7 zjrW?^>VYt+T5%PdM1G`w7nw6Nw9Hufo%&>Jh$$%>^cCkmM40v=nZFKCvBaL|yq8tE z?08cyS?92j7i%ERZXd43s@6iJ^ywkiLBK5wnRv!J9r=b=cS+;lsg6v^b&SP^gvf@c z1z2DiXXV_#VMppQUU$fg{dixPDh!EcUtd4W`#d*=^xXZObxzpDGxRH^k64M}R}Ze@ zmqM0&GcSQJa-Rv_@FEQF+4u;@T!~`L`!6BorG*%^is3hT6U=yBKR$!Ih%3^~I3T#3 zaT9opbT8);&XOMF#|=tYu2GU*KlB^lt~^ian2%v|rwCjsU}YWHBj`v!^_vt9dP>=t z_3-RJh*OadSezuu#VNuRHaa0p887E!y8<;T-J}8Ql?YKe--oeJu9Be3Xdm`qPvZ{} z#aPv<7|#jMLFt9LRAXy6RnaZS_6WEPbAC7CA*npVZ(11_*b3f7qHnN)q&ePG_CvrG z&%w_>mI?HODctwrF*RjYhrfQV$FzI{(>W&;*PfU|1-mY!GNxuwJ}CuQqI@9*h2Iir z#!YgA>TDdjoE7l5-0_BaDwLyu)!{}#oHl-dDwV-(Tfa4SbdSX&gWriu@f6aP(c#f|Db;V7e6pC&po`!0X)xE*EvSk*)=F$Cy9jGoKO-*+`UDoV*5ZT8e$>~?pU6k%%NU238!5ilY|_czj9Mja ziiZ|EP`myA;neNgSHl5_O95n17yGZ^^Hl`% zuz1|3A6u&l>#2rRQ>rVloso?3qrTUSVl&%8thRfKN&Znm$FlQysx3O~Nl#C8(GXGxqS9)`AKl50@nO&78;7E$R zV~92_w(2Q|jr0*?^WBo!fF++8>n?3})vHHr^4~4|Ma`?&yHx^4-}iIGEb=dNP~tp$ z@yI!L_N9yhQ@ zR3_LX!q=I>v!|G&ny=Ux)8EYNr1xyNS1|K+elKe(wU4b0`9gc7Ut?DeePeusmHBJT zL0{0jjO%5L+A=BDG6&I?&+YipSxIb?NeyGE+|8yuImNEO z`X3uuAxilq-5}4j>fzwOv#DRc{kT=Mh#Zzzrfy0};BDK*DYFC(o|pSh%5N7-Zk^+g z)eeUUd;@J{o3{-W63|3lI;>3n+TMdhgEXlhH*E3Ik#NlGQndVFBk)Kr*+_-_6rrRm z&2Vm?0yX!i6(zJwg39~vKPpkrm|6xcss8x6R9B=W-f}h@&+o{_8@(i`)UPjaPrV?)XAL9K=@nHtP1%w1vR*@p=;}~AZdp^l4+5wSPCIc?R)HY%`XAmC zJcc(Nm_dC=bEI;H-jFNee&UC9wNzt;5%%>T!$x|tl!I~=F=f6DOZC^2j~hGiU_&Uj zKJtg0evnW0sf=UYjH~!S|3*r>Es1=)If`t&=7JML^6*%rAGve>e^iH#1NHCjD84uD zMZK|>qLjwU@t)`@a$(#OT$rat-My4a{q>%W3$hik@S<$WE%Y=d+ICZpKSS`Mj8w|` z6QXo}ej*NTaijW@D)2e)Hzl&KY^+ zfS`wOR>KM`Gr0}#dhwm)-m$?!hr_9RcMnqB^e>o9Iftd*&nDjpdPeTLzaa_JOH62m zpvT^`kyPFphr8YW!$HeRvHjWIc-KS`WzDW;8ZYlBUoQSiP8*uwhz@_OVk}FkX0Ujx zyeiXrNR!&DoyBAuJixa)0G7P0ie*0|w*OEoj>xSd-^7Qr5xsM%U8%}cK!PCL&fmBiYhbG)F5EVvjPpu3kUv?z;9M{;Tf4pf_}&%^2F43W~I|4 z853{=)eHQuf5@}A#kzpZ7W|*rK@V`yn|7Sn7C~%qH)38Z34S-KK%IZ}g;bz#;=MUT zSXk{5ewX_U+bI(`QZ1NDmb!yeh5jQ>E@{BLlkZ8>2`;6(Y5}$KjxoE|NsX$@E+#d+ zUC6NU*W}7a75Fe{#OBkHZ0Enz)Xq)=O8Y*XPDZ zyyDwiy!`f0{AgPwyAX`v%JDR&%O)OMd+M^Patf42=R9h5ih#Wk>CEqm8^tz9YB2pd zjy?ZZmUSC@ga7VT!PXh&OxDMCvSy(xekPuTCAwtD5rgu@k14H@tDW9{Pm&_m1zjL6S{;+ml^IG+Js|wOH$9ib&v#Cf|5EMz>a68!rlLh z1=%wR{-eq_*oQD=A_mp?C6Bn2-*;91!lsYpUKL5waON4tU~vns*kneCT#dx88D(tj z{u5N1NC%G0mZqvNT*s}xCs|EH8T!ObD>C$i5kInMA3N(=EjHb_kBWSogLyCY`4^Tc zQum#OsQX^oldcFj#^&E#d+&O_ep?cZH&z@jpGx9c9Zs#J`vOI(Jv z_jJ(RS3fhAkMo$gQa|=Z-vg%7Y&Jhuz{8ztI>>g)K{nv&U*>h`FXB)M882jhiOu;L0{>st!Y?bID)>h1ke)W5VZKS?2 z#RHaMWKM@*T&LH0PQQ307umlEgy zU8P-I+L^zN8m{(5HCmUQOz7H?b@ z5Q#nC`Lgbj30R?em@Hl&i`zXuGtZB&qbBAGI4z0~NVVMM_`Reu+gGAO?fV^1-E8f{ zttW%9ch3lZbXu4EtmcCA+r}yP&9jJ|79_RBQU>q&`j+(EA>h-7C{eaIhj5XfK9zJx zfie|u#`CWt>Z0{-?5VI8XLansGTp+|QoCn(;@=*|_m?lV=1u~Y{d^X?EK~$Xip{3H zJN4L>$4l`6Fq^uPGL5yb7~@cbK1}AwVtJQn{4-IH8gFf;e#B`~&s3$T5&cf)mUc3B z)TMD_;{@H zGAE#gAnu9ds(CEFl@#sfI!bU9`&55*|mt0nG~fejqCBy zN+l{$-HNSl5M|TWXXB=M6HF&+W>vC#@x;mNjP_s_9<$eCojZTw#Ve|r;T_KywX83M z-hZWR=|&|=Wp55OH6&ns;%(UJj4if16i4s-SVC6lU8Lw;flNtm2kuzF!|xv+!-?&t z?484kRB1phzVF|ICm$H#Rom`h^}_1aq3ASWI`-;*~|SSo>2Qq~?87GBLIm^D;k?Cz|^4=d5fz@6J_hFeQa=9UP#p zy(z(GTw?L0*L?O>hM?|gT^e#&i+V9Kr^b)!JMx>ot7^jJXQkti4PObn5fU#q$|0rIpW(5ZBKC%dATy_! zOulzx@%&2}SWj@bO94yBof5BUe|u#%A}>{UN2y2qCl=`4%&Kh5yL-9u`L8g?TmKqD@uy@9Z zkee#hl9*Z+s-30gtO%zZzEv{=FT<%W)g1QS)$PQNCIkH7bSe8GSq&da{>3QotfjW4 zVXFPD0l)EhB$YMa2Y=YqjpaAarW_({*&MGYjGIdv*3ZZxM@HVUi`Vw!rv*Zc%g6)l zAAW$nI3t)U$vn#33eaSp9u~%n{;Oww3hXKQqMMZBOCPGkJOsmIwYdFKGvQzEf)RBX*298IL)jLe(l)b%Zb9y&2OXy%C#^ z{J{n$Tx#aiS9s|qDfXCGD|PVHP0GLPA-l~h5YM$)E120;vQb8M*jVf;Zme8L;b0D~ zob?O;{8)*PhP=b$8ojtZXs+eUKgQJhonu%&cQd;tc>vGJV9Tz@3 zLTR6jWzL9yAWd3Ta8A)zeC$mG>Db6q=j8*&@obUrjq{NWQ z-~1_e-#BWPxnRFuu!>4i)uJL(R^X1a;`q0f9GPlBW8JBG>Ok}a+1j+7t$GweT~)ct z$VYFW5}s+|JA-~yTjK`G^X?m>&~`IrdGi=M@AQ4@fN2?3W=UcDZ8xd8(G9GThYPuM zXeK_O-NsJ*9wqLiey8VdooRW;(~_z|vi#`1#ne&h-&lP2C;U+90G(E+MhE8lF{9>u z`W2bcFPr(Z_bTtW*hZ!x#fP~s>`^)%BzAP7*tPo{52 z_S5P2T$%EvA&mW`DlNm0qdPh4=|8JZ*H#L+#9w-fc?bS2;9X*dOZ@ITUtuL{KBQPKg2NnznZkt@LI++_#Ch2 zpeFBLs6DMT7{Oc%m_whGJj0XwpulR{YYX~|t(Xs&rg`5y_S5sQ1MgUn9BY|v$#9z1 zG091HnV|iB%%*q)=3s?@p=Yv|@mJ}kRXweFc6WBu62YRhy_*93Nq0p%;fsGN0FMs(snCl>YPlFl`y1 z$@}|GnqHCcfL8bMtc^bNh$q*qSZjKF4G8-e$E#BvsEPRDPH&L4Ws<^Od5;q2TWmOB z&3sy1!z93a^qEH#Z`Q4JFcEB9Qx{XqtT04O_M%0#tAu7Vp3gop#}fK$*~&$Xn1VJv z`{oLs^~a9dPp5KfYwk_)mPp6YJ6>Dy-k#Y^Uvc_!?RZr?wE7}d8!&GL?{VRJaPsOW zo}4@lpS@K_8C!X^i`J^4N?SK(q;WPaK2pTIFiu3xAIq;U=l0PBLa%BU9i9WP9*gE# z+ic|d9xJ6+IV$sAk@D{!|p;y%jxF!W(Tw1+=y)i0>!={yL=k?sHJu@1`gIX~- zTA`fG>>MXUt{LOp#B}nN{O4+yF&|v@bUyh;CZTrIxhYyG{}4~aES=$h+<@;E>GFEa zU(;!V&X?z14oqd2Cato_jQ-;x&wDWOlI%>;VqVRhOP{>^2W9?JW~{ThjQr^2v5783DJ!u)DT6n?qj&{qW2ofd_HravXOE zlUuzxg3gzCOj=!FN&@w8sPH9PrgJ&DVeLbvZA=QMPM#p#UF+Ev$-M;O2Eg zPfqYRv9}#hv0Fke(pD?Q*@2v7vP~?W{`+JL^Uofz7q4WI{g(5X(6k}M-8F+984O~S z439JaLPnAQEOGYuyVb1g`M2b~_K(blD?sX4ua*z~zJ9q?}r^>YQqNPN&?SN!&1_&O%o`D#2~uJ#iD+fc>c zN=w08b&gUoO*Z`T-TrvR%ZHeANRvE#QXRXi?;{Ufs}XPvqu5u1JhgSeV)Ffqi+JPQ zcK?nfH!^ zJIuHib~aW*oBv;ruH7QeGuwX7r8)m`e)MhPh-NG|yWla0^BPBU{Jn2-X38a-E=m*P z*nZ96IBM#c{SscynH+t|c_Hp(c6oakXKKzqvvZwZoMVCWIF9#AIZVeXQ-{5eIakc8 z%&u$oo67yk=KPu!z=@p}Gp+o2+iYH60Y@ewn6qAYmYH{(zS*zERi;K-BOJy32RNUT zK9~-lZZ*~Kyuy)8TgsW=Zp2x>&)Dp=_$QA2nX_iQOE8C}Q#r?mayd8Br#M$qA8{TR zmv9XKmU7-*jpisvgm69@T5MxQH_qTh4KjV@+2-t>C;GU^p8JFvnG!=3F^(kaIZo9Vgb8Z&sUl zk@H=;m~;1BKIi-W0@HiCCpg?S;vD)^5=TJM<5Ws&nM&Drnzp}pKJ)C3c_{B7dvNdyBa*-oDV9U8azM7-@tC9m;mzfPp zPI8(o>o}_ogv>_X|sRM7N{GGI0kj2`#^&{rphnp)O^x1wUGO#Lj^I;RpXJYIt& zgQB=L=hng6igU32{Rm9mca&SHssnF|Ux%Fw2jS3&D%2~y3TK};uY}1Lwc)v&H{sUG3t;@m zV`#YZ3!Ev}41HF(!_|o$<|k*jbLUl!K$Tzfp#9KUkWj=&BDq)59r*(+~RfIQPVIFn?qT)cf5B3PVKE;XNne z(R(h)LFA>mhoS*gB#K~%=40p>(+kwiP6IhR7jB!2F@m#~f~@8rz;)hvU{>n^vy`IY zaMx@LulUCx$}JG?sk?{_T1&t`u>y4ewLEZ~;|}-P=5f84E8M9$&n%W`FM!k)A^2@( z6nfoW0*~I6L5Uk5z~L+t)~-H6b7BAaYb|2OIq*h)VG-=-!S@^m6Lmz+dzLk^(2n|IOKB{ztZT|3eD!aTHOHw8n8O>pm`DahY`0rh&VLdo`$gu9X? zalh&|RDKeQ4hhYGE^^}NnnEaQ(2_)>v6XPj^$2bA2-uZ!P6Rq_4kzr91iD$No}SX_qxy$(e-W>)Ck)QQ0{W08hZLE1xbV(W*u_{8dM9m(M4NMHLfH#d?43m%tviVn zn=_G}ycXKBM48YGEkOfi%i!UOAmsUA2tAzdO7zVCijK%HM`F8Y5}*Ip!i|AhNbYp_6|1Xn}k3>b)M0d0-377bJ5 z77`yZJo#TG_vZFMt_3{?Ut9`=KXosF3r!pgt9BRj*T;aldEyMDHMbKKho0cN?~8`P zOWr`L?UPxx>1DX~*LiT;-@G4G0YC^hWGA@W4j92t z6$o^eI6`>qy9MK*hko)eb9X!wLI+3!l7Z7;Pq-$``KraR+qn!>-C?@Mu#wG#n~5?`V=1 zthZ_u{CNqmez%A_x;g=7=A=Rctx-_(%K^;M8tYLHOc1ahR};pC7NcoM1&AO2GY zGji3L@x1d?Ac%PlrKQY=Fb4IedMo2@3yKh9CUo;oA@bDeP;2 z)Bi;Sx6K~t!l74SiP}$KK^`;jXr2YW+!VYwWJM9NO9+bm5=CB%8N`nGLZxu1c}Fv-wK@r3)%9@i6evLF)ia@( zfh?Q|c)|@osRAsb^}w;ui@4`)n!t)H3xN8Q^IVyxAh_#@Gk8V}SS&xB2(A7)aZMkW z!jbUTP%2dq8J<_-PFVJFCEU)y!1Jj`+2Px8#S42hzRjDP^4yMCo^Q;RcrO9_gX_?D z0o3Y~)?Mf;7fVRo^#*ZE&7kgJ1NXhZ0k_(QkF+cp5Z2@h8;#A;;pdytjr(n&e&RTa z-YbPxY`X~j9)6XPXxm*~E z-iSmo8Y1vcvKjg+x)+$-y#|MEM9`+1Gyq?3ft!S)fWFlvd@`zl&hM;)Z&&-Hi>MIv zzV!i}C*LE(|I5 ziy2%bb|4)csxF5H^4B0fX%6?stc9}-4UtBt5E|v>Am!x&XmaWm+>>w~*>pxhwLdz@ zW>f|CN3BPH3k*=f?LlCpkpgY~E4lhTX(+;WJA8Pt96pXoK@k@uklU0znz8g2G)zuK z?!Ux|Y3DVNE3AVoz3tHD>~a_=IR|FDSfH%yPH5eh3J6j^Le-3LbUiQ*8Cz+FJ<+USf?jHl2|7M{zoM?ihJ_z!}n^At%OmuwvRp7f$lGx*EgzQily1yYG-F?qT zn0x~_vJoF{*^rPQZz?pjv6RW{3aSXdzM(0yciX@r6Iq@0;tbl1{3n< zppfk`Xm^P@vi>-mh%UH-&V5URa-m8{w^RqxkJV6(5QzdW$RXk9kKm_4SERf!4@E}~ zppUlhsPrX5hh6p{f#Vihb}vMW6X&49-4EeK4?FZOs|jq(5J%37o8ioa?I?a`AAGuE zJ6yW?F{(n5sA#Jiyj$r=d}Sk%=IJw0_|vc&eU)ju@Gtmp=1h`CS7-W&H^hK6eZ)9KDMsw@g6UUJgpN7D9m! zm4Uc>COj(s4vd+vhE|*(K&Rt5Z0%kJ9%|Xb6t~~p8)Gxjf=i>IYD^z|yd(ny44r`1 zkKb@e-jWD?A_>Dc$e?hk6^L0J2y2Q&L0hOZ(JJ1>J>I%kQy?}>K`=TWV5pW>447z_j0B#^apv|pZwN{+o? zEMf>YeGZ33XJg@^uvqw2cn0!vy9?J$_QBC63#42)1ow;{fbQS((f+tbG*7q~mbhr5 zmOqj}Y;PH`O*(*%EPn|3O71W>Aqj2&nSwM1y`bz89(P_)127g9M~RAO(M-LKXhJO> zNN*j1i%xW*A>;W_ZIJ;AO?wH%Sre}AksfgD+ILVAJPcMTc);y`T)^u)0hVpb0m&U% zfXrxyS3)E~U)gH-BeWjQYhDUg`K$$(LvoQ=coGz+{NbzrHlVT#FP8D?EDgcd5Bapiz0E$eF zqAAhCXy^lhRGeecuK@)(9x`DOIja!temMlf#u1D5- zQs{}NIkNoo2F)E_jDDQCje@pBBkP$@(D-{JWRn<++y|V|#SL}v#7Z5Q-YG)JT`fWP z%x}P9ktnqPPb%7*t3zBJxI)bHh(aEmaU{L#0+K(z5nXOiM0;g=2}P|mIQokqb~hOl z*M3Vt>&;=rl+Y)1FK-OJ+*ga-7RwNS^tPhO5hG%QbS&!AOF~bCYoUFJ7@>A|FKYT3 z3%?v$N1Qs`j3%?+A!wV8R`h;HUeV#`{ktS|2fsvv;bW;ZbH7YyO7sz zC!$~dE^%q{1A1}331x&SA&(2`aACzv17Iaj0T2i>R+OL}S$eZeO^G@G1RAeQmUVSt{XIEl!B|?n4`|m!Y<=o*fDRNz6Tjb@6P^`QDC2q@GBde{p34*f?<3bx%6t)YC{Y^O>*}K6)lsN9<{$`3 zOoq4CTZ5Gi;ppJs9H3S;4&)1J;T^vLFp^V_Di3B5`N4CL{elTn8$#_75y->KAJv@!=q9@!kw*`sBkHlpWL+=(HsFo6 z+*=1bkve)-p@yE!*MS%95(wEvw#aC+0&Ml*qdzE`ao(qg*CC7~`SRX^p;Yv;eX~imo&QdcT5Iq{x}bx zC(6U6l{+k&XZOIj;TGKTcgoO9*9nS!=!E?-r=ZRlGOwKV5ZI;V0)sL=RC#DO^h>-4 zo<8w})AMYBY0fZcD9_`**j8o%hc)0@A5V)CdJaOLMA7_NVqop+5xAqF5_~F|0cSS? zu;bnakgfXJ;%Tx9(AuK|4@4Ss6=uo8AqGO#ah5Ay*vnnABopHBEznI-5&Y|T1EN}D z!MXlNFmaCH>@AqSJwDV8ioq+G-o!Dt(P;!3o{cCzs*byPw+phlrDm~d!o|GgVGayj zmkbKdCc~CR&%x1~XCau;3Knkz=m)P38Vbw9*P%vcI?KYKzjGN(^X}z_2epA##DKy3 zUj%M5A^7qH1Zzkgpy#+4=AGMtY&-2B=VvoqFdYeNJL@b?iRFV!+7$AbWd$9}qTxH0 z-|+C9x7=@9-Q0LNeOP2N2DZ#E0~2sFTEX&xdy*c|-YgE%t7C!j7z<%|9jN{{32toL z1ilQF!9QjD!Pmff(ASxT2lhzAn!|=LKe-$TNp6Pb#(O~K>_lJ{qYthY^l^O!oR!7m zuRyNMYG`^|20WWF48-<5hVi*pPlx8bAZFv4qUbI=fL%9x`oDpQ?QV< z0S!s3;JyQ8@a?sy@P$thEDM~4kTXDi290Rs=?EAt&4xQy?1J2$F>-$Y8Z`&61WTPnQ2K}v z+OM}Bu+zTC?a(v$n*SIM%-2Vgxw_~JV-6FF1$P|kBy4YXf(zSL!^B@!$eK-ndv;WT z+hrAKj+YV&PGg{~S`HL5bVhy?n_$0_Bzn3@6AjKih-TWv!;K?~pUR100|4 z2~95;p!?g3;jL^b=r<~Yro+6@HKloI_w~Opq3j3LxxWCduIvGCKU{>7r|O_%@p8Cy z{y1z^fxvV+10FS91)EgMp~j9$XlRfL6fAe4s>70~ZO1g%z?3J@REObw9~*c!APkkn zG(sb@Som6V5Qv9KK+lqBq*YXle1reN;C&S^J}Vww{BQ#XKktWApOfI?p(s?>YluFl z9Rc&i$KZjRYmk`9edJVQiFQ5s0edA^BhUA$| z|K@;di%@jHE*~w=Dg_(gtwZ|DwUDmsMl_upfV%hrXi)zw+}@FfRLx9~?B1s^!!;Rd ze~3V8w=oJ>^%H#jxqt{U+KRsB{{`U}4k6VM0(E4k!t_rh8t!mK?;CT`2f>+7v)B=3 z*CrsnRk3K>IvSl{6HU0Z%tZcV3bNXh0uGqz!jer~blfci30te6vEnGSyyGXDqZJ8f zcPpb$WDB^THU$@JCZXmMC-j632OgJXk&g5@`XLbukFHTbB};0djR+r|ShpPJcWgxH zg9KWawidp3>x5FVH^94EQB<`;1?KbJ&~=9waIe-$nAcH(=6>fQ{zwAYGQFCpGJgqI zsa$~be;N>mJYcc!wJn^9fNLpEg^ygp~izsW@xX$dt`XQ1fC4`K;JG8fa9~daN^}s z6srM&j=3gbG!TiN3=Kke^bDn&jzH514`j+$hp8sc@S&0w>=dkLcI=Z%X|c; z^)sOFf(*$0mkB=n`v8qCYvFutRe0*F0jz}AV1&UR=z6ddo>9IG44b2&&{hUsKi3KF z&aa2wWv@};?D?QiArY-@ii4^PGr1iL)6w-LD;P3|C(v*zp~@&ge_OV|<4e`ho9#l# zT-FfIT2{qXERsZc!yM?_kphGeP*$O)dBT7q^y4u|A2Q`pmn(SzD?7^}Du#rgW7g+ZPWX&r&z z))oWJMo(DVT?9CWUC=A#JPg&A1IyVl&~GdXvjv(_{)7hn_Vg4GiVQ(b`afaw)?Bc@ zsv5o5xC8^G3HUOYKt(&N;LM_A_(UxUp4N;7oJDWYWWp3wb>9uw&lrHS4~@Y6U&^7( zI|M9dF+U>nv`; zV69=W|L-}F^hFs8CZ1gKMIU#0wmnQ883WF@J;C0z5TNu@0@mGm0!LTx1=D9Aa(Bw5 zz_r5^P|;Wn|559q)Y}d4^nYsHTk7g)Sg>A;&aJZOP^f^vi-v$nQVe{(<}wH=)qn;C zlfW-I6W-Hvg;$#Xf##-D-0%%qP=3~$t#lqdvMCwt%R38$6@+2= z3pr?%sEUH4F2a4&v!ULjc&@g$3M@H30P?qb!NmG>@TqPqbZ_1O*BzR=^!NE{cqR89R1b0ipYJ$9ljLu})=F?>7}tPztkbyze{X{W`KN)=KQ1Wmo&nD~ z1#+Jx$e}}NF0kgzBd)0R8TdP;7pyd;V8kwQ#O!T^k6wC%6;fhw&$@3wg5LtOf^*>B zf7{^V1}P|9vk6XAX+hEX3E=qiYOvLNC+J;T4wg?o;(7{nM%@pdP&qdnPKjA_=UR)P zl818Oe8e-Lk+2#5xgf_KJ*WYFY+b>GaVGE%OoivjCW{ZUGU)Ke8elvx4}#^&KuqBX zyfa!1&Q#gKU+>R?YhCtmx~K;{uRH@r0Y!+0W_vPbsT!1KB9`>1FL(a_Q$O1mVfM7zvng^b9E z5-LTMBqgg5DirmtP)SQFl~U>V`Tg(pczB-AIrq7)_jR3TRrj&PXb|1wN@R|o=~Z!pDM9+PK>!ssiycw@FK z_sZ4)e-^rOP6gjMk!8VH`z8kF8_q!`nRc+B?#M@>#^SCihXGA;amR$&7$)%ube04` z*fcX7TV}3+$H3?G89cjdF@^YF!Vglv@bLa`(2$!BSO2we3EI-| zr6L^i*Y8KoxdPO`S<9{UxXe9h4hN0ctK2>Rli{o@<_-rtUo1a(mSV-ci`d<*iGNw`J)GNkGz!f}0FT-hIl1wSXFiPs#EvRn?~ z&y;a+uoLXgHgc(BS3%XNaC{>F73Wq8f!Fz$2#)u;k=m`mIWyR>{y6tL*9rTEdf|zQ z2)IA5#U4El4=5}mTOT`o6j+YS4@tnffCM}cZw670DmXV-1kWhfVE(#O(4U`&oBI0U zlI|n$KQb52CmGXYP6#)jEP^TTqp^3PB|K@XMNcsBxb+^fju2J9Yfta`nm6ScT@6~RFq5ngcns4@Y7*qTDNlQ2l2ZeX%FQBb@F z`PW2XWLq>&kNrgId{1S@ohP_DdM;JT3PY6ZJT8bvJrj7n9n#9kg&*isTax(%HHK=vz7#o8+P(TF?k$8h_AceKp5l zWk6MS7x0(NYPwjfNUAH1>F9oCiqW%1<4c!e_byvha=rm+{4*sqz6|~@n**9_uYk|= zm*7%m3@2t?LR$D23eTQ`W106sJ+s;I8qyzv7r{=zYfpBif7c`;9H|XYXfjeXlG@PtE4sK5GG7JVRmGPcT4c2`1Dp zgeHSuTvGj8sI-_y3-l(T_{u8ysPPGV^B$qlr*fP&ON%W)0KxvROoU~dF zkNMZ%>n4gxRcpA*=E5*Aa}(Ii^ntwK)iD2$F{~?mk0F!z^))Dsn;$xiKkjSc>f;GvL6rXRpFg1O{_K^MJ)?~pE>j4O_3;k)6?PJ9oU9NQ(7U|-^cPI^rtkW;;rjzvr2r7s%fWwDCjohs8P%feapb*Pe=i2L8p zrdqu$$ei^H?*<0qjN6OwoRAW3{`CQ)M<1aDnP;eX2fvqITu3veXV4z&R#a*EgvUEw z*^&`b@U*0z+IC;24o@xI_38!P3P#dtlA?IC4bBoE3g_J3G5`@1?A*30wRjT7@n)f*@ewDydUJ5a%Vp&R> za0(x~O@lhgtq>**EHpKRBve=9B#(RKXl===W^bhH4$91y_dc!r^y#_Fez0*ffer)Wi4TQ>Fbt{q+__60(d`1bbc=;3zc(IuD!?H@$z&ve>=h< zCzdQoCf~ab?CZNK3LN*FoF6|1p<-p`_*szz{-5ak^h8QMtj^wOE#Uu0-J~xYK({;I z;=G7R6kTV=V(lXNl0!-I9}!1J2J`5IlqdTbKi+c8q&u{y+mIbgP-OG#W9dp~EJqFA}98IX%|4ld+cx?G(QKBWrkE&hT9p zwSM-bmi}t|Vkg98GOn@>HNq@Yph2CLGnuq~Eo(FoW81R>*nE!)5<4%>az^UYi}}xJ z&AuwycC(All<%Q$3nFmsl5|SBWlLZEm04kc5v6uoQOXN9HW-;q`wwTMy>T0>RLznt9M~iNd#$)4jl8rM6JM;rxR4|ksXRmzdy>dI`vRMg(?K^TTd`+CycS@T z#%jG7+ju__*M|u+>r-8HV2pyLZq`X=H?)#z336FP`wHsU$)eC7fmm-7OR+7YOw#-Y zN+djC|0T(@&x0q}X^nXHICdKQvRatEKfMACUiskJYp$pqb`@i757Dg1}DXER)SVi5F0 zi{WPGWgKXiMG1#0s2eJz57Qg5zD|jZw-(_vzde{W!v#kcgyOqp4=}yp2bM2cf}`(D zKpu|ARgTHnadrU5g3|#z(W=uG&O%MUG}<-2Q-Z_-?tR2$5(L|egPUh zZ-mS#L1@491&)iq#JySa3@)hr1-lF8_;kfylwLd?CRq()z4uy7`DYDpHaXDPq8Oa; zdjkZPi&OT=9e8s8Dbxv#0ePq6@TFxLP0>-I9m}rc@z_30dt*c+Gn!D><1GI055<$g zQ|NDWC01u#fVl&^(ByyxO*EfFb9!oVwU#!fe)@(XE}tN9YcMMM&4Yp`(p01rgVkGO z;ERb($P> zj=UC>bF&Ngp;W&v1rt34hvn0&q8I%R%YH`YC6=b&dxUH`nRQQ=UydW4(r8n-9d6*c zqL8*auH$?U*IDR5^U|_0=z0nqioJ}L4aaF{UkUoAUqY?zCotuz3@OaC1rKLO{5+um zZ-x$oL`W@CC&xYSK8|a(4KaMzOMGK~0vGR3ulGCCqm}${%@#J0-=^P8eW?p+u zS+tt|t1ZH(b^5q^Ub{fzj2YTpxP@Y}jr7u^i+>G$9B+|D`Lc&F)*}p+$DG1B&R3{4 zdoQU+Jrbw~4dc_gjm&^JofP6$3J7C)4{`gQ)R%3e9r1#}~z=oawVPNItj^ zr<-g5>+k{GFhzy$RJa8#HXGsgUlSbDDxjLo4Y>C67!3WkmkN5vW83Mml;g1&cPMz# zd+i)9+k7V7oq3V6e|B&UE!}9|+J<3&U*pv(N7Py_NefD2ar&@3UN{;9qT_PVYIYju zcYXlRJniIUc6V?yI+p;Sh{TjFUieie5QI`4Df4AKUf6L3PUMy1-J0z*LE0N8EH*&b z>PURA|G|9W$0Tg+W+c&>h#$Qdqsa4SFskr^`C)G`d5SML%J>=gY(gTb?Ylzg$1^l1 zLLeffmrLu8gnvhc*rt|?*y?`=&Sk8pn2(R>XGJI;Dmg%D9TDiDx036#iiOZi4cxby zLfA4d25IppNZc_3tZv%C(`X+EcxVRSQ~C4b@riIFJOS^BoWQ|_&$;!B7SmC!7cjCy zg7g*!gPgKC9k1_#I@cyHY~oqO$4d0MA_0fLM}qFs>1b}t$b9!m3|KP*r+mI7=Dca}Lqc97z~SE?n$k55cWpXDtLvnx>Xii@(n-erE<^I$rivpw zOt3{h5`LEdL|kfwtBj?QPnCe*>|)fmFQ=s+2WfVt8(Bv_Bu>{1?(1(PzI+9bPh3Q* zdyjKgKMvB*mmW+t!xkNk67h6xAcqM;RVQ5Tant{v#8Qz zN;f7o!S}3@=yqup-*s$Bmg}$KwS)jF`FMm*d|pXa!Kd)QxUJZ>JBlVMMd7HUzj#Kh znd(Y`QpUW7e>=9bP``T^+O!x`Czisr`D5`y+h#hoDT$`6_<_R$UxMIRwrH~+8SgE^ zV7({Y)m{cZHSWw;>kO^18i}RP!YFw{CadeZkLk7X^?!`w{_zz(+e1LN}2r!8?m#0C8kd^pg9KG?50W@ z`5xK|4slm;`H?Wpq*bhMO$dz``5)aAav=3FvUL96ZCvAe3SPZBjW)c#zbe3|<3@3M zFfk7FqX+2k$???7b2pn)Mv+haUtDR(*w{V4SycZinlf?}dzyBN*2-+Ak<|z3*V+-5 zmrI6VnvFBd-|EhC?lD~GJetiO_k}+BOR`M;7E-lqpxL>xH0Lw0i{@!$aO^Uz%8;Td zD9ZjFOd>Z84>TMsVpVyMXs&M^2GLLY7&Jilcy`7&<_PacS+L`(!1iqKqB8#d@2FE} zgTFe+W%m}Aa8kokV_1Z}c<_gAY0ts;!;f+IJTYb_p~2Mi&Qh5Dab}%S%%-IB_uba& zkWuee+$`)zOP?pRKL1~Ii`TQ)xF|B^^*2~>t|j&VwPzJa!$@Ro4ekBM@4+fjG*0t8 zsplP|_&5#nOPzsyFFlQrRU?UKk7)3RBz2!_!401!+1i`yNY;NVdQHe+5`t*Dd*m1; zeG6g3Z4v&l+X?vR3}>AFkLy!O1Fw-W`0k7Z9?}2K>7RU#JKuzY?xX#vs4^C> zPj2EbFm&U3zBQqIoGMim+H)R9`7_{TDP;3Ja9v{qyiOX4bvMLuXg~=)-}FKGW_5f- zk=#i;b*wWC0F$dnIr+(osIfi;vW?$xcNMO}@4wl2S@9*frx@cws|DDT6^>tL6oR6C z94sreMk_f9yl{3UehZj}6YFn+`_Va=JlMf`_|p;8F~F;zYvVzi{)CdU1Tvb8t0`z*V`j@V!wR z<>D7W&2&YO`Qh`bZeuqYLfLVrVfYh*K>(i(Osyu;@o9S9#|iY6f0~ z$)(O%s9k`rX?6HeM-0rPWuW;#HT-jb7oN;_!MiIqq9A~S)Fl_OyvPRJn#cy`Tz!aXx!bwe98>6qj8G5ff2I~Cxda~hmn z;{`?;$vD|I9Db&5!!CUx^t*f-cY20GSCAb0HP9{SaGi#iZ!M(!z;F0$)nf?uh^7DL zXbMIvy+j+CgBI_l)aiKhDgm1v1kTP^V4bd{U{%NgYAO4{9QMmGQBh5LZ^J04T@5XG z4%u^E2|FA%mJ95=hZ0V@EG_CTs<_@n#h@m#+0L_7zdq2Y-vbB}EGXmsOd8Akzu)KR z(@w2}wAfOOzG%m`D9rPm5lx(U8e~*>A}@ ztcLOO?MkfKSV4ASk5FGB9#1(=h0Re5aE+x2wbZX+8v@tj@!;>=`16@;iM9@Qyojft z=N3}Ee*??DZO<+(+rrI!#&fSx18C*m#Rjc1ndUxWa-5yae5`k&Xiy91FirvwB{*@i zm)a?yw}soc{skL$Im~iC+(ex(SJv=`-z+r?3B06Xx%4QtAhi|RqEXBtMvAhg_W@22;R(2{eW^jjstX)|5J4Q=OcwHu6lLdI% zF-47iMYk1rj4Ud+GcoV(iEm-l}uVIg!nT=GKr7dOq&uy*|yO(mS-9z*_B<3 znb9X17T;V)uhz&jGuUXk(IO7zlXBS2=><$DHxn;gUu15_XRu`P<*e?yfJI+i#DwPG zrJ9ms%#WWh=E#Y$tzm1aRMwNdv=nB=acA)Kz%W}QZ^Qhm&e5#7rfh8husePQq{V+0 zZ_f6kWicwaT-Eb!|*`=Qhjln%2x^*pVF_{TdA-wJAqv70VUn zbHOi!n8-zO%Q4QPmcjck(>b0UoVl(E(=UCbruf5aVOEURKqgBXdSy=bAxev?y#acdsvLUI@=$whb}8bP~`qb z3Qn4FZg_%FWOaCb3TUGKy~B;@Yi{W>o@DY_DP zqj4;ZGQ5nv(yvj;lGlOM4UZZI0_HzQ~(bcd>axuw0 z{lZO{mI?ENEYM95Od`Rx@LgVwk}US1mfS{8|9}$CU8M*u12s7F-AZV)Qm2LQJu&Kw zI_9N$(YyV;Hj*|M4*u(*&F-=2mQl-nou|UQw|>Xj&n4k_-#lFDco|l>TTzbj33|$3 z8Gb-o6ec*%p*7YO@XBC5S^EA$J85MKl;AaoCX;?~5d%edeL|Apj^QjC{Z4_t9~!XO!ZZ1bzD00q{c^fqwHeA( zcHrtK^?2s@eURReOX@?sUt%#259fBJSy)(p8{T+V;!(HHa4`7>mPvhw zRjpG|KCBg1yNFO|*>3b**a1)fL}0=1YoK>A1lO)fMg5K|=#eCcpReRVnRpsjTLwbM ziWS`Q7elbLPX-f1%;BrYQ%vfR#S)=nC^;ZbS0pWX?_UHLc+Ey_+bba0Qv)_}T6o=i zAzI}QW9v6vTyaVR9e24=pVdSV@rWp2i)3r<4zlf@X7 zu7b}T74SOmFK~Cib4x#-M>(%Y@b5+t82_7&+$m4U9Pt#RQsTg0p&LSGXyc;7jd=WK zBYEZ;(tq|sR5>_ThDbUQ|vf>j*!MCvlgCHd51+SyD9e5bTXKDjHHb1*!`H1 z=%U|GFH6ixZHpd^k(QkH<9Y(348(8t2OZddB9-AC92rlfy zuL5msYUO7NxmN5+8O`i1-=l01uOq%KrB?+ZIIYo%W+p_zCfD(pzn0%adt71m0RJ3( z%w|%f&C#Eqhi-h%rP`lz*cj(P5ASTp>W3=Sbo@0PZEk{dZaJth<}03d{D~dXX>`If z3M22w(UXZgc}DdP4D2nS7Q1g0d}%j$3`LRuDxR(5eUFq$GvMNkSKR%@%URjtYTD!+ zP5OJ6@aMqYG<|sw*(Y{jO=Sw!KTu(3viX+avWX@0jy)4KZSo>h6;%z=xfbkVn{*N}Fm*dQ{ys}HD3Maa zMOkzD9BQ3VMxicKXzz#J#KrC>>m>q8O+HU0A~X0FQQmV_pJ@53@e^g6hNFJtRQ9Hj z*PL=Tkgtssbrj?f?^3bsYdQ4bP6Rct_hpZk0h3gEOq&;&Szhnbpd*rvBplexJ(A+{ zd?NPDYKt%X`ur?SnCHSae7(Si>*r89pP#EY*$AC=!I)5%$pUp3uu)au%T}{wRb6(n za0A<#s!DY`a_RR@do<`ig)x#(NMUdvE>3*IQm&t7`#BM|-s%Dy`@Wx)kCf3<;Rkpw zsG5tDm#0q!vgmhW1D>z-#pKOn(IMs>Y~s)PUlUGo3atrP+glHVQ$BJ_i}%0-JttUU zp-HB;4fwdd2X@A*&}c(lxZiSx*F4hT=zC?JqY>gH?3a+5zc-nVt>-om{>82PgYd!I zGw8m&4y^Z!p_lP#JZs^Gg0oYw^j#FLyP*#i8L{~3t{j|;y30iy5M>?|LWxt&+{A@P zF)^_V-%ekOD=m^i>)$xanlXwFwYuYugLyEXYr~fzh@)(TY4#6oa@v=KLi;`O-ItBr zhMirUiI5Dnt_ery{)f=)Q$WXr57CV3_2{g54D^%&1WV-K3p6i2r24o9{Muy)27`K3 zxV@F8LfkN5wTy@kMSZiCDbEk((^3{lhJosn<{b zycQiDlSjG96X~t?MA~QFg-e38$$76ZpRG>7>X%zUAqmOK;4uDF{0izIT???{Km7%)>07QF2#;Wtz!M-#-YOFCA8#KB0cZl zNmdv2XiYBB-itA`(_|X?*;t~2nh*6oU4!Wf3urZ4f`0>!!lkWC*@HjPG~#MF-rHkK zC-!B~c*}*oCU>+vPEwy$jC#1P5N9%+jPrt@o*4Y z{WHO8X;o5HlgIGXW%T*#8r&j0AD1tA41E!Q!S-|}1fO@sf2FPPcjjcw4jPH-N8510 z8=fhv5+$2~4zM!pLi>V1e!dRG(T|<*aZw;om$ z@^eqi85}eFIBryn!8-GCs6TiF2deDwr0_AgadZ~ifCMV(eFCLYb1IPz!ULv!wyxb3 zqr=W)z_Sp1`}Yj~{%1~>&uZ{NS31h=`40KgwODy<1OI(>p|>rQXlCCkj5&P=Bc|zs z>AFEqXTXZiec6PMTPom~SRE;hHlm_UzIc4@d5oH;2E+Q3Rc4+^+GJlmBRk5=|9wWUCOh<=;YUdA{4Cy9$D~d%(cdFYsew z0MBKbfbMnyJv#doZaQXj?#kMfH?tA0tzCieUV*UbHr{(-haa8)z;Yd1RK3mnLsEC~ zr9~O8np20nba~C~$v5l|*o3x`cDT!82xXMx@p+3sq*gg${cID`6kkl@Nqca|=gG8o zLNpHTpNiehyK%Vd5-;lTYmBoqu8nVj{N2Roz;ki?>wM~oEl1_fDdh1%7Tdqd(C>+A zC}tUkr9E~e8UBVy=pwvK6``^`X?$cLLwChG;c8F`nkL_efK_wREyx)AFY^8ip5tc$ zNw)NcBJCeofXkjwq&q#6Vc?z+1-^4+R(2KKD;r75jL@Or_73PU3Zo<2J5bc92)(-3 z(VxXg;a&G|RpwiqWGP4U%uUhIBMKMAicyP2Hm=khgV#psu@c4oG}`MSu65QU@cf5z zcjD0Wbq~6au%>7ATX@!8n=A_W`}-EmAx%wVN?37$=KTm@&a!hc+-VQ}Q8I#?PepLi z<#c*fcaS_CyRlQNo7$9PD8S7R-#ogBBj?6KxL`!H6@U&iQC5eQ95#o)I&@Z+cyDSb&n%V?%*47@jNPF0#y;bw;v^NEe3jCrwi?d~=+cnuvlkWl2Ipks=FVlYz;0Kb><>g#A3VX8Myf-1A>k8 z@QP~?3iVgO^DnF&iM9YgPJEg zyy43jtBv4MJ+GfpIuu>liejmo!C=X5{HY~^j}JI-f4$3q-KfPu?g2)~7-KGfW@(za z6a&hY;FqQycr2UDW%IfBJD0>zGG-yyJ0wKXxC4XuwK-zvVf2yFMlq)%Fs_hfzjKmN z{;fZ8UrcCL-fenSErH(^57CFdGF1HHgj~ZrkmtK4y2mD?(3B)xwICn0Mk|uFSO>vS zB};dVCo9Vqa?)B)+f9^7c9}8#fm3Yh))aV@a)Xw}E@fMKH{ht^5IQjGI<4k^HWyOJ z`a6F={fYaS9X3qs-#gMgd2h-XuSnzV^9Zc=)8M-eI5~L-Q}jzFkvU`N!5qFl`Qagw zE%zcl^H7@g+J{S zNNAQTJt^0qq$f}4#JC!CoEuCrTH9#Lw`i=g_`vsaOhro(P1;x=jxM|ozO6%;ObYHI z3%g0yd^T%D#|@Y`ZZWHpbD-!gbIGCImU;a5fLgQ8p>RcU5e&1`!=#&d< z9A!^S!yZz+hzPm!{!GuF=UC~f%MLuNf=h?F_clh_TW+8Pdg;VRYI9gb` zfyC>^((Noeo;yvTjq1~={h=FO-Exy;?>N$zpd&QN?I2SqVwBz{MZab_;IlwW>{ke) zKRTHdD zt+?uy9CrUOq0|Fwd3ItUhS~tE_hX^#2$nu;Ff6h+}#1-;c4VUucF`L$U>ZnhIRb zL`ld{ z+(xsXSSp1Bo}kawh(-zyY>na?40oGdJ&`X66EJRSLK9B<6T;0A;j=H1 z!f5-)4bl!?Qj1u>Auor(~k^{ju1oFbb_-{lZv{4BVnn$35fu(YbSX zlXbQYSibP5`yUiS1DJ2m#b{Y`lzTH8?NtTnFh>`2LIbb~ za>@N<0&d9NLATa7V1$wy9(EI>wV~_jok21z_m;)wYwlyC>}sriYDr&gMX0^Y86Ado z=-iKA0#Bu2ytK9lW)usN__>8aSo>(jiewoL!4`~h0J^i_C7W!RA31IM1y@<)I8%59If6@6$>9j%Imv=lfA|ye6ED=l^lWBH4mBdwYiFn7m z5JO*?)8za`s5agjC;#R9+l)S7=_eNwth~!D=&~WngN3+OL<04E=g_phV=24Wi2^T) z(SbEJpk3DqH;ja6g_kGRY3AVyslQmXD}uN&me~II272GtM5FUYsQ*V2M_-qv@JXI{ z?qC)!o_G%buG63o7oMYCo&p;oZcZapF5+!tVe*)-hMKyS*fh_KUA-FzOU1G=LtKeY z4Bmhbr`ze&HZ8jQ=Q47KLbN7~`K~WMOYLTMgr!jcK%>mtj9NX8 z6!BsRt$)WM-7Q4%tSs^h%%V-Rd-4BV+cR%*v|5n~2V%cMcuX>$jV?gA_8a5!+PMi~ zuDD0c1rscVX=k$)R(7gkr9>F|HLXUSkegiE#0)BQ5TipLEAWP-81?>6!2Ip}`E?n= z%Lg*JfK#ZAZ|f)0npVG?4BgbNX@M56?fYNB$O7`Xd%Z9=zw#zfYCKg6Gjg zX?eC=aFY_VH0gQYEh-E#N6ktl4ytV}Agud!O`Bjx;##AWl!&|gxI@(-z_cKC6G-jk)P zrZ@%3HGss+yYP8FzgD(XqFs+4&bf4s5`H+7aBDoi{&F3sysrnzwm0}Ma2mzFeT1fW z!*PFe8*2EkAm25qG$1QQOJsad<=9Wu2x$ZVV_BHCZ~}%^UdPYxKV#i|8< zrPwmE`e9BE9i8YSW^9Ci5T$O(HlR#3`Db+G;Y8Y8yH!@m8Z_M5V$ z-GW<~wSELPXW6k`eS^3|`#(tbb);y^dal~N5&Pm+^W5Z2?%S3c(5cu6sfqJpN$f?m z*p`Tk`lGP?zb!P@v=OJS*aA5?nZlQpVuxrAoVVlGWyxdMId=wijc9<6Nu6XGroiXk zKEm1f6g;?1nGW0x;VgU?kzDyr?pxI{#6Dq4Xi}$Zr$W)fj{5c zkog!d?&eqxoGV|0WA!xY^1~Lij+ud9ZuDT}?+5VBc0378dttAGBrTc!4hEvCFnDbP z*X;We22|tlr{rW5zk3uWChf!T!+~TcbO%O`5~W)yJX`NS0t8!cqN>L`u4iK-8upLC zvt5(u!#6eRjhTj`_VdYNxd>k{r2wvJZ%OTO8M;RB=fvC3s3hwVJWAKYjtS@Cx={oC z-DXQypVZSsm7R2O*agpu6_I)UWi&4HqhGwfm>zb&ugluA=h-Xpvv|L z8pmt}!>&hQY&Z^_kEo%vrw^=)IgWNC`3~41SNLeIzy<0Jftcw97?;HfHl@iz;U9mH zJTfHss(6`eXl(=4Kb73Ax20gY;}pvMvc_9)`3yT|!m?NST(z15w<&^W&W0DF@5--G z7;laTKe-9KC(YxO+!tb&QZ1KO*T_ z8_6xov_+?k(dd1?i<3Qe99tL1LiQLdaDO5PhRXB7Ebuj#C_NhGzH7mp(UM$cf+E~l zEDuUCOJQ;JS?-+dbhOdE9w?>iJSNLA76WVSmqMzqY&ecPe=1vZWO)o6r z*x`M!(MA*-rv}i(v16D}v?3+kUr$>P1Y+Ts_xOHsA>Mu=#*R)p%F(!R3VeE(PT#)^ zvuy3KEY^&yK20QDFI959n}gAY?=Yi@k)>KOeo?=Jl^Fpz?WPpDOWa1mes?%~Tbg-> zXi-nj13~zBRhsHGiL64B(fUp^3bsno__~#JVt*NKOnQk=%9c@bu@?OnQlh&ai`d`x zyXbs!4Beqcf{5(VXqsqBFPChjUDmHKx8nero*JTuvm%fx&*A1Ln!p7(vA0n_4lAF1E*A(%tx}JOE~Dio+~_Svn%%bKUvsEcEeCx@TF4RRz~+@>ByV z82cQDO~c5^AsqKf2*~f#BO0hPVO|YBsL0Qy>!0n!q|NhbM?)^Jm+8@`Dd-eHo04X)mvLE52PMLyBe?9sVy46JFyTK7$~%;-Aiyep$BEq~@Rr5WS+ zo}DYHVd(bq3EU|yq3k$Ql6;wpOHP=x)Aj1CxKM&r@0`c_bB92oU<1~6E3);Q50VM3 zMG?_t%Iybcb7vE+*k4N9Uf;%|Uy1nQ;7155cEyyD$vE9{GJV@3L?W#b@O;w-JUmSb z`+7=nTD32p34adFr72V^x0hxxD_CCU#s=PA4lgMkJbObaU?=RMr1@J4duSi>w4X3(LfO` z4N_7n4U+cy6rwVcvXdm5DoK&3lu`*TEp1d9+I#SQ|9<~^JUkw^<38uS-mmMro)^Y; zSLKY@o4oH_d-~WYG)22&ewFr)247pnGlL~=SZ2pZ#!undr<<_o#Y{-uKEO@+7TW&4 zB(#NN7*Zs$xnLZICx^h?R!JdMjN(os!#LQ=mdP+p{ZESvpN-)T#+tmQD22_QnJMZA z)u1rQig(3F(5?r8cwmvn`-?kqsplr#+SrqW>Z;j7bvFkojQPcxqo_L?%@-2&u;G1s zwiaB2l+6dwDP4~z-aaKV+&NJ9{6MRp{=~-ZIy~j#54t~m8!N5ainQ)$rI??md1yd1 zoDOH9=*1EK9csu~ey#Ye^9{O5uFw$dM8&KMu2Od3(5<7nQ`-+*aib@9^36qS#T&%D z&{B95Y+${bK?t6v&G~tsV0+d|QI(R(pEufxTv{sk8}$n})^z2XEpy3Zp{u~Rt8!_x z35@(q70(lbIJkBP+m<}y6-t-T{Yx(9Jxze|9B1T5PRHp_Ur;jS0C%1dO=?+6d~v*l z*g?C{FJ?6bcOuphT<)A79T8Nu0fUD};qdkisGK%cF(PFsrZ$FRLE1KM?GZt10^g!t zeYE0gjuZXY^9+*C+(gSaRmvQ_E!QgVdxX^e#g${QI^Q(uCREbo&@iJewePC|wobRh9X=do;Zs z*vJoVp2m6IQCPXc0g(ntv@JzVVJ*JH2L_n2L0|DX{NwoKtdls~Gn;MKMWU73c)oP9 z8q@mhr=tgr`H!YMw-L-o>y#*7XnGaZraAm(^+oa$9cY$~h2$jI&0RdYvvS{GQpxpb z{xiK9+xBR4ON$eq>$)E{OUH3H(W|h2#8dKjP~#f2-8i#88t(*e{nW5K_*wj#;$yzj zcl0EWW1G-u)fR_uRu zQUqzWFQcV~8+;KA!Mj$!^%iPMrz6s;}@UdSgc?14vnj5VuEvGHRC8*TApj|+x$ zOg$B6#+bmy+CZ`7r~|9@9Kwbxy7KXcZJ0jS5ML+S)8@B+=(_Nk@bjdT;ed{cStoM2 zfx}iX*p9(q{ z9)N1n050jOiUS7+BcW^pZCV#At=Z8R$Cp`PV{GK<1Hpk$PVLUB;FFI2~gQeR4 z^vN@SKO*%0k?ij@vYzLL+%l2H7FzzzA)$!4^+EU%A_N2KgXG|>f|3VhgrT+vdr^)kbW z;fH8cx))s@J)6>tf52<(8MGA;jQE&GAv_pBJnl-4iX-im_8^9nI%m+ ztc>xt?Rb4~5uTNqz-swe^jTz&9+h_VVxkkA#`cgdjckiS4JT-0>+4dlwJqpzY8IB5 zKSr_Pd<^}@$g}sOwdWS#?mJ}^mB!(I_I5Z7=*9aMZ6l8paoB%z7#0dHZu?3L3iH27 z_sYUC%-{^&-g$@?ObbV4NjX*xaN;7ttdvgl$C1~o?SOKcWXuU+65|DF!6euc%Z3iSB5 zhkl!7v(@sMcvr9%was~`9T~itV!P2+%BVOrbq+*lmyNVAs6}pC+JmpFZbbHl zEmFjag=l|ggtT|J8TVPxRUx}^T5kEr4{tqOIpn32{Cs+MxZWSH7@W`4eMl~E>kuJT zJ?Us$5%n37g1vCSusy4Jc11?}4m|vq6|OA5!fp7&{^m6l|9hB-h0%X$y~=t1Gw>azx9S9k`ImTp#&^8(du1!L ze1yl#jipncYk6qN>3LZmA~ElP3Ew{pN<&0P?GImDR!H%!w0}F=8tR&HmW?3)09PT17KV&KO z>J{DBuvsou%x*1twCgGzGU+5Ak*KiESg}MVA9q*w^1H9}GD0CY$kdcSEwz`7H%IjS z(xy#c^Xp4x{~7tq^9{Tx#BaN;q|{x$piO7VbjEs_PL-W}UADITgJu$acKRdtEOC%r z|Fn}n4cC;623?bp|YiaPKMn_B2x&{PDcsFL6J8t7iViZ%D$VSCPpmaK0;!L$7+2vvrcS}ASF zv*n<-nJD;I&$~?9vtng3?Od3Qsq2?Z<4Y&-y^&gqZmO519aGQYpwSZ=^7#P$Fi~TZ zUwhzjS8!ww@8W^G>+n`&G&H_-XLbK(Oq?1@9hCAhUHGY+?8QEJ<_Eg>>I;{dxbeCJ z7r+w^V^kl}-*dc5QXMjeH>|uRvd69X`0QK^?v#x=pA9)K-iaO7sq@8W3l-J3GLUda z&QD@`BeI(e>jhI(Q8kJq9{oT~^A*I#{f4J^H|jEb2ESKiQrTHwEQotSJN5{+)T=bw zw!05HS%1c4t!skWYYf-Kr}%oXh+B4Dq_hqL_=aXKMEwnI#0SjTr%rbdsqYDt^WyD;Rf? zOGfG=Z{II&&R-AJ385UeznYdx%_y(7#MHAoNcYTV{R5YAQZp4wyTkchXfb{Ls?U|{ z)#39kmx>IcDe=N8S~x5Tt#>-pvZ%Y{Q;|%ga@ tSeNX5ro>eDtM}+1M@g*yxuz* zo0aFnc=$MOWmHD%7HQ&iS*|n_PkKQs^AFaH4VgBqY&hEc!;`f zret4!hx|kj;f^lB;&;~~GQJnC>u!gc>tq~!Y)OZqO&v+Z>533anYa%W7>b0K&&cz?4)~c#*m!;$ zwmjD0F=s3}l^`p_wCjh6p=$1b}ooqjcy<0h%% z!SFI#S(Sy@>CSM`Nx;8^Fbo}PCK;L^#n{LDXpDOXZSL@z?t2Dc@TCX1eJce`Cfkvx zzf1VYw@~nd^ODh-Xz5Q;9JDWmqI`x18BD3gyiJ*;dZiuLpY8{9!Se3-ql~Uz1V*aEN#JbJPLZEW+H z@7d_E;f6Y_tM=x$4f6FxL;1~_X12=B$zK7KYwvv?8 z-9*2@P=z$GHS*&8v9$GhNP`R&PM=$-uiH-k@8uG9a=sv`H-5&Qw5Rk+=E0pJR*K#T z!TJ5KKL-tVLp;^-@Y=Tgc1JX2T=G!(eQm=Bzv`g<$PJw9qJG9i+Vle4mL!mcQe^e!->xAjaG27g(CUqSqeKmTaj~O8iu@% z;-P2nV_uJVzb5+q30V>k*S0qhON0Mt(~Ir)<5amwhp{MPK)#JB-16~6I`NG z2ETc?k>|Re)jfV;taCUfM&3v8KjHbc?~l!0!ZCgC6C`96!z8g6s_uQ@DSKSFzF`PI z@BIOK4?p8__!XoCneyfYxgprN9!YpaB@iPh{CWX(hJN_fE7C|(iy7l%5Q3Jo+2 z>Y0}O@@6SQ$44MHbswwNc_Fwu5v5m}P_SOS6Q0k&cK@-M67IkY1rI)=S(Rfel6dCT zc)T6hgmYP8P&|_1)%{|u@=6h!rY0*>6lYa^q<6`Y*fuNy8m$J<(kgAmv0lgUXtjh+ zPx^4jMZR1&?EoD=zg)1S#NN0?6-l2zh+d1!xPPU9N^`d&thGMh^6SLIT;B7dSFMo# z@hF}=P~!U1E_~7M0%qJP!KA=S{1Y6l=3P}8xz1cAb_I{#*^qPcGfY`2iELvB3@k5%!Ify--!__mty)eeYqrq0rnhX+<|7=8 z?j!q4A@^PK7KPKM3J;GOR=;nLZ_%^3pYl%Zy1N^dOHJ@pJj>gOU1h_mtvLMU9S&p% z;=_U?DAzuPk+t_FeteC6pX^79lQA}Gd-9VB3vk-IjY2Qz8Wz2agMMQiO%_?eUe01Z zdfS)RIzEKCU;!8mUxXd4yRzAdaNIlKipfKxXwzzU-e+|lBe$nhS!Oz##IC&QVkV#d zEmPcxNyIVNZR~Dg$YXzKutw5N1P>jl2<*F!J|4Zv8&aFO-HRmJv1l!aRG9FK&n~>a z{yE}vUD(i|3tyR-z(%4ca-#I&Wr`6mxo}kMj9V+Z-%)4HZBDF~po*M{ zH8gEuBo9mR;)2(w(EhWAB2KBTqOnIFUXGoCmDA7C_?X{#uc@zi6}VCKy;@-0sC8U( zbDY9(!2?`y*~5qDiC)0zMts~+4qN<#@0FeS;&K%~O}+8Gq@0r948_smLKg~n0Be_F zKu!o!C(Yweiwc3nbJTI|9aahG$p1E&^1`#FT((&3;vHHe_S+U**R>Qcm;MVy^{r`TNER=wf{j z{cmkX(E8TACuKi$hvZ>$^e$|3nSkw~<+$H}Hv(F>6FmrR6b@qcdFNY#|DMSZ@b)$- zIhNp}q6m?m;dp;$A_wLT=h^2*VA3#s_IKY*A9oLiMf!KlUbY;Mbmj`ZZ96XR?#TWA z#;{t4Y+UY@2)!)PF{rhdjI+)`t9}Ve3xn{kjT*b%u%x7NYzKuy1(R}KX1FvX2f=|BFIc97$ z!ty`h`YcoW&}T4T9y1!YPd?M1#8_Vb?;!Shhq3c-c*UP3Qx;Xm_;lt@)gQQ)h}|DDf*VXto7(?fK!TzJJD_ctoS zf5Zr{WhOU{t7F*~Q`Rr5;^Pl`^n0n%1I2T@DduV2;{iUZz~fPhKl7`2#`TA+JED=B z_w-i0Jz~Z4E1eWYBMx%y*y$WUx;^{UcTjZgRLWoN%IR0;P=%u44@;GGaOysvLmvNN zyHB67sr6x==R%5wf&CTf$MX66Z}D!NkjlP;gL%u`Z3>488vR;LZeSIdD<)T|V|#W9 zt_8j4duI=FT$c#$|7@3H_d9n*rmmB?KZI^PV>3+ph-+b^P+X!!-X9r)i{t(>(mN}X z&IWT=a}&k3oojepa{}kMSD>!jSYBN>mG_iH@qm^f_VufyUE@9YX0tBOlFE3}HGQ`9 z{D{gLGsU-zEFQgU9Qq9@RruMKa!*}3r=`wQ7%M08@0Q(oCEkUW`p;nRu|v^z`*elp z*OOctdmRyFD+D9wKc1w}R}34g%_ozb6($!N`BBtBYT`TGJF&MS*u6mExW`X1K|@P% zO>33HCVd+|j9tWiy$PmuXJB$WnT<>|ai%I&VdxgY#}r)^D>dZ`r3qhI(fu?pTfY*` zMoBb!pBvs5{lpE22|VMfFJ1pV7dh35WISXodR;y*Wmj}TUdTS0G%AKtiyUal3>jLz z6Mf2)!8eRGP@ysc*5^a9=ka5j8gT*#|E}TaarV-_PeW03;wAC~L+S2}U8qg&gk-O_ zuv(moP`51HlFJb;&Osi*_VARhQS8;N6zhEvvW|br=(7)XZMT^#%M)FICT7k9{7-bZMt4n)^3U^5iPge9#MRx}KD_xK~o?G@{VU7D%hofJ%@h z9WS_x*LIs=opnQ+vw98N|0*PVgJV>a)(n4>DBRt8jUp;LP@&6d8v3gppWWY{zgTZY zo6SaWax~+So7G__I*)e=|DWTqcI^E0Fn<2NBdOamW=ELt;+rFRWqB%GRFVY8{1oaR zouxOne(30}M_co?;kkJ(#`hXT7PIGZL1kO+9g+gK9jbzl-vc%cT`=>mEe~8A$MZHi zaphW1KJ>M-BEG{}v_7xK3CYvg;rK;-|1TMT$MxprXOHntF>8mp4`r(*Z4@p#4t%q; zkS8uS=G6CQ91~^1v2R76oM$Y%1$R}{kC}$u{|(|VuR{5(=2hadF^Zj0j;xcY$6@{Q zIsWSruK&6fOFwmC(?7q_@j^EK=r6;TdmFfYNF4q-)Zm@TG1k1jgTMHTbJ*)5JkDOt z2cx_=e#tym)?Cf&Pj2V^x?23u`Y%>G8}Qn=V%$VD*LNGCSg`yHws+L!VV6VrPtpKH zZ5YEAO=_I^;TS$^J18bDf5bhv8t}1>e!M-o4^|l{aT`_9srXloyS1LcF>dpChtC1N z@8zd(N(|+V?_9X%_h_za><6iTYwluHh}f+Ic=6m+UK4njdWxRC9&NAUwB0e-D7)~V zv15=ddM+b(J`+{jx2b!?9R1r?vHx{ zikKgVJE=uhOP)spDAeZySsN?!%0F3nzrCKG zuIh{sn{tdFG#mH2TVsXZ0?~z2jnI97?~}vQjfrpQnBiqKeQV1TmPbQAw-pPTKl&PG zQJUjU8mo9LZ;liE8WjVyf3b>w@9E8pa_#U#Th59ZThRS|5dvOr7Ad{s7(D-)q?BHW zr%6+gQL-D4^3TztlOij4`Hj4;?gCNoMETHnE5zQfkNj-AROz_EQMp&V1Ic@(!8zTN z-4jRQ(ffnAZQYAftVRnz{5#q)+lEaW)#Z<8ufo)zK5YC_nfhpl(MRn$c$Hv}`bCi# zw^tJzdWam3rxMl_bfw?5W;oI{moifOV@>IKO0-v{=>v{&+c}|#_b8A(iWFS%rffL6 zYU9$oDw=m@0rd{NhMuLn=$YWPnjBQ+IG>%cAM}g-Zd?%jaUDE)`i_=l@02ybofPd3 zV`7(wX!XPzj_zBqHfR#heV~OksXwXb{N3^k^YWz_kxN+7<}OqV5~cfhB1EP*pFgL@ zND)!_h`l6ysWA?izPnn=m+hs_QR>JO9ZJ8hhY5`}M7q1SlomQ$k!vd#Y&1PdZ33O8 z#mD3rTzrZ~s@cn`54GamOS47J+!k}cmZGQfW=tGfC>@UYE(?1sVPa+ujR;T|99|u? z%88Q(xQ^z5Dhg6d7=VV&%P@CMFHRG?=6kD?Z9RX@gU-?kc)B~4_nEa|M}0GX4rs*@ zL&_;i<26my7%%lU3X^2t#=t*!o#^k2W=jtRuh%rhvW!6-VXzc40zc5$50>=!r3+qs z&7hHQQfczE2Iw^nr*oqxV#SOFkc<)~^WWtZ;4>E`J>t-Pjxnm|MkC>V30jGs9Mgdd z_=10DY5(_XYBS~mx-{EMV_a;J@hy{A%$-P)p082YIf#raP2~@~XR=fO*A$o-N>Ub6*KG#)zRr$=FSo(P%6>53cnAiUO3AGFwDhe_ zIW-(NfJ)DB(lmGG@ttc(UsG_aG)2y2<6hC9`4Abt;k4J`ggCdlLh-w^&_A-sYlz^} zL^zBG3XWbyrHGs$E z%UI>#Oi%YsBVDVG98sK)XH)0X+J3fN=^u{zk5du&r7MQY@5l{)WO3sNXKb`fgZYYP zGz{NE&2ELz(8)yyv7cYzIS`$qQpLUciSmBjpptgl_~VcO$761As@6qg+F~(x{iKQG zXJTf8CfTlNLSV`|%?snyGxl^T1m+a7ZU7f09#>@WRYKDQHGg-IGrqiG85j1TL z7X9_41@^u0e11=88@45R-wf&71RZGKXpQSKV=6lJgM#c^i|3W-L^Cy^w|{!#;P)N$ zwNnqQ_!^6(hd_d(8O{df(Eh-+6gwz~Snoa7{ftLlQ6XVj4Ax#+NwX?uNRt~w(92V> zyFYfM_|2U;YK(%sg3?G~Wd-y42IK3H*0nZ|p!#=~~~=vRgS6nsW0wf}dTYXp1uX6}d+EKU65@R2zPJaszHno(MJPzBuzm zJdf9n#l^N0F(E#LV&2@L%{3w97Ste}KCX&}zbDW+Z61c3s|XJIB-9?Ag3Cr0v|VWH z^1EB4amyT#9#BTXPtQpYYDZz)KxL^|PmAMR22!5IM661CLt)jPxY}U`ZH#+?WxJ{c ziy@woItuFDx4zw7{o{SAsZ+?5TC4)eel&!vxN zm00hB;J^%9f-`YNSo_ykVRU`F)MN5F-cw}2XYT!wM|-Do>hb~Txl-(R{ZjCJHgUh; zr+9VJf-~yud13o(sQ%Z6)Z44^C)0A2H1(p^S%y4G=sVYr45g@$47eR?gk&Z<2Hze* z%F(AhH_eZ;8;A4L>`eGgOu!SfsTi`cgW{4_U!E8K1U{aLd~3h}$v3#W=v=tKdFFxm z_U{5kc5_iQ?$Y4;{n1eB?Fhq*adc1b6t=70Vvm0v`Q`ZuWWRqtZ#|hPGS1U*<<%9g z8tef3g|BdNY8jpRa}jsTcT-Y_F?>xc7FKyibpE;Mp-VeM;rZ(@^sg(NkG0U8F*&Rd zIhP-8Pmxh^3*TBYTFla0ut+tFbM^n>hKV-a9&{cj-Fw2|u%_ZuFQE@?)#k|ApJ?L3 z30ya_9C}0Man+ImBG)q+|51O~o>Hbi>oXCVe2}T_6#na$kA1%)I6O|9kCyzT`Nn(T z>#RZR4^@y$*c~iSO%ojj%)Qh%AYSVUTNo@ui^>7cS(XcZ*;HtiZlM3hh%Aef1`1mm z@XuFH{r+^qC9iRm@*$fR*k#JIcSnj2#$IAiX+)+eL#1|eTESsp0uq<&@yFSWZhI%< z&yD${;{JkCURz_^g0Hxm^+uj0m`#;#c`%!BQA*fRO}B-2(?;~WRTizrNS`FibN)+j zCQJj5dr56pRnk<^*Y@sP5JaH@X)JA#R%~-&#nOIQf6I}IraK^R-xmB0$f8p!gRs+c zF7^ekhyL)3WS4%7tgmE1b=L-z8ux;OauOH23(Ysg4Yz(vQql%nN}oOnmd@$0aOeO> zt6D6H&}5C{&nP~5BF2~5NGqH!Nc#Jq!qZROOU0#<`RjQ2iJU^xjl(ot%(}&@{V-Da zpN|RXxOuY$c7Ha2uIU`w_NktFCI(0&ZU0bha~k!Il0msyhE7E@q-v?@n>N1$QQRB||fP%;cGr0-v|X!0EmemQkB-mTt7s}8ni66Z_f zqI0C5I0z2i8j$0D2m_l`?lQQkY;|r}}J>UQTRJ6C0jUuVq14&~24;W5-@95Z8X_s(e~ESY!bLZc9B{Mw5kY zg*3~`MryCChk@fJpi#3cl^)l{iteZBQ;4Hfe{li^yb7nX;9y$VvmNX*3h9lFJw3Ep zffwfI$@=tNX>!pBN%vs}-E&+={a+|iN>dDE*1PD1@N$}K-lhcsAEi_~6>7>f$E$uK zr!s#9?KX-h&lTh8()oMzYqDVf?>I|dPL>$?GnKMF7m?E@Q#79Tm!wVG>9O}as#4LW z2w4(N{Cz}sE|^F&Q$)_K^p9lXkwB?}(~w<|O=Ocrv0+>2qslC-=@g7vD!WNrql%sc z%8~i9PAWD3PTehZsHk&-)VaHYdaa)=g};9+EpE=CzEGjLLMJ^p_r2s^)eAKnN7M3- z;(zc>9hGgiBUt%`G;Z}W1aB}y?Ep`VJ=%t(V+W;|0a3VhsFpani8lJi2yf*%`f~e) zRIpJ-5BFwL?3))<`XQ8J(iPNbaY-_BnkS{)w-Nn3sl*F6QqG-`)VuF+di}YUCS1QJ zZH`aIs8yXQ?_Q16_OTI+N43V?Y-_yGzD(;^DQMJJ;r%*Oj)+b6h)OSlx6B_CcTVSX zI|pJ|fZ$(*g<|=hb~v-{9YwwmLDQ*^c_w{Zm@7|%Smlw z(BXU}Rvnv()|E2_Tgi<|9K+Z)Y8boL52M{Hrg7Kj+3<|rjS2PTXtQt!+VxMzkDiGr zFx`e)F>fZA@1?z~4xz8^HhS%QmLAoc^3o5tfvcwMC_H}VUmD@_{;1%`FG9?3C-(W- ziqm6rF;+1M-4{h+%^XX76xzV|IDdX4?yp}~sTeWa07sSykL9uFLbnWr`pXv-u=fUQ z2h8K?Q8O@Q?n;DzccuP|YMMy`j71#W-Mm9FYevOC3%N5BK4=I56NIwRQ6qzT@*0quhljoiNAsu_LL~ zawQJY>xaH0E6~nagImyxb^D34*t)MYET$(84D{fcZs$dBYANQ$zJSMH6`rdp`T@29 z3oojpY@EnNby|S`CaK7;`EdMzSZq;U%%99xvZ$ITEGJc_DikA5SfR{z7@qNh&_$Nh_w^ zr=RbKNl)T;Ng+quu_E5rwWh-zwa9MxV5+gHBF_?C`853?bQ^G*iV{c5qbj@5p0qGpS946Ny?U6S z)ShICAynEboJM-Rr`?@rkXKSWnsaP1ROWue>&gpc9=MyfG#-&D9W9r}Pu)NP73ZkC zp$|EqEudu%)9@klpftGkclj9qQyL9izXet_#K<9=Il%|Fn(d=S(Nh;^jx857+7ylzao{G!b zD$=IFAM%4?E2N`Vl``koM`^yVyS&|kEO>r@O{Yta%O{BahSoY;Iy0`E9@lu_SJ@^C zZhwkSg{tt5pDVa)kOz6?Xk%+ZTg1r{p@r2_?=3rV+>SBr%QVvOlugqU>nQhl5pE2Y z*y(;FeeN*@8xCH_y>l^i+~+h#ZT-nb2P&kG*@7#vBL~B`U6-6X_hpMAouC-H8nTi5 zuu*t}gWHZnmo+!gvb_dIsoF?a^8hmwn;k5C1+}rnyzP}CQr$b`++r-H*KO?c{+XOOSuT0ZT z?YN--MBGrhO}X0DtS`E+y69_SL+R%uHIADjI+hv+ zV%uvOXRX!4fsY#KIVXf}%5~wf@HFMs=fQTY3C6T!O0J7<(&Bw5NF}x#HoJyW#)1%X z657o2)0gpWizhj_mvGnBL-9QF7bX8O=HY!-Bl~m$oyZynrvM-7bL}8I257SG7cac) za+`W>Xve3Ic0tFjD!ka{G?lzLkMtn}@nP9KX`A5uzE~5+1_Rajyc7=Te1P7X{UV1x zm=0w0!D}v*nrAlAK>c|zdLAHEoEpYS3o}F?t}Qn#%*KE?O?Dijjj)l6+53;k%}5e^ z#i+2xy*0diaTq@I*XA=1bD$eE7(0XpnDz!-J>flio?HT-|DIr<&}g5}_vRd{;fh%= zM0T)#981-jocrdo=%f6I6+eb4${yUKIlo2MT+2D%SuhA@yYVmAS-h!g z3L7V6VxGnfzPC#72y)(Iw)##y%?8^nyNTU1Tw!{ywW3$&KwfJc%Id}DJbc?w?wQ$+ zOX4lL;aEprJ8B`v4C>AQBx_b4HQ0{K<-+;qzeHDD2NcA{AYkWx{<^4`J7lzC)qi98 zmuCy#ooC7o-A#C5@iEBE)fEG-ZQ=9d_epOS!%c9T2 z{bMmQL-*4CThrLQO;7I0dYIa|x1!>EAnT}};}<_)@*!^v{w67NtjR1a@(~Oj??Tug zj6m7K7cgBt}dkH&2Ok%*(SuFs)j*g5<0Yw zK|8}xIL6H+kLewtn--081C=@OT0iO*o`Aik&bZsRQHoX5<>#LYptK_tHNsDqI_@f7 zuN*~HJ%z`tR?J?GkErMEtCT;j4bM6>h8hFAlN7Wcsnsc1wECEsQF~Eygf<%{zNPms zyCJV#40;R@d;={#vi0mmW42nL-R4XRi8aRp(kJQz%3G;>aB$<3inBghR zGZCyVbaXD5hi)%%1v4ITLcke(4*%$~#03m923+P zH{_;1F?e@#8%_VuhMF7K@sB}Q$g1=`u1&~C)h;u9|6D0W&+SEKJK`xWJ(7I>{i9Za z{kUWG1G*6FfQLO-;llkHsQmFm@>FWeC$4Wr)z~-+PhW|b(K=|i`Za2lGI>9Dls-(G zg0jqZgO9z< z!7|;2oRjRv^CynOwfs-=qWj4hc=ZH!D9Nc0SzyV5{x~4^Vpds%6H}Jr>@w^mk*_D4`}IySnlGt2w~A@=tgxdE)2<*4jGAFtW+QL_o;=;G;e&JA(-gJ zg^*?p=41K3q`u)5DJ{37^LvSwbXtQM|3bN5r6ZT_Ka1u5U`y@q2v6BVTMt>__XP>mAE->1-*^b zKy-H{`Y&w=U8~${ieSwZhv-@7pax&CF?7 zT(X^v#O(aTX&)B92%*?wEwVInmOWc-D8H|N7Sw7oGDZ!NaC-*=j%%^A(-e8Y@O@~z z>j@bhc}$Pj=SxjXw^IF%19W!KeDXLjQwnIOCWV*|CI5GuDE7)mn%S>e>ap;r{F!Ac zqA!RUyS83>tvLq6mrNyhyT{~{xC_DAQxN^BRKCo!m_B?CAn#2rbgkPY>~6`RupYnU zZ=CnyUB+N(N6%EcXe0PUVGB{X&K9fom-SVC9YznHFQu}h6(SE*LH)v=abe^QnjjTO zi{{7C{m)jC(#IJ2U`nQhX``f1Z?57;{b6M7{7FCUqtN|rcld|;(zM)kp}C)zM>V_C za?L#OgH}Ama*1^KO_ua>YoZi&Ngta2IkJrgo9KS8F4QCHnDlXUkxZ%KhN5LXH zM|Ba4>EYw8wD{6$x{%bBz6TG*$c)c$9Z@Skc)vI9G#sap8Wgh-pq$GVW+b-P* zwM6#Gt9~7qY3=D5)N6*1bY$5Vy5C~MABNu`txv@?@8($f zqYAmyc4;e0)$^j9`$mFmJRhoC7a`)oXDMZbI&BGDDerpDUUoIC6+W9ClX4p4C25cj zT&kbY$<1%1pV}7KXEd9fCOb<>ZH=Vb<(;LhcFRfSG1HK`wRF4bq`YR_5L(sqfi&cx zGcDE*m-}BflrM73pi|@gKqWn;?j6l|s`YkBz28dOG(Cn^*6yU4QE^h(*nNVtcT<|8 zDR!-k)8PKNkMy9`9eGK2XN;&BP4hZ*!Gr8tx!3+*)b{Q!8vMuA_RuhON_J?^V=E@Y zs`p}QEzT}+ZDvzVgQjHf8bYm9edRar-;?(W8%{qiEtSuU`vK#-!|B7TLfX4i6(icj z(Pg!X^2evj$UI>q0#5D2k6%X-7+56sX7g#T@L<|qbVX5FJ9xJ0Lx-~8W9)HF=sdT; z(QbyYxcwOxYfRu-siinsS%$Bvo9NB*A9y-hNz&M8$jJ^}742WB(hm1o=-8nZ1*G;M z{|$rrfbkkA?>#O$=4bHZI(2crZIO)jjOQl_;_UFQGo3pZ46DaCpgqKbJxA5iV23Oo zU~I+~LvNvfLo&2Kq$9o4CGxbgLBJA4t9zxwd8f+@W6*Da{bO|2`A5-uf^#q>7gsm5NI^}4zgeQrA18{*%k?d*&CNzxc?3RREhWA7 zPbK&DOF8q~4c^dyG_NZ@i>x++ZQybPe+OFdqwb~9p0JEHPIqEidpnxB(UQ&GE@M#N zBb;_lbZC_(iJjI%?)|2bCaGET;>exU*W(!8-wcP=W6>oSGn0ER7=+SYH?U}+v$*bC zsMX%?T;6nn4-K5hn`Uff?Zv)=$1ZvV9|=$6s4Z;wd@|=8kAvRUbes~|6D{Wz+$qD9 zhrIFT-8=5{ACV_+Tv?!)!r9zeiszVNn>hPjEpGd6|P z1$iX$lF4E&RtTMOzy)Z$cH^I;Zn1ZlSguHb!bNl-JvwX0!`p3TukuhV9Tv)svKHRE zM08+h_hXCcVLaKigCaF8id(+VVaLf2`A7907>34hgl{-+`X*-z+0JGb!{DD~ z&(&w^kf@%`Q4OK&-TN8(&V0oqHCnNr@@4YO8==^eSin(j)mZtEqzKr#=YI^HcQ}@B z6vva2kr}ch$_(#w&UwsKD5Xs)q6ksZ)R2aeC?um4A|e?nqfkj{k))KL5lvJ|Dw-O< z`)}99<-Okbz3=Co@Avbe$5)f+V9ODfxwwcXlUML_o#yd}-<8p-n(w6b$&ow}WJe9X^cIFMP&Z7#IP*Uvs0@r&ELGG6nh+Alb2gB-c*?-D# zC}1q6y?hI!Up9lUZ6!Cq^EL=gQpHSHJ*fXy2>OL@VfopqxT)wdek)%9KgL{#kK)$2 z(Pb=T#&MYLzJMNmJ<8qgzJykzoiOazeD2`KR=o1!7%1e8!bdY%7e_A=+qboYZ?GqJ zOmoI7>{&S5qK>QGYme_O>fv?ncdm1rG@Xml#wBUYG2Se|`;+fO(c+8nH?$Xo7%$mj zY6LQ%5$2U&0ri2|=(Ix&1v?+%x8A=vbUz0sUXH`}`B^ZF3*}zqCSbE~hct{sQ*>5JOoRz}O+cV{_Eulw&`{2r{|T$!fUt ztP*~8JHXw2(1;zjsrWgg86}VGz{S%R;}qRmsIDx-0JBgwv$UZb$U1$0qa}i<2A|%FH z+jnpcH4Y22Dop_Q#&bDI8?vmO%zBt-AVv}Ut5N*PNb=hkMiD=H(fVWr#*`UQEn@>D zKJ-8><5(Q*a3QnE5p+)e8kj8nM^>e}6utB`oD*ut^kzHaAqIS3PN(|mtb6`%JB?Gg z#e6~supfXFHD;4%q#O-}dh)hMKcb!ET$&xY5KLwNL1MuZe7ePp_QtXd$m$5v3h<}g zm@&9!iZ=}>c5s{CJz{q^J9>PV%_2T3faGRH%8pNuuY0ox zA6`Fz`x<2UHg+}%-mXW3IYxMRiXs*(n32XcN&YX}Ir?1)$5lP4lvQyT_xOuZ$!1Ba zO%G%J@A*dfa+6 z9uGI$K!D#<5UQ2K>pwd1<~&En5?zjy7n{=t`!<|mDMX2`N71$KK3ZHKgJ)7aaWBgc zy1FWmWkdwbj(&<`uTQ7U2aDi#K_a#OI*n?E*|^@3?Y8dS#&x4q(YS6JuFo;RhJXa#}BA#7N88ap*=am1|sRK-`*a^nuDvIbHv+2ir- zsTg1rfpc|6Q>LyYoSNSU#$`RQpj{r@oY&ym{vBXA{ykK4SFB&@=_PZrWuVB8Nck;ELp16b!Y5dGfGL3qg8^Z=+SfqEc_I4|H^gb zo|TCsri{h=m&MTJ&!N-+-b9mRHh)*S)`0lGN&ZXCBv z=L@VjT4S=zR-Uvb@?4ydFQk;a!-okQAf)X!zS$wktN-<-*<0MOK2Z(VONro@JNwXZ z=|_s%70tOVXoUqQj$<JePwKE?=E^&p+kf4JN+Hu&Rk4t(6Th#YTf;M9w^ z@u9XH{r%g6CKH8oPqvvR;7K3w@2`F{&jJ^a`?} z>T@T4_lSY{LizAk@`zyG${bV(mc)_W8l++U8%8(nfn%2h@o|ipZI720 z4pNBlIgJ#`pg@*<&=jAp_9kCd;BokuMsHfIKqFbIQrx*_*^~~ z=SP0#?j1B>o&XK}+kF}zemo6_6qlfc@p;^NISCxpzCq@$VlY%Y4)29*;j;EBDENw~ zP|Z4hEjI8uu9p+ulMAc0l{jVVP3EJi&tslTTwYYoje2AUFXq5?kBX% zyFlZg(df{Z13Jl%QLQ8mpRbWc{evd3ebRocoKwnagqq;P)_nNBsEf<`?MwRVHW=vf z5SUmUmt+=mrm047bSvwbxB0>3Uux{!*TdO;jPJy981GdpaYKL_D%q>zj}=F`uUs}P zZJY=zHM6n2{t^oHKNVocRc?NF0qEC1=2FfwUg;C&cAOQ67mu`X4|bm7+Lu0u!$N!T zrQ>2)I=UQQW=LRC%N+cZstKLR9$;0aNBJlJLQ;<&I$g*^OV&qRd6w}iP6Yu6;qbC@ z1%7Q7#r-v<#vz+TM+>3%>rSPZsF#6W*j^6RKVZjK7SQ7I31UkJoqAu}jL@dhkuwxRo1 z7V)bxJwfC87^a~~W8NGSXxVa$*7}{ra;;W0NeidMZyV|LFLm@!T1k%YWGHVdVpzIA zex9d5r4yJ3B55&tnm3Tl*JU&#!-76c_<%}R|6mgr#`w3M^nB%HGW|83)V?gGtug;F zXt@qWcC&dqo1wec&*j4chVZ)KGOFZMFz07K?8yI#9{EJ!%WmVo!D5;|!GIpbuf^X_ z&B@$)G=APJLan3Z$kL<{zw(SloO}b*Kj@SH&PZ}qVV%dl`4}`UgKQeRptahBUZ~{b zVwZZnc3zWCSA~J3?mJwrWsVIYlPEh=gHpCE!o|g>NZFNjEpIFa$tBACXa^x0aC`z9 z;y=mfT`k)5HsdT&z$KGj!YbXbB&FIx7aGH;s-CC1O4k28W=3J`|2zL?2!Ex;();&Q zDgEPktl9!3l$$~qazD_-3(2JM<`X7}T%h^&VW@DznF5{efTocl^9K&2^x$t0dV7N= zE`5Q8qUWe~TQyB5wJ3gB#(Yj+WBn@PzOPxb$_K zz%2S19?lQ}=k7kvvKd6X$K-7#+*t1!M)b5tRMQI7n zVeuvI%g{a$$kxI8Ck+_BeJ3oaSc3AtX+RtbBFhrE?!#;s7^n?D8e4Gnguh&3mOHnp z;WFIRkmnv&UgZ>H>o_yF3_RmUDq*wu&PxGQkr zmL60a=VOz&5gxpq35LH*K`E`{j&*Yq9szDkCjbITxZy*=Js)Xojm z_(O%xdBOMRb)0ofg`l?8lo||*1@>npxDoj)Anu+te0HwpdNUj`9TK!9N1&-mq{){UBlv7B19~3Y(YAt}6+;R5EvO1EvQCyz~RO;PHyu=7}pz4-S%R*vMmI%eL_*e-51|XX$7%qRj>>0!b9-Jq0B5$ zo)8S`-|Ep%YA$NUHpAD4UQ|+Y5YDz1gZ=GlL2JP`u1We9PH{-b2h7+QFXO%)tVPyZH&qTUkziTL_v@*~GbAsx&RxWQmIg zY&n|=UGRMA22_}+k7dStSRSgy^s}QVUg;SPVeFaDYwjd`%zScc|756%I>}h4`h&~yg|ZNFFIM6|sb$dVS_J7^)iE;hKXfvl0f(h*Xr-n;&X8Y+ zt{X>SU+5Bu?|lM0Gb+%~yb?NaIX>Jr6B8yh;w>q{I>n=;xg<{z^Slg0B2;NWdp)L| zsfDKWr&P2rn=3eT4$X&dqo&qRQ}f1!G(-0dJnd&Z?VB4=T>m`eNXeiRFf|J0HC_u;w#hg!naoM0Yeps>)zlMIt z2=0zfw zMdCu+4LI?{9hhtS1t%@qKxILP@!n2L?3r7Fi}eLGqt1$)7cIrKX(-L>xMGWanC z-!4?e`K(7(|6>LARV~7{8ZYq8QN|y8!x;O26pEGJ!)G3!G0fyTYK6T+v&-G6t@j_e zhRnw_{u+E%?tzk-Tk!DWbnGePNk=~om91w|NX1j^nY;(fPi{xuJQ1+>eS~w^%oMFB zqFQMlUb}3;h0Cv|?<4QSZL3BsOu39LwruY^vlcpLwW8PULEM_+OCQ6x;jO+Mc>BBp z${K9J_3BgLg=Ztasx(EJE$5-)v;o%5l}5uJ8G70sNr89eFp+gmFN@#6pF$BBxAi_Q zQk3L*|1Pfd;8rrz;i>spJ6GeKK=SN9qyMcG2cM``Z@9GP3ZAlQ1PY*r2`qBK&0+MgN-o>DQ63_`$^o z2eTV-^vCsB?R|s(m1oiI!T)gHdVSh8A{8c$nFo38`>AN)D#o;_V!&f5{_S}`@?5kU ze}xI7Q{58A7Bt0H**fa%7{DCqT6i%apt-5%XmoWmhBs%>&6hK=_GSvkX@o(T^lDuC z)fn%}8PV!u=H_h~;M`h7F-r6S3?22xpAD>A2Pa^ss5_Yy6<~kT9FUf{K$DKzVzkS4 zd^vjwC58ULc|Ps%M6e0(8O}vRoy+7Qu0nAWFJO)?%Wm&pPcgY{J~MVKy;*65HQ6J` zCGReN2~vfYIq|rwHJ*yo@+dc}4g+qvlJ(s|JiAQ^Z6AiBrqm=5iFU`SDyK2X{SwR) zOC=Wi!q1{@G_Q*FsnsGVvcd;z**xSc`&p;Pygm{%!-=BWka zj%!Vr@6tw>o%_jpjsdl#-lesR+NoIO1Ic~A#t(dxpx%#BBpWZsAJi^JqbmtyFjCR% zeNP77-{8oPS(Zu5a`RzD+hu-8B7+R#I%tq>jc4Am;iLbGP~v1qzI?Ek#Pira@3IG` z?){JI)$(Yf%P@|&Y$Y$oTpD?C8ZYg!iR_mI(Yc?AbR)ToM*a-slOJ@@x@>2apl z&+RB8q!xALzLUD16kjyQgW~r@lFGJr+9TdWwmwmOU7I?eAss`1j%Lx){e9SW=M<$c zR-?Mr?eyn*DczBDL*8!$4b4%Z6@JlFv2p@cud*WET8D42n@Q%3r+C6Vj6W_T$-jTD zO}vFWKQphHDlCrBNNyK>zqJ{2<$v?{iXKtR=mOTAQsh@?jpoNVekGUlVtkQA1v*

6z>OaqXnI{546k>`7TH9! znXnaRUY`j@AM-%P*dEVi--e9?sqparNi3tg__k1;yRzY>X-t_e?l~R>X%CY?b?#HV zG1Us|A9-@s=Y6SS*+W?I>6xjAT_=vzR)@N*OIT)Vj!(my!0qDz6b}^PN^{0+5BUhn zW70U2*eZO?SnRsa_u=``ZTKi=6^M-~N9VpOT%;L*pY0yQ5sNtNSh_P9rtr%?jf)jU?LlIXwG9RY_5L7R)_&W`?Zr0)EV*~J4W-rYf?1nvU zXF=$37UoL_bN!_uaPpQomE1T3)?)0;%lV9hq7_)!{uqs>E77QA=2&Xj`R_3s@w_snLDT6X}-v*b~FSt<%ImxEP-$LKCQn^Is$0Zu6h49L#y^JJQ+vVhvocA9=>yD-#j2DMuzGqG z1hMS2e)4L8l9Yf<3w{fd{R;58`wDz9JQC*>*@5)$8&K-5jxm?d;{)sMT={`7Fyqq@ zq{~Hvg-fj91k1jTT-*qHFV1np``uyg@0BogHXF~`FQt|#7vNlp6qZza;EjQCVA;16 z#e8GvRNgl3-;x28WwQg13wGQ+-VDd6N#XT9akyWX(DuwWTqhI`?*qSMz19{C=N?0% znHj8Gau$8<*Wuhl)42WlXW89PfD3ezxPz?|Ff(NV_D2Z8&WQ!JVz3qs84}>wQa~s!g5Q)t}jFIVhj~jn)9WFR(feBm`c6i1^+)fT7 zr;Nd%Pb#1!8VK!KJGrMhau{t`0Pk@rZWg`()86d@{n9oR-L)Dwjn#mK>t;}q?@XM? zSgPTlEa{S3A|8L#$>HLW7?dpzZ!|yQTSu0ilkvtQZ6CNr_2=>HXG5Qa3^A%L91DqK#X7&=Rv(u^v`kDmRk(DXLZk za3@pRQL6eQTq>`GQ7U10RY4e6=&Zvd?W0lSsU>zW7MgrTJDMbw((PTH;Ir2OV_s~* zr1S$=6`KOf_H?1inkD$=h%p{=>xc4r1FZM-3V$y9f(KHbaFJf8F!bmXTy^3n2!;2c z_2xBW+#qd)x#lJ2ZtHct3Qz6%U=vMYT<_0JT23 z;9KcJ++gVghVmMyEVGy**zD!Ar!+1(s!KnzjcDkj9vSy9r0nuod^*91w51P#tHn8# zH)w@4ti|Pm>u8d@pF3Eng!c=cfsVU0o{Y*v=r{t^a*>okRVcU65)SPmrZOYxd$SWxb@&H!0ZWt-x0?U|`K<0^ZtvJVTyIgpuT{OI6Cq=w*QF&&Gt>8KVmITK9q`_n*~PMTF~D(33?Pf7JGHr z491FwYcCD)RNXxsV>lC|ru>3W9w`_NLyt8GBywMa|^pcjTjT^fgG^@+8XqG5#KIMb<8wZ)!?kZln9}Bx$4`9+{ zVfeLnJPI2#ex~SYtofq>-2*MKNrtCKa%NbElQGg-3=j7!kzL~ku#7y7&#o!s(MSpO z9HW3rE4Fe&_X61LZ6_EVJc-pe{qWGtQ*fr&h|JUju)k;&Oj@>^49F1;y6oV=x?^Nq zaTw<+mw>*L1SWr52E3XL$<7L(aqKyN>pU&2bkv|%ZzrQaW2oj`k3q2{L()iRJE;vbm>zt80r?v?lHisOjol_mA>x3e+#M)&MliNc+>UD<<>7n1 zCnZX$qxQ#qxVq~G6y+WP=M&u&ymc`@d9N33@oOY<$i(F%^(d#i3CHIArOk#TVF$aH zziODrTTZaV3(D^3i1E}nqL5zQ5~kIwi&5N5fod3karugIi#mfoRY)yfikJp1r(I^EX@3PURaET9?Xu_i0mCn;UA4oW`^S z+i-4@6>n3QOFy?ShlrDfr05mJ7k{bemdB*g$3y?HTs@Zl+)YBAM13mtccsKV2e5!; z8lq>8#@SEu(Kb;A?+lD5%N|?oR-J`Myo*Sn&DE{pTUN*Cy z!h`Z*^|Am=FczY;?gf-y+)AD2wJG?GJD7x9@HU>OAfiH@xtA=+qI5D}(sP-NG_$xm zZ4tKjU4*ViQM}c`GMXZHmHj-OZXIjGKUsgUVdWjrS5btV;)QhDviq={+;U zUZqs*WBs0;A2w5mo;J$LT4Q+m72G0Sgm?8Gg7EBvxNyQ@998fKiX4xFAT$h3KW@Q; ztt`h79ZUNyv+>4o7wSb+;wGOGXnPfaiE|V2Zf`Og`zE1>&U3t(7=}I#SCIHy=(o&@ z8vEnuc83_I?kL3A)j6;xY6j%8pPfzb!`HL)@phsuZPodRUExRIZ$vl-M{;oG{A^r* zq7<7`)6nj_7|ss62=~9Mkie2CGyViNTuX$@^=h=<#~HMZs&W0$FL)oCipHrI@$(EZ zXw#I!MJx58@Z4tnZHm~#xVg0oKX7xF3eGrnfvXMjrykZH6iKxK?}Zyk%W4B22r)t9 z{C4O%FcrQH@1!M#<7rnxGmiAg!?D&Q$dVdyLR%BgeS8RiWLVL(qfzMRz8_>X*I{Yf zS3FiXgH{HMkiKFb>^4!RV{>~!r7joOu={^)Xbm1=-QpFp-CXk@F=$yhp3NUG3hHVUv3v&WlW3_3?!Io~;%(+* z$E_0X@K6+X1s;S2lSRN-`ykE0xtN?Uk_O*;MS95C`434YX|JP-6T(?zWc!)=oMM7c4u$X+PuSmQBD7)@xDf z=~CLPIu^L=0ylJn-90V^q40@PI4%&;6M0pMi1LcwBMxDA+O(#+hJ6od0+;4vj`!XZsxO)4b4Q#1DbN zZ3B#)cnn1cN7BmfNHkggo2&6iK>zw$&Sy{@8x#_`-IGJ$TqU8yGfB>10&JK1Z&_AiC`M@$_5<>hx^aJ zf&O+08vMSP6dnCY{E`X|yL-^yY!hlpT8?{|BlXhx5b_I}%69x`v1fY+^HYuI{0wwy zzvd%4TXi0vk4nRrS8jqw^;k6RbS1|s3oHy!WgT=Oev;NC{-`|Th??$4?(7k`sB4L> zJ1ls&GeCJW5;64J5gPx@it+G{lZDh(TK}j3BgqN&M>WE9Un{VzF~xf}l9cK796w|n zfIX)Xo~*5en#k=CdrT5@(sMwPTmhZy8^ZU-6GRm$_ny^+X!j7t9zZUbub4M{sA1nPrOe z(6%=keg9+3lkd#okn2HNq9gbfi$tl*iz6Q`Vfwzi1eF)4l2@=cFPGKKrL822 zD`bpGXUu%u7(A6au1WDO&pat8Z5`!V+(t9iVoHBm1KW24)tqU-mr>2w*dR&snr6e8 z;#L%zL|E0JMZE_{Q@gedDs0cEGh3@rK6nY-Zyu)AyIWA=Y&|xQm*7v!2GHIA4&%={ z4jX@mVy0p~HJ5)R=cI57zxWTU%~-ZIT!+kOOrZPr>U6`afqXkx(U)B*@F_-z?CUMb z_MIZ1b?FSPiP=Z_op-6C>=eFUGM|omuZ0n<-I%5F3lq}5K=?}u-sZ|;#)>*dl~u*G z&}q0sETMBKj<0$cXHVoNE*Mb`dqqcJgx4i#Q9lFcx2ltFnlGNJ zJOa<8ec{Yz4tstj&{X?OOgX8GZOVgm?Q#wT>^VX=;*#M^TNRS)G0yBuK7E+1$474R zha{66bmMjD@>@rG-}(e}>!UFbexL($MDH{y0P_~4eJ5XV&5WsPY;|0qkiQ#*cTB*U zjF0~#=`x-eWsN76h12RrY4UqH1B|>S=(mk4iN)Q5V|J0)=psqu-OqBqxiP46I~Qvd z^_TrhR0aOz7Rg9>Vn@%Hut>U zN!jDa!ZmXi&N}g4FuXyAPIyfQV74j`kcs zMY`3-VBdBOtqYcd^CM>*Kj|EN-?{(_XI%z;Ss|4FEyreDiSWp+h;zKeyvr-|u)*Od zXL5Bq1WY*#eh>E0`bk8;S)b>3{8M(%F~i_(Q}M2FC0uGhM4dlI!1D$5^ls%J{LwcG zmOXOBJwr!O_4^TgQN*&M_v}&Cs-DfChA_3@J^XA>Vz?e(C?4O1VhyUear%Fp$QK1# zz9A9SDgqv46!lV&1;l}<;sN-dcQ{R4ujZz(?Dvq>i*BdzXT@K7=v~oF$U!mP6hMX>y z;o#LO(0%Mj8Lwi-?powHSN6k{$ZR}66vAH}hJqc!TyxB@f97@uEyJGzePM5q3%sCGk$F5n~hecA=D z9_odrt!Gg@CLW)y{l^tfc?1sGZ_r_cCsZGriTfrfgVF2?%&y_E>U1GD>!l^meclG4 ztJhHi%V7I1M0z6k6-(x&fso%LfrPsuh&O(N!~gX|M}9txy|tSZmaoT2X9jSxMLC|k zFGq9#i^aJs3}{$*0iF^PqTzT&db#^5UGxO3U-ll~PR>D3spWWS+F5A-G@INLk77g5 zQuLj728E%RWt!KJizD!HhaX^Z-Xu!8%i6HeWt9@O;2^ey}@d9J+l$TWtbm?Z^qp|6|h+ICN5N+ zjV%>wRCqfFZF5#)MtdU7;3Vk%@iUOJMvdQQGnRSVi}1?a9{SYFUeoVhST}~{LbvN- z+CMqIC!?C!D2$v5(VEyy+@@7PbEFK2Ur`NHI%Fv5X&4>ZDZzWF zX49lDXL63pC;9FejQ+r!uMNqt&955e6IAKd29}dJ^_unFN0IN#)3mTIfp!VmQ0f#Z zx?eYym#Z(P-uqI#kY6szIEV3F^5S$;CyBh(j*?sW1H9i?gOC2aWqYs!(okPZhgt8w za39BSxGKk=Q@YD%kn+_i{)BQP?%^Z& z_rZp|myQ^}^}kQa15BAD)Y#nHQtY`T6|iZ?#Hn7n(`DfGW;-s>yz zT^7svuvMk>@PaAddhQV&eOt)OX=6ZqtUb2RJX3mVONm>sLU zL-J0C=<5Z0I-aCQrIAteDL|30n)HGUoxOR*6@7g2!ZU0ZGDO!`A3%5C#Z+`JkiQp@ z#X30a==`iUa?4NQS6<%DKT2yPzoZ5_m#e}*F!+qpE6V7;;$!MKv4(oXo|EMCKs@nn zKXYA}F_!9Gat`RBXA4R&{-FUc?&oB;2-&PkLLxcZ7}P?~gI%eV>){<~2fmiPaLCUlL9-8gKZlbMCxjn-qPp>nG2O zP`V-UlV4zagugnZ$7gXtOa-wRCmfyy*0XKYAoMdx8}8jp&oaVTy{2Vr=?@^xo+z4yD8$RA( ziVF61f`P*U0vI(JCa=6kg>~`Fml}$G5fyZyf2AP(uM5ew`r?-4fB4Xv7{hRYoT4Z4 zjcf*6KV1y8MoLr4KL^_O%MqiNj>Do!wzNQ|8|CIOXCJ#a-VompzuQHqP5U8m&lBMJ z7foK;F$DkYUL#P~*g*%Pmr>r^zgQ!*36yL1l8o3M%8p9GJ_nrSGRQwS4yJ8jImx(V*fFpR9x*a@^31H)bz($exnc*aDE>#M#?H7XH;gI6MOTFx+vo9>|pJ`2fJFj6ok zFc71*F(z!7Hh)XH43~WSLN=DE*xXu+@eT*kL){x*T3r=v+Btv|mTkv*&&ToSQ?HYK ziYAF><HWzv|Vzcb>zB{}YDS>}{I zXNR~w8M6h;L?3eU1;r-XksG0bVcla- zZlhK2l)Gz{jqm18#4Slaf>ld9xx!^P1T&JuV2kB?lb#}d_&KNCc)0tYacb!qe6uy( zxV$x=E3n@V`6V7)*|JZZhIklwPn&4E`tnIQ{&g4US^LV^f5SVh`%(%cMuc;V+>5z$ z1koJpa|& zv{!8cW^FsdEe%vLzOpzSrdd2U37*!-wHd^ie2~;eaUETOf3~im&V2@WKfhpN(0Ggc zx5G{lHW+UlK7BPN-D6&(99hApFb@3m#+tr4AxEm~U5&4|GtO0_zNyo>L)4`2k9RhE zQq5Ic8ruDdL{_fG?NY(yy>KDU9&;Ku^qE1d@e(>2y9GyCPeYGSURYrH7WFo5rqYEe z{KQ++>4dopoxI0UXF&yqO=CNo12KHr?5SWEu!3HGcuL`CzJr~cAIZge)70Ljl=UKw zN^=%de(G;*oRdJFkA$iBsyI32Kfsgo){yRRYg)O}9D|1T^Cy}Qk=BNI>^IFK&%ik} zBzTW!YQ5=tmpt{zW>fdE_2k>Ki(($%p>+$+kT&bEdMH)!dj?f0;Kx?xMp46^8`h&| zcQ`$jxJCc&*pOjiD$Urc$r}b0;Ix~@bYROn&~_e6gSXz$^x#vJ_Tm}*R#d0mI&*ok zT_b2l`C>A5YeoGng;YGsn0a;VXkLOOiLFn?Uon4?W0^+RJAY7byAv*n4JE4s%!5(F z?(;dZH23@fN}Y@b-%0lTbQe)N;Cvr1k5l10O1x=PcK~KPOhM_OJbaf{M)r@D`I%~o zlz#Ul92&;7L2U><2bir@pLtMGpw?4XU6 z6L^;+X_$L{F)4(Ip+{vl#(v*LuM9@x_!|rP`%OKxf5453LniRnZAMgB97^d*52=hf zkguE!rQN!wWKng7M5|J79x0nny6^?|nYcY6cm9dyjo1Sf|8c z0&~kdQW7shjYkfUkWef+B+R9gbP2^qqkm>>l(ydKB+9-iKf0k&hBSQZ#+Z8}5rv5HyK+@==8{{HlA*IhnnV;*#2V z3w{B?hia;?v&H$RZ;*GP6a14~LRokE(VunA6o!7_>ZzCEZtHwpa5or)kF=ovx_0z0 z-V8gUuhXB%E%@0@9-NO~rX9X-pL zeTlk`NwbWpY1|{I*La0*<{qT4&C2+Ab`Y<-Yc;=`F=8(Ca{LX)LnQCYTwvj&_~E8b zl07cL@5vj@JIOcjR&&g0>ELHlecVl2*+2#s4{*m5bH1#Ab<+ZOvL4)9dSz$Di!PqQ ztG61Mb@`3rTTcv8z&BNX_DBn=M&@jIwbV>%Zyy@J@aH4+4fzMD`*3q#H$VQ(6#n5= zd!Bu%@lUFv`5$}P>?iF6Uwv~df64q5UJryh4+HGM4am8V5j=gass+ts{N=SKd3 zb{m}?1peBnQYs9Z&+qiz!Vi0R@`t}0@tJkwc}`fKAJ{9*iw6|(V{Unyy_s#u+rG2o z!==JW+*_aidsj!-%#C=1ir=&<_9d@gR?O?B=2GNtWq#~@amrjO!KVmZ_+F{&G*A5$ z-SyVu50Bf(2gaS|ol++Av!=`Py1C1F?Y`-BV5TImcczbA0xD_ZUu8acL^{S5HBp{P zI$aXc=0#gRQ;E6 z@#NV##!N)NiT~ne#b=t#<5%@p@kSm7yqkhKpIw$pw&QQ{duK1>S=gGsKbg!gdv3!2 zej;m@tbUOXSdP4+?@d1B-2u9MLyli@r3AGsmhtXw|41US6CY0;;#DHQP#9OrH)@{b zzZ&(?k8=`yfO0av;9?-zWhthJK1MfZ)@%Hti7ox-QAw*FPA%Muwa4XPn{hL4IbnbX zI(6`7)lA&}tP6r?mf&kM=GfTz2;>DhD3l~b-p_~O-lq(VOxEFV{5K9%$LUgxlpK9~ zaf!Qr>jc@}2*R$32l2wmT-07Wp1vid;jus3v{pLf_CApXujh0iBW3#hVSUA#ryEv>rH)a(z3f z-$9imyBffke~Ol$;wf#844w3Jqfig_Ir?givusYnuFq0vqc6*LqoYaNAqz!(4dMCg zm#{~TvGa#>Fk}A_Fzo&e@=p46!_gnT)(gX({7dxcKs=5=B7&O=mrgGnv$an&4B=SY(?W$lkLF7y9(#S%qKRMDIg1R(BFff4f0hR#PZd z%9j4vy}+V(BWYeB>uM$YpbyLY4R6^<84ufFuIm_*nRp+Uek*2-k`>9 z{#X^RBMFK=xEm91Yhr9&5l$(wp!m=II52damPyCcL=`J+Kh%XckBvdcm)aC`CKG#R z_2Q*<<(MUAjFY&Pq_DY+wtBmvU{Vn(RTxs$hY2`QT7+tZGEj3)2=0#TLy?~)P@)@y z62mTdpi+V6R#)Ir>%%xT!+>8^_mmVM48iPdlM(X~Gq(ZFL1 zZwJR3*!g66k|08!EWWNM@fP;pJIm(qOLWLo=_o41zNT>@kiR&H?j4_WqeKpl)|ezrOzpY?Qds-jIJGo$jX9ot1NyycP!*OKWAFX_uwQxyVFW}Cpfa^3}hEKz>z2= zNGzTN4~;}n>o)<5cDX|KOdoK!e++Z;PD0g59^0$;5f9XCg$EAVa4^W8*(Sdao$4TP zBD)8;E#WX>SkKk`-KB2_~13eSXIBFe6#y_QSAUz1%x}2G3vvS~6(E_~rvntXY za~NcP7{Q*#rx3L!5>-zOg1t^rP}OXQl7}h5@*^r}Z99Pig(y^4c?d4;k%iaI3(=V3 zZm2(+34$?V=7J~^2Q)lH&%c;KVuvHHyxIg;-sm9U@40SxJNl&F1rMv1cX20cc}jy57QrnqeBMk z;4OcC+_*XmzWwB}U!6aYV&_(rXX}GZDwrzu}{#AhkAg9r^8OSCUktQBAm+(ftV#f(8k@45VAY~k84wb!lb*X&|n8L=+Wo( z_+4R{`U=Q8@&P?|{{u;@wGwmoW-;WHkA-#bH9`BdJCrI$fPepCRD8aXnZ3Oor5!#Gv$zv5 zu!Z+G<+X%1uK5dZ(0R0S#B+3K&N&o)5@6mZ4_w{q6E%qG9hQWjP zLCY!zBBz$4%S-}t-Vn`b`;7tFctg-SHyV|CVJzvA0VXw-FmlN=Fp-)E{v(RfuDyrh zYI_dozDj~?XdFn7oPk&GtK)q(Ccu~hFZjX5qZt}!P|O5LxN#%~h9MRz5AvQ-YxJ?y zI9C|HzZjxc*#b^;0_ER>JT4#)?OKrv-u!tp<)i~T*)$p!H8w%!k}>GnqS-jyC;(=B z*MprB7r=5~3MhSzLBg1JBraEm&viFY<%crV`N;$N5VGe+!-^H&(ob@4+Xg1`2d-{35K{)3gBA9d&R~%;QI1UNM-K>6!daB z7+(<};;0T`j2_gV2>B?24YIOm*VaR*(K!jFD6T|f zCKteMe~k7&z76W%J<#p81g2x}UYPYQ0_y9Zpv2O22#@oIl;sa0{A>Wz*Rz-R!X1H^ zKP&`?UB@9Q+7M5@avN68y9()bLKN=)6I~MO;Xi@?;DQw(#P}z#qdgt`LR7H4%rqF> z$k%iK#zED$RdClV9QJvXFm`7wv8=8-D6p4M>M$0+?Q?;Zi(Ig7ZWSc)-k8b5<{-n# zymydx0uruyhkVQ1kmiFpFjKHaSJdyK{<*bCGtn7+QHfz>nZKxs)}qY{nn*t0p7-r| zhjcoX;E~uLZt%J4@pA`}ML{q+ANhr8xuODQm8T#t8WjC3R2!%Yx*pMJSB)ZUv$~I9{S?&m?F>^=KL#FuTZESK=a*S`Gh~O}N9p5r zA=&j2n(|!-23JL)h2{BZ-t=v7VU_{tWz-_ATk1%1kqmfy-$qN6%;2zfEfmJ&q2UK) zVfw`x$erhAe!V#!@-4=IZj=vdhjRENIUcf3&O=izYf(%w!-VXzL4M2v(6g6=Gj5LP z^b2`-r&V^*j5?qKHlrovX#iz1@uFt+!OLCy20s4Hd)3SOHHOZk1wXHg;=;`JV`*Bhgt z^*InVI)KNEKSCu>dXe3v5cqKC9%}P$Llb!oi0`jw!`zF1d93s~=B9c!stKC_v7t$z zQg(~?h*ARX@=uf%EsxA!wxTu30>(mj6zpp&LM1N`F*}=6p`6LO^~vs?>P{FI4tn`4mZHocs>vtXu&KGs~I4 z{0X?G!~+)G&xYMSHBfl56MW+0(7dR27)apH($e?HIQBeJ^8N*9UJ|%J!UMg#EQ#fA zorl6BX;2_R;p^j45LN#}8~*UVi0M-JQ^FuHkzO#2*MV&h+74p(P2j(!8uWXP^wKzXkcAcMz) z&s=jCow3e_;GQ$kEAb5!X2-#%h)9qd^#{@?q@f9S55d3a#jxYo5b8~dflZlxOuXSN z&_3}Iy$N!ItIOPBOUFVqh)l5M;zHbn!1jVMG>`p; z&TsccsL~aa`!n&ekTamB7!1z?K0x=-Hpt#|5b~2pLEV`z@LVw#P=_NbJU$<8JnjSM zA#+?>QVIUufiQpnGq~kaj;d=XwcvD4u?~WxJ zF~J7E+EEW%waTIQ*IAe|_aeBe-$Go$ZRox}9Rk(?giRg}#Y+od9FM^WZxf-jxwEk8 z*gDvp`3|lNL(&oP7i9PC%kX_zFZ1%^9@W2xh3A*Fi>2o*9> z1*u0PLtSyV!UR00c@O;iT?;dV=HQ{#(J)?ZGwf_pfE~4Ku=$q{Q0ZBTw#0=iG1uYBM}$|{kHQZv<)BGU9$)9r3!m@0aE#i6Qj|RY;uZ^Xyx++;zvVbx zR~tWTwZn6S82b9<@B!8hwh3Q=jObSSX z6~PL_el>wvt+9>D$=wekCWQ>a@RiO0)4hOt{3VAY@s zOtDf?uSqGma`_)n7wO{k)${TD*Iz*7bd+ZhO@}u-Hsg%EQTTxG8}w>HD|n24 z3c~(eY?Hncrzoo6X-mQ}(FDledKcPx&wwz#*E-eG5PbQ1xN=VhKF#-i79L2$E+4J& zRGlht=vW8`AIMq1GkD2(+ozys*+-alCpYkW&5(@}kG*($fR(R;M@;d8(2MIu-ULsn0OMHk)?yUHR-&ty4%!HAjzDKeR|?!U$Mg843+Q)>uE5M!03G>XnT-lEf}-#% zsNkallbNu}X451`@N|+xW0g}GS**lwJ#*oel7OtxW(-e^7d+qvwLe6EWG?wvSQ}4S&iE9pV069*Fh_dBnSP!(w@6Qq z+2#Eijr8^vJU(%lDV{T%DcZGJu+Pj;;N34|a$gt=90D=pq8=#lJ7I);l~yuWDlaoj zGEWMk9~CgNTf+rXS9lMh(Tb?)urYIcoSJn>H?Qf+4MV>RSJ|-Ahnee1vP|n7%yb67 zVI-P#nJTYvLE-u5f+xE(neau=1k>lMG7pR*8QW2Fm_uG#jOP`5l;JmCaQgc`M)JHh zlhyK?`Q|OfC=OeXPJYx7Nb>!gc>PS~muH)R*y-^2{w^l++iWJNubkO>e@O7MB9hU* znQ1d$lx$=3g#Q~KhOrfn7Tk6eGS(|?(4W)1)`YqtQleatJw1RA*xBtE?YLk3xE*wg@Jl)nrCKjz-Fznarf+k&NCr zUmHu_ulxRqY0SB^v(PNLL&zhrnfWaHnu+f0V}9>?Ex5?@aV6hQWoEoR$1L){ASll& zVUnDj7{9S9=-r{?0=b3tOrVwmBbN}%D*!G?A4K`0%p?tYWnMtSb|@?!MsO`wB)Uc!^+UzA5ix^iLpj zN?%~mB|;HD%bA1Up4d3`?qN0^m>@7S=s~TO@u&pSnMV^Pz%JsP;9%YXB%bw2kR^;m zau!ldjG{E8AGHC!Vu4`s6yC;1Wfz*WAri^CO|e<7DUGHqABL<|8qk=TmdtxzPe1hb zKb!4K{ZZQ_X{KYEv^A?x%&gkiD^OkSE_l8%mI=O6iQeW#-ZvgnjVmW0!)pV z&+lF{K~|P%pH#I?p*caPrbMC7)8f#^O*zb%mlFi-3oi)zzE~hEoXG6d)?hxTP6N-$ zt9f6aWhl>FWYzDxTM$94n1JKk;KXnZWM!$tl>L&1pd~Y5UiSgPv$G@M=TbZLW=)dK zDP1qdY0XB#!NCq@Q_nCo`R8JRmqoeY^B6P1wV}(*L$6OZcPs7)42DKCB{#K^dM08f z+i`+%S`N&XJH}|3Ule-(N|kBuyo4f)YHW%xIq}bdCfdBs8NDkrXIjliGG*5e3Kp*| z<2jXk1-W76g7J3If?IRGF!s@d%u|gRD;K{Z!He*A#_5g$JRLrnp@%0yqfwaPpyfm6 zgPNwz!KvDU^^qe5%jDj_w}ctR%#$7=$y6Ytxt_iziI-8b$O&_?h>kQG>Y| zk<7Y)KIZBbGvvhc;k;WU(c$_gf!#rbE*Hu(JL}q+@&!t0v(Z6Rv0jVOzmX{zIcfu1 zZ8pf1aPop42{SaW^blk8VwoVQ|2z88alvNY-*e2EZDHtH>Qlky>u;Ew(zlry( zxh+@`(kOW5sSK3{WuS?INZIdlC9!^WIt zM6V{JS-j_gUT?C1M(Cg*$yv;&k!P7(mFv)bftA1`M+P>XDrZEu86L|*m{QX^o0L_$ zp!)K-jp5ZCX8l(?rudLCG<@+zze0KZXPF{g7NV!0w7$U=!$CzJz z!+@FNhK@MQM9+3lMx6CKWYKL56>DX&XTJh?zLEqTr8MNe-Uq$)mxA|82cbE_m9a7z z2{WH;g60aI3weDmtS;7rO)auet4Sb4gV$!raY4~@1>nCY4PDxmghCpk&{C_3(4BS$ zb;YWnkabTW^CgCb*JR+4tR&=C>VVYDQj~mK8tA4+$fUvpl*e=+^+orPdMH5e?U7&+ zs0nFF-uUaE-zfjrW7Jo7n)!Ko1oHWifb1XI!~58$d_BGruAaFAW=;FiwCHYhep@8t zd?N};x_QIeq)znth7euu>PPk7XTaZu_m_D)h|u#&RLg6OC|-EU+^_FIu{&?0zF?j| zn_Q0~U6wH)3iD9QXW;p^QsDALgx2r>#0(yv!1p{$kVWHoW;b7#CQN#WCWOTy$Vq{% zyuZ%@K|HTp(8vfbn4#vO-LQ1tMYz(d3>FKYAmx?{*p|?aYG1b_37$jnJm3a6R;+@n zF=b47tStO(QpeX4$o&gc0}o_r1eB4VK4c zzbC=1AWLwODubczC()P{BIN2UC$Bfx^M!h z=TN1wNk#Opq?A_eY^mDk@|0KxjG{7a9G!41iSBUK7Eal4jox8@kV|9DsO;hEw(-KE4XyO+?|F7EjPcj7zQs5+;=ziRdS>+Ct!gBx3uPEY(P zr|Z|taNF28&fvWZM>7n$#z>CpJ?>;rzsca-)INw$t$fEi8@}PP{gg@IRTG+ZXC2x3 z*O?COAXTR%+o;JoZSKwOUmW9mizu%eN25m0r+j=- zzkJPLQ?6>#xZomMI9``l^*a-*gM>pxA4M}hc+r~kr|HE^S9*hI!@P@FB&swmA&m*C zl#Otq-^c(_+g8d=d7UA$%Z#VOpBkbcHAVE)##!WRb}6~D$5^~)-9fs|{S^J-r@)06 zt)Tj+b;PQnp5gdV7I2?^CvrC9vblwSyv4bTB&s{q&(ayY7tt>{ z&&ji??&51E1KgK;*V*HjZG?-Kw6Ut0*Qj`}Kj$hMD||BH1Z`q(5|@Fgob|)IRB2}% zz2o?vs#R!+PtiEh{>!J?x|)9RvO#b9pV%AGVVEQ##RndL{hwm*e~W+g-^agS-BfF= z@dJ)0sIs}dcFp1G_aS(%J04^I1FNLlVafarEWh!w6PfMM@0SFo+XHdMs0RGuqajXB z<@-Xxhv9(RI{bHO9hm-nfS0Z+X7LVr?3ZqfL()cJy~rZ``Q$G4$(_w0bXH=Ig%z-Y z1x@S`u^QffzXVG5Kf(?c)7V=df5Q5nyI5bSfx$Q#@7u8(8m5e6Z3@2P!h3^AVUaF| z_;eioFbvn;U5qCz8VC8ij$+%6>-fbq5%y7wz#UIqvCYkF$W&3pJL^Z`OK14}d0;J` z!{$S6We?U;K8j!8bH`hM=i)Q23-H*u=iYQI<91!*Z795FR&UVNuD+W&l{4w{WoySIi|$NBZlxv51nswEuqxTF~()_s9QwMXX_aoXGi+`E)SPRaBzr)7SF`w-Paw%03i zPpa2*qtlAS=BJuDr>t;sqMAE5eL@r$*_$QujZ@(QRVHx#o&D1`Ah7Rag4OaV?vca#-dB zH<23AnQ4!?>6xjVU04!#O$Arqn0kaWl8CO_?KZ~8XiBF_CEz5RJnDS2?l$^oQxR2bS-p|~08&hu8Za;3V zPck(`$%D=8 zxa}$?+__1FdtaQ+#ij4$ZuJIKwJcDpo_}i(r&;u#Gt^OMFIImfHCAGd%9YUcwd1P8 zWhzAS=R>&tOILB9l%`joX+Bi#)jM4DA@MPHaQ6lAmr|E%G;cidj>#3hTb>{?@6qPQ z>0cyaryg+%4-G^kjM|9eW?P}ItrO|;UPhO%brw&`KT4H4)oB=NryBOLl!ol4BQ933 z>T}J6(*h<7MRV5BZyPnLRO=!{%#|j3$+nm#?n|ZlsndiO)}gdSdAiVNP7WQWp2?0b za1h=II7bdtM^YdBfJUa((DKM8>U4K5DSKK^hR@2T&*$8x`qG!E#jPqDpyNdE&Ob>B zEfq;dX3>K_;bdh5!wC;$P|H|pVG{d^Y*+urR;Kdq=!2?4pFR21c3?7HDEv!}&oY*~)XVGI4Ze$v!S|tdUT0lpfIvSw^?McBKK|OoVw)l7#++AK3ne`}9Y>n>hc| zd|`}q6dPkv!LHM8LB(wYWK@zN7e6E^bUvFZKgX&N|61Ic`E~RNIOA z_g>M{=ya+c-9ZdS8;W}js{r@Upo7uIbmgJ3^zhyol2y%+7E>9qPVg79wd67xmb`~d zkIbj_>eh7OnGPcQF~okH{D3UeoSA+&!ZEh63G4cL+r)}!|2k$x%AZAXyS9= zANhUTfp#iCt7=S`O_HjT5+twudD1BZ%9*~_uFUo!$M!0{cAkC z>#8Z`!oCuX5F7G(L<99an?wUHXpn?sFYvm;DRlj}c=9Q-mb}RwC2}{*CL_Ox5sgF@ zs+?0x%a%VUl@2oS(i*BXbZ3%+5D!}397|QoQ^=NW3PiQtkj^+?OPV%1(2)s|^c2-6 z0e@`7pvRDmT?ORCEIa!C{zft-eIhj{$)!b(!>o13hq?779^6Zu_{!4jW+*`8B{*dyG^!5er8wH zOd;+*buH)aglN;0+w#(+5>JXB}s%d>Bk|oo*efN#1?khWzJmN2rIbK|;C*e^+CYQ4&Ez%^w zEQ`$EBO+V(TXRD%_2@v4hIr<`V?MoU- zi}e|@JbX0$(_lngRNQ& zjZyUdgIVI6*GjqAL^)!8CWB1d*h1zQ`P0?q@2WJ@y4l##zldLXyI3bKl~79sZh7zn zGVR(8ahYv}_@<;O2@I2>p6oMTlucG_5+6exHyz@1#~&a<@AcdU%&?#JenPo@JNb8M zGFJr}blyLes&5a9t9I;vM~)^}i4+&Q5SQQ?WQ*HzcK?l)?3U3cG}iwHQP1nI+Pl5K zYAtw*OfMCZEdf@YL1s`*!$C4Z@S8lD#mCswI^tpf zlr1Rhts3#^WaahkHLRPgLzT4UIQFsPUh*VInc80bhv)C#O7yncvYpkQBq`pGUXdC> z%a$dw`z7Aub6pw4!99zVpfJ{@xLLF^ZW{T+^MGeXIgz;Cfpku)Bl~WBDI5FrF6%Q> z5%)^ul6xukG=KkCq7yWh6xqKa`R-EeWS@TWUP+3Eue!$)yEYu4c$J+P)sM%|*+V?X zS(CT*6GXZ0he&W$Cs|95RuxW|%>K>WK+IiM(vY70B&^YxRBlouo-f9cFQ$6r@ze9< zL4_&t>USV=MN;HZ$7|9Zd4mi@NYh58M50vP%*uFmR9feFlSh-rQJBM$gly zcJ;IAy@gls#JVPYOSO@`Xa9l7lSDE{F;H|W9+N=`7jE!=SZQ>nnJhiGn{B*OL3f^2 zr5bx)((Vc;;fSe|gg=N3@k>z_`Yrbn#>K{nJI{hRWXumTN4Q+rvZ6^W8+?L{-54SK zZnsg$Ej%uCwLe83UYSK5T`h&nbAUDdVlQmUIwFj({XnHPuu#p-T_i`g(4e-r^oHdX z@tlw6sr$NS+N|G7_na6e%$}@FXOk{!fAu|KoX=3XPnyD7z0)-6Uo8n-Jcg^B>n1EO zDHcx3F%V`P=IFkA%Z13?jCQ=D{29BPO!=5w^-ralcAOYTUrrk)>~S*}9%(;Aq;`VP zX6$!*`o1=CUCarmOPC4KXf?V`PD1$Tbv8+FH6isTFIZ*w5#%YK+NC=jpz--`^yaT+ zLh~tQ!i$SrNxI04PH_$uo>owx(zkM{aaWn}>Cr{Poe5v*?>V!C3%_g8t4lm-#$piG zdFHZjd_8IMZZ+=P3`b$ymTOdV?qBxZo&w?Ntn|u_R}_T8cTqyOh!$!z@Pq2lmlrN~ z44`FN!Sv1Iwc@JZ)d52`yqeaB#^bO&m*E^|K^l$Ox!*1*>)4i3$ovOukfA+E-Q^Tr4 z6Hbs{E}2!+*EEQ_P3pW$ zKs0$N%9l83Ncs${vbTS$jc%pvABJQC~L19D|uT^+#7d>9b@N0p9V{j=LU{s^qLlN&1D-lagH=i z9ygbm-8fAuz({naUP(0bd_HcrQKsB6Gg^9HmH2-CDf+@XvcC>r5?}pbMJn2lkQYO_ z;$P@Ck*qYME0*|*7s`f-cMc_!aoxx1wDAd~uXzb^==ZK_aXv4;_$G%q&eRb%l*@{{ z@)OD6ZcUP!Kb%V6(uAQtVDiMTnvHm$AU3KR!8wd~CX4Kc5#7!$RPTWjz3J^s zyS2`;WBe7su`5B;yTynus7)64sc2N`%D5BV)ep%L?Vs$Qyxqj9XD$DoG|3J1Usbzu zb?C_C^(4pHMznX~Ql`i*jEvy(frzZr#9^m1@z-F9W159%>)3E&7xxrj>*!*CubW5{ zH2le|`U3K5tQs-?I+DceEFj*qIMJ9rdi0(}KCyiK7h72rlc-DA$s7r;vi#>sB9nWL zY*A8VRsEbQFN|EvzC9{Q+9FJ7=t>2mcZnaP2J*RDg8{Lbl!)^}Tv%cwPa^7O)4Ay_ zWZmO`q-gzZQa1Ys3H`PoYkHZ8v|pUA%+eZ9M!nJ|`zM?fbrtOrMOF=w&|5qv;c*?A z)E3J28LE>^j%d%*B5Qxo#@Dw1xxx6eyVu2&s&n>K zS9Jk7KRQXYD|{4@S~Q7md)P>}NdUEfV<0kbJXslU@|3JPxRUL#?;tNv@VQNAHhXu) zysG#PV|KQt5!o+3MXrn%v7epH$wRvYBFY_3KZTo$BR6-lwo6Tjm2fiMwBRbKw|>T! zy_-k`%BRVVm3{2YH6>*2Hf6H*fg#yAV9$n3J5HoaRH@&K!({4m53+u$1^elnBs-upw9@8UMB$rh1enIcm3ww7Fvog=!~n@a>9i-d>r zYssQ$Ywl~7H9hhuna0exN2)h06Rv7e7P=~Krt+90qhuw7c~#4W8~i(HrPT)l^()x> zifTg7-d8lDQ<09b-Yz^p%~QDbteBcFbfm8zy23GUj*>DbGX2wS`o(CxaQx;(nkHL8 zU!9Yt8saOIoBNw;m^~D~w38I(jj*Q%Og~jA^5tDP_31c4GbvrWm$*JEBuB#~g_f2B zbXNePJ{rMf;`x76-GvS{X+j# zsL`!EZ_;DqrU-*qpQEIvo&Fjn!Cgz)NH^S;75?FWYUz#O4A>gEctIbKALJTKZh}@`++(YRsKDA;D>$dM|z@ z^-(;xF^S+oq1=L1vRu%M@uI$n4EAE`fOuT7Vzr^waZVvKnIpwv zTt~nZE+$x!dvjwEPRg^#HH)r@^!!15=UIbzpmQSUuq&UV{XfMY4o>He{pKoXYz^m@ z@9yK&UgvWglv2gV#$FaJt)Sd_i$mf^IcvmzlKrAs#mnOJIq{?|I%g)~#+|*>Al|rGj+5ElD$Zz&;N0&CxlXwtu{);4gC4~Mu3*)3e@s%KcNfFuYZoy z40@3DUQtOd1`Lpz$Tq65q=epam_R?5)T#44@fu>N@Fb@G5@}?Si>xp&GMKu^%F=T-fmP26D1D`Jkp`9~P|0oj zqCEy~)JgjhUlVMii!W5tzbC6mo#{)Fhr}bISR_MgRTb!f^c@=N70y0Q*QYvpo9MLg z4ANtIk9@ZBr!KCYY^v{S^0MSU=~!@@el|KnuUu7SW!70x=aL9&9uQBZ*0_leWj-ZK z{DBy?LI(>12shq~ir%YHUloqsCpVeAc~Vb22Jg{uh3_Oh zEs(TaXc9#ji%FO2Xkq;Rbh^KK8`bGGrwhw!sGsoz8n8dQO6hlZ)zK6}e=WBokuS0- zr|eL5v$2STnI+S6=knN?MZ0MrR_9_h6{z^=EfTS9v*^nmckv_(Jt}{03N}CRm@4ER zr+GTR*#OaT@s1vWc;Li%dT)j;-NV-*m0=fYxnvTzcFG_6vM-7z&-hZcHB(Ngters0 z7Pyk>opvOCx({uPa-0I{SKq0rlD2L{L zNMSWBy}7BGqv%+p?R1)_8@VcTk~9}CqA&S5+f&FD_dW_DF~b&#S1ZKQH-+QamLc_eH5R4zx`MU00SUc8I&q<@J6hUhm_H-Klp(A*hZ1HlM<7kx!$6EoyX> zwkvld&Xahi-Qu1%ourQTCpg2D$zmJNPuThKOUkUAFU zci{@Ex>vH09jKP2mP4i7j!)VDbN*(ld9Y7Hlb^rw*ZL)9Vj8VF}VvHcmII1IunS;a#!}L#9b_0Sc&a}O4tMJ6LzYp8{4om06QM= z!Y5C-v9(EQ?3}V}Y@X&w7G8*FO;#OeN4?pC`=*p*^#&6%v)~Dqy6uWHe3ldIfI46%|zQ40@Y{*^g zywjdd@Q}vYeZz4M9>Kn!n?^p*FJzljx3Hd<&ak=na@nP`bFuWIvDoIw0l^JZ0UO(? z!+SrT#j-!;*iUAT?3n25*lVUfk$)}Aj(+%pT^Er`q+5rvsm2zpl&vj}U3rFm`Zb>Q zLsQtmSu?Q2;4Lt`Z-#q*Rk2Ei0mN7{7hf=s#(yuFu)B1Rfz>>D_VvsHk`u(RcP9>K zZMPe-8Q$4=`*@Ze`jpKc89ABPT>1nv+@)|u=Lc4MK?5r%`xw@oT}rM#lxEjGNn#UY zQ?awHJZru85+1K=%IZa|z{#G4_-IKcT&fJiUf!G81s1LBi}r1J$ongLUa*#Z>US73 zVP9CU(+61gRwG-aUV{%td}ZC1dXc}m=h&O??bxy2uEcD06M5gr&&c<+gM9UO=($#o zy*@hPBPk-*!MDLCD5wd7+_cE1GE?+)*95FzDvvAFrsK=ElEK>qvD-R-;m7Nb;o;9C zpw`%u?=#h~9_11E^@d(J6Ho-XU;kmd+&y@h@Dp5%{l;p)9mY<3;LFjjY|BDo8pq$vf(*+vfcr_R!)(fESAB+uPgAAUun1_XbpCs zt&f-N1-5yB_iO61#piGN<0H3U<8{HK@dSH4aJcyz(>>|ob9{Mr8;TlsR3O)^Tv zy~n@f-jl9y;BgBk=WFrRinmxea1cCmf}zrW0A{?I!tJDU4TMh60~NUq?EA^1*qJK_ z;q9*hcEP<2eDJO#Te7eg3$=alv-6wr)iPt&I9DET+&&*)P>evYvQl8D_A5N5YAp+s zPJ&!pDvu4miO<0qEOlxjyKDYWe18Y9*UCci!1xF3LYpfrY|vu+IzQrumm|mwk6Glh zryE-{TNO{)JR1K=xD9;+gRo!9oo!W8wsDU+3S*O}vcJb)Wl-)Th-l^cj3^Xd9QlG4 z=H9`B*R-+hvwT>Xup4U5W#A*7&+wecb=dCWNO-%w9OM#)X9 zl`_&WUYQL3q3JMkNP`{tnFQ~La-jtovh6Anm>X6JSuYc?$l@!U^Phk-HeSL`3o{{c zk~j7|+XZtqIEeBLgx4U;-cK%J_UxGmmHhw2Y3ELyQTGhp5?n;7a&MuhDvbSVkbrMx zx!|kjS=g}sKK@?(57z&^#PbHP+i0&Ejz2g2L59v70p0P&S>q<+7gh~0+Tt!QD>KEH z~Va3P0QF26jBOp*8C$K4jYfnNux6+V~`@ zdewoyw;sdkO*(L-NQqswhQ+t9S>cYJ0T|gg0QH`SKv7;5PeRAw>}3w(l-HwWRRS2h zP#e2~XH$MKl?_E^4u z68mp`DEqtV3NC-E4!2JHK^8h3xUH84oinkxcV4NrrF;Y^yZ*yx)S8&pj+Y^HmK~g% zX$)TuJVPd}&A5yiho9STh6U4YASh}&o~GW4x3i0I%B(BMRf>;+%mMiB<&VvEPk~fK zJBAy&SSO9YAF)S3W$AuML0x$0tvmSDWI(+65bn^o#aAyB!o6*Ca2_dxtMNuS)`QpG zd%%0Ml0~>f<_kndoP=XHW`e=(OSrD!IWud=cv#Us0*emudi&-jD2CT$*=W!SubvvP z&ZV>PAN&Q5Z{-ORixcs{xMBF<&OW5LA<(8VtG zILKlMPP`1ohZd@`Hx!j|;h0-+{=@;q4V=V!*OIa0<%_^+@*Sd|tti$Y9{qDzgJ*ub zgO6&ig1W9(P%*{@zvy^~dX6uHB}VEj_S3=o*+NW9nqirq8RYzH0LyC&@T$tw;H@JK zx+^cEfa()ibq&R5G!CPQ+t1=1tBrAO&=`D7UJkR>negUrD4cO0fV&H}!TEFNU|gvO zYO7F#)Emk;_u?2leWMWE7bY=%P8cs<*#LWB466X&f1IkQ8sZbv`Hv$CK)xddKHNw6PRJK@)r%`oYYH*QsjFSe`T ze+{irpA(BWOt}jsDS6mj&xXC#se#>^E`#Z*4s`l$KA!qWgmsrSLczP4kT`@UU_)9vwAslDh#Kpj3LKsYwW8gCx1i|x9LA%geFS*oFfgZdL; z#N?Y`sj&e?+0KTQx!PFRsEtz;2)up1l<|u*#1oWnfOKIhR(`r17wtWc>qeY}XW#Ph zvTZ-`jzjKPd$=<0eyqaoH(AS0{F#YIJsJb>wGdT@AAq0V|DuywtFX^pJ3)R!E8cHA zmc;92K(lHO8~Sw_F1nt8JN`A}Zwh0H*TgpVcJv|k=VDF#T&I?u{n?HLY1y-yihTT3 zcS6tLCANBN3mc<4fi;cVMrP~sIhM2zX|*52-sqglwp$%1*KL2`W9&v&VAW2JEtp8g zE?LG}$X{kF68!K>VWdvS0ADcatJt!n3yF)0{cz#JXprBw+OC>En*Fa^vQ$L zldO5m6r40Z4u`}&fnU={k`XH+h?j*luKIEh&sKCHja5r{KRh4YkS#+Cw_C9nCRVcW z;RO37V+B4oZ!%WbiDxqm8o>0j94o6845NJm$;@YG*v><8@RzS``r2gJ%J-hE)Xlr> zq+1DWr|cEHi5$nzN5|uDji0db+O@dvw2)mG#w)d0-TiRLAYL)hrv*8YG^8#%=b>Dite3CgE zuM_}o^T(4sT4WuYF90j2IxM$n6&jpg0Rj6*!nEkIu&DL|nqrWOo8SHA_n|P5IK3XY zl@>VTPb5Cjsg94e=)kzAo;O?r^c53f=Gi)2 zBp(aov{rz}*?i3Wiz{c1l=+-VBAo zg?;Mm@QT|Y=HqTScN?}%mIcqd@1eZN8h?CZ1as2=p~YdFk)LZW_T6EH{U&vxIWnhl zVUq|Bdi{XeQJ-MlqG*^iY&RtJUkAq?Ik>+%48H$#Mo;%!z~Sg8(6q_~C#M^M)y}O< z%o_=OE9oL!l-!7?@}}n}Z2t#oUmi_m*u8C@5=u%kR6l}4#F zPa4gchY})E6hek5&b<$bMni)JNs2T_ljiw5zwgg?t#5tn{9bFF|EzVcbM4`|pMCFZ z?@_Gokr<|1JDz>z(aUz5j$*4co-r+Py{ySoYht&24ZC!_665{o6fZtma;V;YoA>() z$C|6vSUFFPVrooZvV)E6c@eGm7;~eEj6;|y)A#NbZ$+XC$v$k%wn?x|VS!QgUe=)1|$(l_b(#Hl5F=KZtSh5ZgZj4iR2Gc(C2kZa5 zf$19&$!t7gM65^zdq3#{v-CzR>tcPBnf*GQecx5eHr$bABbZ9|(vwC;&McE@a$msc z{B32=T)1buWz_`c(mE&B&nAf7pLUWr+S*;RlR%%ndypk&KKAUm!&Y}R{h9T~PdqRjD&!%u|lD3l$w$ zvo%L~Q+3lAwO>Z$bea>J)wqfcT;0et%MW0dtras*Kl)01M#z*2I(Qy4TX{CY*Vt<& z*=*~)^St^?Vi!Gcz+DG1G^?V|;CAv)?k-^C~u2GG12p z>|<|zmOP)p1O%S6t!+QXCKR_bvn)f|s}~yB&?*B~XH7NZFei;Yx>SW&f3{#%+kY}& z4b;iX=uN~Stb{$^v4^Srl+7EXlf!It&}IyZd93e@GVAyKLU!QZ0sO$Y80L}ik0h8{ z*ttDPtjPZ-lYd%;FJm!=Eb_KzC&~n|W4rIOL*;*y!?~Sgzv3d+eE&q|>tQcq{<4H@ z+Ga-%$ME>6<8HAVUfg9%e?+k%Uyd`6YtNCfj27uNv}LQz-;nR4c_ik7fNkxyCN?^U z*$a}KZS599c7@52OEHZ03ZQ zWKL}syDI1jyXF+ zJ2@{Tq&jgsTQ(?^>`*Tw5%w!tTmAW@=UoSRlMv01n!KNw)?2b0T(0nry$xV_61!}8 z6~}&mQfEbOnJ^nn+t^J8t+tUf?lP8j6BvhA(-^n!V&2-~Bdk&Fb7tlI5T-8Jfzb>c z&i*ZqV?T{oV;v9uWdNI?l>$7VDcQFq)$1qm& z6PYPdEiCs`Xj^{Llu3M<$6PVjU}HK@^0r-g#LKp*XS8Gu$e=bp>k+QawnW*obAPX5 zS0|ie!tMU>>fhb59-Gy|9CWYe{W%%Q%q<_o=C;3J0_JXIQoOR+_J$N@iJud@WtSaE z9nr%)N<7Q7t*hqQn=EF7u54l-94cfMZX3raYh31iGoHZ{g#t^~-C{qybzp9P31NP` z9ms}0+`@Z4=O7a_#(-Eba_sc4dh8XS8pbvM74KYl3*-6To{f_;V9q_i#LK>Rl((&7 zFPrK(iA|C0Pg|;Tl{LO_gYo}2gw^+|VX96vG0Qi*Fm2>3voLHbW38FW{7#+DTiPzi z__!Og21XOv1jbCF#hPnd{_Qj4Se3>o@;0$v(@og@%O|p5YF9DJ#(P+&udi4ouK@PX zOf|NQ{$=+So0F#82sZhl71JC3o@aYLomufyp3y!(mhBq&#p<<68uMxVF!D8eB~Rwc zJtp&dZsr;GPh&nLw4>lOZKHt2{UQ!WM<=@1XiZ+DZ8b|pPj`U%IIjiG0kTO zvTx3;W&O_FX54Guvgu&$8%=(*eFIYO_g~6tFx6KI*!>`F^YX* z>BB~UZs57D>fmKZePU?02f1=JkqyW&VgDp2vz}uz**2qGpq@|wCtW;usN=~qQo`!2h-M!a zsIuE;X)-HnhBJ>V^LY>J3fYRShGfC_LyU}FDRbf7684jv9TOl^%8aVqMl|+YvU+)= z*tA`;><2ST=9lavW{1Ne)=XtGb1#fzerqJ~G>z}GD}IKu-lGb6V+a3bozRY*+c<>{ zIj6z~y?Dx`dgLrbvd2 zPG;4s#O!LXon*A;Q8MF_1v&3=i&+x#L1K^LL>y^D+~n`Ddg?vIA^0qbKNd-d@hCQx zCz;6^@q>(9@4!O#e0IP#L;n2C2-3ggEPJ;-f^>4L$U|-r**SSV+0q!yo@Omc!16eD zM1DS7pB2I$w!1^*v>I)-zh|?LC)cxX4@}5*t#-z5gNT`#lgB#WI>Y=*A&=ybvuQ4}{2}4@*@m)QsCK)spZfQcC2b*uGYDh{{QkuJE*j6i z9-l`V4(5<@e`EGUr4nD*t4u;nJV}e>dxKY(vubC%*c0uhL^<~$o8xzxbqZ5s`U{b< zUOa}_j1-Zvx%G_d_nW**MOV_f^(=c(u8Fub?jW{|BLC%yRMtN48ZqCc!T0g(Bh^7Y z?1B$o{52H?d{*r*kx}Yq&i^xHOJw)3YeSE*BRkKM|IuIQT@(5LukIiC|NZ^Lf31Jx z{yY6e@THNc@Xi?SozCV)9`)jjyGC+`U5W7IfH9{RqRXw8jR3z>kE!WJG56aqf&V{z zH7b3!wvt@e{LknAeP5#~qx~ORJ&9CL^FO6}_HN;|`t#$(rQxG%2d-5UZk)KRcDpOq zgbx}loZn$r8)Q7Xc1J=&t*f36+XMACS4EQAWAqqDpt5XYNBva z%6;*kmaVmwKUN9*eZ~k+PY$hJ@A|T)pYa!3aUpgCou|}_WRrxN*DLM*1zm=>GG%s) zvj)_BzCWkt=eQ-pCx;w`Io%$@A@AC2W{iANqrJsl=qNl_do$&f-S<!W!4@cZJ(Ej@FE>{3Sehu}@gy-EUWa@Uxv*eve)K zF+IE2ZU<@}zP75(nc#vILr&CQzFZ&_&tiphbXoMqsP4FSvnQyyz{sFAAfQU`fB;V(LdQ*{rBCf2}ZDYu}i3WVJ&v*8L&J?n2^P>Oj|E&YlYXATKuO&11 zKmFf&nxn>l1i*hA|F#kh?ti0yJu*-gK2)nfXx>(^aGDRv%Z7o4M?Xzd*betp^`QRg zetN`xEv)XJ1ksZ!;eYJ4A{yrZuYSKI0sQCh-{y6h|E}ASzvWpkIYhe2kb*7}XO_;b zmun~KXFJHX_fPl(9zG?j)4q_qqx$|Y|5Z<`a{gD}FVSoM=lB2D{7W=={|*0R5=TRr z?qrA;y@grv$Ki0_5zJ^>ft$8cx;kPhXYXx>#epCB7DnD+d?EyTnwR5}6XW5{xmBor zY6sK_`8dWm6#rxdz}gS3w5&D`?uT2TBsEL*_hD}oyf2u7*5OZ~bJtubu!^QQcN3$uItqV~0JB7VD_o?#^HJF@eAolri7;n7PhSNXoaM8NQu=i)8)O_R=HdZf4v*Y{A z^XZrm-uw&0ukbaRJVcrc1$5!uY|)(i`#1<#PGzc2i`FKb7a1k{^RMoEFSE zoyw`Nb*GO$wV++?Y4FHb6)djGggt*(p;KZKtYZ2w=lWY%+ov3sEJ&8_E22A%{ z;9^~4sJU_~=U(}f#%Iez{qJb{H&q!wq$@*mVLgp?L#}501gUZC{Qj5IXw-%biwDr8 z+5i?qld)BP79RZ=k1KDabFi+B?>a29`qq-EumgQz+0p69YRCh*#^JREQ=!?#0DE5v z(X3!1e9fn{ygU-<%rR2?M^n!l`uKi5E=F0w#nOYEif)I<$x@wL?4=;ke4-Bb^+$>q z?D`Aucgw>CW0up?c*_5D+6tC@iKY*gMV$K4)p%56K4uU7#!YXPrNdsTah|PrIBEUk zvyMDX(@la7?K3d3W{AKxE+1VpveE6zX$*Gyz$tX-RQu}6Vrp6(*RH(~P6e#NCsn68 zRjd0nTTU4qM#*7a@G&eC1brG4xDbEUegH0pFe9VD(7=66K8; zaF1F{830d}`sm4yWQaMx1Itab=z=;ua9+q^Z@V!FN2}qCb}F@9>@FDMkFSaNZNU^; zIHs9f+twCk}K$XL7JWZozG zprDVNu5E^Q%Mmbe|A-!@L+@0!bG?qrg5C8OVBf(+EE+i(6aE#`+r108 z_BGpZy_E~+|0)-(G?&5TCVTw5dnR~nksNNvjsS5S{n4)jFj3xrWjqpq>aV+)6JOf+3N?e_B8iP zHIiD2l0a4c1*8_uL!n_djA^UF%H&QO`{FJ)bKwqJ94Uf(8_UqE-V~2m_y9c1!j$Y% zaNj12{*JOz`^UR@KX7O|3O&Wff<(0mf^RjdVrRo@9AtJ2Q+JMoj5)HnGRTKsnj?nD zifXXY%f(4UCqwS@Tr4T0(EnmDhN_jLmtz@h+qeMh)4O3>gY@z8JJc0(l`WwxX&S5; z90967S}|gY6L2$4V7zDnchgQ@tmRVyTbx?Bq;(-2<7`~b^IplNDm>(mYU-=r(Pf5# z*~e*a+dJ|uH-W!8H=bMdX^hl-6gGEb`HWZa#N|D_`6(yxYhNrLzVHF(tfU2_$M?d5 zP<`>l8M*@5*-_B$bOxqI#$v8#CIk=ZrFP3@;dQB|IHoQeYqiwj+RoinMSK$`D=n1T zKb(X8u)t~(eie)s3^7gu|27*e8HvLtwDjs3WpaKlA@c^qA`MB&?H7xRsM6=*C__Def z>WaK@a7Pblr9?{2hhqI*PB6C~% zY>$Al<3&&xn1L4dn$UJ~F}^<+0{W?w@XPT4{4-z~bU7r@{`*&fliMjZ4uz6w^vK)u z=%{;x|4*31sd)?nU%vt9a5D&G?jHkjOETUXAI=T$eolW5KF0UnuUD-+aR@hyuLpjw z6mf~a5Ie`s;;vUT(uZEtx#FEX5!D8%^O$O*0$OeR20Pyr!pfc(aDE*T5C3(93;r7f zkq6S?>Xa#B*<1R8>lcr6Q{)t(J1K_RDRJDBSLZl4xmh$yEgjztxk98H0Iv7_=KL@Ofzpn%+48^etfb_Xvp1zbQ42ZQKYj;~JnMM^$iHzZ|?D zKEg~g9=`?{;`GAXd`kl}6mLJonGSD(?uo^)#w`s4FUP=<8y9hqd=oTTq~P{jjcDW} zhIg{j82h*x+I$yF?H{7tNf;7P3r7mq!zHsjF#3^>xNg-M&f8BJBsZXNd`}1JMg4^c zb{}_Ye>C)Xug3Y;gJJ#r!Q46@BdYK~PP~Hug5Xh66f>r%5xblP;(Sap9;N}W&t99)bmVmrC=@oIv<)n1U;c?2gna@?or zGRR7?1v$l`VxFdq;73CQun$?NoGFV@-x9!~&<;0yaPZ?eqFsC@-kioj_gZ;Wb@zg3 z*XdIGN9%k$9F;y)F!_g-K+iE)kbliYykpcOJm_X6&UZS;)y|9LzQ4_*3+C!Mij2K=D-! z?EicPEe|;1{^d(>j*}Hw4;w>HZx5mO6i0*jY$k-}X5gSIPk8cqJhnC1L&w$>T<7kA zuOiH##amJ|j~78(^8u-GEDxW=H*aC!&?yUeRox7iyP_~T#28(5R%7jF5w}KC-`X(>;=**K#!=`0 z6V0FlN8MUXJ0iRwKeL$Y&|idc3(i9hV<^~S(Tu}_WZ=fNOE~-SD|&rX9rtTjFulFD z7Lp(3VE9Q3jMtb1oq_u?#pXCn<-MZa4uhrk(;c&$&}Vo#Twq%uwdW-~9nKTiN*wh# z-yELaI}0j9HN@9Hd;`NF-q0&51KZh&n3h}#Pmab>_GTt`U4DqzS#~D|1}1Z&pBi-C zry7{1w_a*KhPf}K%|RU5nkj&}t(0HQ{G{Kfm~h+e{&2E8y}3E>1Xwu55ssJc=lVKN zafNPS^oG?#Zp7~#k^5!jFAh{foRUe0EDYv%vpYo^jEM8>86 zy+|yZrwu*gJM`U{8PM4oCpC^1lZD*9 zCG=@;4R@n{3-+zD#SP!Ca!bzZ(C7*Jjz-&Hl zIB*Wq(`HKTr-qGX{P490!06%_L8n+&@N4}8+&X9&dMK>GI?*m#>TQWy7ecs#=XYSL z%SpgPN!VtQ4j(5p;4Q6du%ka5?|iFA&F7V{D`^Y<>lDLwF;8k7PhO^@(T5XwDaMp$ z&b-U5{4JS%GCPK`k??qT$odV8H(@;j@OPUcvsrl%# zJcDl*gh5G9BrL0W4B{oqVo%9D#fq*zZk;y;g%>Yy-k*DrpP0eL-VOji{aI+|w-*E# zthiea>hxk;FMclVreCs$Q2nGt{=2?V81LdNHI8K~bGSUmY)Iy01WrzskhH24Q`QW^ zr5YJ@Xs`qKCw&RdT{IAUmp4Gi#0WTk)E8gv+623XS7Avjg8q|Gyf0IOW0#b}>7)=m zHue~3Gg?yP`1)&^DBB|sZkK-nm#`>!T>l1}KG@KuHui93bUGBRRu<#4PoOY;66OYCf+?Q11|w>X5q4DI06;*WIF>v$+o{VR3cF5VlB7v~(Kr+XCz z@-H{QU#kTuIys#-3yNW6Un1nX_2RKRSAb{c4Ch|h!2WkCShX}7)KC#M7b}Cs=}Igx z2*aPNlpuCx7WF+i1@=9Rlp06mja<>pdCx$lG#jeEJ%OU^5#o(bhp6TCW4L=u2=}8V ziS{gKxOnBAkgj$ROcw6N_0zv_%y|wgoxMS8=p_98U;$n~J{9J-Hqg{7WzaRwMQXeJ zK4yWR{#c;$l};FQ`@87F{aHBBbQAsdV1!_iaU)Fauo5$H4Kg?fC}`0FgSs+0ZP#Y- z{G);w1ZMEU^bFn)IF8RWJz=!IF)nnohDUo{q<+7>^gB(|Vc`KuJ!KH0<_EQJ(lNC# zoEC&!rIAVs+_bh_x_NONw<2^q*c_Vyic@*`bAUA%zFLGuH7lU%oE5^h01R@FXbrDx zpvZDJOgQvTYP-DLzktqHp9nS^H6ioq4WNr+P&m&X69p02)}{-ew|?Z}jvb}Wa*8yy zcMKHzFu3;NQqJhbWG*6gC_O%19bdod<#(HJrOKU!oTV%SZ7*D<)#>49oVOVOi z2uJ!2gimjlp-%fO7}?k>>eO_Tnh&$D{WR;qVQd(=4$pM$=9cN*=RZlhBKkN|K@dKy z1A;dhiSy-rp>S&i&ek4<*XP=Sp*({}^QysWc`jc4{)9dn&V$EIJFqN32+nhy@w8-4 zp0xFkSv?22OTE#2mAUeQsg*_G`@sWK=4s-cFcY*tbyZZq@~)_UOs1q>y&vLh-9biw z0!~%tga6Crn6hORCYt${VhkEG_KXZvRE;Jh@-N_q$fw$*Tx zqs+J`i7J@;;EZV2zEI9Ex3&5MmrIALh0%3t=lMfwRp>2;1ks$uy4>2pi=uDMSt3Wt z?3l;zDn)O@mvHeJx%^=3xl-eJIBJ=shNBBlB%1D9pO(SA#SwVwy<{H6xjycpwI&pg zXv6f%1lXb{sePqxbL z`C~HBz~vZBbN9j{aapKtatO|OOvkjyOt9BAkUCxt)4gbMOcCyM{DcTy1!x<59DhF= z#qF>;1NXl9Lr~ghEROsL3ZBd0>@Hh4r>ca9nj^q^nGJSWPXyl~CAj0?L40y+EEI

Pv$0b60#_!^fZ83cqPa?AtL6DNg3xPn;-dZ{C_NvIE&5q-qTmNE@hrj*Df@vWaM%|)0uF$WJk zt)Tv>0jYJnIMIlUbbfyU6uNzYy}8G6?@brDujz+A>0jv)$=NLGb_X?D7zuoCEl&U0 zOoay(;0{hi$*LqMzp0Ad*E2b3<5sIkO%%8MTJ<1{FrwQXLFW3A>Sdc{`KQ7S`1Y@h zS-~?m(M=l1Pe^-Sy~L}I4G$}+nzQB(8NPt!ABdPFTG?VKI_ZCvT(g-a+I2>oFFR&% zRo}nzDrs>f4^QI{DKmqevf=Q(gV1K^Q+LpZ-2@j7z-jNjF`X4aW^1bK@R7pz!4! z{=DBQI`Xra>O|!5cRSm20q$8+`)P^N0Jvx{M=+~&pund>AgCC{avR=qRLDT_`?=RjiY|!I5^V%4}$Z@2sV1ZfVroY z#o1q{qfvtso>KFX%;|E*NwGtq;qE_}v8f(z-_65Oorl0|{15d1{0ka(oIq3E@3=1c zEj%nefi8V7LCHY+y2A*`eVf_rZ|GpLnX13O!%cNCfY{54RB6j2STXe$TwMPfYdd|x zIynX%v)+rERpxQ4f}fCUj|wDrh*|i4Mm#RH>vg>Qz(8m1FJSW!rzL~s4?ZY)cIrfGFNCTx(a_Eor9Wj$AQ`2g0g-?aLf0( z7@B^Fa~i&t7GBQeyn>Sd#0=9QY%d>CGxg;gsb(p5wsZ9X-T zY2zhxmAozKw}VF@O}7Pp)=BCLHyL<6+zaD>YtmqG7eDdVFZS!wdGNr@84a1mC^xl) zbKN)!f4&|DQ3}^Zt*2C_&L3?D5^%z%z1U@Zk|xIf;=+Yd+(Oels>H1Xl~+x0fBrno zHvxE_w;1RAZKN@OTDkr`C#kIQdT4mH00ZjJQyp!|JzdH;w7+KwwKCnbZ}l{(`Ka#h zrOs-t-0Lb$!9P=L@QM$|_j4a}u0tc>Re&y^+ti4URfY)E8+>3&9tT~jidZ`T5HwCP z#^*0JK{uG9VstR-oqNLR7Tp(J$aRP2C1FzYaVtNDF6(d;PcjMMnhH!&AUX?M7Uzk+ z+1UtQ7d(Q|JIuusjq70zI~o0Q*JF@M61?pAM-4nvz-e+YX7df`29sM{bfg6)o9^KT z>c*gC9uY|UoZGi}7Dfa&a3!Um!2YkDz_DV27=LZ1{F$3L?Ex7u>e_g*V?YfovVP8a ze6xcgdtTEaI#Jxs+Kcb>JA3GLZs%yRqZ5wGq8di zc2-7UXXF44Z_}{T?+$;aeJq@tH5OuGl*9`D{ZR601^DXQfX%ljbo69j_;FSfe_a|1 z>BF*c>a!5ky`lp%y=!S*vNQDW;H1V8pxVx_mh70A7UC!fvQ-uQ4mpY&b$xM2<06c# z8cYwQL{g)TOCB{~Px}boWv}_s}n&TUnw_i^iq$WA13u#V@_3?*H)g?+_(h{=v*Ed*QCq zO1k5f1C(z+FVdMfSm60M5f)bs6CXZR2S4_-aJJziL{4{-xckqpb1w#}(eS5JIHN5~ zQHC=^rMxDtsOk~z_&bc+9O3W$Zfd|GCfytUu`)3al-?j2)e1K z^>aGX=rwo!;&r&UAqBdNLr{6@A$Z$VkCScdAo@rcE=r)7ZBYcBcLOjps~8eznMiGy zy!UQ&l2s>OUGWHR^7Xl^?J-JU7Gftbc-49|clz-t`lnb6jJoW=@q;b)4bR1!euPV7CAHuF zR8Bqj7ytT}b5h4kEuD{>pC6H&LDthNj)UOJXGKuCSVS{!7EAg(i{NH{D;_Ez2h93V zR392hV>TvpdGA|AgSPDh$1iKJ=A1PaPE~+g4<=)bw;$*fw$a-5X;S;C)uA_(l>6Z( zyAo>N{fN7JZ!W)Fznh5bS`Hc*h07O&w;ov zwNN@=R{Z3*HPqJa#YW55v}&HDpE0wRes@R(8G{{YUe!ZeuMdI|F9Abtdw^E7DtV-E*1IH$Vu+Iwv zWKTff8b{nk%qvKrh z1wKxmlS3PJ9*4d565G5H;rpI62*}ZaG;Ja1tv1JHKNG;LLKCO94ghO^5x$8H!Mq^~ zFl4|XdP&O{NaQD}{nYwqk4R`=f&RK*xMg=I)7W87kenr=kBTc{v%m$?zs8_-5+Af9 zWl%5SLsj)b8UCF|ySPCiGN9c5mDai%;F|R^oM>AcbzXIui;R?`k5$)5eNLYFs+6ma zh=MO`?!i&-L^zj40W|ZN4pLsNX%2{q%*BAc&&nszwV>%p|&g^oWa8sTV*gOt;%(Z~o@ z!gh;#{@9V5=k|im+ z+_#=4M4c4PkNd-CZo`+9ENW3gJXS- zSl@jOQq3jrv@b5eu|=>2{Ke|W)SFe|*lsp|LPM->M!c`8}LqU2hA zc|`_);CGIz7-j^!a+Hz%XoM+a=5Wd9mC@?5GAJ+jCBg_Lsq^|!5{<*RUxKu?0vMRs z2rKSsiC2*hZdKVB7%Qj+?IS;M)L(f)rPE-3!YD_GnyZh)*9zeSznvSivX!okd5$Z; z`qJ!SH>et$!!X zYnpGsi*qsDe$UfjW`6{I)}I86GfiCl>k>L&$4Il1W=>=cnJC_1_<~@0C8d zFHnTu*w1vtu5)J>Js;wR;No^tPOhr>M60aD{QXdQ`TiwE%oU4=N)I*V_r+C%RI z25}F3Q{nZXbMWd)4W2x)2446(W7(axBJG?CzFUZ-j``jb8fLqqoofIFF!|iR#L@Uq zG#Z+gofMU>QIh&O_pW6gOpm%L8JPJEo`+qPyfey(lLk)5C+(?dzdM2RiB&||b{Q^j zY5~kLErgPWH2lSz4VxT~VUKJv%z{`Sf``m^DmhBNLnx&y8oHc8FLoWGB_Pk*!F ztMMZU-?#+^6;z{OuN?hY_LI(ga)JJJ{z`XR$O0MN2(#XY!losjIAhF8n52CMA3Qk? zXPo?Tw&WaT;B_1<+C$KD%|WQyGEiz9YbM;~?$!*&bM33)*N0XvG2sB2{bLsH-5n*8 zJMotn$&i&{VUNrcC~UpJQX>spz~aC_W`_jbrpB@%~S4!OA^!ywqo3$0}$ipPW)n( zp!an*b*hnp(>mw58wnSw(!XOEU=ks!cB-aNN6aSbZR)Ubs`U5j6K=?fdnXJ4(;X{- zzoiL=udYCIA6bqp2m<}OczBrp1qb+^g#$JYl%3MaUAcUV>W`faBNPTfP^A*~d0)Yy zLz=4}ZPdaSUTW}Tp&Y!fy&^RqaZ4uP@}XULTJr?0*Zsgfxb=*)QOl*Eas$Mx#W1|M zABS{mgQc<$ey|RwH{Mrs+16_)Z`C0X9@~cx_~v*wLJd|FIAiPck>KZapH`KOkUF1U zwVp!t7V6-~Mmg^Nz5Dc6B62-JQ@B8z5J-6-=G;5yVeDN7-l|xNMp_>dJ!R!NuaCR9 z5fhC0Ef@1dfopncO6n-;oq4}Hv#z1KHtmIIz5Fw&-(UPzXVA2yB5s>m0TgW>1s%cr z@#>SuT+4W4xIADWWG=45zJmLbS@DW6dV3?+YpzHA@4w|PrLLr_gWC=eb%E4&3EeUW zwF(cSp05(Uz9fT7FqZTr|5m}{zgi(xvcu$I-&agpW&ua!LNUXyT=duF4!>ruET^Ej zAC8FEp<8wsMhNb6x7SX=4+cW8m+_$^atBK7r=C?NqQhGLc&I&!vz;`D<|g)Wy%J4M zOZ{}v_8JNWkEUac*(L6-?l#Iw_Ks|Ej}~1nDB(UoU%`d@E~1KhCU_}OUi3M_n%?m1 z<7aW(`QtPGO8wsOwfH10JK7JnCyfN=E-nJS0b1h6iDxkGl%`lTavRqdaf`2^tV?^( z$HKkz7C3=d@N>;(u*izR`w!A!!kk#Fbc(<=iCbV+0G|%X=>ap((^BWtM}2`9Qyq&w zX(#!AZ%u*qiTAnIAQ}8+k_D%+09Ks7ghSs=1pSU3=&Y|qD?Tf5@de@h+4URYuF67G z{WTMvZ$9JZCJQk&&llYGN76j`OsV-ev3)Jry8ed3pMN0Y@pb49_=eG2g}CO2Kbj2? zb1A&TbmK{7FbTQ|iepZ}uj+%CH()u8&S}P7n%BYdNfxeZzJY^pUW9jZ60s`b9?V!F z{ryXtAPh4nKfulIx9O9|2e|iEd$~cu`l!9G2Cl4-^d6izi}hPCaAiLG(CYP3diRTD z*Wd61bYD$|q*po=^>z=&2WQkF)W->Bzvw_pO#%IV>#5ZF!`gp0qTfVX^GB9L&kw4@rUI?ZyYYsFOt>D_&hjAl%G|}S5^>ItJMvIc4rMtmXk;OvvJ(S z`LdYYF$CHV<%mqrr&LQ@PfoV`gC{2x!A6^_u>0c+*tWr19MkOyfAY6O>z^DL9X(u} z9AY9kw#^T2nR1Zm-$T9imqOq5jg-#L;1V}n!*D}C?D<;8tx$EQy6=~OuESKR<2Lz> zF&;czfj`fL(vlWy$on;rb3QOqG*pxiZ$?+bR_!kQ?Xn#rTUoUEn?YA6zTj@8M$&-U zu@Ks1W4F9G8e>()IUoj9~eeR(1cST8^$3CWA#1rl!%nF)7PdhPO*`)*A_V?o{ z`&2w({h`^0q$w*^oth|J{I5r_aLr&t16S#sY9LJb)E} zl6|7LPI5A~iK5@zC3nn)>G;)mKHBV^0OJOP;R?HTpb`Cz7Vuo9_S57WM`-)vSjnB2 zGu@Iqms@z&PgHc^sHnGe6a4B*hD%4|F#r81$ek;q9w+aLR8%)`)py6y?pYF@i;kS+ zF7q)J@IAPU<^l?hlQ|=QeLC^;d#P~@5w5_{Z3D&izqix2*AKa--jQ(Wr51k9Qx~jy ztSESL%2d2yNC1r86OFIt+SB=L3b)V2Q8YoLMpE-XiRUH5JN|7kf<@ioIQ{N8*tD>n zUQ#HRI$q=sj^eX7{=%K>&!O=8Si#i`#^Qx4fygU*jeBow;ieegrc;=u^z-cHP`xe( z`mUwmj6I6*OJN@F(cA-vg8AtGV*1w^WG7N63s);Zg)5x*M&`+ zPT~Q|c$iVBy!1V6D0e4YSt4@U17Q>h3J5`#(}j zI;h(FTzvgAhN{<_!T6^A95YZE^>+Bfywu}xO-+PDx?@HC-ovrXwM=BVX*Bm@nF&3_ z_lEvpD~z`JNi~OE<7Ad9p!$eY+@bwzseZTg{vi{c$GLy41FdY9uqU+if3h(MC zV{y+#F#ZxRwOt0EYv*S@65{(dF-&+qn6vqGjDGojf#2PE5}uCKfe*q)yzX!X;s#&m z7Wh%lzDAvXS)mU>w-(Sw>up@4?oymNZwxvVWpeKQgQ!X88Lr>ILF)5q(}yXj5;6~0 zj|&s+9zO@heO}4s50U8be)vIeEhviIK+H5n(#lUnlmf6r6WlKId5^R|-R+mmE`{;NOT>TBe;ODw5ha-Jxee7sP_F`BvV}8mq0pMwXgZ2_J+GV>U?bxB&iQ8B@rLrY*_`8r zc<1wS7A)ln-u$wa_B?n!$%X$%_a6D}3w)R6aeRHrzSX+aGEzKkFL~h+O3V(eBXMh| z6OE$hB&ocMJhpvCqK{o5`M+P2zr*`T#j`Wyt>7zJ|GtatD(WU@H+&}D_v@tQ!z$_- ztDfA%8g(YJ5oxL!jGd{R$`+F_c4x~{R$4y9%UcLnS3~Zkogq&0M*J5J^T>I@ zA~Gz)n5aA<gk?j>JL3qe!-pe>&_yM9To&Xx|8o+&ZO{* zJ+a90CC@bGNzF&!HA{Z2q^DB1xsSYc-^fqmrI3P;Rm8H(jdYC)ATxJ)68E7g#ILf9 zv?v}Y6)R7YX5$US?{Pgj_~{ZkT@^`=6||7Arq_s~-C5#3xSagpGNi^4x$!7T>3Bvu zpny~m8~)CHYl-?nE28y5;N>6K@tuCe`>hq}whAPjn(@T6b^=LU5JdL<*hx&v zLx|<=Sfafkm^5{6CUjXQ`C+|^49?p`3KaK{x{<-;_n<)9zwp5sUK>%Ga=GmFW0GM`*NZ%uv`EhAs8Jjv@sUvkWJHHl7fmKw+B zXfZL^oJf|fX(SK2UX%LjHAL~iS9Z_aVZ=P4mOZXi!zO1muzz1KArBucC324Qi9(VC z$-l6c+{|4`#(p;>J1(yyx*pzS{0DE6sj-Ii9k-Ag$1!FgKkKw)AL!9Dq_ue#zoE)T zGV^RH(HRy&yb@GMxut+CElwq_lj6zDlxw6+{x*5r^_cW;6A|OlBatE;u^8?w+KW?n<^o4ARXMogsedn5a{Qkrr#OKslexn@AUp#s+ z|5nR-f=Opc=;Na#YHSMe-g}jd(o7)}+>=TA^eAGYzn6TNa+uWX9U+hHr<0EF`^miF zIpp;EL*zBOnJ}m{rJ9X{oi%opS8{heY)1Z_jBKSU;Em7<6!tR?CJ9m zom(1VReJ?)&)*?X@(;&P<>1ELvyfYv429?m@bE~4N#IG;^*aj%Q97;(55l2Dj4i1d z*z)Hjd@sr#pVsAl!qNNEjnbRmATCG9Y?u-YGG;CM#ZN>Mb;dO}AKYN|aoj%?3A=V+ z#?uJAedPy)?8WVbP?&ID_~jXaH`crG%V;y?_QasD_YRruVKLm9*>vd~^sehODz1Z= zzgx>N#{L4lRF2~AzYBO7eG`MTrEi(tRpd+W%HStW$nPlu^IeSIy?LDYU5MiH3at4l zg7Lj_T=H$k;PFpn#zAYmnSHOa;k&pV(ZByetu+$?3r=F!{3?_SYLHmefQLuYaA$cj zOsy(mZdZ+hnnKCxz1DQE~N0FQN9EGob`thI6fO{OL9@B5{9e6Jbtytq4xU& z9J9HPs-rhiq?`rgRT=QVaTEJ{9l~|f3^->T$G4ZYXqB&&*+2eCcPSXOw+TMKb0j^v z#$;~F2f^ehCqeW3BZ3{lA#A z7=Y;MI+!5cIa@t)BVu;@;^**Xu(-4s0WX44b!7*fuMlkevZej|5W)KF?O0Mm@WkQ}SN*nd$2 zho&iFr~E*)HuaI&9*6!ZG0Kah@bOV2x{o%XH8Tm1Ga{fQ0$Ngi(WT=Ci=ZAdY+Dj$ z{)$3FR5HGlFT}oI(GZ30LvI6Lsc*)kb#4@{ZrqFAei`s#5@p8W^s5h(IPNu~b^0=g z{p^_*`+S@|8w?c(S9C2k#p4ZQvB%vU>yGCjesdOdHk`l<>0WA+XL(oEvt%Bt?3EARl zhP?D~5VULqdAS?Qb7FBVc?pvDSfjR2BAiw;D7!Wid56a$!fFT9f@J3l^>d#g)ieZ` zovy+#? zF15){=!vD=#Sb4ulyAVlndUOv!>z@RxzNynF^iwzg28OY`bRSS3R6&W{1mEMGV$q* zFCs>r!r8>ts2U^25%Cpx<2v47%7BA=GD4eg!E{~>#BRi7M0%#gr!X@$%Bpa9=$8tZ(kR%atU$_gCyXldLeTbb*bjYAu0}=x9#PnMZa+>;io~@0VQ3VF z3u-FDyLdPPuVG&5cJYb?otd;nTyW8VQ8(6fhV&OsnvT(po;-6 z+CCsfeR^R=#|#quwl}m_+#-%zSIOe}>`8sUG6#Wkl916Hfy-lM=Yy`cKPRfMYKUXD0OQK_5U+oa z%)4epBD8&oXXgyE^P($p(Q6Q_l6yv8dZ!bYzS8|v+fvD?!aCxxp_Y_RUrf?^YRPWr zd*puf6B07JkX+6c%50C2#{@IprQvP5Gj1e)Mof(=j*Q7Azdww`tp%4!NKqY;8?ld6 z4J{`5bN&)T*Is!1%LLv=(im}W3fbQ#M3g#5J|BoA2Ry`N%-!FFt5lTPKd$wwkjC0x z5WVXl(KCj_u=^PaRyRfCO>HPTDZ@(ihGcCU0?QofP6XXZJbN97wz-k8X_<%SR7aSd zJA|j7tuS=75bw&RJF`=y-}V97?{#Jo%Q$*TW94&qiK}4kYZ%?x+i~fy1>~xc_P(w4LW; zXo@GEU6_c@vr7?ve;!2ZZK3daG2*jk$c!T|Y%-bQV@H-`-4s;n93>%rqXg;Ve*(5~ zui(Ru=Ym3oe8JlGc0uij9D(p?w!nqID3}{pFW9@{lHk*#V*-VnuLb9-j|x`NfubS$jf03Gk;GUGVu^%W)=d$G#)70f*9A@@zXcdkSi@gr^E{(LYh-w(mYMZFPy ze+$;$+k%6}K8RCUjb%04vEW7s-mU=B8$+RDu^mB;+mKPe10`;Z%s3L9Co;Qyq%iu(KsZ1^U@ur;?v1_aP;^>lG%JLYRm!SE!|z^EyhNiz@N&)u)BC3 zo_5DDvpNw=ePVF1G!Ns$WseKhMm~aH#a$T8n2G3ZU#0x$SHh$@;m~l3OlLD_e>a9} z)B>zqITxaw7~G9X#GoVbcr!K{->r9ItM6e9e!dFnHi5{Na_}EM#UW)`n#}gNshwt_ z5eVSgrBuztqoY5ZV|vXnCOoln}#eKq@8EZz`n!KEcxe7~A% z@u||s;%A75MckTvi{UW~EduqHTkz&C7Wre+ES|4Uw2(EA+Nv@e9@-m`eQ7$rn2Mlt zMi=rQj}V}Nj1UnTF{eI`k^s=W!W8{4@=*AT?I^Y@6r4>Xe z?J9}BTS3;{6_LMH=w7?Scg?B&C!?yDdrrmA8NAll)H1AqHnhHlF<+n!4&OINg4?kbC*z_pqul{k=l9^@iwGo* zo&(d}kvJ*Md4=x5X#1Xk_sO#7FPd+*<4eYVT-u?5q1uI@2hNd>?k+;7zaZJ|d8EVc z0EyeH4Wmn+NtLQI_RV#}t`2uJOg2KrW^JUFt;UL3n($Rr0e7M=3@^FjZU5Oa`^SsW z6x62eCW^tO#AziX{-N|(g9s$L{B4$4=N;!EIP=ERz;LecSpteC8&v5jQKrg z_+e~_d3Sv=$7Lv9og0COpdmP?G9M45HFp_5mtMP9AHh${Ltvij;pnro_<7;<+FEW|M4%R`tC4XB*S5I+aCJ@XM!!5f&I_y@M4rXLVhiP>(miYFf)QbKMtD~ zIpVO&BAIav$?whVcn|>JYnL%n=@QEB$KqjZ1V)|KLVKeNzK*iQx0?QFZc4>Vjc{xp zBjp@Qolr*)z$`Q!4mwN0d1RogECr?G6A*pkAf6&rW*n}8^BLpg^BF^*J?QHl&Fq|Y z8g{}*P@2_&l1J}wNllfhZQ0X%QGt#7c z?Jw+r#+FdrYL&>0W9av}j6(NJ#`d8m^P>1D)9=qGyuBI?ABQ_Q?06Bi!jGtK%*I4% z-t8sl55qy>ShHHn>&FM8w%;bC!UvPWD7@QapePK2Lh}yvBqqy@qdM|0Ca+$E&Xf{( zRmS1xb`Knhb%RZj7240c;Jip$ulLo)nVZ3=>{$;(jbOyNcw^Y>?P$Le3RaqfZc3DD zG2ZRL^^@!2@P0R9B`amdaq-$jX2TPPX$Ul7XjLY&;4` z)}MkcL2_i>yP*O-L60D1yaGuvy)Kw#vRClgLQUqpLC$hCbIoNt#y*vhd*4FPzF;m&7PIEr7`z^%;_-*zoQ?uVgxx7!JZ58SbG*I;y++Tv>LDx}R` zj8YGG7~3tB*&fxIHxYXz1*6|c`VojmbH(p*)I>d=X-GY z@*1r8z8V+45VZA3`P1%L7_YX#)TsxsSIXbCR_{i$w1#PxZ6z}fw^DuM zvp z*rk^SHAb309120jh)pu%Sh(^9hWxF;)P5rn=J_42bAAvSHV4liSwOtf04_ONQjMAi z0yQUL@Qx^qa!Nqc0O?zJY%xZ=&BDsbhY%LSVje#o*>%>K$wy;nsqFf(OYyo)_pYB9 zbT9_Tj}2nf<{09^(w+D_AOiE+7vNuLFoqtDz|&)=F!WG9{G!iEZFK>MI?v*%btZ<* zu0Zd+ScDZPqtQ4CW5lP?yH0jpa#7c1yzaO{W(c2<>xaXLrCc02Ic_L|{|&&B_r@65 zX^nqUe%-R&7Cn*fSems2XEu0Yqx)=VPML-6=>aHjF-Ou^7hLRZgJZGoh$~qy^SPuH zs56htR^WJzEg}uZVB$DMDQ~$0*%N)yJUapA+j22>@(k#=XCY|bVf4?*hVb+WJS)zE zgJUMfBo!n7VJwnIOKZt*kK>Q$5zPNuC^L@LUXje&-!I_wZz}UgYa-K^?ZAo6x1nx* z6Q9g0@Nh^I231#hjF5(Hc&wPt{eeR-h&U>7Q{)%@4FQaF|M|_;yfivCpP&aGG zZ>>g|aa?OUfm6?iqIsM*Zq@lB^oj-o4m6U%X}xi%Ls|#Dc#Ak&4!{ZLK3FJHl4@c8 zk$sC^k+!o62rE@ZL5P^_x~GJl0csd+-wT5eDPyqrBboCk3Hyv9ayGz=wugN~9k(RQ-N zdn+kbTS*j(rGGztSY{m6rkQY)YAW|k3d4rUyK%431bGd^;BNnk+^*;g$5D#Xx@0_g zeA@!=O~>G-n>prQRl@qX$(Z)o0?GF3Xr=@zUnYS2Wq@17LNM=5WIh+O8DC+!AsuEZ z(tXQWAMr$U1N7g_LHSS%tbgea@*)WNTl(O&^Jb{53`Af|IL3D`gL21a&}ADjxX&C^ z?F+)VrT}c8w*s-!c>2|&-7@32@aZEO(kf6LI~6bNKH|-s52Rr40=(*3g=bnmc+(aH zqg(Tl;OhZ}CU4C7x)H7LgLlAI)C}2x&*ouJdFqClA={wEti+3pYcXwpgv>ZZUJ~pX zcYtJ_JVq9U#*mv!?a7s2lknVI1y9qhQPfWn>FfY3{r8z<)JtQqCG$|sIe}`8!tSRd zkiKX!*xA~MD;*Evl94d}ITL}oo-*T@xz&{!_QsYmTw>0Y-%Vsne4ar0gj8>0orTS- zFF-xwE(Yd?q4RAO77V`)zYkBaW~>BWDb>)LdK*WiT*bVdQqAV4Dy*Dy8L65t;WSnD z?{;eJ7Dh+03vMnp%$Ssd)?*8BqwFEx$BU7uwFU29D=||8I$$ zabas1t_8`i*S^d(;PUGVG+i^rVA zN7^%EJZE*Vpsg2t?{$$CmnH$R4@gJ$0EA2R)HfrBp+f+-I$`XEVO;8Mp~a= z_;m3A%-auP(b=bvTU`Ug&NrxWjmK;$Csa7~AQX)=Vc9<$E4&M_&#M?#hNl~5qv`a$X9NPmdv0tj&`87Ko>n~+t|NLBZbO*t*(+^Wx zituX8N{kq^1#=C;@$E%A-1=w9Y>y#!g>WcxCSOI0piK)%$01L0{=O1cuI?ht`z-SK zLKKNqS4B$yQ79B8!NoTPOYUSL-+c`fM$JO5=oqN212%{)uvt2mL#;Upll>3Lj3c#T z1XJssg}X0)<5b;OY_dIw>t4suuDT8D%M+mN6oU_`>Y%N~_&w+t3YjyoGYx~a-YEp` z&BK+z2-sZ8#{%iO?p~jX{aGcjjgdY6czi1zDL+O+^F}Pz*>A$z7p@3S7zI)Da?%u= zO43%jkuQa5B(<+QY!WST|FJnX59x=2cb8+Gw;#3()UjaTb`&mKjh)Lp;QC}H^i}%F zY>%;d>fpW9@FpvsM0Afwb$h06TyU$;MvqMeCEtXEA|w5E`ZGdrZi zx}*83)6dW0#2KzN5aQ^EE zh+2(tYoqM!BLah%I7C#KJ&ix@@^?@|s zttXWdH>qaP6Th;2vE4cXcV|m=9>p<8Hx9=qEe zp-%)0mklKDy9X14obv*sza0XDtX{;fWpCko`u4tX;7eqVC<$3U6=V^+dO z{OszDnmz6~a^45Uftolp>j;_j_%l(@eM1hvABs(Chlt{_8gh2qO>(a3At^8_BS%hT z6W@o0=Y$}qZeOlV^40uKK z_CF+sg(GA>7g}x2*g3eM(Z>?k>Md}nWjegv5;6T?EbLr-Fi4uam5z;rS@1rPlVZ&9 zxP{(jS1`YDKL(qH0b{E%VR;BP)_Y^%#~A5bBtdAu2AOflhv;K1n@ZAeofBxBOC}3y zrjbE|77(3eH!|;l2GPusBd*E} zohIbum*B77eoJSID*E+<9bC5+V8B8_Gd}+ z>ZD|3O|igG}AYTiDEMWW@j>~+GpLN`Y4Lp3B?rp#`2L&k3HeO!5e6XJ7cfjd>O zIR66WJKf;T)WfsiL;R`#h(W6>a5hNi}{XRN=be7fe6!R%Uxd z>wiYxat9o1&_bhg2RSpdj_mrd6io>ZI5KfFLPq+*E6yB_f0v`gJp$hBogx#f?(zu2_kn;W*mnky`g*Dn9vS)@`}on*dLz+gMLL4{maM6 zfS?@WzBYqwEeRq^KE{%7KBvg0LuX0O`g7#!rsL$|(QGnqQwe!-Fo_&&%q4rio+f`t z0U39pRAxWbadl=Y59%^j^%l%4oxRLxyTOc^@_Gawsl}VXObq;R0-lpga0D^XsfxzG zg1rzdh?mC0hhdbTjuAPtFiv+j293_a_Si)1XxIk@za=u;qt3Z6bLQ}IT$bvs$`-sw zq#Q>~+&93@au1Gt^@Wd=+xJcj#~|NiXapR`Ik$YchZW+w&MCys%fN)v66BUfVWvk4 z5=O+LyXm;J)+c-4NtU#)xbvhQ{7+vav-%g2eXB)e`J<`0yR9$gYYQ<tI5hI6!MwwYbW{?=VgTTUW$RSvptqpj$kIN|AVHFo0R{19}!Gu8*aloCRtZf87pOMzw>L=s#u08Oa zvj?LCcf#YeBjS(R;H&0tZ2K}5HYcpGRLK$1XCqJ~^q1LB5AwNC>^_U2lwnBGzX2_! z7bGxC2PM+lA1_}-t`?sl%l;Z8{%1eD`xk<;K3N*$7>(x2W<(wQN|q{5gTMX+SV&`$I*T_6r0cs+E`NOG5oa~HSQXSKz4>ow%Y=)Pu z3(=xE99x$fLBYiYjKwrKfAo+UN0_vKvhck;BOz`0KGlP9XgiObf)l7+r-N~2(tPE< zBLaMOAyMZL>I>bl*=!X&hPlDzS0-Lgm(I6vk#d~v8MqUXfrX4zkBP0A;KpM5&ZY_M|$-dGVMPY^eVqe6s4ko|NQ=^87OQo@1XVTmzoJCPh7P;aQQ@Y z#=+L=znFody6v850v?LAcA1M~w0B!twl;{?DnhhNx}(~mYnZs<#xv2dL#pE5O@5*r zop@1$%SF-m7+&;E{f_8+<4EzNq#DsaHBYg7sfqYP-Z1gY0~X>ShYcdwMT=)y)r+w8 zp=d$2ns|87MbXDd4e^)=3$b3DL{zN7icUFP7M)r@N}LtBR-~k?CBC-bUi4$Cx;U}* zigb4SLs6pnVUgZlk?6sXZc(anv1t45>EbIUy~NWbZ$wFFHN>tz{X`y0OGJ9>b4B|c zzl)kC-4sP1s3|v5-6vWqodJ6>QC4VYn7 zyFen+UR@%Z;i4@b)Da_EDmp9rQ9Vm^_-2%7=keL%9@75nKW)+y4@n*_o;fvB^zZQ_ky%rJv5SF;II8-LsPeL#XqD6==}pnQD0wH z?9ew>w9BE7XqZ8@Xx4+-qFDxAqN>^Y;xDmpMWM>+qIJu{L|4{m-Y_FE~ z^gk)YCVL;|QsN!l>oH**E$1`&_T88<`8gst`Z0&kdSINL0QG6Mj4iu>d61$^pev29 zgAGu-CLLaZt>~rv5o1&K;ohP`m|K`KtotjhSvQ24pwfvFehJJRd(g4Dj@)r#aM~gp zmkNe5`BO4scf*iq*_PsWo(M|I?jvuRF{AlJBCYw{vREwbJ^goTC==myl{uL-nK@hR zz_d^FW+pGxVf<_BrJCyHPz>9HnSoK**V%$q7ULM5FXjyYuLTW91~Ns-d4hpvKXJO{ z6b`;@hCxp$*8c9xJWbEX+<{6=>YD)O_JaL*xcm{BzdaJ(3m#(skO%l@aRg48=1js7 zccwzhTTW;w#3N$QIPKraXlA}e@18X5)a=V7=IzDXnXkwvE(IQ~y_p#mKVkE7KPlFn zgA+~CJga0Zv;4|?;`Pahskf+u)jWn7yrdpmkIGADZCEqPHvjOvUo3(d!tg~J*edVG zJh2(V$i@7@EfR}kTW(^>o=$8&d<1l25XI7-mzRmb9d9r*6FWvYq%q+Oc zU36W?y=DEVmy#uab!i9pE#)4yam)}7a7>aMc=3TsF7f;ypE-Q=_t)Isi-XvI(T6z3 zu#3BR-jYojl)?Uec#`ipy@U@^9nJP>(B!p?ySOpE2)D1nfKN75W;J*9=Oc3x+0|!5 z>41ZB^hecpi7m#z~_MOOJO(iyx@8xHyxFbmNwx)$X{#e1~>V*r7OaIdIJJ$-g z1z(fsPu$CXX>#Cg?G?GN>wNg7FS6*x%Mt7!Wo>qkS&?M-Vp}exU60qia*6YxChW+z zo5BlK=IrnOfn1+fRbFMGJlm`K8+Q<2xoi(3PFPvS25U^=#(2(@ONB%+N#O-+%)59{159V-I44_#PZ8T`-M+^qJ_I^f;sm7Q|^5#C%mmz#l`g3 z;EYDsb8RCvSS|M}lBYA9xYzYX+}h9C?A*)$gagL>vl_J6mCHW7i`7X8X34?PY$RF8 z_8s1vzjh#lSH6FMUwwWKZ+py^TikKhx{jU4e`?TV_gW`%sr!~?oU+nz@4sHaj*38y-u zK+=$$&(4P&dTGWkWF|%1tZhw(bRM*aSvecU0cAf?=ojAUq(v`_>*+z zKz$yAEvy|3Hj^v3ohNPhG0XnY<{|ebPUeB^q*nsgtCtafx+|BZLjt+J8{Ft* zm1FE`OLKZ?TrD?cKq42L)rUPhLX}O+xGB;0QD>dc@25fSXE||nq3~U5IJ^1PGvVn7 zL;g{>2EQbxM!Ys{7T-TngYCUAjQu|1JT=l4aAPLb((oEvHceo_9cer(*-$--A5-#| zYLQBzu5X-V_fJ*p;e8b)?bSDhI;Y2Q&P~?5q9viZ&c2kNm%(1h8OVASXmfHIbNRac zu3WX>EVjkPgtJ#kW7FJAIDg4vPWSI&TIw-@d(oW87diV0KkO_Pely9I#J5#4!KU#1p~JsHmRR3G8$GKTYWx4xq7Uw%pC0x!_;;+cG9MI{#! zbA`)3Tg2u~lBZgo_a#9;TDa^RO6=TvcfR9}tMHB6Aff7~a4xD@ESb8llAZe?hgyUu zQN^|+-1l%DF6W#TUv>Gp^>?fF^o>Pd_PVn=XX^Qf_RZK&XC4ZZcQgE^QBlINAB4Q$cfy*u-DmGya^zE568Q}$)3~W_x%AKFzU;pI zH=Ld*Pq-|%Ofn}xm(82~mYdt*YCY<;HZ>h^l&^XpLUZqL=eC?qq9=vk+&zIi`)Y|f z*ARS86n1P8|Lw~eu|d&QZrh?T+FLP}T6fvI?RM7Cdlkx((W#2o=^A-lVDAmA z_`HB$|6a&9i`%H};Z1z_<6wz(od<2I)E4TFa+Zvc;(YyVH+#|fIcGLPnGN6ZgZ>z( z$OccG!FtYmDA}E<$1e9Xp-sO>(JOv!TvdQF*Eap9u-6%7np^ad)3E-=ZF4ndCl7EF zlH6aM{c>Y5`J2h=cg&L%bu~+Ff4L@6nj21A`p=~%DH^<&;Gl5D-M+kLmjzoH)Rzs| zN`=W@#%yNU5cahczf0&qdRt4LckkH3)-KK$=lW~#-Z%8<;M^|SaY}*OEw^Kbx+jU6 zE`O4AvEUb+naPi9JHfd`z2JPm6;QTo9{2gk52_ixTR7!gIh|&1CsAFJ!|!k0b&$|d&xxwqVo zW&5}sgL*<0Mh>s$MueQAr?ND;t_iQiWu-egg@kIVcgB~ip~ckBZWybiBgYO@ z-zI#uM4A4&w49E*XGO(B2U%JE2SjHujntiqxmRKL)X6;-5^{dN#g$W8O&v=r&{kE z@{SYCU(aS6YjD?RE@YRrKjid1UeFCE*76Zuas1$FP5z42a?0*m$|Vix5xT}DvxPO9 zZ0X*7;jCBg)W&`<|CE~Xz7B!>it--LTWv1;u`QZvJA~6u`9C=8efO#N(|5uy>dWRh z_2yq5{3G05wb7c(i|6Q_5aHpT57ra(_pnJf{|aj}hjMRErLmiXd(lg;3b>x3Te*X0 z-KF>BMm9!yFgtWgU+QS`!qR1nF|Spj!Z(n+bf6%C3tm*mjUL!7)a$%S>vVnTboE>g zMGxuh`LDUmagJ18PL5qcpV7BgeYs0*o~+u)WEvi9FXU#&(lBLhq3_ZioV0(Ek|+oE zWFY-@nXyGN)hy- zjw{vG?aRu=T@hX>(dE~Tm1CoirE?c=P2;TnqJ_mm3wGEN4}QwT0wL$;#^0UxNthwM zFCUER#Z58zEj<4Drtpg3DAzn|KP}s9L6iI6vWf_!!sc*8XXq z=<3`-{9VsD+Tyd8H#e`8G>_DxQx;6{AmhDp|XFKe;&B5QOaib~Q^Gcr$bxWj9D~z~?gCkhe zRApMbc^kJn^fbK@&?DR%Un#wthj2Bmd$_njPtIZk!-n4uV+a2p%+6h3PBkW_^C#H~+}r&eXPp?v8NQlC4fQthG<}rRPH|MCJCX06-%RUcGHJ=CWvudz-CVzS zAGrvnpAx~>{oI46eS{N#X!3jZt!1~&+#xK~UCMRor*Lfn7VOV`b==Z1eQ0LuYff`! zJX^aVl3tWoqRRPGsa$6{Z{DgW>FoGSw>n%BZrLbz?20BiPan01Bi1!0MiVCEz`Zm}`@K<)}HELCNr=ZA9F zpH63AIGqzG`b7zCJtwhxZgc6${i=M(FLUa)D4qWu`<|+HOrTc-2GcpuvZzvfG8K&( z%|EX^F3H{D#orB#5Uz8Yz%6_9n|m(TkLPROarYFX*cqQcQns*7BKmkoylh=L9odpf zcRtVKyraHyvo;CYhN12Bdv-3jvS>8B?&CbJE2R(HTV9J@^WinE?Y=~P^3u5*XC4S` z?R@B?rRnTNk6~bso}Os{P|Uj>B@KKIMH=S)`DM8h5ZQoJ4=K8 zG58Lh=qskLA8lfF7MSppH7`kSuNCtp^<#wtx9PK*3rA4Jaq8@(x53<;4I*yz^*zFx zfRWso-|_wQ=dox;@@6Tsh|u<-WYOj{Z25KYxrBUbD5J z{vI0q{I22bBI9g2dutx2uvEbA>9d(TU%=7uJ@qupU=jD^r3;@YdP8sd>9AjijN={O zMbIU&uegTULxhd0Gq~v*-V*;==jqHxi@E6!qlGsGkz$*E4cx5@cepKA2J!{_)VaeG zi>My7sF~Re&i0TA?Qc^k8TWW3yX2h(JNAb&`*W`yo1vD^^}SO^Jy>maY>p0pR_w(c zUKGslJKIge*j~It!x_l~UrqM&et%Xu)}F0vS;n2OS7S5zByRlvTIB8=s~^i9^vj?UCr7h%#h4kGn+M%%2kCw%Q?ZQ8Qh*_lUOTym;QYF zh2FWfob}qdKsdZ2j@#~3Mlarv=U@99uuEOLX^x({f9`N# z8!ffCkHbB!YXgq)eI8gyPA^a7Ew>Kl*NPozm6eL{GacSIH{5zxyaH!(q*M|nE~80T+G%)P2-}pgj#G>p zz+WGfX6?Fr9Di1A7299;v+!fqa=PPEFnhY>7PmFjntk_7f$QI_K@UB*XIs4;B+-6G zd_}4}U$s7wbNL3g?ch%K&F;_CKRb{9o_ve;nN`QGF*wDUt(?SWw7!&BSoWfyXS8r* zSrcmg^fdRTay-YzeV|r96zG}$`-M42Z}NY{gW0WiZu}glTA|2jJRi13#QA^80d)>KkvsFS8%Oo{Tuc9Xy%9MRvtoYi#pmUsj&XQsB~$&@GD?JQ5x za}$5ApIoglpj(Gs_qtiQp??cyJ4f-=Ofu&?UyZ+>c##enrNS-<)37#j`arK9b7jjq zZG;!B_R>(LMG~=62wj~VPS;#mK$U+v2tQq^weH6+=ka(d*S7i;^)Efd=h}61XN}ge z>sN_{ZNt~FTW9O>sr9xr_HLKNpAQq>D~jM8GvsLa)upV`@~t%fTqze3S-_n#I7g?d z6j6Codv=^dp>XwNJFe)W4?9ZNmTDdN%pKouD><2-&&5n`7l(h&u^MCHzy>(=m#p&j z7hZgJPI%mXCf{`ZC3nE|4gFIymrF0xqyx?5_|OVV-tH9PcGcdba(<0;U$QlOIk%e2 zsFA*p3sNLDVIdOnh;iJBW()rQpE$m_!i3*7nxzJr^J(qMV{G9^Wo})i8s9R0DEs4@ zly6#}z*%h%lC-TW<{bXu1M>j6K7R%S)F$jXX#FKeuy6N_!;oRrhJH8zKC& z84Kvt=V#et-Hz;nQT_O}x1MpWxrez$8orW}a}vo??L}P4-6Y{jeWCvwg%pj~5M z3s+Bg$K7?+lk(}%`7+IcZQ`<`O0{|d4>V_bPtJ1;IIWuL^|+Jh_MRrwwM1K3THcxk-+S@Lw? zCGNz+MDA+ZC1DE_$OaA45#IZ}k-IT)FPE3B#b>?UM-T5?$T~ilEYx_V!8^azh@j2BQGYgqRN9*VB{}cJ$E>_FK8yU5n6Ja zOBDD%KNhlFPPou+;t6URt;cJh8EiFj#UOS>#twG)6gT#9poFVmyogm_l`r|7x|dsH zUcilQDd7u5pSX%g#w`7!$2++9=BQQ|7g05lE{eP%EUEe@^#4`PjXd#+mS6A9DNa%2 zuZjJ*z2+Oalvzq#wQUL|?*HiMqy2cLThBSe&v)pYbzKtEK1b=p_kH*o9_hTu(1?3^ zaw<1$lQyq*-jKD;8qbSb4@pM;-DADe(usZGw3eG!Wz7yUPLZ^!DXDWW`oK|M6=6u8tO6BjsW3fA`^Q`5L}G;+8P!-~hVp zu0*lqH?*|6oqtk0-VVD|-S@x7*>=G~`jbKUw!`KYWpk|mqe z*+3O<_Qcrntijr0?0XXt_aZ=-H(QfPM;&&fyFXOXPd*O3*2^st*aq^K8{=5bol+s~-tYI~M(02{hI2OhB)l=k`oLNa-VlPW7H&0_p2Ic#CmPtH4Rj967|HtXu6E`GmsJEv;ZNl)6gbA_c#*>eXn=zr=DnH#nr z>ZK#Ce@TC`)W0ky{rB~+|F-^XVfNqEe_1onGNaswWpvObWE54GI+O-dZhAWd{w2k?!lF9@+4X`}kdp@&y;Z>&c zSTS?&bq?0u+jL1I;~5iHI?S@Lu!X7k^|s70_8NR1rZI*O4l+C7VcDxwz&z^L$FlR3 zs%4;dCiC%EC^Mt_K7ykhp#A;{bAE#pbIb0;|6=G&%Z26 z&zO9|VWO4Xt1;5dsRi!1Uhokf{pZTClk?fY6V-U*#xu;|&F92CtA}akv@ov}w6R;K z6q8igfj{Jkvxdue;gOh#`aISDu#DdzW6>IgfAk7dIgi%ktNz8@+pc2xCaGn(jXpSX zaTPtOybb5wv*7O{(I-PkZ{f2s{T#hCJ-l5lo-4cVAMe?-W?bqW!-PaLShQA~e#W1= zH}Rb074f98z<<72v;Q*fv(g?f8sTS({IbQPby~bo&U`Fll!8-UWby<*>+#P0bHVrR z&oIdzi}4XhVdnn(`?Ofb8)m7cHMSa^f%Qu*Fz44=GL;*_vFy5ybFW>qbR9S+kV z<(U8|Vk2I;nkMw2ZLt3Qeu&%kisbotz-+4&;>E52;|g0yUTp+x%O^54*Am8#a+BqOR{}9Y1y8wM!1YZ}Ll90vbaQoLNdL&@4f$BX@LN@w)y*Sw z^;Ds{+ZyJJ+$OW-Ka#%XHn8=hFnsQlf>#e{2yQZmId@b@Yn21&cASNo77Ji!o;v)I zW5GBij|^`}By{2*GCDaIID*&7HEtrb-Y^Ay>oY{**c-+`e>NPLy%|JTYJ;j=I23Lk zC$~3-kgH#e$jgB^qP}ZB^iOO8PWWZg9C?lRkaLRI*PbQmSF*{UwQtCZl#j%{_77R= ze2QFCj)nbvJh#U>1+3=RlGSt5h<#Zi(2BB9d~J%i&~FKNHq3y+UlU{qXF>k6>5zXz z3>*&9;)-NC9yf@UORd*$z#Y;AE zmZ$Y*?<|GsV>6B*(Oh@B(_%H(mDc3^r2Of#vKrij zdW!VYC?3bLForJO?n9?EMp6nRuBi4{4CeqNk0L#Ha`zRJ`mdAXw0J-g$3tp4?f&X9 zy5xV3Q#EPK#s6~o%&rtQ^{Rx^Vphfx>EFh=v{a9tRAo8QhwE!4gVxf`0oC zvuAU$`7ZQH`y6LwR1}9|I?R&Jnse077jkTmByiZh<}}I+z!6o`i6S+_Sd$Yncn|# zXZ(G~)mD4YN$(1vA3nN9)$zo+Dtl)jQ6&$q+ovm>YYR>4c5`g#=stq9{_0WpCgQl~ zue)$Nt*3E)T-H-5X0JFS$H%DLB~DaQss!ik2}62bdJL6l6HgZ}Q{eV7i@3`?Lg)iG zzSgOq&*#S6cti!JtmfG2tmhOgI6=FpM4{zZqd3b8hdJ&2*U*O26=3%IrmcJ!R-8Mroy%QD-8OC>6?_YV9_szR$U3y7=<}N+-F1+L2L7 zMS9Pt?*7iFoFux;MC?-UnWe`}6W^xkwT_i3@2SF{}!E}2IiR=7|7FiE4d4j!fa zYF(%uqj6N^o$XYRQ7W~v&CBd!(JJb>UI}$Rx`a|Zv5(rpUZAQ*ODO+qHPrr`9h8l1 z8Z{6iPqj0S)Hl2NRQ9eIYVY&iluk_+HTj{G`Wq%qg%6LKO>6#Xwjwo!dgjM7Grg)! zsReAMM0KkvnP_1rKsPuXbdnwJFyvtudy9WPDuM`9`Q9v@0DM3QIU>ka8MqZUw9(cwLmRk0j(aK{~LYhoDnt#Ht6wvATZ-7Q#g9Qne>&i1rPDA+^Lo*#lP$azHqx9F8MN zXzuw){ucfs%Y0H`Sh18$uGIm}CJ*@Zx(0f?OF-Bn9L#rz6GzJ!h}g=&9rrkJ40*## zS{V<|-|YaE=;>hEwH=<$OoX+oWuSiJe2{cYgnM!}@OyF{{J9qi?s+lbZ^xfPJ(>oU z34PF57Xwd&0I(@o(79jW)jEoCK40YN8VSyCa21^ z!SUjJFqEeu)v<}VmAApi=qRv|?S^^&0#N1kh#Xmc500BTft!*!5uBa?W_8QJT!?|R zsFzT>e<_^PvInWGNaA6!5d3vKWh+=z-a_0Pq4jtH?KpU$(WPb0QjRmJYVB8O=5qf_( zy-lf$asTj@cj@O}PUmlTqUG($`@FV+P9507^GWi0Aiw0Yk@$~SHmy1&yHsc7v+>WRnE#-}}$=DccZU<;vUoNz{K+k&X?R$~;Z z(LoMhPoeiwL8v_38Yw@rrc_TlpwUE8L<&};nti2atuNQ0$Jgc~%h&DHqeuGa_l0$6 z=f0%;m3Ykkq3XcN?3o`8;Tnt_U5 z$572PEvZ?H&QcW%7-V(G2kF0RrYfVm%xbqLQ5S|TP-UA-sm0~rsp}X1QqJc@(D~nq zRIlS39^|I>dgSj|$Ok*u-xhaE!twoW2Q!$#^DUHra z%A@VbmJ&N5h$K?HQ5qN^Mr;dOaJvm>R(-;A9lkTOAI-t9KTETq?}z>7%dyY++U?(3 zZ>*I)57Y0}$O0vCHsYZm8@frBl|NyLKOPWbW$&rt0oSMad&68dGqe@|svW{JV*8kL z#-DJ&3jx+b*vxAo+wpW5XE;SLQQlE_ z&w=~+_e){cOjHqHd=iJJQ~%-Lw-wowcU$pD?;l+A#}VIatHe5_8|y57g?Ba!@EnW; z*uF=yY*^_sY#H8 znENsiCmk-uUiWJ;ytlv?N>y0bR#7%SN1yHAwgwjlJK$%dMyzM}H5}lz04v^7V5?i| zal3O7{!wMZ9&xF{$D&%XiuxG$-eL^jh&uf@`X};w^OKSZ znMP|btVY+u1nHCdo2a{6g=p{ar)c`+P_!iA3Ca|kPJb7PM|1iLP};`n^macUYKU(~ z5e|P*!h>nF{%|jawP(^MC6081k2t-5 zofstOGH`UmMe^>S9hqen2V1zW7Ols#am+yZ=tw85)* zE!a95!r3VoSaDjK2oYr{KX4pCDHP1YDTtmt4315q;FA;u>m0P9ZOR?y&woqguBt+3 z{xnF=T?4Fv34Dw41)~KgVN9Tx?E6?lBG)#M``s>(dn|Cj@K{Kp>H z_vtzjKlp&B|00eO^Af z2w9+0p#dM;XOh)uJq$0A15zgjK8H(Ta-}TTCM&?5fE8rvb0L_V<_n(=7{U^JH<;X) zMmil^$a4W>GHA>90lj4*T;GG_`-y_WvH`LybED;VW{=;3=ZTPMl-9z7Up9VYP-w~6|LYSMk; z1$lCpM^?BFk_(ktyzCD}6Whl7yhU^S$S1WkWPjvy!ntC`8~^x%==N~QPo+(yVTwaO*Ssbr!oFl>V+@&e zctb{CWRuC1Qld2Rh|tx2WJ3Xm=Oq1!ROcH*K=v(?@sN=FSDujQ^$dC7s!c3^r4sqi zO+@DYHgZ5@9;~tYk^of;&8cG);2k zU>j-6{X;@p){wk)?mV-3N`x#kCN`TWQfD1OF3yf6p;BqYcuuq~uSNM4IW|3yyuOx3wila%g>Wvpcf5cUYdzu}ElecUk>liG zKi~5j`baX@Ismma8t%t@B`PmciRhvZ2*0BQI?;_Fl#&NGBiDei);b8tOyJ#i2m@|U zEo{@f21CMTkYrd3aybL!_4$1G=6W6?p2dUXl43AjUqVWi+@Z&`8q}{0!q(nGxOFZL zJk}k6y^At|&NvSGF6W^dIT4k2+d*Uoz`PWI73(5lFslxlrvRGow!oeP{&1+F5WZ*V zLdAn!kW*v{=XmEJTq7LLEvSTC@kS7MrwXPM)4)Aj6!w^%hqs#viQh&8hCnzkd=o0B z6VOgg2KHJqnYr*Rys%#hWpNo`-Z##ZOU{J5J|Up*Cp3G2#>rbmM!++mwgKS zdgs8JfH#n|Bn5sf8Ya#16fOze2TqEY;9B=7fX*&(|7`~@Cpw5rYyxSR$^Q=PV;~M! zLFyg}xFx4dhR;19$A5h#t$n{pdJ+Y?dKS>|(jGQG?Iv;({b0N143tF=Kyd|byJ6e=8Zz?31*#4rIKUewZxg?gy(=_$YM14pXJ`%V)!qs_ zXLgZ*g=;`xEs}J!F)*=(2Gy4uAnarX>;0CH!kmBPRkA%~J&XkJ01K$wt`5)L#DTYR zA&3XafXqf3tnYv49Y_@fhdItLoaYP+Jd|Ld!x26kZ-Q+>ULbc*3?A*W0MY7eWWK#H z>`~|=Ym!w4TT%j)P5`C44M>4>mCnX!|7j(c`zMu5;Ksp3Z zHNt$MTv(IU0;lIjkoftDaQO5);4B${9f21?;`Ix#>==N*Z${zm`!irD(gD+Z*Ff9v zBuJI@g|j9NU~?)TiUWE;Tjo8SzHbBRTQuNBt3EvUZ-IVzOHv%YK)f>pjB3Baf{ky1 z(Yg$!E|`3K;wphY8UjuyMTr-^Hw8 z;nJB6<9{y0%n=#rLLT_@7hqq|6v%Z2Ld@@R5_7nUD5Z#kQE@56+9&&d}rIMH>E5 zGaGJZorXK_Ldo~TO>n_A3OWxSgZH_L4Wq{+VgB}5IM`KBmfzbCUjH6~mT@iw#kPZf znHX5-GO)h!A~6qNK_2nX>BFD9Nry!kv>bPV(!^On93+7^zL>}OFNF1}hv6eR1$DQ6 z5WVUE@c)@he%iajpR~=e=)c753l*V&*$)lZ^B}0)18(yBHfm1uz(ao> zgkLp;qWH}qJ|a!}R8=5UE)?EaNkBjY@Id?rFZ~oeoL-ssloG+ zY4AqN5mx7zK$+?u(C zkO8xN{(ru~9vZV(!{ikMlKpEdWU3ayzB~))zheY&Yb7Y1t|FS(vxvhoF|f-p1@Y|< z$w9+xxbkutkZl)8+`BPmV$)oZZuSGAkEY9rJ!6P3lk#>5Hh@i$eIX)VTLahzcz%yhi>56 zqzuvCj!+>_$Tn+FVpf(7hOdUm8r{=iU~vd?|EWRimKxdGaIRSoUCyDvb`Jglq1)uprju9Jz!7_X!Wb&)BUC1OoP5c6L|Vt z8ZL5o!_p`_&^#Lf-`Z2)-l9=*&bFN}6A#E0IspFFClPEk3+($X;gJ@u-&i15sMa(D41 zxcJQso|dW+yIXr<(GMNiV5$O%bys22%X!d$c|N@B_au&)vmtV21nk_h6iQW&LZwa* zap|4~LDNG>q2L@MB)JiuqXIHfw;bA+>%fV;C*-zKKgoG4&5Mbg0jVh#Fdk_SmF0~@ zeZU<0iVu*g?RtFQSr-g)WkAW@2wtu?CQa|(6YVM*8h#yw7YzpBWFrk$v;LB%at%0m zoL^I=b-`rf1@Cq5XOg746l72HJ?ai|Shd*_92A$q7mqb?U2uZ<*BU@+YBkXvA0Z#= z+K9HiI^4~r6;VaR9>ov|(-e~YRR=_zY={JXjo5Tf1B0MduujYd9FEF^ z2~VC-r&NKf@rZ2vr4FBdg!792X~2>DLSXHkO?F`+u=uM5e$&gy_qG;d>N6KsIlUq` zuZ)t*nR6g|SQXrd1j(Gk^P#*s1hn2s!5!=A;CoU9JeEX~&)mJlChQ^EG$IObwp<{6 zp?+}FL;?0KKT3YSYhrefjuVHo2)b!8`2JxtNK|waj?_kC@K=WXSFoEDZI%SjG793H z)5)(r1-$4;H==SRgcwbR6ZMr%q{gz96y!f7f-~I6_M1ClMVK;JT{{4C3eS=vpFncf zldmm%+m)+ z)uU*rvj|m-%OUSsb(HmwF?1=_0$CakqRw46&?(E~sO8j2)cw5D>{Un}nj7&9c^3|$ zwstoZR@;xb-)5n%krt%jc@x?J$1c_7P*|FeC!gC?wq%1!=1M%&$kf81wKd4>)xR!&Lb%McN(IbZ=sV3 zt5J(g63WWhjidws)gC{Ot&=E zDa1eagH#oJSar)7j_!5`DPSODy*IEX%4F5VJZMdihCL(EpmNk23i3_?$1VoMcP9g- zZVW{nKk!`qjev$8T+|nX%a(4S*J}ZWQ$f%!77O#t-jSQ>jpSHGJF!sr23@&m(v>d^ z9+ynv)0`yedKv|ZTh_vfqP0YO#ukuMlY@N+w?Yc1o)sx z=U^U38vYzhBTw5_ zlHI%l@@tnZ|11jzUrr~HJpPKe)HRbdAFC!E%j=2FDj^t|BMQy4Wx@Gv23ekS9@g4z z0SfaoJcw`afQTP-}jFbdEgvPi`Bm6HI zyWqv6d`Ri90KG{Kz}ES&!?cs!El-A3vHUtq1;MM@GZ1q=ovh5Wg~ZD_Ahf6pX2qt$ zt}lUbv||%&7l{RSw zU@8c{nhlOVYhWNAl%~(+b1*OsZl8u)3e}2{2&oD{6PwL^0m&jBI5aPF4*U| zfv?XcI22q2$9hgciNQ&7%!ThMc2IEoU<}-Jc**nJ5(~1mo={mV1f~VsV4qw($l6E& z9@T{x+v7pP!wO`j96|i+DbVCbL9W6!^3CToSfA*H7bp-`818`g(UGvM;0>vs(LuWR znL*$oUsxR~2JER0*fTv0Qbl{nTNy1}i=Duen+*|9eL;%lx2tAi|Ef@& z{3yEjbQ-;6??DuAI)c0&DkH)^K`TNZqc^A#)!cZAZqctPEwQucQvVS0IHf`xq&-8j z;ef7BUO*4^I?;{g73k2>$0*n^g?ccNiO7N9=!W4RbZc8J0?ltI;o2W$_*;l}54eD? zZ+nKmS9v18FWKnD))Pn>-9=n^zH@YQ5S=voiyp*mM88LjkggdnK0?I#sIPffl;QqF?s+kkWL0s;i?jv08hk)~*;eSvvUSwxHVO3OffiaQqlbb51JDVlj@` z4IezbONIM+(P8xSKbF-Ub7sY_gw>yYXT^FP6vsAW1Ng>D4$gL+&DLI2Vl(DnMLA2X z@s__vZ0m&xw(gz@u3j_`?<=XtTeCB<3a1uZZ1BTtUe?!FN#4LVc}v*Mjx5_ZU!C3j zh|iMB?_^6axv^IcI@O04YZ)SL+U(!?f$yqU!EiuIT zeAJ4rI?+lSe!fgk?cK-v=U>OOwFNn;KkT`k-)iu+9S?ASb`i3k_5};~O5zQ@+W7Q% z7<2AxCBv&u#I^-{nProaxO?q6d{Nwy>1$NNaFozX9NV$}`xtzaD#YU@%P{9!C>Ha& z%ioE*1zUXY#P1F+#xHK9;G97Yvqy9`wsecc)~7i5;LI!>V^xZ~v%;}>yd3@!ZGug# z4Df3wA#AH{j;BV8u+8o^Y-8ktr!8p0hc<7+hxeVwoBk`rGF{0yTU8Y+dT<#Z2X!nH zau+M6sNuWikMYO<&fu&WISlQTiAN+B;Y}-?u!PlLI&Skd7dqzs>+>Jkw_nZdisd7~N+K`g~|%he&>|j}BhA zC>l>GPsjO2Z|TGmTfAYXB7R(GieKM1!1i$%JFSbyqwUH#U{ekj61t2NlNxbfPAVR$ zcfglZZsGv%L~N$+ix2e;;sX<9_&;xToa=fYOPzPe!CoEs)vHqG(5)e6RP;LbsHnxu z?`*>bgVx|w5(WX$1LRP90tvWt9Ws1mA@6b>*#9{PCZCss%z+gk!HeQWKMMq_t(Bl@ z$b)xr3qY^20+OdcCrLjtL9RIidieUbl<(_{x#g3W{Tm@;xCA_;UceX8TzL2-0^C-3 zL(!vD=odQ#;gA9EoL7;Ay<5Oy^%ZEme+6cxhl2H-D!>-CP<6f$kpC`l{h9-uiy9!s zZiTp;6r}i_hIfHSp=){(?69bVoz4o7Y4VGByc2|n85uwoUgmo@#<1zgUidTwpt9*Q z1n0)W=8jmx{hka(k8OZMr9#SqFFebIY0&ci0GR7afcy=AxGJ6w@A+CUV~Wr1ZcT?c zmDO-$WGmd>kqBS5q=1f*KY7FN3vj*J z@v3&dvIP|<24%G)kjzK%juCM}H?gnw^M3L#;J;Xrl6s#2~ zhP-eQ=qZ*XE>CZheP0HMK-gzOgp7bVo59>*YZzC*O*BWk!AB=p78F^-g4GkG-t!;Hh?>tEd#DO2g|1-H;0xzF z`^k+bTcC1vBI(gu1`fG4AkjP@oFrF*hxsa^s3!u&-<=?1MiRUfTLF)a^x?#NS-7iU z4kCWapm)Xw=0yk)%~Ek_TCyFa9&QKkb}evBa)W=ncYyg0e+Y7th2y{Mpy~8o(spDP z+zTHh5q229yitRHE7!xy%R6CF$2ESb&m#v$ONiTE8=zgi$g823gujFy3>WPKk7-^o zXPGffi!mntduVWT_(dG-St`2L66S}s_;2T1e-0hiHlzx3ElmZWEE?`ciF2% z{ZSnFD=q{{aCMH5nVStrjARVa|D*$XXEs3b zKo!{#+sHdHJ&XiprxC}f41#N(6YIxkwVPd z;$To-3Jx9m!wU$tfRHgEki0cU)MlRp9aSONJv;+qD@=*v=3zqjtb=`V%Agpv90bGe zk*w{a(4iAR0!?QV%{{B(+kzb89BBogWHsSwZ#OA+>LIk(ES~)uK}an}Fppjef*l<4 zTL{51C0}BqH5cB$)&wLf0jEFeLC`aOaxL#QvHM~I9&USJz(WTrVJ2j2{vhSW$`HGO z->>V}gkgy%Jn3zNHtzICr&#)l7!G} zBv^e87@G<~&qpH&oo)row&s%~H9YQ|2@CZG-nG6WsBlC2fh*+9CM3>4#tf4P3-%gWD4g1LI zA3MS7)@L%-dY`xPjta!Denz&>>?FGTk3r(AKJvo&HMzQLHaWkul`M}kf<4~TV9z>j z2+(dsiMhYg>C+ylFhc~jiCEA#W+bDk^~Ut*5n0-3)-@F7a|5kgAVB2>enAc9y7cYZ zMf8045|n*jho0-^jOMw`rmGgo(QBjx=&iYPXq>2wW`=d5(jhIn*MAeebE6`?{@N7! z;`s`d2TRb4?+l?GMsjqjXd6}X^f1;1Wy7a37LwZzzriCJ2qKf5; z^vjNHG??=kEwHOWQ;M_b7ZM{#N=<_`p}*9Dj87Stt^emZN1n7ohdQUIdEBz9BI4nhP{Mm-Imi3|ueNnnvW+t5__JNWxR-m;Nw$a@)r%(nvjNaWBqvs^; zL0|d2pyjy+WP9@)auP^ElV{e`y>qA2k38Iv*v-=Vb(fzbi}#xJGWt8xX07S#p9%6b zv_M~z1dzVh8pPosQjrL!xxHt1~TD6^U$0x1cQ{>*?;4KGYcAOdW}rq*qnkM$;}fB5Ki2+Sm0KGBoH! zg@Ym}yQU6RwW!nkCx*~=A9-5s);wGsxvTc4rWG!qc9Ea+wwvv+F690EIGvq3O5vXl z-h6&^F}tbDie2j;?lqTxvgP7x3=T}yKwM2UY{|Y{d`T9)q@an z&asm>{VT&Ry^+Z}YB;c)JFR(ZW)`uJ*u{K*)>&HQ@Wp5m46BMh%Us;A}xlS8pjOO)?$CD`($d}NBl4|9k+Nq$H7`<^oE4_ zr0rh>Yog=M>)P;$cWR0y&(>r!$2%DEy(brc$?V5UCFNv}fE^oHUx!a}H0gVJYNW>7 z7C+C{V|yi2vG0RA-o%kntmONJiQnIb-R34?J+B;`+N#VR5y)XQ&iUi@X-BZ2K>{fs zPvY)u6kvA^Ov6*}+R3yH@w`GG8@6e`Iw?!eW5+ggIYH;Oux4i!dqq7K@9q*J^jv9X z%eU*iR4R>RXyvepTQu1xL6JO#2e--V{&bvO7C_sLUJsQo7YD3ZycBDKe;3szIqBDWdnOWQ@N-R%{%;P4KrC@7CI>!n)8k>C$>;Pb?l#tZo&h;^IJUF0G{UBYLO_JvVBX$w_K3;Spu> zFqJZ>%%kRI+@=z@by8tFE6w)Dy`UsI=Ap`^S1I1aB`QJpE;V1tkdg_SLuG`V+8Juo*f}b%zuipfVk9+v z`w;a{?h<9fc}^*0PiG4LhT^-(kTP z2Dfc`hsNCW*vRG8c=gv1ob#UnuHSKtP2p>*{Pt5=@y<`?+(|La%sjv@@z7w*2IW|; zn=R}2W*zGqWr%6J4o2y;3YLkviogC9WV4Dk)0gA#Fz)?ayz>u3=8Z?2AgG^gSk~qzkXP7>`dJx5lMeYuGosnyk~lr}*yG zW=6^XCG)~plx_lRM1E zryk6*-0!q=ge=~F@DcO0@-K5TdXT0`uxO~>BNLfj!bic$Y{jh4T$ znkiGf#Lt)Or;oR`G6gx!%*pRl%;@0>CS@#%aaHxE1s>jJ;%>ZW#{ZZxe`*dgv)N!~ zUhrvV<+3!MzPkXeH4x2wIQWElapxUpPmdz*X-Z~BO&9V~)CU>YvTw{CtA0AbE`d2x z62@rGd&W3PU14t4M4`^ zqnM4a^Oyzu1Gs^bLiqG~e|nqTJf?VcFG^ax2(LW7oN-o{z|by>7g`T9-&dzHT#F>e zZ=*Z+OK=pES#yCSr?Qj|{$j$IOk8JX{b^&aQx)~{m8s1293^~GD~qXl8BOox=lsm5 z6~H?MJwQ!59Y9eSempNArhNXUF-z_K#1CPsPO#Bflcu}_%)OYZ>8JewnisNe0~BEVv%4RSO<@q83;HU z3eFPipq(xO%U#JZ(sC90ZM$Icbbi0tS`rSFD!|tx)zIy5m)z2FfSKVj@L~Kh^nbkr zuPpLl>ApNtA5jE3^4q{rwG_xIF=A>}27MRe0glXth_N^b*--)Y9VW0t)DgU!D?ngq z57ezZ0cX-LK>VK~7`qThyi96AZG&)wv3&-#86<*2%tf%YnhDVg<3wVQJEV%8hREXi z@S$KFx+d~K$W{;r58B~|(Nl2qO*712ej5Cw-@%vtZt%nEB@r9RB2!)8$(7QxVDY&L z;=ZZyc{l?ix9B|~PQvh{TokTpu7J0@93d#i9j4X|66Wv-xE?G7Pt8eK7^ViDtN<7$ zj6=RcINZtIPF`!3!;s>BSXSi$S(`-~t|j<^c~}4_@3=sM44vVM>s9FXOMncEEAXvE zllNVsmaAuRjhZ&u#F6iH=Kc{W<>uU9z+17*7sb}=@shG6Q1#hF`u5y;=uCeMbq^4YiRL!K>1rMK;=P5k*Lyq8BExF?7<@4dk59(u=ddeX?%4LD0dQ!wZ8 zr825s@*?;BNe^VJU`}5gOQf0b1$_T}H=0(UPNzmwoGS~(cya>Acou)O=^uV2^s|61 z=+ndtN_)FHufb?Dk9))fIeSs&x<_#nu{)male$-a2ro&b2lB@Nco*I;~w(T)hkjtf420Yy<7g&YmX#yTg6Mbj@u*|o~%5$^eX&aq{s$S4tM$!M3fNV0ckDI^&gA-Na#^S)8ZDEVsBG|~_y4Vu#L z{QiOaxQ~18Ip_U(zhBSi`<~au`oEDE>qV*)>t4$Eq9FB1YIj~PrJZHOw|8@_Gv#z( z^T{k~c|$h!NZE?7_~axSx_789ah0In{rIDLF|jNZHt&3WVDFWByT#)Ch=Bo4Pp>_&5ld}Ru4XBI=?0$b=_Wk>XSgyC|7GlXU)zym!ih@QC!lALG4 z<5UDyWlG@s!W6tJCip^DVlW@P!N+DJ^xvNg>kZt&^2tVsirWDdP13Mf#R{@B+sH`~ zap-^5Pcm9L@Jehp6zDpFlgegro_m#4+{q@?t3sl9#T3$eHjt!a&q(AkIk@K&0EJN- zz;UV$3|Q-sqMrsZY5s-uwNTLUFO#478G*;JB1{%klVGd}0cH$1s$D0RwY|i-k^$YR zlVrm|aVWT~2M+rULG^_KSzTud&g!Y)eqkZ#r_KWOoMjOXW|8v>u|(W|lms@iS-|6b za{pi~WOeF*b9FK?$$dgcrAfi25GPnIstS9n4ugvG2w9-MpUl$GAhtK6h*r;h(A>Qm zOsmR>;?sJ5#r0tFcX}#$_aKu5uY5u_EbAk(Yz|jgF_^^4M8cH1WzhF39x{wBk>T7V zG7=CAoa`BpL5=YvhcR?CPJx-XK9j1Q8SwA!KN6TP42tXY$dOa;hy-zfkIhP8++YE- zCuH&C-7j$bqX2|2-KY9a8{=!7+t?-}i;nmbP3u4C#M2D!psT;?agU4&J=?qp%Qe2i z9<3L##2Za|;G-ro>RN!e&EJaCs95^Hy&kmcgd^R@yg?>yD)iKIepu9a5q6iGfobCr zq+yUl(|*5@VOTvKcF_V|-N8c}O=GjU>HnNlapIU7*3_Rt zADjOkt=-qc_6lUM>Fg=^O1T#P?-GSGO8?^3LZ3NjrB5MOz6D)6#f%oru0q;gP1t>x z5k8a6!QV#Y=wT6gtW_&jAH2bX-gZxp-MME#{l5Jfm2a1)Cyqj>Wz?|y%5d88%>ml!yBr>K5T!%>W09ZlH6YRoDKr)1cQq(#N(LLfEKy1Dzwbm0gaW7gizZ+GFTMWf5vEccpDL($G`xg}REtB>DyW z%$s1@9$~SA$o1-Ww01&-K3aYezuoClSHFHMJ*s6+o4Lo*nLCW=5jh@;P7%f>o-^n# zod>a*(q3G&yb~|7nNOGY3B!zc%Yg1VNA9RwkbC!{z;W?y63RUU8T*}}wN#YNYD|Y} z1K{kWgBSGAA6hQOf0eGPh1kv8QP_k+l+^PuzWt(t7 zPgFsSUI$|O&xwA#5}cg*gM2$?3t@)ZuxaHM*eTD>;FCMqOlBD=9OaT)TW7G03M6VD zKatI!)M24P7;w}B;aHn7^vp0JVWHMA7%2j4Qte=}p^z`%%Vs!g7Qv1mH%Rp$+Y8&V z3MSbc;bHC=;k{f1MKLoVLTDDees2NOg>Aqsb|LZSvUzeQ4?G(=urERb{;jYA&2<;a zN|#KsB3u~qm6w1{N;?^5a}XzsO`th9hZrY(q`hP3Ktrbw%<)?SuE*mbf4vYpTZtmy z3o#LCO(R{M22fhM6>RK*&7!sQ$BYvQrIAMlw-l0<(I1JT-Z+6%!ccTCo|L{!fnlNL z@ML2a>=VCAVs>Yf3l}p%euD~}UoA?czu1HMUMXm>5P_;k7a$^15-#P*fO3ij5wibF zUf$jeWd)1DJ9`a$t&oAXAC|C1wUS(~a3#ms4Dq*2ma%Dx1w}Sv7+o(91*wWquV~LN z@nhg%bT|xdO@N0Nr@%BRHs3H&OrGrVgSqFoK~csEm>s_dR{z~g?!8rm$W0+o&~Xv! z#aUjz(H5-g*bGdw7bqnmu*=#8TLYBIF^Pq+Y9bo$v)PQldggFlCIa49#K3OWpQ0?c z6u!ON0lV4f>QRlw;G7@^CoZmsz;j06KjSd8?TLlJ6R$|=79c9FEo7C?HW)e@O{!)J zLrR)H^zTiAWUFY97;=OIhO0@+0e1-6EDJUdJz-WUm+x+~fn^KWJV@Oma`YYte$3ni zhqk_BJprN+n6wFA%BsLb)nceiUIQUw9#FK6L%PkjL*vm(Sfy(VV-*-4ELaEa+v`Z- zg#xnNRt9S7Oh7@khXjcgLRHUdI9*;&7UfT6b`|J=+TEj2Cu#~Ag{NTkKWQkwnMM)< z?MX}bd15JT&Hk5uT6#L$3@}3mkgvSWs%eTa}d?A z7B-F-v-Nl<3Gyr>mwy$&Wiu^E43sA-Y`$rl)*Se%Bntz(ufQUW*|4!(4NMK!kS!w; zpmpL9wALY*FB$;F-dYfnwgt)@Zoi%jNX7- zOXFeJJb$SB&GI1WVW4Qq&Z2fj1MO=-IvdPD=Xwq#>E^-%myM8Pm<8r3xlnMu2=q~umW-9#Ka}Mrt*xV+0LWU2&A%;%Tutq0`*hMMB zmC)7TZdJ&#EZOiYa4(3o>?Lgp!63Or8+b>L!=|72_|ZBipxC62sqgQS2Velu$>rf$s}J+A0&fj*wTqC&> z7C_`<@`%elb>cQ>6WKWplT+{0*_l=dVXj^zVN!KO^7bs!u>Kd{$S0i0KXW{dplWMUP@6$~TSw{>(=th(UJ!Y^PMU0yKS1sT zo+gh!%_iOlDH8tlG`aI`H7Tv%L}C(86019DWUxGt|JeN;+2H=3n6^ceU-u7@oRCy< zKkXaK+&$wTlC>fiPll5AX9{E{eol0DB$8&w*L-yk13KK_k6b=gN~UNYC)~NEPIDvo;1jB7#rp1AJ-$XzbVpdVMU^5 z-r=|FJR-MpQpnBuz2w(ZaWeV!6+dqAbK(=^L+t!)_-;E-k-`BN@><@SXg7`!mn3I0 zxn~_Q;wSTKlugJs=Zj=G{UA{&$|Vy&wV}G+2eJ(Bkf61P$)o;qSiv$Tzt)~->+Bdd zlcx)cyk#tJwTsWmTMrErS#ZXmWmwc_0ktm+LLW7edCjpP#*2Ynhj&7JOcI>mnoL|T z8AF&{Cak!16K)Zf0i58$_d=9M3&cTv>o8i=j zGjM1|9@M&Agv$$7!41CzxR@^qmD8=D(qta^M1;Yn8SD%?HVr~Q=7DyQ2*k8LBlZ{G zk&PKK@b5w{xjWA0wGTMMjC)0(wK*4F)b9t*j6h=Yfn`B%>453$6L9w31OCy@a3B_L z5XobCVT-lkyf+d8UBy7GW-iPWL_+984x|@Z!QiGNFqj_-4NYsvo}KYP^6vn;7yxI^ zxWl2%A+UOG7m@32BvhC-?1}LP)mKyD(uQl$+8YQr*4`q;v@+v-#2y|m&H%ml-oVSb z3>qw-A|ZQ;*d5AtyE7dgw|^q){Zq-4!7Ie+MR)ztV!$7CC z;j8NvBA87ePjD2RJDT8|{1-B>FqF%_$B#)=91GokKlNzfKv9T%aWM z*HAHY-6--b!O)~Pl2T5rry6lHHGU9N8>ZA#x(|jpwJ!^)^4bE*{qjlb_Lnkh2+BGB zqg$yBP(w9^f1vm(CDfQ(GPTCz5OwQ9E@eI=f;w}#fU56w=TvA1P{R_9l$KQ^m8u*^ zMQz|y9|jvKg^^p-37LabvUUlj8?8+_x$UI3T3J%(db6pY@1v-L-Iu8!->*?=^VO-a zeZo|q=M1Vbne}DtXyBv^8B<;%A=IPqt(5%4Rch2do$|es&QU*nmU2DfMB!IC)QrU6 zhJm%Y)Nz||N>f>h(o8u)O-;z7_Sr3@8aU=u|Ge|mS$9t=Rc04;Y13)S_P?{#y_PVJ z(|9p;cF{N`y(pQwkQYJyT7QP(xKE)*)ZTJjnjEQagBWT(Gnb08ct=Uh%AhU?MmhIQ zO?Y1y9H8WSu29h#F_ho3N7Q~f2kOA!f1IiFPjaZievULdm)P{Kn)=H6tj0`KI7;^) za~h71ai%Q&%lR$GP|{z_sVhGmsb@xA9N%xf)P|#3)E>8CO5i0+HT)dm1S-6vz7FiA z9?o&%3?-eT9=dx|+L}((?RUSa@TXqX-49!+HNB@ezTvji;GWCW%P--S!}?;XMd}xd zo27wIb55a_gB05N{wSU~r4jZ03Bc2at#J8@N#xZ$1-F>!QXP$I_@K!~JP@)Qo5c2@ zfW6+hNHPT-3$w-k@2zp~oh5kjK1ckyWi{$)n~p~!J@A6s6fAOVB|gdMVChl?e0ilQ z4p^>=PrbIrf7S`3h>eo?=6hefB-IZ~U142{`kSyO+b8y-58%kf3V7UUB@R))izb&y z5F)mULnmX%6LG0KVDq9 z4d2|Zk1w9rN2%!yzGD3w?Fli#3zT!H(5t4{DRB^#JEk{Y~WhFepn;q6_&(99=i@cwEM%+HyQomCNfs5Of6R;|U} zdsXqHE;}sx?hk!!{uE|zxir1_#7x>#M~C@)c^7?@k!GSQZ{ekvyy!xYAbLzK5n1}%)-k&6>OMx) zpb(GOE}|ctIZMxQYryB?PSgI$8Hk)qz}=g#(!4>MDGH!ysWzbPZl0k>e=cQ)Tkg=G zQl;rzr5wg(e;nWA@fZ3+p&{MU?oE#|CG>UKKlDd7^H(mu2pvx7f+9ASJE%mK;ys?Dl{E+AU8ylkk)qB>-1--^O zo`v+fMkRE5$O|v}`~qutNi&P07w})|NZ_aTuW-7I5R>>PpuWp19Ix#4V1!k(=+wkj zw0vAPewVoiUw-orZ~vJ^?|yofj6jW@*7`FDQPvB8qe zh3e+|3H>$o!!4fp>iuxaxKfDfRry8lWBoF}Rif#n(dTvB=IP-jrqk(5Rcmpv-er2b zcw_BVyL|e3f*Sp;_X}NQZBK8|cVR^Doy9j|BhctdF*;Wvv3^T#DH0kitM^>B3d^iJ zR==e{hA~(bfxXuaV&yznT62XVy?^>%8RF)Nd_&8Hw z7&rm9m8+mwR6(Gx^&39#ehzl4B?OWwZ(+~SOhJ}<6IrzK zE{JJp2|6!p3D!q{249PXg8kCkf|p|kg5k<%p#4r>aN_tG2pPE#m!c~mbYi+diZ={X z(&q@6DLR4;IVn)fa(w4D9|f`YnS#3snn1O)Jb`~7%<$G1q?>CB-sMac6tQQh`x#;a z(_TJs_~HVEav$P(NkXtI?hR;;#K7Tz*N_<~DfoOf9lk#+hrN7BfqOv{IORV8dxL3$ z@887)4$lXO-Ag&aB4sauj@K`E$nwV?w?qX>`79e4=Lj(o^-vi!0*CG;LBOD+z}iSi zP}t`VFQ_7Be?QAYJIxhTcZ>iYHxZ=1sD-V|SwGvKzvRc%m5@^T9c*J&1%>SSIwLEY z$Xqmsod#YovV1F~FDeF&d6!`QnR>{4Xa;*U>;w&c(*&~TT?FONBEU#(9r!(Q6!>*K zhHm+*B+PGyK*+2G7ANvSRBp3i%XgL+fZGtHGz~&7SHnz`IRe8cZ$VW`PB38`4!>qq z!2Dum2<->L*PkLNC06ix{1eQ*bsN60?8A%m(NIBi`4b^Up!E7RyvzCq?F)Q?k$eqy zE^^?%qXYErv;%+a3V5YG1p3<}(%zd44U;{v^sk)2JnA0!t*?ekwQR5-X@cNS7eJz= z9lEXK2y-e88d^TUtKg69xxNg-``$pf*a#>@{(}Crv%ueY4@}p%!HokMux0mt;7Q*A zr-Wiyq4pf?JwL&p4=cc9Gs_jv(gTm|cIX-$CjQ&EL)YnZ@Y~`C{5w9(p7HBoD0>4}v zQkpRho((I*$k1GHQ}KrlVXSla_X+5enZ|x634svrDts}Q6BJA$z-tsi@9a#$Z>`f% z^eK{%JE$zMoo-UEr*AE7u* z8Gz^YR~dglum>wQTgJ2GIg=OEPTvRk*Up2Eh4dN51Rhb;L!(9SD`Lsk!g zBYcu@FK5BAE91Zk{0`ges^MM4Cy1W5L9@a`IK^`5OVI(ivyA1hx~2%$dXK^3^^Gu;)<~pg zwZS~sSg5Dl!6s-i89I9hYCo62e5Ojp<2Fy=rCkqi@05Y@a0~mrHR13!MW}F%f#!o%@X6K@0&5fn5ti3r z*{~|))a+#}YVu&g)3=aGs^FxvxWG*<8a$p%1LcE2OdrU>KdKg1^4`FoRuiyNTTND) z&VUD-=0Q;EB6!oe4<-}Y=bKLqEUJ(Ig=QH+MRqgz2Pg}2s?DIdWDZmmD+-1Jb3r>b zo}4W2fNfr>;3yXh^M5W7gzQcMq5KS(?Q@f8tPcl^y940xwiJ^5yC6g6Fj?Dqg1i}; z#h3p0xPCBSmEV6=jm(NnCujO!^H0R>AX}0@@QW4;@xQs;Y?Em@Fr`{COKLmR9+3dvP;OsQg zy>6Vib#LK2^ep7>mb+8ef1;Z&cPW>iczqKWd}8kxt~Qys)09mA>`2rqFOV@~39`Xt z5j}UXnf`J(0eO!%@IW(=@Z;7ztbf$%K;CF5v2N*Ab4F4vdTVYe zyhiq;p7z4%OCTzC)Ztv$=ZeLWW02k|E)HLxCd_Hze>2vijccW3~;g$iuF-hLcRw#0y( z)IzYY+X!k82FThNmcI_10@CYN!+}rBpcC(aE|%*%Uf)F?l~t1_DFKm+_W%R+W8_J| zPvW^w6HaPGgODHu7P7v9ro&dOW5ofeHgWhE>;%yY<@~@$&T!v&3B1d>O*{g1plZ(= z7+Uq5bZ?v_jbGP5n2aohPMr(Bi7P<-kpmo`u0y8G^@ftrBJgL~_p&*AoDf9(>`_c!RFa6SZ!cJsi(lY z+8)Ba&Vj|go8;r+e9{$_&3b3&!I97zMDv3S2+d&o_EF+sVO9z!Suc1I%Si+*X8$u+ zgh8IW9nKmq1&JveKw@~994J=>@k>cW(nyD(&Ycip&LxMty&$58hG_$%q@npM8H}IL zKUtv&xWWZ?C~Ss?d-qA&h%<=1jv>oTjiIld0r#m3fb?3zf?vx?@6@RvZ|1bZ#>2d+i6m&Q%09eDi?4N7sXIz-;JCc7@&o1O3=W=)TY zH9Kpbvc(7BraR1Y(twBQ8e~7q6CV)zNVH$*!@IgP{K!=`&K#&IL4&|0J-agP2W>^Nq&LnKs;4KzT19n;vQ~gHAzcVrl1WZ! zMiB}P6BlpRVHCw9!^u(LGMi{>qz|mqBNeQzf0J`ftUD!AhnSvu zMZ%p|Ky0Wycx9Qu$U|25`QixNoYO;|UW_F=1YlBB3Y3+rpmSe3=+>Ko&^${JeG$$# zezqGlyfb&bkVKV+Kq(o$sC9E%Rvf~1%e0vN+ zE?Mw=Y8V`Nyb-F7CBtl;9dJoA1A_Xj$;th$@PYMF&9tw8LfeC&e)}TOH5G8+YAuM1 zZDid_S&-DG0?muuV0fM$)Tt+d@3y_LVd{CvFRO&34`iTBot^g?OpsC047j)W5^?m@ zg2wwkkfY3lW4+~YI425fTcZf6V|g4fhR|0@aIf|)zu`eLWXNxa!rx-h|IHtc zrT-(+@gcCD^@4C?g`g2jlbyj$Bqyqe*tEYPi!W)w>KjX;dY2JM-MT^I?Ak%&R~)qT zJ%YLi!qD&Vlzb4s4{<8%Av4{KoJ&6mg)3LU;Vs6nHfsQkCvCy^t^<6MiX*Vk5Dd!l z;DrAU81y;??+OCpu0{d;y~R@biq)he^a~UQ(6CbB739xtgq4>LL-Mm=Sn{!yZ~QNt z<&V3ee*asT{@xvKzvu#khvKk4=Q?=GUxSRQ5(r<{2EoO*$ar-$jHo<-h9C*SvZKww z)xHQ;#%VBFUJq$mXCPks8k~9&M)dXLK_K4?w%2+=`N4T0r=GB$#Xh(o`~mv-snEWL zt#hW@gXHG~us!4h1Mh2r{Kn()B>96E916_@ zlQ-|-LH|p5u&4souCE}a(mV*he*nY>>LBQtBKb3y4-Id!;C{D0RA^jtjTOFr~^w%a>DIz1#Eh~n9?D@pwZw-7)p9Ox?#GrO^ zKfG@{2Oo+V$XhKYSUy$(y?3P`e8_{*j7$%7W-pU~F57otCWA^Ge~AiqWg zRtywEU;SOMY0!odQzJ57_J^F5kbxc76<~eidT1}%0x#48L8JONX?rdtu)BK&4&4wJ zbnRaPmo7=dJ}WUnMMN@Cg2O~%7J-AA5g@kd0GK<=3zl3BhsKy_*jH6eazwU6&eTqr zcJmCdnSE&SWL-HNmKPc;Aw~fXB!5LROcm-PUX5(Vgtq~XuAT`m6=XsG%W{5ozaelv zgW;oH46MoeMRE=t1;ZI^ot3r;3hsFWCucdt?PI+Tj{}I-|7VV`4#3;)3m`px8{|B+ z0KX(n_-pJ2Qfm6}ugx1C-<2o&T58}e9077(5x_mcz?JPGu(B!w&PK$;*n{jq-(5@AK&lJ{=~woG;f_dHas4?7f5;&B%S>7NN6;4v@*mvcMC9u~z z4h}i7?y^=p$dz6}7D%vXg=tdk^Jpz(nOE_@*SSHREj!!T*h$>>>9HPs50DJ$BjQ*H zwy^%Z(NF~#VVR;u7LIT}#|835^+O^0|-YgnTUk`McA&g86izm=9-T+-q-ACjbSK`0bMtqD1e;}8V0r@n*ghkc8BHYU_ENan zxdmGML|~o7O?Z}i7)ne!h`rJrM#0+=Mt+?Fo-SJ-v(F4wizRSjTNRSxC(dK{()(7D~R73 zCuW81B;jWhGzPB(opOC5JQ)S0ca6ZOSr_bWAHm!l2JD2)A+G%x`MpU4vj1g(Os*&7 zuT6v-H?1K)B@(WDd{5e+o+P3r&7gNm0m41&L4dPC>B$OsvuzcuA#wb~@L(`~R|OKU z0jw4E;Q8_@=w8uB5|~{0H<1m(VsY^6@&#B}S3ry=++ozO9Lm@ALk`OX`*p-X=#?EH z`Zp62&mRJhpV^@3IM`CkKz?(N`eejct)Spdn$ zHv`&3gL4|oUaB7h-=GqpU)MoTiZWYQ|0draia=p^HV{i5>327Pncw!pg31Q?^o0xE zg^95Gej=G8n+{^NHn7qw6ZZf9!jJbn1$9Rc!l>CysB#Q~ZqqC{-!}(HDT1#lS>U7Y z4DYBdkb5Kr>Vwna3mhO}YI(5GdkD_>#Xx}W5wK$KWy6?p@{j+V7#dr{F1F5z%2I?_ z(--jBAqg5Q-;&*PmN5_B`@>h4GN{`X1}!S>AQ`$G3_djz)0#N)d#sy$ACH3U;8OS) zDGsl@6v>i@9mLUXh}Z~!A@eequ{j$ArE9HWyFv$P7JCd^OjE(1(+AUDO2FOcuL)P{ z1)M9|1`F#~kS^AHCiv_MR%>n8TKN+sWxBvVt~*p(r4X~9CNQK}0_S@VfxP|ydt|q8 zhOs0qqilpe4nF5pie1B=SvPP&hCE%-p+e_+O5o~kJgRtxEG}CkL(kHx$Me+%xZdd) z{^8V)mrjYJ{M~0Er>(c~lIvY~l|nUEDJo+f*+;Nc=rwFUy9AH<&PLa3%JIEZ!no9_ z7cXosM+W)%*r4YKHqB8%Z+s*%yz<7mry}rnI|H10>;pdZRhrJ4?8drZwXsT*815)P zkGuN+A*Y~9EFb!pO4TvKTm1Rx0@a6t>(1fgnYwt(fnJ<@>jOT=&7$nJYVbF=KPZ|v zAC+&O#72>_=%sNB&(Qf9mX&qHS~`b$^Bg_#{bfI~_a=g8RPyl)0|k1Pp&Z`Mxr42S zIAEs8N;?Cq&+~0N+DaVV@HQe7gWV09@eSR*jMa`n^O7Ejn5&;*!#iE+Sy_+@h!#6xVQQ|PIX&J?~$u#XOL~28y1H-HWS}D z-JHwVbo>Esn6(qrPo7>`{q8tAxbP2B+GvlCUlv2;Upe;be}=7%F-EV2>A7ov!VbQcXd2TlKJftQ>x-bR7ksYeI%0Lezn> zPiUE|2A@6WmSURNeqt$(SHk#X zLod=?Hw(X?l8ajIbfK_g)hJ`BBv#S-j27t4!zagd@!!F8U;?GS|n)tBIv=SA?+RuOcZNMPQA22}fA5?^~4K=lkrVdp19$U!0jJ*#|= zlP{5uo(&1*xF$GQ>6emZuVHv<y24ZK9<Y`GZ~hx((3-%3%j%w^==B|sOA ztdPsKRajzTI<7df4h#22qgP5^NG8V>=d(`t1Hsp+hC*qa+;JO?-oA>aTKeKwVYd+Y zccLMU=_vCi4~=!H;d#qGpzM8$*x;Krn{i|PM(RW4`md8@@NqM2t5*Q6*m}s_kPSgI z?Ad(SDp0u=$M=L_cq)Avmdq5eK21Hiy}JrTj`R`6I~Tm>=K#@&1Lda|;6YCTv86nq zHn|+464@G^^~RbE$H4W$9U#8&6xgsHi503jAQI|CL2J+QXrZ?W=#6 zr~~^<_Ix0|1M;?=2Q8K_Z@j`fP_t?9 z4ZC^7J=_3@_CAPv(f}cId9b!A5x$Nl5=oQ}(+6yz`a~vF&H2iY3T3|w_aIcV^~F$p z5HzuQO8Kd((A0?_o0kQbT%93nJG+nWYzjO+mkv9=93aoE^WgNUA*hXs0mknLM65}J z3-#kf>f>{w5MT|h#$nKNRS`A>z5rX6vCw_`mK@x;jB!y5fPs)Q)+fg1S5~&OeXix~ zuA&ygYmFnS^Pi9{O3@%$SPD=i&d#3{iSdsP!kio;W@cYVpz6Bnl57m|*Iz)?>NZ2ogK| zB$)#$e4|`x7`kT%6^U*TI^IU)X4}Dz1t&=Tegp8A(T6Esv*Fhb8npgnNXPwgvY=== zOfe6Ks!0ljKPtn->1nXWL>q?pO2XIa`mikM13y}0f(%?=4Ll1cuu_$W(vlU>)b0dH z)t<0$<}_G2N`d|?AR~MKk-cXhkpD6?p)YeL`z|zx@o{Ic+J2ejc%~ASyJyJWfn{)E z*pXD%-66XZ*j`+<2dJEPgb#<<-b%e1>3Opl=JxiJO((Qq^_v9#&>3y`c6A1v;}#Jw z)@lDhumoZjafx-tJrcEODLlOXk*u9N1s*(H03~i3(A+FRZd~9%?#>v{i%|xyjTF>9 zSp+^N$wco%FiBe6M?9Cvf~jZ)v8@OJFEkH4RinsP*><}1t1z5p{dQjaWntH-AEa}7 z$nlQNWa+cn#54O4NqeOPOF}KcmGxL>xL@K+w{IuUSI3aucM^zU#cgs&>^=!*Yb|lz z?WE_(0jO$Q2%-8X;6~|r0&0<@Ejm{t~_X(nFm{ z&O}*z-y_S9D)^A&Gi0B|M>Xp&p#DW2Xis_>3S9FDi3FXbu5CDj21mc6p|d}bS^5=p zxOx;FHT;S6iiL3TwS4qL`x%lm+k_k(vk|xE7|LGQj#SoFq8kU^p!S?!D0{0bIx=S| zQeBCW;@n3lQRF*iw=oDczb`_!1E=DV+;Mc)^csp_xp>8Sw@}RQSR`tF2dOqKrn=HP z(CnsCbS2RSogXVf%eC&J_}+CWjSfa1bMK<`c_}FUVK%Bh+Kg5e-9lH`9d%If1oh2h z_Z%wnQ9*V&ddlu4vD&7EqNS8jz~>m0Z+jU{b6Jgs_9)?Y_3LOu*j%(}Y=7;-?dQ=h zp+U4L^)kX!C9qR#Gy)${_P1kO();95rE(oodiWNVT{A_!qmIFzSd2El z-;V-s1S76!EaGgOf%q}9_(gULQd_Koqa)4HYI9YT?W2Up@HuoD;wetmf5=)o4N+HP zQU1M!xLY+9%~+X<+O(Ug?|;M5=;&*-xV8)h#CD_lX3Xtt%;K4Aks5^x#hM@E>D-ec z`*__;L~H#|UgDj$4B|OjXmDM2Iq?2S@p!zI@;tlUCEU~X$-K+2TzKLG7i!e<{kU)E z{N@H*7w{(6r|_B;dwF(-i@6)S&hXxKU*t~z8^c|@XC;?r7IE`cq-!hwS#kGW*R6fC zb~$fT2E}##7Qu~aJImErW6pib&*3^OisvfDn)C8bpXFWX_T!?PP2A&$G`UmP$#V70 zQ@BxS#@t8sd$?k0k=%;RL|&MS8`m#&IydTbCr|XnB(I2`$#p!E&AqlIft#V2%C$b< z$a~xNw5FpgfV;e;h-Z5&pPLvor>1!0Hty_>le|Xs#Zulbc?E9g@0=Q& zqJkQJU0Y2~tu41p^ElUeM-}g}kYCNAb0syB&DvbfL{-gCqp92jU0mLiRSMkGX?JQY zd*o|xh@atYUs%GeU6#nb=J23q?nEs&TSJI9XJ|{!+LR8S8UHEIN#Y*w+qrPw*;G|- zLgYc7RPrEiYvn!es|O=o{*!aOLhlaV)7KT8QQNniS{X-9)1IG(QO}l8VuvHyc#Jv~ z9xqBsdsTBBi)%PyX73HWx}S4q7AR9IY!*_TFV1p)%u%L(8(DLjXHTboi;7WQ@*^Cs zs1&uyScQD&=hqN9X(ojv3m{IVCSfiQu^$QTJTVqreB8^w7mrr|MjaV!m-M_kJ@xeQA<0+@8Z-S$?)1C7!*@Clpb_FNnL@#HdWfW&u zq9s*uWQ=oP%APY{r+ry&av6Hgd@otG5m7Hl=J(>AO|VQ zQ=i=fIc6~thEgJioW|b{oc5fx9KFhHj%PqVM<=v`bA8f)qpE03Ngw{hnLXWx8j%U& ztf^VSaksUkc9q@Y_{LTmKKdj?El?nw)2}Kx%Q9T4jCp*Hxmg3})%PEUuclt)T4T3u|kr;rFxYsf5EkwVF#G{bG<@g^rL8XCR8B8WIfYmF3HQ%8w)?uQq9vD57wKe zJ6(!-;{SyH)B2S5YyU;p!cF>`+H+d={D-=b)p4}%FMVcjoGSCe;S+s%lLa$qxR6;Z zqs9C^B2SwpNHXh(9O!{(XK1qZ9xZ-vK69w|9_@Wviy7X!kXdu>4;EKFO~3W(qze{~ z(!wng_)16)eN?5EPN&ouiAI*I{+>dwY*J%cd^u*{_6mC6NoB_OnH+x_yLW5+*jt+O zOq`DN8KSw3A+)`I2yOK#4UK)4W;ULDPoFVrqyM}9g^pbCgHBdiKyUMy$K2$wUbn(~ zv~tD|nzw3#7VCI~kGfpL&J_jpr*r*uK2oQZ4$;hK-g8>`?q{qg9L~4e#i#E+qL{CT zZqhCptY0zZ8ofL?0zcm)!MEF2Qhzm2gpu%>fqA>3m&#Vdly7M0#Q! z(09joGrhNgF6h&t|K=2;6p>EGN$NWzU7_nC+>axJr8be2H ^B@P z68U=>5X?KwdYIH<&By{snCrz)>$QiWe@W27vdW%|B;oDxB&fa0Bk?1_Q2*@+sBHHH zpDpaJO}$9ct*i?@o8loim%ZBG!a#JV2LvxPg*@lIz`bb;o*$0D5eW^Fb1uLz{gz#0HwMyBNY?xrFv7o#^16~!6 zlbfI0iBE4AVR%R2v2z-^)G7_{)>{Je<_s*APlNUJX3&n=Ou}<^z-DhX*kZp2bjoh> zf4$fX;SX)#Dw`co?`PStw}G(z`)~5XSPtU$9Dv5_8W4Y+f+MUqzRGMTq-|&CRewWa z@vEyK*5M9QChb5)cRLK_w~{gWE98^*TxdAv2%^28$?AwJu*_x)Tw>Xdml{%xnB3j~u~rr~rCf=Rjv|9ueK_MIu?If*f;$>0PlPzO#qWy`T9DW)zdx-B;Ph#7*Mt zAqDo4a*$;?7gn4oB4hkZaIC~15SIt-DSc#{AIsYZUV$208r%xiiQ$6%P%EMhwKLTq zZP^X>x7LIQT}$D&upd!mUCzDrG2r*b7St{sgRhVGFg}t#^t-?Yx>jo?UNmcjnZ51^ zb#sHF(I7p8$*W9a4BMVFdL8F65wFDVf@;Qp$4e$#ZwkHa)*mLCI?k-@5i;7>v5CP` zMT{~Qv@*&?6L?68-G>+dp2@K?Hu7K2XDF9ig!^YQy{=s5+4UGk#9G1VcX=uP=<$QG zDVt_=-|7;h+@8(UzAa=*&);X*%9D99igCShHM98vVO-ZNXHtd}n5Vl}GIxfWnU<5! z>B`;eM$=!KFoAj=bzi>c*Bw6U!u)qYh+aQt#7yf?W1iIf$8^|FH8TB~iQ^tv)%Vb& z%<>T-nje0JIVjyx8~5cp^QEH_zrUP^$gy~)(#0EJ3>QJGyTWmm;5-wg{t0guz0Z`z zvG@Gnv&`y6%JmB#Xw+*-ePTp?Bk7q&Rdu<^;aI<~$S}$+1iREDM##pS+14dOo8(_( zu3iXb{BM=v@@-e@l;z8q=cS*Sh=>n#zIPG5Qy4Q(&a9$!hyKx9&VHkO;RNGtw~1M` z=ssRHQAiIYsxpcdl0HI(l0HpbFAnBg1x)P|f{TEEj=$!PUk8#A_uNG5AAg>}h5rp=&+%EbpZ0vC`I$A$$k)|q+J7&wp1}fUyt@SFHEYxD zCKs6^-&}lZY&ui8$DA)RrI3d5G#otJfo^$|N9*{VWf~X$r1Q-q`7Pro$;ExsjmGQ0 zOhWapL%a<}bDfaw7cmB}3MT7aXgXpgw*J#WyVm?*8dtc{KGl6p(WeRYWlInL0i0ysTRvx`!miQx+0RcJ zFlFqt7Gq-dfffoo#+P1xm3d?5!|a;>45vPQ$5>8sXx~$-$l%3)Xi==Zkw&K)!+UuF zWs1FKHdLQwCZqakZl*AEq*~wTd6gdHwZ)cEwlkxv8@uR72ds@G#dqP^HyfA|5mlp} zxhh6KDioN1t)BF>K{2NASrHRGdYT~$8u-mbGLFzRXSV-RC1<|~GX-PAsQvjTL>Zkk z$`(Dzd@?`5m#J7yR_#2>Pe^=;Ok-5>Y$C=;eN847-!RiKU6WD2pUnJr-arR0u41k> zUSg)bS;tsDmSfuT#EdF;h~uN@<(Pm)ZS+>lR%W;8CZ@wgh-v*HZS?Oz8#AXRj?wsN zNaud*rSF^anT;Mt>NoF}LdMT08KE6KX3E}=w5D?;((R~1Z-wTd#O?+v&O``rZMH?z z$XE2?O9#3zB?jHDjz#)`wVb;%O3>cpgQ)4?59Dzr0Ieu^ho+oWKp}Z|QQ-Ig(4c^a z4!r6@KNdZqb}FPI`Qxw9dRIlf>e@rpqQFJ=39R@3XA5dLT7>!r|3hBO6R5bZ3?vmh zijVR}VX`pwv_0j3p|IqCCPgJ=0ZZtGKAEjviK^qJ{p{6K;l-md;tkQ&r-bSLb z1uf{-xH{z%(u(*sg{b7BIa)VTfX2pep{}FO2(<>Hqp8`q8*&IdbTphM(LFN6DLokY-vf6(~IuO|7U#>0`a9w~>729PLnK3_l896^A+r!l)VIGs;9S?<*V*UnwbuJQ_l@kv%cEnXRq&q+ zH_){>4J@pqsQSD%+SsCwt~y`V){~ zPX%gnYUlo|{|_x+mx%TZeneZ|x1rzbFC*E)%iN>m0@SYNj}C8SXl|7jXBh|RYxi0H z9<7nm)Uzn=-8EGG&Iu`v-hi6Dt|Q~fVD#GJ1hOQQ;#lw(}$zIg*EFJwbnTGnuDd4|TijdQGHN-&kv;!Si13>54q=^a?pNZ`1{p7ycLxsF)!mJzMTk&LCIVs*VP#w9v*lFI1bo z0l~t(NI`9ot0$IaEJFGIx`aP2z3zE3byx2Mzqh}wZHnN_tS#(-qY*So7=q7u6*!<` z0;xkLY)xG| OSKclunY>+WbeyRi`7WA?`ReauWy99U-jD<~B&qe#A`QDz19o#r$ z$9vf2;KeC^em-hCOdIYDFP8jZ4SS3sh2$~u$@fg>!cCTErvnS!q~WiU1(Z#m0WyIZ z?CbDQmdVfedY+AiE56g%uvNfzUFm0%HnTy}U>c~s9u5hH>a13%4d*gz*|kx+Fz@#v zQI3WlRK@W8{L6`~d)*)#A+HbFZP_gUemUE`O&`V_X=2?jA6Ra?2H5D00?m8>L>HXK zLyPoYXgjC`3(X|?d8`(!unJ-mLN_uW#TxeGx(tljdX8D!dV@zi&wRbQlN}qy$bR>4 z%u;#^j2)7J)>(X?e0DYKJv*OO1*@R^oMdSSQ$-i}4U`NerSenNY)_&_h*n3YCPJ3;E2P&sn_3Q0yy^%NA|NhL%n;(hrdp+2_ zzlHrHwahO&0RB^KX35Lj+4~3$RvmMPX1k_Al1SJIw~i^d)Gyfe_5FYp3{Ph zRlKWllRq3Uw}jW>J3v)wKdhDyf&IN>KzBT!Y0`hmDicS+*ByV@pxIow6gnC9t=a%J zz6T(BWj&icqkze-6EJ=L%=>1`UY29}oy{=hv!+jjpm@h#xa>L|iV~)?#b$Hh!9qDu zoj(sI*5rtGrMdwAG6AgOZnM-$6JVIJ8$7Cc%GCRRv!l6g@W+?Wy$;ub{9{gVRxk&? zR2s9feCM-mT?TYu47rsiVD^b;=pMVswC5)>Jy%&6=W7nsvxZ$2Cqg{tpU=E=?7mVD z`F=qkwte=7f(mmmTNVYT1~TxYB%B=|q%5HHG!xo$;8VE~TAyEI+NlpkYZarJ&zuZ) zG9`yKi@&mK;eAZ7MiwSsInD+f?u!@}ppCG9bW0DEhYtg_O=fUcNe%waw}y)qUqyZ1 z5>Rz&A@~em1cuKvA#@d=Q_EZgGVmW{g~@~VTnal6UuVmB@9dc)jjXkB5_HcP0eQ`i zP+PwkymCqy`FD!tfR?rUDwSZXt64YA(sUes=(H_7ND?Az%sm_uwYM1_%Puc(>ua*I-c=a$8DxC zutEjMIQuR$HONwS&$7yn+48(Pygq2bszh9T-rY3E>kmnf8LqqITKs z?8}2=Z07P4ENop3>+g8N`hC0DghRfpXviP>8z#WhpTSU@ki~R^!q^XV6s{eU0n?;z z(WXo0u)(jF_sPCy&t;>*v*kN8>FQ@wj~X-Eugz=$&&gglR*j$IVX&;7O$!4*lFS#{ zbe`%5Jmz659k+W5LDQ9ON*j$RGJj6r;1ATGd@sccYw0%6e3~ZTNM*@YYO4C1T4&1B zYZ(=Mr_GoS%c-MXfB#Ttr9NUiJD%>a%%^t~RBU>JRcw@2?GZid`$^uoD%;#JeouGY zFt;(E_nS0qy2^Xe-_qk>;%QfZ0+o7wg+9=DK&zx)Q52Xy%uzK&i^g`o*l?c^I0WdDXt zXwo6W)9=$dzg={aoe5pJ=#)sYZyEhj{F9c99z)}~X8!yth02l9G|cWYy?E^+y;6Rb zh9*YQs!1tiu~!`JEf^rCZfmHe{AIxgMGs1xJt?o)B5P_b@YNuDo2aR-^votb8|PF9 zI%||IZKyD|IbqpIozzqDo1kO#)%ZLz&)^&_`+{xEuEkJsp9z(iYDRy33!x>o7f9RA z96GR7+NLZ{0rdwG^s@XsSLNl*O*|Nd44Uh?7Q-Oqx5yLi+N6wjJF23SLVN4ZWtQlR z&t8i9ix&9JNBXBGac3GlUQ+&PT%RW43+*tmUM~AwZjwRTCI!UsBK<;!OBLR_TankMg_7Yp!Q&T^ z$8yRf!F&=)-8>q{E|$XC?OVzG&~4~dQv*)aeubj~I&ou&Hg$hjim%KWPOi$taRc`y zgw7AYU~TC)cmQ4tkG4pYGnYm9(XRDm&ysw6?e#gVZKgs@zNBF5f2!p5yh-HN=~1H7 z21#VtA0M*caSG}*G$UKKJRm%?8Cz&wBI7C|$(u}NVi*1n-IO?v->#cWlDDdn4Jw)> za&x5MOQb95`gfPys~9FKKlDiOpiQ4%->Xj!zH26>eTUJca3k_K%b9MPbeBYLo+Fxm zU^Y?RF&1YkRggVOZRFK|Cd8@toKS5+2Y&HHj-Xp_(O{xCdF4_^0^5us!u~(Fz4$H@ zuiwR{^7;GTdjm`ungZlWFqC_m!r=pxVckJ*QH=LuFkKN3@gZr@#`g!7^Jm1ersd2s zEEK8^^106Xjj+Tt5|&9tu`QE%j{mWf5U+Uys!bx`r)WLz(VYYP>JGw}u?rx?KLkQ6 zEZB|DwqW3Y7M6FOg>}j+LGe#Ks5&LXgC#t3bJlDy(u#oE=?W0FaypFL%%7R^J>Qh- zCGc30_g{=jfx|N;LGRd8_IX4H+p#hPo^&QLYey}}@^gXxtr;*WD+x3|ZiT0I+Zb-% z2P}UAB=R|ypynFUaqmMgXPgIk2*0yN6L;8_a0K3}%0TUF9nha}6qX;c1VQg~_;1T@ z(2Md1n?g5+48uXA{4Ut2uZJq%h4996FIWsbVy&*ge)|~1Ao7GG!T;F3I{-73e8DZM zlD&@Bpo`AW1mnzDn3doO7Mt>+yJsA%@8|o3PrTVu9U&vxYvA&`82&TwnRoa<(T@v- zY_RYy`%G(?>n#mXwbF&1M~z|J$U;_Ga23{+`$4`zISkGI$Xq4)u0Sb3Z@U8wDVwsF z>@Wm%Ooc_uCxFtdYLF05fg7(8ERfpG>gO21s%s}8V&MXwcM=Bi1`$;I)*?D;^+Pg# z|8`Q}s%Voo;R(rqplCB^!aAz@&yzmXs-))JA)f2!Oir}Ep(#)0Y<_RcCbdU~Xx6u7 z)a^?rJ-pP1_V@ME%lNMS^Z8v$5-V4|2m>h6KcikQEO+XzK8-G*()L zY_^oLDgIJK_1>Hz-g|S=-z_CnchPUU);yRdtP3LF?I+NBxdIZaK9Od+x|0~`i}a9I zIbCvS7kQQ_PxE@^X{Cn}SxE}63Vvr%J@FEHv|=eXJ+RMeE+@@iF~@Djr^8ey2WS|x!AgiT=1VwRjo8=Uw#&e zRLP=wVegqL&#cUPdYq+GQ+9F77T&2?!XSDDINrxRC*}(qT=b1iJU&)5shVHA?(_i9 z+yBA-GmqG}5_edu9nLZgZQwlb2`pDKgePDRQcoS2@^qdLr|1IVwc*g$Xa`$j48U%k z61-2C0;2E{0EGmO=Kd5VL`uU@!7>m`@q~wgIq za*~Cp!e*B7%mPYlHDP7K9MJr;92WEom`iLT`?@ZjZ4M`}ziBD^5cq_Z?o$OVg>_JU zcqwdJVhp>Ij9G}5IqwzX`{8w#VAXU|YYIaU0GuxAII>E*jd$8$js>{y*^FWT=^cn%|p+uxNg-v~-^~ zwC^ir)ptW+iv9#>=eW;a^UK7pRivB1g2-DI-I3SxIrQ`G)t2L60M zmF$-IMGho7<9FL1kil>(;@DzNnz^-CU4GY)`5)$z@I+Nk@kA+3Ys@C;vml!LiWtZZ*HCt?i@P~ zf4D6YCj2@h3}^u%`ultC%nNvtV!2v(Fm`&cSDn+x0 zYhN9Tm!VHr-oSCo9BGZCvZy??UMO#COk>W+Ay>Rcw6%8>ZU{>i1hoG{x7QocL;OCa zr$P#w#Ks9DPRWu4ogKJ3t_d&AF30&F6wx4>f;6h6gs-RhbN!22a8>L}?nLE%yv%MN z%E<}EDf^X$9r}vGo2>yT*wGr#S(Js}hIMf@fo3@Ps=FXTVwlh)Dnnp5uo1cQUKCx~ zZccnX3&pIl5_~k*!ZUipg+;fI2*n~9bc>sTPb-(9bLEQI>8rnR|9dH+&GAV5@J+Fx zWW5=V>iQ_Kv@F154&~rA?`9ys%~w#}4iDkE7!FAuDG+YIF^l^ZFcpozaj~prfT7fF zT3BcME$)WiWkKzr7ET}$-0kZVgdQjI1_Cx@ze<9mHU`;)U-l}*?Qc*?yev((oi_k{<9$VnmukV zvf@^gm&n5>A6NNp;Jw0iTs+=|%DM$*y>TxEExSevmv(Fu^6(l?ro_Y=EF!q)MQx;Wza6$kPV{kx9eyxuCGGh)g8FpIQ|qH~WY(kI7sY(|gen)&&&Jg})sB()6Sznw+n63lq?Xjfc z#iPiGua)HV6C0t)0Rd?_hw1q@0c1c*l72qpM6@>7<6HYoX~w6qL?QeYp4&mF=Q&B5 zct*y0#e_9tuKO8Y>RP-~FS<yeV-TAY`&sL9q z4ZDDy)q=5om58*TpMyu%V_Fg^jgZ+I;&rH-81)?`p0@zMeH2Rn{pcYT!_Dc7#2=(^ zxE|TOWfV=_?@E#LRbfdTKPTlo2q7lEH2v)g`c`@jIeg!VJTjR^|NXm93bktRoF-X1 zS>Bk6`EHc=rSo7UJp$&}matRPf5LqyTRwmN8p2d6p#Jbdh=V}hX`e3&Uw01j{=R@9 z$@g${+DZ_Zzu@x{N>CYJ2@-O*`1N`oRQWsr+3VG8>5T}mS@{$;q$rE`9=!*;;)@Wu zpYQG*1(5AYh6agS@N`o!+w686>>@f~4A%+Y=Vn2}r)HQT?gU}}7eL=m!FsQIFl@9d z{M0-F-F@CLUc~czHl%@mPCZ{#?gH)U_MmU454XZ5z^!K$&{f*bo_MSV)BA~VF60x$ zy0t@H^<`)py37_e3Se`*KMY)DFzKN-yYven*ESh+o`KZ1oQXvIR*CLD1(I`bf7>_0sdXz3k4_x zLPMrO=Vk@5D6A9tZdTG{B2}8K5=tFVE)j1FwRg%*H&QaX01Q@0JU2 z`SWA&Uu_0;`gSb-Qm~$R4;{} zi`)hWhofX&Zwl`JdxV(#THw!iQ)#$mgHSeX9^HT{$^FFbWQ>MBjo){dBr2c6YfDV1 zTg`HszKRj6rLI(dqXyYIL4$Vcz9MLW78N?Xe~vjR_)MaR;f+(HB~pZYBXz z8RSj4EuGnXoR;*zATG&v)&;7LbXKqq!I|qRNQRMF*R^T)={@+nTMQ9qkEi;#!pWz4 zp4We{h^&b`N$z?Xi>d?Ok)t~c$@QyW$nKvFg5f#CMEc``>D-Gw_=AfRS+nFFE{Rz| z8kOaVWL`E|Tfm6y`D4N;^I7!Onh`Xz^%oILyMh(6qRABOLcbqKCT+i!MRLlKL{X`P zd>%SQ46A04O*5{MrHk~b(!CAjhx`o^cKi!=;hkQ!vkH*p=dZ*{ss(qImkWLR&2ZP4 zlXQ9D9DHt-Km9%bCgE->k-mRRXp6)jA|VJVtKqNrzt+tp=vWY$S6E8pc?;po0Ymbp zGK?I5#9m3ej*{}I#d2~@At|f%f=AS)$$*==YS!%E~K3sYHQ;JXRA1u*w36~mkc*I zGL^Ib(#MTP>kk!C;eyND=Qpo8$;54(a&{JX{(cyzp!}43m@42B?)GqPQPQYtp*N>8 z&W8Jt+xk1S`Zl(V^&P+Cv8&~~;^LUoRO&`kT6sA4mlBYIuszFz* zrw+X4-h47a_-7S&cDsn%+tSF%r%&ac5+m-Cbqu$Yi8$SdK3wDJF$hv?IjQp;cYbEz z)q4{PxU}#eT&oo0#_b-7IzC798B7(fY~~$n>y3I`<<}eB5BKlfkp5!M{q=I|f>k5A zPpc<$vzJ?NDiTLHKQ59}T@b^W28`rbwLUWCT~*vJLp1H(e6IEJccj%Fj%lCN4CDlAa{t1fs z{EYqROsp2_yX=8K@_DGhM0aYrH4|#S%v}}_E1QB3YdGTPeOYMB_;55zIR=@{ABX?C&p_9mucODQ|Ion9x%kK5=~#Qx zNbKb`5bVbaEgES)47Rrm!p4``_Vw#QS@q!7!BucA>IETp#v$Nh#0NI7d1xV{a<{scvCzI zd$=1-xa5Psm3%|1OP_F+i^t$euU;XGzX%P0!*CYF~8ih}tAK}H_qq$w(kA$UdV~FGOGF1G|oGCBq z7TuK7W`CrIM4Lp}LZwANg#SrD6zak&EH0`LCO(|SI!snG)8Tf)X-j63jL{j$(6>ey zeg7;;yU{Arymd_Uqtja?edr-}++~Cv+h3I`I%Bq~GhH-|mWni{*9gv<%oZM?X}C&O zj^%RI!t=w2$mTZ-L@suVh-JS$6aAgUET4>}YklGb-RGj1@0TKx!5Sl`TmKQ`$U36G z;g{9^^kCNgbv%2URf4bL0rba9k|holkr_Hg)XSlcR%_;wAY4XXI>^~9F7~0fWna@P zPw&zV%C%U-cPTldbXD*xa0;&M`ArKvZC8HE+!#UR?>!NzO+i5ORKLG z(AKOV47M%g#;k7o-)(K1)N!r2;*b-KIuTB<*GbX$UZ(WWiX4msj0DMgqiK_VE!{cP zPfzCErxgtq^wOZF&4~GmHt%lVwvt}cL*Kpe!H?aq)50ZF==i8nw8>~1MQbytf?6$g z(jAA4et+N=D7Rv@eeb9>-?MG`dzmxa*iN0L2k4=3+vuD#F;fTslnWN98q%KyM&y`v z3>|K&Ef`kulS+x>uu4!}nP=}Es`~r&)!YN|*6ld6Z0_4GTJJKMOu5=m(q_M;>o+!0 zefu3GD!q~fE-<$l__~#T|ErH%{)FPng{@^*0@MZFbO&`f=Si7O2MSI@7q(@V_=}4^?IL%ECN9$;j2L_+Zj&3e1yIg*Y?s=zZGfkzDB&F)& zGqXYkOD|-h1L^^I&mTj&*SsG8y}pHXihc3xJt=hmk30Cz=8-nu$Nnp`9ZD#3l+dT; zdp~i}i-HAJeh;wt#Sm8Wou%c6S?pq(AOpScOocGJDX z9-;E#irCx6AN}joMB_T$@pHX2RNCZ#56T+h9UGpYi9Z@qznU7y_l|L48^IaJ~6Znt+QI1>qNZWUj-NI{6=z7 zqw%{oNgVpf2pjjm;C|Bg=z-G=+;(pU?`j=}_gYJ+^U1O{C$LaoAmISJx940t)sE}3`uP4n}nP%O5o1=F?dWx4r&{` ziFRWH>?_@Z+*LlKuuLs1^;`!VFOWdW<0jzFyZ$&}1P{W!B!%g|QJ8OCqQCZ=QLIlL zs+}c=J?0rBR*Gu~1 zcXv;t(c)d`w`eooSK5Q-CO2@RB7Ju92*&<>)lm5ZCWCtkr`UH@450-`m1GWf-$u7krp79MC zJ{@qTrw4TM)`3NQJG_SB5M%uS4xO!n_wrZZ&a8Skko}k)TpA5k2`$jSL0z2XSPNRa zF2lUNN$}&*P0+N+fTO3YK(#iUg-e};8QgnF=zb4h?&X5(x=!f!`v9sBe}VS*KTm_|`?^tbzH)M9C zK-l>9&rRD+; z4sU~w3AZ82J_1x0pMoV<7_^+c4gv0I?8BvpFv(6^e6hO_nv0x^iIi5-IVfnuBm(evm2tzQQ7w zDgjb1fTEEvz}3zQyn~$BR6`l?aL|TDR-?f*c>~Xk+6J;#fv_@N8uEM;#EUNhJh(Vq zJY1H8p|X+CFichaDk>hHMFulN_gnB)EfVep9f8bZU2(tpG02%14bl4vGa#ULn}&^cD|&cOw_In~4dzE_i1`NwUU!(X0;? zTfFEYeSzz73_mP*I5|dC^>LTTEG&dtJReVaF;tNrKR}QisZpH6Yh?ZwZq= z>yh8Nk!1ePT+uZeLW21G!3o2)RQ*9S`8q605O3;DP2L|6w(ZIj>E#fSje!r%mdhk7 z)@>7+w};SOrsL_;y=7$X<36Fy&>s40{cD`r+Jh^e$cQGMbR$a(i|DdbpMGkAB&kPTJFBMFn0nNZEZ0O6oF6*;;$i`LG}n3VFiMVy}oIUHgOsyZl5NY4b!) zS&BBE{lh5f%o8e(j}kR~F&AD(d7=OVZ(*wHaT2)fn@GeTTsfam5Ot-i(Ber!Gxs3-EZ}xmW4NY-m0v4Sp@&A9Sw)5CK+)T&$0Qa`~{|r{{+{y9zo2; zU$9lBk1cD;0r|I*Vp(Z3@j&x;h(xt;+wv-;eCmYX3wc+`m`^Z%O*$*bd7$@QK|FS? zqWGQ1T`2r0E7mJk6z}|}F1{U83ex%C;ceIf*uJ3v21-uA!-{rTdb|SG%ou`6{z~GD zzqY`zwGQy1+!e-t_y~V@E5NhCWAMvS1l5JZ#mrhkJUjC#^u2t_%6GqlIgMu^_-6++ zHSi40kS>_9{~CA;ydXMO4Bvd-!Z?kcaAaXLSaiIF?q})12XVkPyct3@+n`@Z%s&0- zffFCC#JwkLpewo@ZX3J=y`^?g&1V{Ggo&``K_ysvd&9se6S39BMo_lpeUg8}sh?H} zn5amKgEel$$0@pE>;DoU*Y(IVZqC3wbYe;dnp)L>UOrAhmxB%=a@q?`lZ-}puJcawyf`#-nG+}4 z>VX`k^HA)WJU&mp8@21@Ae(P_=z3=^DQtu12Bl@3$fA zHRq7HD<4&@R6|X*AGsjb&$UO!@dC9=9KJjO3Def1W3DA=#OO8>M_c(H#_S*WUcQo2@!y7eSl0)~;Y(%bBF(@)}1ZuCIgkJf@pmX_7=-TZ?h-X)z z?1D&Sr?8QGlogLcX$zlMI*7D9e9+3kV@S5=EoYox%UwQ9&;;=g0FySn;^BdrB+NbNzJGs<0C^e!Y$+)gz?r!MN1KqZ}Dm&H4V^kKC4}p?Y&k^t4ii zds=yud$zfStM={WJck)0d-=&|dK^K5$Gl_Pq>As*N1!UfW7NQ(o0zV8#ut>N7Cq$#Lb;T$@tz8Ot?cp9Z-R zWQiKH=Ct5s!b7&}eM@T~7eqq0yEZ|R}G|aYG0OOqQvt6++jOi+~l?zuh*OXz9x7r+v zSHv>>DOt3na1k55d^htB3Si?d30TA8>+I(EYNlYdh~10!0`qwqprN=K#-^QQ+oHFz ziF~HlBl#oie^M(-U8M`{b6>DV(}yf?!hZPN_MGh*`-(l0AIUzStz_>%O$JB5LAJTU z5ay^lz)sB|m>>L_y)}tu+rQm}#kbYL|4k{Bd7OdssP;GopP#yg*dX7wbnJrD*7IcX4_lg`3EE`rCFxzME93a*~1u-qvWRAzd^ ze#=uJ{=ExUD<{F0EiO!9?{c1}Sqy4&C7|Gc7-W_ezXgwWG@!R!cd$hBb1OfKW*$EU(6|#OhAV@A=?-|ZE*@^Z9|b?GtiVGM z4<**Fp!(Abn(suz0u~FVV|TCx<5Qrr=QZ#y95`^;5A^rOz@p|JW_*0vu1vr%w0H@~Ng=vqc!x~({gu3Bu=BoyF#XlH| z+;Tv#TMpcQjbLxTRWZ%?ui09^PmHrS1LG(wD9*44-)U7WU%DPfg`WV`{${vKhrxod zHZ~yf9Lg500nd(^?10;8Q0{dDt8)&ZVg3O;Gv>pBv_%kpGMYJWp-|eB4ZEy&L&TzF z7<}&qpYwTc>I*3_Tb{uV-fscfkGz|#xdw*D6oPZeT9DYV0bZ4!744sR0{pygL)qhc z2u_>{HaV4`+wzCSt}B9y!9t$lmjpY*${<-FU@USs=(yj2U($c!+}jdp=NYi|GehCF zV=h$xjso+6LJ+;%%x-q>hsH70aFtcVyW?>Xhweb|l!p-cx)DA+41wA^B~U4Y;i&o{ z2-J1w`J*`yqZ$Lh|B1nGNe%4TG#Q3ID1##ZJ1l7^gt!e4nAZ$vsIZBE*4`)ZNB#kH z-bw|n@2SkYFB|CKDv*o50L?@4Y{R8oc)NsW!uE`X?fE=!^1&tOG_Zt4qviu=lm~+X zADH&;5X@D}gnPc{Vat+8ro%t0EhD7GZ(9>#cr(wH8|3#yUlgFS@+Z5t#0xa8#6pFt z2}sTR1v8GG5pv?+3%5cl+6`Kr87yk@V(?59!wvo8;Bop2 zJY5~eWpM^*{E)j~rs`@=J5Wn#t96!Zdpt@=6C8#1*Unwdx1B8fu=TlBwZTcj-2SHQ)3O}y;J^bxR<9Y7 zirvHAo3cURGWV3w`mLhSvSqSx;G}w)yybl1&c#&VIN&V&`Ylj+zs}ccx0A8(N1T!n z9sJ8>OkXEVvo1oVxQ0_63PamdTFU~;5{13lxxxvgRj6p>AlOB<1*v7m!s{YgVe-jS zNO9V76j>ZBI3}0F-Jg-d`97I1ICU{gup-n$P&GHKEcK&Uc*NRB_;TsqvTgS@g!!}d zg=-A0k#wq~uxMw3U@SHeh@zRm@kAu|Xn$2%QPp)pgp4wlP!I@w&h8NStvJC&x7@Sz z4$K#{-s~1c3|B#SWD+=2+h9SB(=oJvXtPjt$`!8nT@<%puU5FnW}#q%vpScDOoU#F z#a0*XjtTcm`U^D%f`!ujtpD5EMJRfzp>THn5}}fe6goJx0EOmOFgPdy9o2d&}hLoFC{^A3yQ8KbV!GNO)yKiOhKo;%%(VVZ3Ldk`@R3S+!@BIhWW z9-|HB%`*IKaSYh28Zh0IC+rWOwLErr6|B0a2R&)hFtPs)t0-27`S-rDlM&kd%(Ysy zad3!83ggxJ+4OLsFu+{!W%u4nnYsj&IJw{W&eJ#($P94Tl>r`Pu z%q>=+tPX*S+eJ=))Zukh57TNt!S3z(%0}0Y1bMe)wlt%Z#aL*-=DQD>Q&=n8WTXs+ z7HV+n^%v2-G+j7b>J778rJ;M$54N{c1tz)gW>#vRY?o>UGwJMSowo7p&pl80Bc}j$ zr`Ivbjh9Kv*e(`bWDH|B{9%hf%?90#H<(3?1AA^F%f>EQ%%a*QA-8cnJXvv!5!=(E zO-^%JyRSDhqubf#tA(ss`6~NvUcvI3oY{x#3n2cFGDKhU0^RUPX49; zcJj996aW5kiLc|`2DjMFfvs@Zu9n>}dBS=sl~|NCun7NgJk$Ie&q3FL!c3m8P@f0U zq1v$JFk^}SgV5*X2+@;2^D?F?@Z>ut&gVm6ib{!S{;X^mvgib(JKtc0AHUvM(E;11 zse{|w2e5JOeW=a80!RMV!<*F&Z1dx2c(SY&CcIV`NA}h7Yn3AS(w_vU0xBR^oB?y4 z?t|Xk2=*rUBqT|GfEB_IuxrIds4?w=ILD9h^89ZI-@DZ5P<*;S0|jZo@=T1UNLF z0?EYy4^cVHeV)c-|EqzCx3t9>M=!(1%1oGZ;u;W<0hBnaLeuv^m}PwdOyZoN?6j(Q zos|HJc4&gp_6>CAlrwPpLo>+ly8t0oQetF1F(2`vMR~ufypXXLE z&weKBNRol454559+GrTsz~`z(zVLYj&yE`*14A7OVwf+6-4oTtBQJ80X{!O&{GPm8 zIRS`N2(#63} z3t7Vme0uVV-73%#uk_mjI@8p|WyL*kyZ0Pik>UGpw$DUu5_jNW@-VTF7>$$_%aSQ#+1ftnvu%LZI1za4e+M5v zR=|nZ-=M}hn;EaV49N>r#DYo{aj{`FG)+|y8;w*IuZYzY7k?IlXHp+1r}NI(ge%}U zK91+ay@i??cVS<-l=#6bRk2p_PI#>~8%~KA!05~0K(9_2Toy;e-tud(0&DQDDP?hL z;|t(MHnVH(T_72e!h6`eVbhKoEM5IQJmE7gilf%SozXWTTICb0>e&lU*JEKr*e5{Z zZ1`_dF+6(N28NNZLE^#_M z!_5h1;^R+CVd~^GhUb5P)gNfm+|>yT)5({gC~} zVC1X)om0cR(Y?vMLvhd(^=?>(mbFepl26v4>{n~Kf&xtxpT7-Rjy;FQ%wL7xXxk$F zY$Iei&K)gOn2cJNFGJ4HR5||*I%s&}K~yAh2tCrVMpsn!pa?jG%0t4?ln;jJlG`fe zs@=iat>at$!(C8e`!Li&+|aMDxz_h~xT9@4laRYf6?b`=DS9Er_h!nQ zxSoK&oL|C16h3k|y3?VD;&tbsYauQu`jZLAN>`#Qd$SS8Y*6R7$tbvZE;@Q3pOg5L z#FbXbql}^{$lJc2t3P`djbM&wonrTteMN?x|%jcf{r&=g}#ToIPVWVL?3l zvfCNmSeA7J`9EQPkGG1%@Tqa z&6W9ZPi;4-6uN?E=Tx}qxeiMH*}}zbTOo<(Vr>015e)hw!Pb*!h41H>2ef| z`Vt3^Y^K7D_q%wf!7tt?F$pH5De>>~HIQs(5AE9mf$lvHV`sl(H@@6p=PAE8=C*>I ze41m*5x1w_z$XYQZ~fxgcIjW;L#{ocy4S5vyORz z<1;afK9tMQSq*4f>Ik^9i!JTUg+#?A&|6W&aD*%kx@if{MnNFHlQb7i zqJe*dGGwR>5z16jk)f3F{`PI65}}e(i4v6|8k9L*Tufc2nzAb$URLZRJDabbMiD?|KSg}Ddvdy z?u#`e_lf_A)5gdnlIl3$k zLuo5R)){a)=1JL*Ps@hw>Gim=Cj-Ji+1Ru>ALadXVKf|zbY~^B7R`d2ts#oehU3SC zRgjsMjQq|s@ct-`L#;2#>F@8!Q@f>v@`-nFIt42f6+HP0N;6Ca~!ABzPY_VCKwPhQNN1fO26t7Z3ccsm?LNnJhhvKtLajUA-+vkF;K z;s&v{baJfU4&BhlU!8}fIrb5`tSv8e;&VOp6DWK=?u1VJaxx~24+DKa;>q#yI3mqYk!^YztuSIxZ>s!+3 zZwt>hTjb4=f^;{9i9XX{WH$>HYJ;ThqY?ZsTp(vQ^^i$#uamyV8pza?fMAyydbipk zU+OgZ+!ju5#~vY_KI3tw+=kR%5R$m{Kgdze%el(W1|Q;;;L@N(PI#&#{CWc^ysU}m zX?ulFFKFQ$^_SGTrx16=KSU};2PLa=$dL3kV*67EAH$y#!LD%3G9;J2{5 z%8+As?Z6(s9L$IRkyqYoct7eOIk{;a*)p}B6h=y7>+cLgjb9I%dscDW?@#9LtQ5ql ze>#Vl z_7a1}3i5s5H8Rbko)oY2B#l^s!@k_i$M``>c#Lc=-b%)fUXRY&ej@C+FAUtL&E?-( z$<$>H#A(@oD3N(iLT9}q+EZ1@#;RLnwUQZBaz;qSkO2~gMP$?3pTyK<6>>9Ja9-lR>gZoE(2sth1MV+p2NYheD~f8?B12eIF(h?JuDL{U{0FC*^=t{DVSCWD*bxbwHU zN4Q;C9XAG6VNv@C=@1_v`IWL*Yq5o7RxKd>jojxz@b2(Y*wGaw^t>kgZb>ZuP zF_;rtM;bY%-!hdAcxG8k`aU!g;tik*2kZP@x;sC zjJ!|vN0m=G$COx!`HEa;c-0ponfr~*+ifJ=y-NenCoaNYtc9<~V^Z(y39UUbBzcD& z693qu_Ja|+OlRQNyqQEQP6EapLqpw~%Y)iDp>z|+5bRLI(P};#CaK}>cUwrv{Sp>+ zNg?ZyH{|73z{XCO>;CdW&*>GIZ{>%?`HHw?;)IU4JH+JNXppQ|r0%;F3PLpDZ0LrQ zZ9Z_Z1M!@eMhxw9Nc4SM#1$_mpIo1jGV!r!8M6^(3zp-F>tqbYP9|PfJS=MdNYs8< zBY5j^;SN0tk$&Uwt@RQyfGU=*VUTEcojm8>tG$mIY}@&pv~bJ{tpPI(UEpEjN>$QV z;{dbLcsPz2Ky$P@cBojQxi5w6B$34B&j67z)yBDk3X-cE1uOL_*lia}LQb~`5{(p) zx5WeBg0)d+y&H-B?+GdLCvAQc$x*)u(%~=xS*zR;{V$JPsxKGPrvDLz6Y=EZlH-KZ zZ6OAq+sQbi52PS9n3&XXJsDrju`D762M^?v(WXa9uVNGet>p0Q$e=J-m9zQ19U%iN zKa!@QL=fA*q}x>jorz|o(d8|%FP;OI(@SNa*y97&ul3)GIz-*GhDA{;k<(Kb#mj7f z<9m70T>XB;c%@^JS0-Y3kAxfkyNTHWQlj?kF(T`XC=7faCEB^#6dpDo(K>$sE9@R3 z`S^DT9EQn+;qzGjS6rlKXeQb%`xR?f+(+_)G91@G?rbKM876N$@G ztj~`{z`InuXwiXLv7soosSWfDQ;`aH2DpE)!22naMXn{qhz&_6davK&qE-&a^*;g5 zN-27va0Uu@&!g|)3-W;L;Cj(9f_ufB7pCbGq6?B}1q&<;eL)GOJ&(_**M4V8rY#VZE&WJOo^rZ!(TmUYtIyp`=oCKlbK+uw?j*ZP zhb8Bk6{jW$I;5u11;#g+;W}wr_uNFmonU!EouUr?KHZbqG_;>dI9tk;K8h<3R!(64 zrM_a$pNp>8wR56C?BQAFYqpPd`jQtFad#&(fys%KLXI0F&l}H7KC+2<@Tr$MJE%&3 zZ1Ll#Z8sE@-s_+|iq0^mYDtx>K@x}JmSN_;i!b{!kVVg4nMK>qis4_UC(usiADE+8 z?zlY^B`V zBB}X;uZ;8b>5QI98dW_lr*d|cS%ty6(29=Zr>N>$4@PlI1v7SIEhTMeMy*!V5j;EB zO1pT53FMD`tq_(pR!n=oOAuhJOD7+2tt?5fr0W~1_`j>y(@BMn0*@cZnbwg#bo!IP z3WemQ%>1DY`kt&jGif%*NE-=tugt30@Ew;~{<&?; zu7i34qLW@B(R`KO6W+$gNPS}OTU;#bh^u3-Kbb3dHfJ%r=)(ebp=ApDFe{Y}`u2_P z_){*JZuXFUUMp>r^Y|WfPm#}-{I`qUbhb(Guw^V;v`LK_4wkFPc_PE=6qd71Y46x^ zex>Z%BZaK`FG(9K$3d2_G01;w(ZVhkpUVV?7O-XSbXcSK(QIRcDZ3`;7#rWuRZzb^ zLQSOq@*j8}Vj}9A*pSw2#-3M8DOTQNLtpl?6%EepXPzA;h)k-`h!nAWvP4$>hdy2~4w&axGQ(wVud@+;Vu~0&A{HTUa*^f?k zFnJm6cYdm1Rzfnn;qFa#ocKewW9CujgZ&SBRDz-4?HZp_?WmCQn9fVAp!z#|t*%Ir zpBl&t+(ytpQ1(r2b9qy; zBCGEpL+>x?ej4>H$V`W>7*!N3%`0tO0mv5YE&$8X8*jo?YQNA{_ z*l7m}SnmXV8@HX+Lg~w^S=W~VHoB))vm=)*ZR#R5ZTfm!DzhZph}QH(yt}&v8HHPI z3fVn2^;fgdHRx*7&XZ-|>kPBo)+*YVZdS30IAv%v#a%-9ecxii#&lnsAJwTghRjVe zeN!-dRrNa?qg5wRb8KU>yxqvnW)=e}70k|cel{2XhS~g?W^EHWeVR?#9Df_*?_M@_ zD=T2TGRS7n`gC$jTEnJE>@>UW*?v~TrG>R!Wn$AbxX0$%6)l*4$%Rs^Q`!dWq)Hg=v#^*Vdld5AJ_hBpJ!{xzf}^e}n%#KlG} zF@k*+m%>IOayB;OmE4p_r-=>n;A_(#h7j)l%Q zXFR>$3Fl}@Trr4%g!g4E3Xl^mnjWk_M9d;t5`QC8AOA90m8S$hOi}l&vd+ zrM)M9N0g#qUpv;-Y{1L~QScpT$Me4@agytrSJ!-mzTg%dQY|It61%aTG8G-YaT|JT zDxi_}n46&}Xv8YgXb|i?xK@(u3ByYB=2ZhK|}fNZsK>{$#14VY(@Vk9qj?Gz^VLqHt@`F${{U zVN`;S=#oVx=bs{s);a~P4<4wG znGey7SfSI?P?*gtMP%9y7=&Bn>xB|L8+=RZCTBzK-6@!Hdffgy=i%@)mn;bKLI0IY z*e=zL<*Ux(0PhHVP6c3X)k*wr+mC6Tr|>&-5lOaN$92&X+!zIH{%{C8$CcshZh&WV z8@wvcli_q0ExMCXGHD|^wd`!q(l@Fg_qemq`Nj7AKJTRVg@7ItSKT++N9aSU5{J4T~@DgMF6@g7)r3jzR{u zJ{gbnnYQ@4I)n2rdm*})V}Fl3&h-hU!l8W+S*Vi(F_%wxUwat#yANQ)i)09H{U#1` zUz7P3t~hBE0l)QH_+0-QF;6(&OH@B8JD1Pfm$9w*XZ@%j8C^c$e#W*jGMI-d5hL zLaf#c!7nGSt0{3aTWO}lN=hE#IM2p{*{UDe&iG7$vgat9=lfjQllDAT-v0voWyG4X zD7eY2+f~aJo%_J9qSKhM4|>^MT?<$h%_pqWqZMqxsL$+{<|4MYT~Qz}P6SNrXSV&K zxy`uAN7x02#0CGhPGqNwBH0^LeAvw5PIj$c5z|a+*os5n*kFfi?C788*nomG)-e7B zTlcD)J<>Lw$?K_R|FveYb)~`Vf;Vf~{3-LEBm0SL=oV$0+7vmqLS|CM27U4J zy3w)hLH9>YuZkhZ*Uw>3M7?H>`W~_ByRS05jR%=v&6_N}Y>Ys{HHE#Ne4O>6__4 zgbZ(v4L!N&FzaP^kx^;TD{r?@V{SjqWOaH>1W}hA=;o?iSy5lta&&EtJsM$!FCFin3 z3)|SNd2Vb$^onPR95iA``OX=#00By9c;oPt;+_q4+?&MQnuNm=*kpLs;Y2b zK2~7UBPBQSdx}+$9z!o3%4I&^Ghz>RbO_9*O9+OtquH=SV$6uYDYO1( z8tppMmVUA`jM3D&O_%QoVBT2HVFLM*%<%hB%!}LB)Y<1o%!u~}rd(||vnKy79TTyh zd3WwOZQAP2{9xS}r$tuG)Dcf6%GZkynykpo-o1($!%v7AoJ~*9m)y}3w51bi=*a=L7$u-*i#&{-Y(JaQSx{>zC z{z(75GK(2KN{0Dn&-L1Iop{$rIWo6bjHg?d%wx7v=}eZXB{S8_kZD_G&vdxv(Ea(x z=+o9>OwRpD%=T?}=r^B^F)E)K=0eX2Ixpj0x!D;F=8MEirclO&$xw)7;`B!7*X3b! z$qH+Fl2tq{oNdmicCTO}lgnur=NjsLPZZ6cp3brNPSg77-L$s!C;ILTG4A?sSw||C z@zS(lP?Ppbc6?gzBc^5Ip3JJArdHev<#0Xfw5z;JH#KR8ru>3U<$}yUs#uIhpEec zT+GzM`)3>v=yD7B5TFW1>y&J2XiH-O6DYa}Fo0>9`U4%{4Ypf`tv zx+ao=MlnREm|#;t4f$J?2(bnM6gQnDwNH8kT8lN&KV=mnJ53N?5sB8N|HvgOoIHAD zO{2r1p=`*1_#gH!^O->HR!gY*2 zf?bngY%U~M?M@Jb(}|c$t0O2-k`y=11RX60@i=iL965!eY+2~!D8lZ{G!myZO!BQ) zz}m(TCq3q&CvqnJdY3(Oa7!dzKi-NS=uDz}?`P4AbsRTMA9=!AOWlR?`8mQ7hc>$G@Kt8@8Y6+=?g%|`bQs;^okRPKGGy+Y z$)QzDE;Ej9+l49o?8-T^-oj{W31LdjCA!Y@AN?UJkAAo>gWjR&Mo+pc5PE493w0Yz z8KqJ?#^;qGJ;7N;aAAG4AbU=JBbi1k{sQqgxxSEnl!?8i=T^%TV#GR}4PT9=I6`v|E#3cy&CriLP(;Sjb z86@Y79dXx;z`U3mGCN`?{HxrtuzwUMvp2+chMlK#3ht$@u`dHbq4_5#Dk?qC8Cxa#SLrzGl zlfb^eGcYCLjPRxNEDXdN;(Oo?Qgzn=ZntOSg3UuxzkiU#v#!W3mxZCc8iIZ8F)?^L z64x3Ksm}`#XO;GAQSn$B?tr*WDX>c=Bz(h35{)Euuh77l-J?jcrwa^D z$iw8Q1ioKC4Yf;h2p5jQ3srmK`|l@N^U4RW|1*L~=X^ZY-4F4-oL|&m4cos|5bgUXwsHlZ5+FC#JK$uW-mUWwui5lRX(iGIR8^cSd! zmg*HDJpMEe{Umr6rH3_M3eefjW%@px#mzU47|B!+jV&*Q$vRa`U9^V1qMw2_Jip@{)V?7T)6P-wOjRacC)i9ExjRTHrVZLWG zj;HR!NoNVP{TVGXzad1SiIQlKnKfSWR8W?vAo7Fs{d>RO`y z+9(v0Bgjv$By-2_z*vPA%&R=b*LRFZ&2zp?1G19Y6;r%q1-0rm zZhH43?ZgnbXXc){W;fuk$pV}_b_{gcR&1Dk4M83`IMLjKkqdozGcp6s#s;wCxZr`= zH5i=TP4b_w$F0zGM6LaTm#^R9m|iJHFDfOQyhV6k9>THbuVZeS4zW(T0R?&PUQ}Q~ z&CWupWHmm|bcL_qW}Mkn&H2ou5H6dDPFW#tz80b7Z6+Cfeh&^^YNDwti(pX4Wk(%= zlAC%E99F=BNBiI~^&ApRolxDRAPV?iio%ns$SYjK4lPc>X7)L@Y&nOUrs5)_<9o2H z{x`APQcTpe)(ZVoi{l6F$aV9+wkGs8zg0aLTdDJ zteaE|qds@&=5ZXRcfN?+#bt3voyL-Vk1)IUEe?t~LHDH|VysQL{a`h2rgsucYBgln zoxqLVA8?M}iSUqO?zz917$;WZV&Z>@*$L#Y*Cg2$oEGyu9n0M*v}&hg8RyUE@n+)f zc`kPnavjObBd|t09&HQD@KQ~PL)X$s$c-ALJW~LTSs81Lec17yNtp5EF{Wyt;VPv6qBLR`4D!B{ea{NXeb>>5 z9hZlPHO;6TV~)pN&p9Nvu$$!LdtCYxSW;t4SDTu_m z>|erWB`EaDigKKe;b-K2l5piJBy=P3NdG@xpC8Y8!D$(Z{)@acFNg67S|L<T1G?Iiy6M897gl8aC|Ix#orNE za!1t@<9)~A+1kZ$ep4(wdv6Jve(|8{^N>87$O9X(91^*m#A2@`#KpZ4@JS6-u7>z) zHxIYZdtx^%$?}8i5j@0&?@gw|>4P;4?=HZ0t}@;C-yjvlnZmP zb5b5zKY2tjU}%DmS9f6fn!qc#CoCvx3 z%H+t$rQF=4fynV=(D>vcx<=ID@2dm-mvf1w&hGUpQUejG`S!a9t3KO@gb!SD8f!5`02l=|9-*4*g=yE)F>752>ND;^MtBjy-`>K2 z{|mofEQC><8O*8}7@vNOpU1zGpWk=k`|9&}S|ctxWc(dDl{aAe`37+~T8qi6YoQLV&s~)-X3})ZXgT4f z8>7jQq#$~CK(+9T#5G}X%s6sy_GS7|rkS8JYC4g&mnH7f-a?7Z4rF`uZDDp3kK`4s z5*B|O$DH1tT$yYbM+ru9nQ^*A=qxivuszm+$sFEHY%lT|lZpso(K2Jfsa3By_Wne& z(tC;U)#b6Ikkg~*N<9-kJ|j!U)@c(1rIE^D^&+AB0ZF1demBPwwWM#zlnLE;rjvq- zGU5LIN@159O*rI-@b2+R!bG<}jI`NdGD%OD6m$M*v$hPf8B@sbd$weJn{?&SF0PyJ zPqc7G-o=WSU;HZH)0#r{Hz7nN*sLO3LX~Vj9Y{W2%^*72qsh@eIkH5|y3*1iQuwq< zoP-;F=D2g;8P}!bNc7eOLBL+w$_U4jO4(}_^izjNMD$dV{7srBtj|&vHjH{DT&FXy z(z!aLe0zA3P*UJYueXjC7Ro4*^-F7oMhRD$&cSy=-Qw|Ndf7SQ(L8%nx%~)9UMGAibA}9DvLU6P<`OEYK{(IVP`D^%1u5)0FFadoDZDz< zfGj^ALH4&#AW4(CY&+Lw*B7Qo+s?Z|^`%HMOoIolyzx7om-vvD;5x_eJ&mDbhlTu; z(HH0$Iq&HyUw_fs7dF$^s`_Y+w`%lmwPp(k?K$oHp^dtxmP7}2zNLj@ zHJF^pC-h$NN?N`96s^tiXGV+V(%#7rX!h1oYOz)decOAGE?YT7YYbhYea8>biyjTp zW3$BIJs_Wcee5;8RBniVQ|3VrubxbE_0sec z=O+3`=OCr~&z~N5=PbR=X@m|L^O+7GE8-XiB1-GzExIE(ik`IbE^Y9|ka}~hjxJI^ zPZzs8(XG09G@X5q?wP)j9_rdfcWE`y3hHq*LQl{Z-qmz?{vF!SFPHk#@q{+^(qry@ zET`3t^60OZtLe_JiFD9Y723Vw5Y6Yf2@@LK>B~#UF}>B-=@~1u>4)Y}Tw1auhPPM>RqYIM-fSKIySD=Y-d$wVinVApN+J_q&cOk0 zH)WV^i5TgHxb5Ic{x->@&fN#4Z<5f}GZ*VP-}RDVZuW|B;+~hrqu#OIHNPw+>wDaQd5y^P=+u?(rn z+pyK|E(umUN1m5oB<xVwl>_sHTMj!iE&A{QJdeS##fYY>R;6sr#N~*_leN#4YW9_k`U5~Ua z^MLx@lPC{2$K}ciI2k<+4-z>*ziaJ7XqDf-V~djE=PA;Dd`<`OE{X-M*Ip-lDr#P z#KGe&d7D2#f+R=C0i{UN*?R;f^K3zzB%w2+ocJlFkjAJ4Bz^^zU${V;1yD!F=NKAQFBVOk}{ z=}Ak`xM>-=`%VdUWgG*+-~{~o7h#41AMNXPp{(zMHs6T|P@f0$kFuoXv?_961mX?% zTxu=g{PQ(7bnVKtoH`Hh=>XF^ z8S8?^3?p&NXO{yAZi?Rhe9>2dNkhs)6an1X}0bwn4(Id7>g#-^l`o09#4^`Y8$Ie#r0 zoToxIEgH!o;+Qbz5b5-#Np<5f@*s!nBACL>(Mp6YYN-`A&p%Ae^s`9!yc{z6+k0*< z`$}{xCGey-hLjA%W7Ks=q^?edM+3#-}aZP<@f zorTEzbp@eZzESjOJ?^z+Kqr#xvA*n$zC;M9v9 zcs(v2EA2lMUx}yWo3tauj_$$Kl`7DUe2TjshcW-!YvSf+%9;$WMcbA0ct6N>7T&po z9}Da;f!rjTwcP)?S2H=PACBBt=de9i8ZNmiq%5$Ote*dt$T#;B*+x?wRkr4IR!1By zze^4TJ;Z0@IE>%;0-s-vM&-~eA|Ch@C$6qSOW+J5)1L&lEpy?b<%FR4J_yx3a8|_= zw)|M~q+b9*#97E44@6>L8Y($1i&`EF*$d~%=xkT=$>%7R>Nbc1L(m~48hBVBp%w6LSk86jIKak(d(VovE=+k%7#-uX zndeU9()-mYwYCQ}-59*33-P(a9L2Yn6O%n)Fp9`YX9&LmU$b5WupkN>tWfZyFhA^*WbgugU{D5jnq;W7~+ zJH2pteLK0oNerc5xbJs!Jtc?q;kkPbR^6Hlex4~QW>#UQY%aE4vV+YX3+(K7hep&T z;(scGtd^BSXc`|fsgFswTqc*%o(UZ;<4Wca3)G#B5IAl-=JoR-D@eexM>3eV_b8cG z=am`y&lU)2DN`NU<9Uh6?hdyz0J z*BQk{oUS)Ii94G||0SIuB-GUBy%9Rh;1@Mmx%cEnv1e%j-Q=WxKkJsm{YY!7F@Em&jmmFSl! zV(urdqcPP0)H@5jo4E=aV(Zbg+MZ-h2|}exC7LEJz=g+72>r7LfA-%bzcUMon};TH zC%Is7OCKrbcz%V8mZL?jj10e!VLc{L_^{{@Btukt3&i^U zTr4h(z|*9sB-f!&sQKkIc`RN@I_0jB#ouM{W|-UGuG55D;AwK6^YT%LRwKly7!OW8 zCuJoiWc;5(tW2}QM^4x7FWrO_b(}A6iWX`)y_MTy;ptuz)O4;S-?)9-xs-6Me&`7I zu3fl3zJa-IbiHDqi>%;Qz_)VsV3FWl#>&cw1vP?+@~IM^=kmgo@vO2(r8SaPw^HLUb7V{0-wr#Z)ZEd+>?e4Xfl(mbqgP8aK>vj6X z3;wU21$@aVj{F_}6s_{#tf8tehVsvJiPM3)Q}{Qn^(lifGbpl2gD>?VgkRO7P5BH{ zl%QLQA1oe5?GdcvUusmK!agqJd$lJ~^3KxK`MlfwV{5+hYxDO}pG&%_rH}Vh3U(3J z0jnjg)n{@{_o*%XU-ymacNT$s%>^#h%&vu0PTeW~so^|6&*TB$@{BL_A#@s5yLutD zAnz4l^|&!*y!k2rsNMuBCtyEcOjN-?v-^~l%#LtM?b0Y}#*y#5C!58nP)8mWx5$9{ ze0_+&bjf4BN2V0@_E8!YC74EiGrVSfDkzXTIl0Q(;pjuYbI5>IkpFFd_kan%`KSbc z+JBe$DqH=jLD}y-i7mr?D~BF_lIAY{-d|qS)mn4@gX4esCoH0@u9%xz&pjPTRm(l( zpM4X|msI=1cN;lj{U%$SIyB~^weuYXzO!s1KVaNcYOZ!7|BPu9U;m-B^-Om&>e}k% zl)^7{e(Qh(zrkS)|5!qn_1C|o2aM^RZ6b)F7>KAin5v{PPyv&Q~r`N^copkdhf>x^pM4SD)xya6|&|CRXJas zs$bbn-T4_ub(Ef@Zb(N^T|QIj!RBZxU`UJBv2vzoY|^56yFKZ>%|+DUrfACK%u}k@ z@f~$yk`txbp38r^kn0;*b&mSdK7;z8wt@0!J4z{;{GjrgYyA2P6s630@sYA z-d<1Lm)}X{eC7J#&BoI6L?zTglRwrGi%O^?{&sYS%T7wuQkB-Zq)Qj7{i1eBby9Di zYEwdm^_2aAcK+glh4iHXV|s?-1UkedgqrvMF16jbj_OmdqnyUoQ(>K5{Aqg*P|Clq zQ|fvbD7S5wsj87*RM7Q&{^dtB?Q%bY;^mc5%e&rKn@Z?VdpDa?Lph1mzdK9$vU$DK z$gJbk^Jqu<`GG%_@wm5?f$XNka7ilV9!j%?O zaO}b<1N`$F>M12}W4iI#VXEbCu;sOdPFA)dvv@_LpYcQ%XL!`nV^;3Y5tjS@h4QSv z23ahe`iFP$NP)!^&kGh+%3rL^Kd-U!S1~dZGdAVvro`~3x8JwgWc=Ck^3NjP757G- zv)oO~xVx1WCvKmyTG3@@-F^A7)&2AZ)?*{Zcym6EwrF)R;5iRp#kd;4rTL7y)1dMiUyYQ z(?|2J+_`1B=;3s$exoppA<+un>z+7^Lwe^d>X&F*N?(e#SU-0Z?^IN`#oz07mWjWI zEDgz6>!Tg4wdb;Q-k|q5tB}T*Rton&@E%&+Rs3HE?X_-b=^5<;jLh5 zx%|U8bNlHNt(L3NRvdJOXKt~<>hVawWs_u=AS92`dZbSZmEhfd)J_3ap?Og^T$E^ER2-ZEshs1&$h4;2*toeWS$>wI{xP|>4Ti&M#UyH$xE{g+& zqb%p^23SU%k1#hLUSfJQqs3fz*?hCPHsz+-zm%=k9`85b`~17bir*$?17~Y2L`&5y zPFqA+CMa8*EBOwXhCFk#OrFqY(U5f3Ozyw}v)vyhEia_&TV#0EnXX%S%k00scDzxu zC9E1Yms>7qb+hOUsI>f(eZe9rM%g04|FG%QWIKzJmn{}w&V-tmZ>{2~bjn-)lxgS9 z&MY-8*f7Uzt7f-(*6m0$Dd!ue8{~VYW+v&I?++O?-8AyaY@1RvuP<>ePt#gtxvw?N z;$hKv^94h;77Be0=K0kZ&FuBonN5u~<8^2)vE2RQsacS?pZUh*H>UoZR#{y1Z!)tp zljCW;yTO~}y~I-K=Na?aX1S(LaXO~%YwWD@CY`h#;Qcl8(^Z-pX#d*OEh5FNQ{jPS z#HrPm$Cj5^-l}P~K=Cf~jI9@WYyBE6GZoKS6r@D+a+1q=sdnMK;Q`8mmpj^WRf(*n zXR4azhrDdwn9eNAh`(AEk$t{qM=~1zhoS3msHqL(X=v}EP)bGP-m~84xk>{`ip(Ut zkPxBFWTcd)N~x6gqD9MSNVJS7L?QB_LPAPL^4)*n&U4Q5yuZm@vUQ;3_%rdvwNR|F zPX@`fyy4l|= z^HZry$>^lYI@@{!dhMlNrA`yWhl4z1+Jmp@Zv{Focq}pTU4@f z_7hudT6dT%@UX?&+YgcZZ#-^4n}vNxim+@j9J|IH$0z(kNV_6}`W**A(xn$Ul}bD_ zxg7Ok7;15OKBhqf8+xV7y#WUiG%E49Tq=xKp^+vW-}k1z}Vp4(V<0@gktK)yICFJJkdZIGe36?o?$#RVmVr`;CX8Fg1cl>y= zH&TKuw2>!A-$@hCX;s8tp@hu)l~3jt5|VxRDOc6zMKo5tBbWW{pk+`5)Q*nBwWEe4 z%lR8ehqn`A^hLOH-6aP@IpWhY1@`Y8BYh`B$?}OWz}I{{crnfJwpoE}_q#~uRk%U# z^n9>LE8%t<7jrYx?O@8fEnHH@QnJH73Y;gN0iB<&z`jt1<@Z^lCNT{Z$LDa4`RBoZ@yJ7~6h`SR3fU;J!$(0|x5O^mCL@jO;$Ho;&)C zkMByP;9JT|vUTfHZk4q+shzTdluVfkRgO*Ea?(SNi2+2z51E#1Us<_r=#eFk`LEQN?Y!r#o^lDfV^ zihoeOnpU_m-t^qQ-F(HwBwk9L1^;zr56`I~oiFN=KudPXQ*94vx<`+xxi;n%r>s%(yUzilmoAN+|Kfh6xFXpm{UmP36&vaB{^^I)Vp8j=;kN~RlffU6}~T58cB)I*vi)oH{$C)c4owDcJt4C zb)tXQ5AfvX`%<&lyHOw9*U&u<3;EAROL%evc2vB~JZi;;d%PRsQv6vSi>SJV;*?zR z1b$556n>c5720cGEHi3-i|#n@&o|B!r;Uvo_|x5!`OS+vc$qfus2Kr;{O*Vy{C@F3 zCZNEJa!NwxMne#PhqDI1deS(`+VKN_IQu4VcE5>f^+6fx*llP21U(VHhSoiLVr&<^ zD`7Hy-Liu(-NEs%1h!DKTV(k9Ql5Olr^S3{(=s~l;Vf#6-D}>te_wbPdjI386^GLH zE~ojM{!+BGk3MrNOOk${c8_;ASDJt7My=`n#_i0ul4-Qs;xD|VHQP;>_r&o$cAVr@ z*kx0>H&0N_zi&~#jUsg7zF2S{Qx&?NZtH7_GA>SA2rWw_6Xm#e1J|(REXZXevj%&-oLzkPnKMt?@nSv+u4VgUXUr(;oPNZPg&2VToS+MHrb%Nj)aU4685Vpa+Y68IG=gi zBrrXmE3!8yYhCk5o8TPL`PEFmI=PZ-{gF`kwUO9VZimkP2I4NhjGH!nCOhG`H(_p8 z5X*;N+?C4Z#IIuwTq?C9FRn|$8!-v+o!(9M{XIoil=*S#+b(i~D}|gx*+#IQUP?T- zJ|wE#G$K)AL`ufalOf{Gj=;BdIuD#@S4ZCQ-XhK{MBc%wE|?xw3hb zxXE#P;&UthoilcH<9u)GPybiSODmkJJ)lCBhAyH%R|io25B%xE`FAO{{WIkt8cd~K zzfN6>*hPOi;m?RGxl+4^3aJ7q2kJ~9L%H0LqKytTQ8Pa*pf5TB`>{=#R{!EfIjZ(j zhT8|J<7_nj!BLk|6Y-}HCMeODu4^-zenZp~SjsFr>q57R_fwCx`shbCb17$j0qtNT zOV?j-qBC#Lp(n^?(4l>ksAZGSQ_hc!sd1OOsD)21P>Y++QycwQ>QQGqHTU`->f-+0 z^tWY&bglV$W|!LpM&U>xRct6p&z1j=N__X5Zy(@J9S-ZFHy_zUL3sjo?b0%4?(b?! z)LWV%d)?`#BP{(TSCM%nXrLXYuB5cqw)5-O1kfTS{gjoPJT;sCLceU#VRmIC(SD_h zv{&5$>f7eebdGKR@uXGMRjC`y^clY>kMhH` zt3xww9!k@}A5T$r$*I&~_oe*f2|Jkb{&4!!Eq|(Wi8f!5pGh5axU&Hi~j?9h?h;J-#bQsQ~F9@ zluw{u%-Br%GzQRpV>=nCgh;AUwG|%T)%$Oq8RdY%R9#45Vqxx& zX*h42JLWB0fV*ZXp~+8On0WXi9Iu=S{U(ZdzoQuT+f{*_Ng7;!vK0T*%!WU!XW>$t zU1-RmtTG%aWY&MFr~Pl@4`m5TVh)(h0w`{Z)#4tTdz*a3KFFD%#|3A952tUWtH zC`|iEPF~yqPb{ZnQLjF}slEwS{A6Sz^vHzsyWmW<4~*`OhWP2bq0D<2HnfdLXYV1X z-*6wUs3+iD+g`ZdzaQm~{RDY(7M@Ic44pFxD*ot%n^z`~MY=D+Y`O=g&NvIYJIs); zW{di+ld$1GS={>D3bbq^;Qm}GNSf}C9VL!<@X369a^^f}jSNH8{9!P1AA&foQPAS# zAkH@xcK!Vff7d*OLz&NDjiVMSe11TrcWuG-DOoV9s|%i9lqM6UWpcc z{arG#`t^>KS*t+u^6@asN*y$|{3Z9!DZneg3@*&~2yvKTM6PPSBH;_qkZgZhQsH)t z6kM4AMRyj1oPsWxB!4B`zDYzRIFWSTn?hFE4UpD5XURl^Oj2rnmTXL;VbaxjA}G>= z5$O#;ucYDjcNchcw1NDm7enrN{2=^!pNOLT5)zeK%Need{(SQN=5YuZ>R_MVaUwbU?1|6r{lq}9k|@vbBUv`R zWZI23vO2GtT!}dheSVGP*_1`ld$FH1(ZR&`dl9*uGYKRY-Y1ORXZEOlDFG!{`1mA{ z$V#fi`9)LU$_Fvn{^lbw-NF(tIWN-lVt_Nhz6bKh(=hC%4@Pb$NILt7c-r@ocP<~u z(#H>o&+K2^*=PPFL-H2cx4VRV32Y>>!74CG@(Sm6hyq3}h*+PfC+IVdTes4Lc+IjP zE-PZmtIn;QNANH5$0LP^?p_Nn{{P6k!vmy3=@A)89S`Y0^uL!$>Z^K=aa`LV73Z|Gj;7gAe zIQrNfvw9xEG5Hnfw=oX&<~CuDS^!uPk7%xaK%jpQmA`M z7e^k>#&G*WY{)(dQ6oQLrC$wdi`>V9&z7MW#TT^QyG#~5mB5y5Qn<<92(NWW-~~1m zed`jjNjVIUuk*kae~kn`%>%JpO1 zqQiK|UTs5O_)FY-^b$_;NJH7rPvKQMACCr~gWn}8f<+a7(D3nlG;bq4Roq=Bp*!R7Z(;MrB%vAKIc?&>VUGw1ihgPr39ekK;U?XE9+_hpmA`=5hH z_jhR3a>R2%Q%T~|3T5`O`v>3 z0&fUYa2@@Bk-R$x!CkKmXtz%Q#`Ul~vK_AUHp2Gm$1tU57cnHl4Alj{$Tpii@OZrz zwqJZo)~VZq&F42@>#K>jPsZTM<|~jE-$g8UZiNj_1H|dqO-R|X6RMOB!pQcO5T781 zl~-M0k+4f}>I6M}|KKmISLWjy^+-_qSwc;KIgGX!t%A z{F|-d_F7M9%4&gX`4p1gJps~>zJ-(jTEV0BsPH;>MElq(t~g8&A{lMCf5rk-ef6Pf z`bCHstbo*r98fzH2H({jFuWoewq4f8cISK$cU%awsZ$`gw+CA1$HD8?eD1&dA+X|w z4$61g!SSO5aAA=MPWbx}0^6!!ieMbrh_f&tq>9_Z`Pif=iX$!K&}9EYaAPtc{oqB= zYR!e$>bWqhu9~bq=m_3BlOVJ`9NLXypzvcW?C%L7{mT__-W6vUs7-+J3$AfH=8Xe+ zWo3{F*bL@EE<&d7Ce&*mfY4Mu9KYutYzw#n*q#CttsX<^M^W5&rUvrO?ZEX_C1fpm z2Ax^mL_>NSdRU|ZTX>DE-I)fRd`bMGbSJq+vwSIiCRA2C}T}GfMA}{EH6Y_O z9)xQxLb45t+^WW%nZaPba=ak0C=2%^Yr)(SWx@Bw z(U|4)2aQZM1zEHf=1tup(93_0)629_;--k;`Qe3vFGo^Qw5<_-J1Jx8e0{J@8|5VE zDJWN*23HwNjI6H%(K{3@@+^Q)hyFlgtO2rp(s;y019gjKabmX`Dp=%^6<-3N&5MRP zI-g*!cM@dxXn^vLQ1E}EgKt)>#ED}x_EG=f@}EgyRhtP%ryIg7dr534$$_{>g>bDh z9&&BWFywXul&Blv#j~66QwWE50{5W)X<;XBOA0V&e#77Q|KQ1#4X|SFO``GK74(wo zVD#c<@T)!vURl|2;j$7wqF$027oCCqJq0_{RB)wR3GCW%8YBFEb6#zmAZ^N85I61j3uZ|;j zw-C0pE`$Y1sZemshrAsdk2QUTpmk_7PQN6Fd*@3aM0LUU3o1CZ2T{^j3?I%32hGJ| zIBCTM)Ze8I`bk?cbH{5~5j_t4Jzm4c%@*jFnhJ5L@Mg9 z)44~n=C~McH}QtH_g}$uq6wBtZNln48@v|lh?TNSuEqU22{`S^arCjUL6fVCp~3A1oNCz&Q-r!%so`#5o_qy$nR}qB z6oL6FuVAe(lcD8NGHO&Gz^RcrI31<&(xsL0f+Se1HxB%cCqi|^I2?X+ z9@77oLFw}@;4JM>b-@H!u_+q()7Id!A8wc}I|MJI>oHkvCV8ci4CmAmL9(kFN}Q75 zMX?T^noVJAx;7r}5y$R;o9Je(hWn`VXi}$(+oS8?Pp>e4z1$1mjmhKehhF4Ht14O) z#RmjaSi?H+SAZCipM^;pTUx)XBXmL5*8OOl44;Qc^Aq-c3KZ?|?CdhcLkK%kC zlv_RprLw1DobW&GQf&nH8>*OlNCH<&%i}E@dt7fU3xkdk$TNBXSfwc34`z`0nTOzS zLpXdXehcXra!9iHOiaK10p7ezz;Dh%T>3ZSRA)_8d$kZdyL{2(t^mJh*TYW@f(vw( zHPLyrTo zp+eGWtOIAYufkEKpU{wcA2eRZ!LRk@WY@WwFueUH8JLv>X2DkQ`tf{NlTN|T(WkI6 zg#qKpT8K6g!;Z=aP--fJPEHMPSX(4Mg|&IKXYLu*q2zF2`$v z<5NqRuAB!iHXJ6}ONWVH%r&snFMxF$7ePdvKCYM<%ZZtZg3`xPa|%$cE} zAaVwtl%E9OGB?o7(?!2Kz7WtNiV2BfFl1r?{kT@hnN|ab-jJSpnmfh1g38))xXn}# zbX#sfpnMA?UCo7WYvW+V2o>9kYX!+2Cx1wp+uPICmXF)sX zKB9t#<><@FFIYIA!6-c#6JF+pG`sEsP5q0Z@?BZ#vzrYw=Uf}Z9}{C{EH$RS^{=BR ztV*D*i`u9(n~BWjIhORmV{I;J=rF6KLKvl8&6HB)1=dWRp+Vk|J=kx^-by~h9+FmM z7s{`o%a8nE#3%ouzXcl5lUH8jPE|gq?eaKAPQsXJ+GfMLutUtC?>S~T|17ii6GQL2 z*g^-qOJoO4#c1zMv+2OZ(~L}r74^E|I&JgVo0*`>V_SO5IB)YFHu_^BwNdg7dv#Vj zeZIqulFm1!l-y1;1JVkteubD22MguyWV~b-&&cIMeodqGBTv$%dgmDn=`>~^Uz=93 zUI9bgaa+(4(*<I1 z+z+ck)-aLk^IIkYu_qoF% z^XYip;6B{G{~E?gSA%BI358ft+_G5`RmP&R`nw`-^(X@AX(AX^ zwHj~gj)AV&a^hAkg)4ra#6y2BL&VwjIB)HCRF4%1xix*fR=plVZWh7o8#*9jn1CC6 z{cv;OZd}|}4aiePy*=_6c0~a@HmTzt;j<-4u@?TtE8zI8gRsQ@FSuC|v{3&=Ruo2J zhyHDtnka%=Pp6Sf7hU1(ro$ll<|ULr$RP4j#wh4|1gcL?p|kibQG z-0q2*n`v}hQU*<4dZ^W5jd8s;VDj<|j{GNsOa*}-7d0_a<{+8}HNnfjGjY?_a7@zA zgTkNZNc5Q)44h$z@(INlN(AV8Ee{5rIh#cC2Oao?E5z1@0Zjce2bUD7W9hwJD6J5R8IGMGTQLK4 zLZ3o&D2GG-U7-5;A6N}(;*qvcbb93kUp$*&;hqGH@y*6nvslatkQW5lC6YZM&p>a+ zD-aKq#;qysAVRId=)S$UDr+qkbeLi5pp>9Ea4CNHuM5YYUyn8I!nr)#5#1*hV^Xp$ zM((I0i~H80x5a(*+A4zqZ5OfOVi~Fky*?jS9Yde7e9+h{gC&dhfviD41}ok}?K{_T zfv5_G&fbRJ!>jOg$2#R^s8dsTHphB%J+H{5C^4oUs?MVk_Z`8p0 zDRx5aA&9(7DuU3Db%6fHcLOwbO9m_CC~XuR$Z}$taQI#XJk*Q!_-TbAvvF z$GdZmiW;cn2MBq+l?S@`n$fm}pLQp+U`&Kdonl0FOkY8Ln3uw&Jx`>DG-8-T zYM*Haj96xy;6%} z22YkT7RTgSYatS|K--oM=x*c7`s&bUW}c?p=Q~k-YfQ%nKJWg zuQ`*Jlf&kSn$dddulOQ=*Rv}ZlrhR1)=`Jw0X6aSLRQr25uM^|PFa2nqSV4{xc7Ft zq|`~2OFOL2sNVaJ9sebeu{h8|Z#*wbJ=6+d<^**x8PW#yk8e^W{D3z5%U6LE%+jKk zPT5OMR^3gnI+{$4jrH>dx-LA*Z4UjoaWCaCO@a1UdX(##dYB848)3V)9$>y0yrU#N z)tRDpJ7%hV2KC-FhI%^Qf?I9u&8nh+^2#fubk=%Mw`U|WO#W@^ZFmCcK1voA?8 zq3m8N(p9KcobJPf>&C(d)oytA%bPU_uI1Fi#8KC4KXjUv!oH5Xhbrp52tD84vn{!utjKR0kkCqp-q zbv@L%;w);qo{<`<8Q^E=Lac*r2Is0vss(NV$&Y(S;eZ(6J^8LNuEp;LCPq zaNQqfbbSy#C&!BU?6sA8F0vcshsR--sv!y8sY>rnxI!ClkEiaf{mo`bws238X;M_h@&r3)yQzoD}AtB7Ibaqd6co!scHE@oGhHxu(qj3keivJN-p zNbUzU?o5Okw`6ubJN4!<&Nz6G<946nIxO2b?bC@|@U~~1?YRXEf9+}3`Aq|RENBN; zJhqp6pni>Y51+%$R6oht%u*xnB7|GDb%ZsqUClloIL+Cf9p$9@pn8OWsSAb35`iNdDeX?#5d`cJIcOoZ_14T;h5IZb&Yi4O#ae z`$r*}lNzgGhtF`_B8_cam3}x^SCh$J9=^uLyV-K0dOJ9u=eszG*M>x}vYt`%a^f!C z?PZ5L)Ht7!-7E~PSo7FBa?OXbO|erF~3oaS~79Adi69M~iJm8{e9^_=@rDRwtK%!Nlra{8P2qVWdcCO?C)(3MX=f{)%n;x*`2_{5jVH!7kVJ@rmOOxwa)6b2nMRBdB zPH2{!jCw}pSo{T7{|P9&@dsScKa59pB5?n4Ffjt+ zWkdx%XP+Ry_9v|(4fl) z@4d-K9zH_vkR&uK(h+v1M+!fC7FOIT08?c#LD;o}Snx0w3XD$RexH|^J7kLEBhtWP z&j(oZLJZFQxX0;e{Db4G{NdDf4IB(j25^^yGrz-NYsej#XD5!GLX5_K_&X2?$&P(cb?`FTJi`>amWtrH@dHpiBMO!jZo#&W z2i#s60a$i0pkuQFR*9NHd(I88uDcH-(<{M?oQK%*jp+Ze7<%(&VEclbpl`edK6##l zH?2ZU-8&EF@4wAi?@I=jA-J~G4cucT@YP>MJbUQ_L~VQwsWr+#jO^jKO)FU@V~dmf zRB@Mr3U*mQE`Km>_>3UQOFw&j1r6aGcj7o;rvNzBPIL_s5m$QtJ;o1?~he*=y58< zN|%%V#t80mP7%z$Ov7HO``}vS1fh4UiAl62Xx}^qi>H)=?6w4m@y-U1+<54InE~pD zW)P!NB^WWdLH@`chmt%anCPEHMAFs4Ql|)vdOpHt#oHkLD-!$_^9iUjFbl7ey51P* z)F$8?X$9g&hM=j`0_BC%!I^gz+B-&s_~dPfloG@IcdH>l(iE7fq0ss;0_L3?B=_o; zlkqJ>q~ywSm{j|N4A?6{>NF1gT2nwt#EVq<_ma6t~4&$y*cZPYL-(f?NCh+H1fM3il*m*kz&RCxY&b*Q61xv$@^ARLATLPy9-v#fV z4d9YD3C2Dj1SOvn(6YfFjQ1RYheB_NZ_6YAQ%~6X-U%Y7xk6fRI;=djoV=LS30J31 zg&U3@u<_by&fKYicszYcCWX-Ob-o0V=sE-YqGm$i_a89jRuW7#jRyOx-tajs9bPVM zgkHU9$lpByJpE5YVMY$f1{M$}hd&Uo#2X}=qR1?RL*RAqKK#7T6Y46;Y18{vjP89y z>fD<@^s|C+rp>*J>D+mizEEvNm#sNXwH}bAXP-Dld9$(fqu~%{r%fb10P_T3|wpD|b;}(=Ri3 z%u12al_8C4+rFghd=idy{dv}*oMi@W` zU;jY+Ty>%6HrLVLdV}b$+aKs(SECrazMV|fd>7{Yns?OQ$ttvbtOvb#s~uet_k&tj zZccsv_<_28;xb(p8P4qWDxIQ&ffn z9mOA|j!72N|D8%?*1BA$cGh&#q@|F$^(2&1a!jJuwdher$KFxag%-5i`*?oV`A|CM zPaaisERJ40fzVqYPp12xPGI7Em(WIm{&c9*@;O>?3_x5F5=M$u&WvUn=0*@fGe0IkT1B*<^un zGKlRngEl!D%t{|aUcL;*8?Oc>uSz)FEkpWURA6hr4VjY@3MMv2Air=t*QKUO`t2V> zjGisNDZUI{_Ljuw+Gg_JR|;B>1i~Z1LHM3|o{TMY7IvyMfOMZR>|AmH-W|A39?2VH zQS)EO{ilOJe`mtoT6K8cR|9KDSCZKuBFMRxQIb=(n~a*b!sjP?uvNr}ED*GDbM^?i zrRoZ9?U1$61!lxX!fk_hpl_|p5ob00x}lz|99~C8M#31aC&k3NPMJ(x{e~=f zb%zsEFNap^Akt>B0l%(~gj+&wc8p9O)W%(cUDm~5xHBB&PR4TAB}0hfePxudd`*Vl z)iN9FJ=ghF zuh*Hjyt-z3Ii=NfUGzNO7O`ox$qV(o($j*=77( zErIFDsL!T8Kf5WE8>QB#Ch=BVFQ?P}AMp}Bb4?G`r0{zmTJy65qD&3GKIV(IPNwRH zyQ%LERn*d#T9oXS6iUubcqSUZi+BHEDpj^sf;T6qo7&)_#LIE3;!CfNGOgDM2-`HLP*;KfANnnw8ynPx}@@zRxAOjn;>#2d4=<*zuA$$Qrw&R_pn zhx&O9s7uA26t(&}l_?obiTqNdnB#=^Xx}tmMxrCH`u!WzCRJetgIYJg!a|1M{&O8Y zz3VHbGc}Pn_)3>QxI2nEcxlj7!y%H|5u(nYR5#I7>}7E>oUEChDu95^5>m{d%9Oz!F~g#D6ZkmtJ& zpRHU5_VFD=Ct)fob&|O&pwYy)#^CE2wShNK^8iX92y9M`3^oCF)Rte3;54fWT)gV6q z0cak64(p?8iOPs1`0iyP@wWwrzM2DLwTIwI-#uwqIwfkf+XDg3>E z0rqSO=QtZ-l7EyM-l~iuyXv37(1ooyIYWOyg&f>$ z$A!quBJ)IU6B)ie*`l$W(`^A_`*#D^_xd!c(k|hus@`yaHph|I-Z})bW67@_K_t#z z2K>#kp;X&ns9O*=x^8RbOm>|nc`koA?V=3snBWvq{b)i=%ZDKM=X)a6u86h1?}&Tz zAZg4R2TjrE$?kQf+_^Cx`6wR%jmvVlwYG8GiZ(+MoKwpAEh^%cG@6l^0b3F);zod5 z#BK6(NLo`vlM!NEgfO# zj4Uh(4k8y`3VpqQ{&M2pD)7wKnERKf4mu}lA!Fh^NGM7nAD28O-P2ZaS{r5(tLLr6 zYQZ@2EvuZgjjJOzajD$)rgh|#=uxsOQ-auO-hv;go5_4ugy>(|$$9R4%jF-q!_8As zgwNSZt zewZsHX(au(4cXLqk`&affslA5=-wDgJkLcUD7WFPj8T|Wb%zAxyuvHOZg25S3Bh~q zFznA8hgT+rU_$H_9J==d4X)nBIi2meGy1O3U-bmtoDRVAaSQOp+Mgf>7x1`HkHfS) z2Z`zhm>KdO#|LW*OkEWP6J+n9)|=;WJZKy45Ea8q7lavETlV6NZ6`6#U_EYmr6f?k z?}|ar;(~QmQw5@t|8SR&xnP-X6wW&8foe@l8XBnIJXU z4lUbvVB@)mXkD8P5tf=b|IJ(cbgT#Go({sNrfUV`wTH>+B?c&DEzs1*9_w!!;PI7t zxK*MWi*)maxnp7I`*Ve0STz$5D)0sOn=ayt5!yKk#b-_y z+{jvl2Aa|RTuH9VGIuF$D%|}D~7a0!o%l=f_r*9aP(cG(3@66LZifl zS|l|zH1b38a|S#yZbsEThw;E^UBR*qZ?K`V5g&}p6!y{mhnpYB2^4lb#I%%U*pyR^ zu@YVQt)~a-N@zj5b~ffv&G22f7*oHh2tuc9!;0ta%&+M~%mJ%al+*f|^w)3&`u${O z_S~G!Z189d({S6Lx#=5Ex5j(ZlNHu6gTjbCnN`zhqP3jf^WiPSsq|96=4H|NA(7^@ zv5bx8DQ4;hS@!3^Hg>O33L|8On5lbzG3FUIY)Zv*YEr-lW_67M;i#UN>Ymz1vF{CMeKdSxXtoJI(Aj7mD^Ox1c9D z`_o_CGx*kL3+d)3E%dnx2R2Kkkr7w?hdz?gXw+Dk-kyi!8Atr(eXN2%!ot`Qx(|E z^!+Sl(~P4TWx4Ov?n^wDTe*;V9U#J7REl9982zMlPN&nQ5sT>G)~Bh%)=^ARwF_FV?H+JvpEjh%*XTpQPb#lT56*a`_KO}{kwMwYZnvDTr&`3 zfA2|v-j*&XdG?do)AbxPbr24Z?1K%@6;LHJ7XIXj!^YA8fbtu#@aHdhVEh=;=e~#a z4<3WN{eN)Y^f)=W(jI0>OF-w@Qjna!1LD8EBb#R~16S2S2)V0|3;o8UgOX75EB%?| zJ~{x&rlUkt&;rLd`@ya!f$%AN3siK=WAK05z*}_`dS39bOsMmXelNho(FtIjwj0zI z)`H5G+wjZB7&Oez5RViSxW_=xGoCnN!g7x?DJ4>Yz&HGQ2Q|gC(OYu);G3-n;RUa=QX~ zQmf&7YBczs9fAELsi5(@mOEM*3!|nc*uCBvZa@A517(u9u>K`HPHqAN6B#g`YXv9F z8%T=BOyoS}aBGP)dY@Vaf2E4RQn>=Ml*?cb?=pl=yF>n(u7diEOlXUWgH_(iQ03VT zRoZ`==LXJBRt5^|Ckpi_dtpkl88LHcfqmkEpm?2!wg;Yqfx}%0 z&%FRQonOO|Z8G@Op&2e$I6;Q6uX5pkJ#b;u7vkI}^lrFZgo)Th^4kjFW0nGS*x1G&V}29AHYg1L6vo_W$GL41}}65Ys2+>Hq$ob|svPPA!1tN15^^Dx)uR#nEZ zuTr;jcH3vLNA^8s&a8-`!`F&4f^4mEo5MIBw4uqCnL7( z7P~mxfQ`QYo-2P8NjCOBVc(KzT&2kKV`UerR&*CO-H$p$^TfP=#yPu`-53rZ%*FZ=Wr49T`pH6 zhnD=6AsO63K?vub7RX-O z+RNqQC^zY;HM`R2I{Vvk31J59NWgRR~*T z2)fBxP}KYhMpY(ZWTym<-B-YV2{EM8PPZC3x;S42x2d;NdN4 zoag?KfPw>jyEg%cr)uEm$rr%iI~Z@Q`NpZwT?tkTmcpwK{&4ckO3?fM3NFikg_xh6 z@b1+$i0ci+V_)yX?#nANIP?vuQ zu`Q%^??0G3B@<%)t-!|RQ3Z>F z)wnV8kO_~IbuDuMYeWs9dB?ZQX z0*WZ^!?NRxkhf43XV%fMP3bzEYOsP3w@DZhQv>HT8$qlvANWt4@cy(yaL}>F`FZ|m zy>9{L6ouie{BGDPD2H|f1)TUu6*Cf#!OX!<5@C4^IQBW*9SVT>X9=)<{|udXI9G2N#*vVfWF(s?e9wHJ=O|R7 zQbsOITN@lV$vXwNXXh&8lq0%m;LE4H?8ozUW|8sq>>l~c%zR!K%pZgPx zy{1I|wYNf{Lohy%%!VQ-(R)L?p;oCms_AHB`@I>^{w5Y?8)-o3j40&R&%(n|?l@PR zLzmr=#@Q8esC`uy|BBg)0a_d6)eAs#NFPjfXahszPS`Nr92YNnMv^xz!@JXtLwMVF z=uA~7xp{7&)U*oz3po$hilazs^GH-Bb#UNvDE9v`!SS^taLUEsQ0Z@hKX=T+Wria# z<777IMrh*VSrU|WBhWH50@oe=2fZ#D;CWFB4Q_hk1Lbmv`k{|&Jyv2+coayBEP(zA zJ209115Vy4n6*a-&xo^Sa~DmlZgj;}*CTP^J8$%y?T>2CqVJwtk8y?aaBAcOm{JlA z)-`t6WcU-@c5Q+m?_R=Q{Sf>cd>rQxr=0-9=ra5)zTPfQkJ(sy~0ZLEUq zzb=r!os9KEy5P3qK72B~45u85#a6xvhl^RmVW*@}wR0-Q-|@i7(&g}*=tIP%GjMax z2#oQlfU8HIf_s`Q_RU#=4#TZsOW|>FEDOPqJ?oJ37>=haz9ZKgLiFm+!(jIdFwy1_ zTrIu`bdnvWna#q>>;z1a(#48BpHQliU~SPgyzz8AepBs$W6yQ5eEn`bm2QSFJ0_C1 zDf-y=z64cIwZWF2SkzKJgm=>daf7KBp2|A_W?BuoG9N<>SiLwL*n6FmBE zjThVPFo+q47qlJmoArEnq|*({#ZI_kmByleXM!R3SK@lzk?_&71gl>C0ewvgTF-GM z7X}>!4W~lzSSE`-iML3^`i1y8M;Y_m%TTIzGY-B(JTsNMP6!UWj_jyDc3>TCCj22lLOp>^6UJ4DwH?P zvLJQ`Uh}h7>rDC+~GO^G^D2cyEP`ymYjL9It)A^9p^u zy3GgvXL2;D7~jKNhXjzCj+3NNK8jRI9U`^!^~tfGhrGqZNyIOiCHE{d_^VA?{Op;> z_{lG{$j+_=e&*Rye&M*cyz+fdlCL1gCpe_?Cr$;Bxo`c5{W@u~QmUMkj@RNIrDgMD z`x5w~X_xuaMwz^cCz1dcbCMsUNi;tXBW{+bNy-dW^5ww+61sF8SvK}2zb|4iIVfx) z6PpZ)dZRb@HB*r|9VsD^(zp2BW)ISNeF?c=FrNJVJDR-LisEC$dId6z<@1UwNYLnL z@-%5JNjJXA2YfIgY%C$>;`%LpjV4h%XTvLQyU71Ntw`F0KfL9)k>o}0D$@H$g%*kL1XT<3>p zTLbV-s)FcSehi9sF_7*w0nG;gfjfFzp=kIUSiUF>eUeV2j8PIks#}0J3;u)oYX)IV z`CjM|@Bh`}?oiH36;=LzgOClGI5FlING8W%z`OI9^5_5#;jd$BpplrxmBPO(T`+w2 ze4Kmz90XPBz}w*>OD}vR-pjZQXVV`+H5rU~m1{887eOiG1Wa@fLvC9T3NdPU`Q8WA z^6?~j4=#Y><1$!f{}g5?UW6%gCZKePJ1$>69*0lY#~bk-DEEd#XYb1x_h%v+#l3?| z(~WS|v%Q#kbPVn)UPv|>nPGw684Q}$0i{Ww{(QbmauGuiR zw+=TA7VpJjDJb*fBbd_@5GPH*sh{oe{%m_}ojM<0n0^Gk)htFSi@&499Jjw)hx3jY zK-Ta=Tz~%uINy}uEuC4!>rNtYyN|%#wX&EqypF`=_~IgGWu*Mh;WchG-t=D}uH^x5 zoeM3=z|o&qapfBU+g5o&>qlE0s+oa0(b8z9JB3k< zmtjV(&85~%ucrnwRcM93rOc2Zm-=<-Z;+NSj)eg9o`4oV`< zhA^j}70`by{#hL!f0XJ_TP}Gqai%0R^9?OCC6lgsJ;*9+>j6q(LjZkIv)rm;scVm$Y3J>Q^uc+e zzftR}Y z+`(Q8+s?eNI7_Do4rYfLWiizINlcxhCSRGS%Uu1P#Qw3;VIKIGvzi04>=g2ay=}jk zwt91xe*d+Iy*uX+9bLJP(LYErdegGlS$7K9AHD*kGk*fJ@vkbka{DJPBcJ6C)Nf$t z@`h}T;v?n)qrx26_KfbW&SY4b!K{N?9-|Y{!wH{PFk7}3aC0=I7@7Ps`uO#BW@wHx zvt7-MxiEekb$j|ChRSwjPPkUmrjJ*#dmLtPR!?l%r!Td*tut%sv~NZ91IH|;dQ}TE ze@zNAR(2ojIU}8UJNXpjnP|*vC48WZUqv%7U*4y;&(UL54!ClbnR7(;n>Z^|8p_-m z*Glo7JGs{33Cw53tBl86H7Yqdo7Ux!xuw63T`U>P22Z!)hAb~(Lz4!xRrxBM7btMk z|1)Nbi>7fUD|U0!w%%cH4~=IM;+j|$#()j)iC{-;3g>QhQrz|N8yF>JRVFXx3|Bm6 z5A*lh2VTW&5ig!A37j6potM7E&s%B9Yq~0sz)iRK+eI?`%FKUcT$v}IW3!7~4hiI6 zPL?7==IijiJr#WH{E_^NGqrs7KPBGmbu|C|S|(rAZp@D`i{P!_Ci1H@9`Pm`0r1_s zpO-xJC!Vf^uVU3~nKYChb^f`9cbneTGk!8U0 zLH402aw@5qH=FT`+q2i096fo7v;8Ya((A_)x5NRGWh+OvcJ1Uxn{MV!3bOf)TOtX6 zCy7(ZO%ZuDj!;!Ngw*OxH~=5_>;}v!h3HGx08WN9hdbrjkJX z3>tVZy?An{`aG}mqMpCg>Ix&BmJ|7J+9dGVSWqgQ4(noBnCHEXU-jOC_&RG7$-(=4 zP!$j9ChEj;nl)cL>KT7ZBN*Nsso@J-orHJNDMHP)d@*OA03Wh5g!BLlAuIig@Y>oz zux>hsIlEY4PHCuMRbMP*g~SPpvMIu4t9ZdLFj-hpYKB$WGQ#{BC-J(yzc8akUpOxI z$=ZHb7S>)uI1bDNs=gW(H>=LbIuq9aVWeR!y_@U(+)v@~A`bMO!Xd``oO z@oqv_|1-fmYM9_#aZHd|dqG&8mn58+5h-*!p2h!W_o0W#$V<7?D-`)v2-gxW3aRsl z2|f!p2>+$85mrxHE4Y907rJNc!AW7m1baJgp|pCMkVm-*J@1kP-y|0_X>1UtY#AZg zXLt(gqE~4Cn)9e}r5Syuj}|U|{SFy*`vpH+R(R+0TG%n=fUvu9zu>ZQp`fxTSvYEc zSy=viuMiVHR9N~wT=>zHAtbIijQ78P5z5O~2>0S6F^5?v{K~Ep9vv_iWJ_*h>`rY# zw`Mk8iXIOUc{)P+;mbHl%SJezR)e<6)_8K;1Kj@k4|eWlg*>|v!qUSdgc%0PLbQvf z;9XP(TSQI7Cd>+JZ@SQNrs7kFdK??2^%x7N$=% z5{hyH@ZhEJYOg{myU_(BK$0J7fv126C9+J1V`I(*#D*okIs?B z<&I&(f$R-J;s;M5FYW{$a~&jP2fxLH$DeU=kBqSBt0L|+IgP*kWrUP7x5cc@Bh)R_ z6s~=I4Ncpl1@o~b*gB&HJw9ne)-yX?>Ng8#%ZXW<^(k;ILd6_=x_yud&AZXmO(bc(N7UVk$xlEIuzpz z93+gms4CoU55Vgm>p?Pa4Qg$_j>mI@@ugE7`goOKK%KT=v#%R|DEOh4+!!JGrM~cV zb0s!gW(i;U5#arPGrl<$h%t}i@ZW{a=+M-QJuei6IH}*5x~LJ$Mr8=m-r@{kQjpO3 zr61S*Nkzu-4))YYgq2}WQMOnP9I76mAG=(b_97XLCRhtkoTdpn4-JG_-s*z1;&^n{ z--GvUl+Z^pM5wwrMOeJSNjSJL1A~wE;}fGk9Fh7RTP8{inj2M+*?$-VSAWI2^apr` zdyLO|wFPCVMtHb>k#N(p5QQgiaN-hKnE%@zO~brVEvXd8m+gk1ZW=;y=SAEVI~6K`+-c^7)y@(55a45m9 zyv)9%WZFl4SYmt?=HCk^?XK}8=Tk8MBg>4eA2*hC8~r4s>ppWU{d~zFj*z4RUEV6_ zFuAeqD}Q+HYkr|=2Vbu)Ps*|nkhXF4A}gv5)+aad?QZ7e{OL`Q_;)*hD8ZY295)A+ z#6BVI&neO{+?}W^>>*ms88GGSCcZpD8Z?TBU|UKkymK4@du3O^h!MAVeKCvSn{<IWC0M@#EA-xf%4L2_i3*$~+KO%-MxHz6nEM}y!VP2R?<5=HNH;^NWD7r%c)dRaIIChP-pL$+|6Mpmt}Tm!+GZY#*>CXUU=BnL(}U2J z@sOfE3Wr23!uf5Juw$Y!{`boO_KEvgiwpw$Pbg#9q2usYI1lzCGocq;FqF=LL5ww8 zXs*GMfw8zjWN6J0nJ#}f4 z*db6;p9bCHjG_8{11KllgULU%5TtIA-U44-Fe?Y<_&MhVJcn0MncV_t5C!lJ(g)pJ^;4$|fG4wkQuAi5Hvf^`c!)7|j z{CEeg&-E~gmBEcquE5qsZ^%(~e<cAbx2J zjP%JNo6B@zY}|W@oBJ3>YU~DwJML)t=nB7fgBi#e8H4u?dpPPo8WaOg0_cgn_X)?K z&nga-a0Yf5WP`?Eb1V>PrtnZB-d>ToDV!nx=Rp!&TJAx*_R@ z42}%C57+)w!naIWI6qN}?!7z~Ma$voTe7%1$Q}OcDukJ*PJ&wGaTr&B4APcY zkwwk!AWt2JL9gP##wHmG+8)A*k1-_TlNz48hEg-Mq*AZPy?_&AOy zzy0eVM(k8@E;K_;ksaq6TMf&4azQEo5iHp{80B_Wf%733xR757O`BR_K(>PrG)GND41ii`w$K71(-D8z0(;tcOqq{M(j+ zV>|ERRY{r2TyHIlX8Mw_E2PUykpv=eyyK3LS8d?Th*BT=|I~LDf z_krD(cR{N+14k}M#78X7{GOHgTtyjEOUC1e@@(|#7KwO+hrz;; zD(L%a4%$jNphV3HTPDZhBc%!O%A^iMlZPYwa2Ad+6=%U_XP`agCdA|!VE%_sq`xl$ z$A?>lkl3w+pZ!(AyJE1AYMX+)RK&f(^CQ^UKN8;uq@dvO z7|k1o3JDi~_;^q!YfAUyAk#u{d+ZU)<inVxdgIWh_|+pb{PCtJZyF9hXJ3>9V_ z&=X=B25{}d_xP!NB*K!#SZUe@P63`m70U_Q+YANg$wBz{#v{CY^#<<#cMB6OnsJPn zQLEqkA8IsRzz(%zxZJiJkEloq?oQ%!ou-9j;bCZ%bRPE&ydfc14KS&KAagekqclWc z&E1b^@FEG*O6>*b&K^8{;~lOGsm4p=|6z2xzOa7bTa1hj!oK-$Fp!cHZ0%MJ=e&;Deg2v!dn1v_g~;IW4l zc0XH*o!h43i8;#Xlw}V4-<5#-RBH&YACA}j${^s>6;LwIgXtHX(WE*bG|pOMn8;+G zvezDMWFoMB?E}#hd>l&384i$?E&{IdsO#`{vJy{3z- z#y2u}#|pT+N`lF4hT=6{4ZCd*qw9xZq~q@vaB>#4;q79N#)@s=GWH+DDl6fj!@nWz z_C5G#l8&C?pW$Q44%~QE3eDWo0eYI@pFD>y``X}ywwR@iz7JzHHi%kwD){?aaab(ujR<__8vT+J$3I@H8ZIML%Fg23(rj2TjNRi9WmmxMThgJ}Ia{ z!j8l6;Miwz{rdps)jtQrLVY}Fb(eTV`Cw;BKBOG)fHW5+;<0ElRGa!j;lffdca9+6 z#ax+G!DTo-X)`V@)I;aMVOT%D3tBr&@aMW|7!aV2iUq0AcTyDx3`U6shnBEyN(lO= zcSG<)6$qH!3oFOCW5~@Dz!aI`t)fjB;kh5YWxR++bU6O}C$j(c9mczJjYUp=!l40uE# z%BBogPe?^uVF7-q2!)tt1^g-<4Xz_r;f#7^jGm&7X8ymRLn;#^RsMjiL$uhJaupAB zB#Co@MqI9GhTesPahLZjjC$aO&W=~0XN4hb=)DBfml)x#$JLN!&;~DZ74bE_5uNVY zfx?`#kd+#N^v&()ZJ>z>rQKK`>O-72REnHyF|$(i0(Jyff!e?nbid*$_7zOQ58ftt zx9%%8ejkf!-PL$um=pRsb-_@|7^^z=p?FVXwyg)*anlsHi>$cv(VsxkDHb2TK7@WV z{=>pgi&5J?6>8g?p|Zjo#^y92>zNvFhtWC=dP) zjzt3IA2i4K>z4Rm!Dci`Hh}@@V`zR>%&8g!PTD_@4AdQh(C`zmhR7oy-#~1pEJusE z>bSD*Dn30FfD!(F=)ctl?+@OAb?Y+Fy=5`3=n~H_!3RHDhhVGY9*DbKhbuKFV2z5% z45i28$NU^z95GnrR(WD~NEX^NHR4PqhDg0VhBdJ?Dh_VMuP0_Q; zvhN@|{X7C0;SNVGnlf^P@)K^)G9=Dr@teCmenhh^|eg(l`_0|xjV#+VJ?(j=*7FgY2@duLD$34q*AdS^j@{WtM_(Ty;lwPdZgjl)`|FeSTBz6 zKZXkLQZPk-GcGuN5*4OBz-Nau@#goD=>8)C)3zMNpS`D`D`2qDI&CLrPfmopWG5Ec zx8XmE#c$60Ik`&%TvWSAP^^n$X~!$<%XOA~sP9c~TZ%WAcT>Wec%`s8_fIfKZ&`3Z z#)NTmJb{b)*2~OL9l?1y>#XHadu+3EI0D4Iw#ZQ%=z@5;f7^|a&5h8 z+|EA|9u*|)Bs){?-=SFcPGTnas{a~GU3$p`FY;n<-YDaOrde>)gJ^zG-T-$gvX;B7 z7Rl{8I+iQzbz;fyP|i;K2Iqd`0c&@@g&9#*$ae0&A#$$6SfwkU8L3QNcArNn_iK+m zr*st9_*r#a%H(KHwM3m=9k7ZUEOr7dIUC824^!r5?pedmdi#p{Qu>DNH4R}EZ%4CR z9_4W6{(0P&G@do0{t3F*UaQpPUAN0-@-K&4dUc4f8+Mnt>HrGFz$BCIfhIc#(t=K%s5z`V^${kvr;G4 zvjOE4d(Ce$JNZ$(XdF%BHt5wcD!Rd(iKyGOzZ{h##jSRg zXN#(?vr~I}*_?St*oxtm?AkSI+?#(F_^Ho4cqf};cKN0-MtA-T#^K9vX8rJUY^mIA z?o-!EwnrnG_s*KiUHWN4R_7P9Z|zpG1wRjQQGUzW`6F}L<(Ap(so#aXRP_k1bqK@W zoO_W~i4gT*)e@QnmvMoy``KB(0c`W9RwmwVJ!5Bfh5hUIi8H8nVHB6@@wTA_oavKH zCPSl+wcoyrn@FVS-6yUw>%XV54dYT-%jv4@slqz$%-0I;c(WDfCO?h!9yrUc8?l1_ zqj`kCyTz`mLF0s!+S4W$eAzDWVDw#G1>X6_|_&V?#!ubZt*u2?t$t{CiclqcGBt% z%$%6XOa*-9Gkom$+cAyIMY+vv@8AyBcJ*df?elfk_Ma}R`!kr?G+{Oy-1m}s;*r4n z9zVg2Fz;iv?!<8q(|S3ds(P-{Fo9D!xSTyN`-t;VlcJEV=7olp z3_32}k4IACQC;^ZJoz^Zn%DjS`lmY8FToKjWco&0xWE@@-6d)rg<+j4|Io1Rop;#fxMYdUWo_J>3c5m1~00cH1$h*Be#k z7U9r`*?7%-9;j`3hZnb4;H!sg#J@!xx#MyJid0_1#>E1p6Xl`Wlb8K>XR!lTb5pkTAq!J63KKd57UUusG%s zhOcLEruJ@-xl{rC+b3krkQ4l^HgTSyGY1Uj_Q2Z4ov?k+Yogoi2NRFvfx){6@Z0Ge zESgdWZ~V)^^=B36?e-z{8)z_!e?yGLb;{osXJ~M%CC;J^H~3XEob^;egP$K^w77n; zINd-Jn`Xn4!7oUo$R)hoI1g;Smx=w2Q=w4%C)g%CLvQ~J_+F=hedj+wZnHkVQw)bQ zLuP?K67lTXFFlcxdOiW~lgZi>ykzJ<&0b?onK65Up`(A~!M9h{ID8h!Jcj2n! zI-HJJ1MR6cXrX+H??@UBGn9sbgApzA5jCKuJsnhc7Xmdu1>7P-VD>`+4_%1`?YA0O zkdO(JPL6}e&cX0@=3{V5iG(jsC;5M8!oa0x7)It;gNK-B8XNopO7>iZS(U|*boDcF zd}|JJkws*CvJonj{s7V1@# z3;Q*yAma5-GG&k~o{Dw^c)B05J{;%6t3HvXi)CSo*<4tnVN8Amo`#lyMUdA#9Dk`? z25Xg*Fjyu5Ca$Z3^OwKCkM@(WloFusT`?@1cmu-f8;OaWHr6#9fQ?5^5ji>qnqKt6 zqT-pbEpQiW=025KZM=ucS`$Vq?HomCM6P8o4pwGo+9fa_V*)89!v)Msi%`0Ds z#x`>(m#p=U-g~T!>NXzEd~DaE_w4>iuaVtPdpu>Bv1e;I?-ROgP@x8&R^-iAg+F93 zKBw5S2RTgp9b?*mfrK6<&vE`cRT?E#;JmR`9O*td}ITa(PG84J}_mc+n=D1 z=F4(qK!J7Xd&=zW9?Cv^6H70#7)F;k8ZdW?#&NyR9BGT!ZPe+8 zGo-Ye**;!|p8P$MDIa%|=`}W|_uMn5U(CNoC;c~rZ5#iYJ)<*<{cYJzdFq7HU-NI% zKc59qO@9}2w@N25-C>XECGL0WyS(VdTD^s3W%8N+reXB>>@$o)8OJ)DQs$h(qUi-E zqge&>9;WJ`Idj1!hTVF{k%7*$w4&-zu4vy#)}w6|YtWEF8Oa^7dU|6Kqux_Eh9(IT z={g&UNnVn~V*Mt`p&BjfmihuFuKzUk&^ec0d|ltFe^arQ^#?afk0?nDPG?eAZiG_f z1zr+&HOy*YZY1S*JXSLJg|4J{MvRq$ot)KqgNIDS=EsupBjqHDS}oMr1}|oa>r=|6 zZ#tE@Y9zg*m7-+_1yOtZ=1E4)TR~q@)tAUU8!gdOS7ReoI7+=Gg3intVr8-NJSAf= zmiqSm7+s?B#A=}PhQ*cg)$~=lb=2cm@>YN5MM_>q52Z)A=u^4x&sz1*9U&>&u!V7T z9nLO``b67*H>O@+$fJK4G*h0v*3{yYNn`x=E>kg28ERLJB2{$l10&nIo_ZbJ%B;)g zB*q@;R`wA?sY5w=l+U=aR!#vwtPT}vQPx#GmcAZ0C2loN%&=HTruD>L+G?K^<OurwDKwPw>(w7Q!;JnecG+kj^E{>BY3W(YlE2@=8Clg6^xN3^bQyDn@minEe3_NOj7@H(M$Iv&_Zp3*mmHW%)6EHt zlCcBrJ;8*UsTfV&3Ttw$Hx(L(bPmH`{)OH zW9m?P+V&re{_5lG;nRoMpw%7hq?b)}!M+;HnSB||#{yltv@)BX?rg~Rdv-G`AME48 z9rIa_QH#0Xc#?UMYr_6~n9nG@Fl7^bGN_BO;f#etB-^bYNl&|TlUgy%lab_QFn2l! zQO3vjGrKlUrsCoX8PD0()WMf&5*KbQ({gAAcl(zob19{ZvCu82zbucZWNh~{J@wjb za)Y1Me;3cv4IgyqjlcEiUCCqVJMrU~luu4fn&=LDywQPvRPc+UE@ZOzZ^>|9%oUiG z{TG@49%rzL8q=9#%bmN44nnMkH7su)-n{!OV z1vXFiKQ{lbD!a0Co|T)Ja*E3DVn!B+nUvqq7-??Lt`fMZI=Sw*Wby=X_nFB4&qTS6ql1)>F?nB)({Ig2vR?Hm>|MQb<^rqEJZnnf z!fWcdZ4;`wS)2RV>{$|iZufCcHqexxdwMpvb7MUBc+7G>P~C~oDo^9{M9_|!?ifCD z*d$)9&X70B9K}t1(#LI@Je_l5ZgY)qWcj;;Y`80J*<9D&k$lsTLVn1qcHa1q55Hy0 z1NQQkGOl8WHt)g>9yZmb0v?;OLpHoW+@&?7)d+?&s-7 zj$-oH^eRZp^QzE^G9lyq5Ot*J9*11 z`?*yoe(;ve41R8IE@wC($5*C(&+@N7yN%u5`EXWnN)&C2s| zV$d5{wPPw;b?Lw*k&m>4c%yQg3$8WqfrHK0u~(XqYcZLyI7H;XyPbnCbFyGylL>BD znUjOIBt7-*o4_eNyn`VdoGeX~|%EDb`x`HQf#MHPd4EXkKaawsKt2m@wT zfkw>=tX;bu7xYcX6(QD0!8Rz|UJOph2{e2?f-y^W;^WD|$epPJ`v84>TyBC6dPex5 z${6co1c;Ko4p#?jVxo)!%Bw14b=owv_$~`oSNG$%{wC1&9garxSaRHMhse5%g*+ z5Hq>OBHJ{Z{Lq~M>&*1Y)L<=s@Ou|-{xdmnc9A0ndPxwPd5X8vO(2iyPO>JZgdEwq zhU}bmm>j#9PI`@BiaC&n{EK7ZWZ~v1#Qa}2e?KvY4-F~e-`2e1#ZE!a@Ioi4v6)Gv zs}8V1ujewg5tqro?+3`JAAX#B(;Yq`EQ@5Hmxo#FzwirH&axV>E)srL6(=(4NyB$< zdLE@jCe97##u#trx>v}N<%xSpb&L+Hc6B*#@zadRM$o*u$`bPM&1f>v?nktqAviGGXdL{_u5kUh_r~tAFGWGvVV8ZcOxHzEtr%KjC8v`SsDAv}R8tx3_5X zm^r|&H!376rWo_TRMYw2IlY|w(pg;Kf*l+`b2Zah*uuxY{mXyq5=cXR3GX@8kCRgU zM5l~7%}RZiA^#@$kZCqzCm+3vjf-6bb1NV43;Slnkm@>aVNWt^zles%-V?d_oT2Q< z%E^3Wr4w0OuFRX2NT6V`Jei(k!n-WH!`HN@@TZ~=@{QTqeALrcG7rMpXWrxZCDW&q z(yVxPS!f_@6EvCE*8I)SZr#Lfy%)wW>P{qi;y!42d^HU3PUH3$b+dsXd9YP`6qEU7 z0q5DD$31IE=S?gBJY!CLGM<4-q*uqH`aWPGU{*zLCD<-?6!%UbMh#k zGtwCC?w{m8Iymy)>e=LI&2^^0>>L?a(n8mGO##Q(VIb4Bm7eZmjlm~3gK~-rO85Zw zS@>ms<-^6?ohjMu0r9=@;z9vCq%oBIx6zTkFhhk%z7@e#onp{ekAyLT=)LWWVUxHV z{zf`Y%nx<4?|Q`U?zdsEVCh4WYxj1AuEdd?7 z5GL;4diKY#U;L7L$#Cx4Q(~-qo4k@r=lmT%((?b6@+r!)Ff8B@@9|(E@p`KR_i`)5 z*<2)8pHGI4T0?$OF%N1(J7MyYEigrG3@kk%P2|jXuobm+{Pso0n0?a_rp`6u&gN?K zy)~k*#j%pN@;JfT@M?Tu);^XWyp6L+9?sb)Oyf zGXpf~hM+uVvtugr&tVL`wR8{jtu=u)%gv`Z8AmZPE48?f_os0mj{N0ZW1oq6^cb$@ zygs+NzLf4YG-nP*?x(ltjHMTN-C}|b%h}F3hOFi&Kk?W@_*F&c>2HpAnSm*>obkb( zw9%Sy?jLi2xtz0*+J8KRCKm7L<%20&?YA~}VzB}rpzp!S3+YVcBqLfa{v#D3_PK8Q z(@DqPu%K_xSinsgp};g%_A?*m$J1L2Y*ReNL;FQ`xeIIlQEt$@+DX9=`WH$9S}HUc(kK(#K7?edjZ%O1rmIxQE;PG z^oM?m$=OM{7^%~Gy{XiM?ebL8o=D0lu$rp8`j2|gJf#AePn6AxN7M)1PRd$ukA!oc zMXfhgpjO;GNBz05kt&Y}Pm`x%n=+kNZ$}%v&ZGhsZJ~6B*HOo>HBe34 zY3f6Hs$@(bLp@PUrHt)3D#~gmWi@CQm6iIM;`@$CW;B{nGNXP`u@0XpYG(|UGJg^6 zb?&a!?_`$h-$hZYBHXE~cRA|7@{81y&vn#-^Jl3#$3xV$vITVdj$@R!22Tg>xJ<R(lNU(iV za!9F+dUtI&J!9=Q>P_5yh)FmMC!d@q&R+X@xqm01YcB<9pKpP;=WJNke2LgJjs>mD zd*Ox2X@DB>*|Z`b`VS;S>HQo~*o`DNP!%$ruM)3yJ0a)3IY@N!h?0^9%sO%$X3y`0 zlI0apbt4J}e2`2!=2}>?zgPfr~*gPJAKkx118;ACgPwXcW_gw{Ap7)Zy4?m zTKMJFYA8L~1D?Zn1Af$jF@CP_tE2=}?3coN*F8MjI1`$Geh2bZ3r-Fd&vknxJpY{m z`^#eBaz`zx-zEqB;n5@@UF;LuavkPnRD*lZ2&jh5F!XOIaO^HvU9b(l+=?T8?IXbN z&2q@UHw*5M_Z54VvSHWjnWV+A1r{$dgyQaHkj2IFjb~~|t->?1qQ(m9Tn3Sp@d*HS zVn@%lACP`26=aXcLD1F>uvl(6OeWQvWPW{nZCw zrivM8PbEy6qk)#Yhah;X<6pfZq8+{uJk+h=_KgnE3C@79AT79V9R+h*^wER%#OgzK zc!n0gKW+r5i@f3BEE@Q;a=1T2WZs&T!ozbZ;JI)rx~F79#!*0-Z;M6kmBV7P6>D>@ z!}IV=u*&O)YGpaRWV9IC|5OkcI(eJS_V$05m3H87v8NLie3wzlW&)1!2$8u zP9OEqE4mEo)+AuIjVAF}xfs|aKcE`-!5+6IFzUuTxX}0q7HV{W`S5E{_$C%DE#DN)W1aNn$rn?eMJA|)OTR0{~3B@WT7=L3H-cXz$3Bi zq63vcVe!SQQw@u3%BS3d-j$9@90 z+mrBXSr!cc5Dk#g2vTZYWcnPjS9Qb-(Ac;F`jZFY%vq7JW<(#kCVCB@uQ?4L>fZzH zT_^4{pI(AgT>680ny1E9+La50!s2$gVE;g5HxZgOlul~n|JsC8~YRXO)|oPAHP9y8-*F} zv0x$kLe=z3LG#6BSe0V{EjuI0fS8kgK5`$(%9y~SXgkR8T>-zyZD7T&+HXfRVdR)s zkorGIXW~}V*M{LHDU#AeDW#Is*?SG|+7&57D2WCUD)XF#ge00(nj|R=hDrlbWQb@G zp_Gszl#CHV@spu%U*BJ_&$Z8W)>-Ra&vV~Xp2E{_yFo$TiMfkiuYb*>U`*C1cr(!! zwwCL|@cvvd*E|OmzQ>_qH8Srj-3@kXE2-yaWAQv4&LzLCo5Xbr8uayFO zE|rtrI#TecU?}YA5i`q0h)y%Agddrk;fRZJKX9;rT(Pk)9VCFw=sWJ}HrdhClYeLuRCkaUqv&?PeUb}gi1 zhOZ|EPZv?sEkmgO&e7!9+#8tsZ>Qr*<)HM;PfD>AQJI;9*Vs;_4^-{w3Y!n~hV=nr zHZqBJyT(xcp<1*d>@`7)6>0MyPdaX;7tNZRL&_f&x12j5>XALXJ%K4#WRe(!E>mAe zhfS9w;bC9Npt3A--SRt09-~Cy-xMONn@d(dj-_AS5ZQcq75$^uOX_C?;DH;aQ@P|k z(ocJdLFN{upT^^-Z;R;afQdw<(ULyPSEjNrbI1>$1TwDIn_LTSBBujx<7@7lY4^+u zf_J#l?tob0nevI)ZgZnQrfw(Rzhp>NvM-Ufm7{ws_E3^kK+HGaCjlSc5tHqfL^Aao z^}PR#=yIy0P&$-Px}zX6ZEDDuk-8)vCE&NA)l_!NHnQlZ4k!%vplh?M$*G#>bnEn; z)Jt@o^u>*!kMCfzZrEm`?|VZ$-Jh1=bANW>j7Be_TRMbS=?UkL z#kF9^(JT1l$;I62fH!E;{vmkrJu7nWT^^n#r9mE(BO(W>1BX3+iI=}=!!G?h(K!nV zRvdH=nNE4YyV!=K)I+r>>Y>;q8fk;F?u_OSddo}JTpo(yQ6oRese-dA^2RSL=a87H zY&>_yef-d(0v(hK;Y$?k@P@(4v`Ckb(UQ&ev>xc7m>(ArD zv$ni-hO}gQRT_8jeHxzQp^8-_Td~w~33(@S(;iL_#GzB(B8AnHam;@_dboHJS8zLp zH{19Tt-l(^yQMi0RRd4*bU+bmb{>JwuM5I^({dzL*}L#2N5Z$A3zGak6pRAip2SzY zC!-10@6f)`>$va4KKweY9Zz5KgI{fDC7Gw&!B4c?z=hTwFi(Cpog6)O0G)1@#qGw% zXz^58eoKrlUaGSPjSZAX(jyb_kdrI1$Ggk;#=8M%X|yc%P_iOg`EF={c__AtP(!l= zQ}DFbf#h*o9$wIth@HCrh%@M4c={+Wa?o=RW`niy?N0&ZG{t0GkrRF#d>Cz2dAPg!3*NH$K9)MRgKHBV z81JX_;EPTJaPgg^*fFJ(R9M83RabQAVB;|C``-#2wO^6wtWY9(!^h*20TrmS&KcKb zdE-^9M`MfpUNZSfHI7rhNqmzD`mMDYjc?TPlY z4OzN8HC6024{Mxacvu`ehBdo>E72qpx76$sTx$>?OS6fjlY538Xh23`md9B;;Wyjn6%o$CkSe zV4ZtmieO7%TdZQoXsa3r=rL2w|OgKhX-o8a#G$)W-At~55 zbuMwMoQ2hD^NH;H%UDhE1)k{~OTzZOA*W~Q5;bl(YZ$zk-8&ZoGb3lxnJ#{8dizgs z+m#?@ztvce;$CoeS75r~lUbY79u}cEk6G)kWYhZRv8|cQS-8lP`n;|IE;on6?hBN? zF8=~f$JT&FZ42oC+`@7@IoI`uZj%0Ig z<+Fl}Cm^VYvd5qIv5bF9+3}aN*j3vYc&}dr*P~~EukvMf>-v6H7a(T($G3sSPQpf- z086eS>{_b89E@gxvLJGw@=aOhOD#6Ad?a(!TEbFXG+~o-7PC_8grhcwtRr(eU6vLL zd0v@t;6Xp!6}?Bh_qj6F|K!AO(McAX=FRTq&t}e%W^AR~8m4$8p4onPW@ANTokS+`2C-L&LYLRbV9Bmi^wCNc zGIIQ0DoNZ<_?`hoR$GnCzAqqU`==;K!;W^P#nN297ikWcP*iV4`S7m`@0!+5 zf?R9K+r}h(JnJfQkuj#4!*0--W#{q1YkugVM*)7Qd6ra5uP1&Y7teK&9Zr->A`2#M zq1Fe}$vyoZvQ4|c6)GxmEMwo8ddak z^9piPZ8P5(`qy|mD0D}0VW1Npn(fu?CKY{D&2^tJ|K?l!}a zJYV{#z#2LWf70FmLgV=^HTR6@_3@=m3gU zQSfcL$j$aX0N)!*iS1c&2GOg>@(xXhNrqi8%jhpmoZbN5try`2l?Jz93g51rrw4R6 z_Dw;KO=^{5p=W2puBk^Mt{@+Fx}JcpQ9009cA3fyaD<6l4gqV3hHcBmGkwK9SlGRn zK8_s1>XhAJOj8PMkSQm1{!;KKekk~4tPtl068cu@8f-7z48mP~)?9Q8y!|f&o|XwF z{5{|lq}k&N`QQl7-}9DR za>9hv<_dI5N-+&*ek8TPhFW-EKnu4vplGIyGo^OX^1XX$`}9nTeeRNpVZ7*4Yerd` z8u;y#6?9|!6jITfNQc%v$FC*Bsha#+oY!AUz9M<-bjk*gI+chVz0Tn5$V7VR?sXF5 za)@r0&Ljc1_K?i(7s$GT&>`nsu#2h`)>QW-*OwjVwN$0}W%kSH`p)O1fNrKawpQfx z^m%yHFNzzq0!ffgAFpP)0Iyj)7Y{C7OQNHj(C?UmSlNFA8bFosxsSg1eEU(f-KC2+ zFWpaiGux>#f1gb4TYws~RQO9*+VmdE!&H`{qnef6$vCZIe}!)2qL3Sgpj;wMLzR+ zDBf^Xj9k>{`AlMv3ZH2%LC!+6T{Iml|s5( zY6yAtx|mp$SJS1FW6=TAMZ~CJ8;V{13;DuFl+{s>!=6Tv4*yP6KEDkwn|cskvsi$N zbyi@@fjRt?W(nVB@dN$ZW{Yidt|FiLr_q4IO*nR#Df;xo4qYD`$ESDp;JYz*cp*~c zGA-%HaiP2M>d-1lRY)U}=!W9op4&-qOd+znm5AM+jKZ!XwxA;^!;r42EV*ztlnj%( zN`}?!A$G(4P}R}*yu|c3QqIl7i!w7&j<*$wmLG<{#zGLp2(}?4RhO2&B8LYF)gWPdMG_ zS$O`R71&T}0CnCLjXyrxhp!YGAyt(YG#PvmoNUCSR-WR&vS-LP#gBg@o5&yYD&)V) z)gsTg%aHlO4`_pW2H&Rs8}0JAN!%Y)kr*o;#mhIM=G6nphndUKakC2K)1XbB4y!`9 z)gGc}iL=n-T@w7uFNFM9qRGGh^9pC#){yh3B8kn-(WIhMlXPq@=i7JGpv=#Dc<4V> z95|){JL%8EXEL1mFjobLtDu|#Tfka$uIt*#x;~Ih~I)rR&XQK;>i^%FBN<;h@T(bd zSSr?*bQpV+b7SL)&x{}BU}HS~GtmHrR8Ax|u_N*1jvSIU-3`|}#uKHgf5;|BnfNI9 zqp5i&BzD~<-1m1IdVEF^FLtO$i+1cKE*CH0gSkJ*%EoZ~D=ZyPdvTPXGH^0sMd4WE zbtbQN#)Etu?2J~$i=G{Nkr>Ln!Dsg_BL@2lu)pC0q#ZJ71alu86?LAxRG5O>6~qq5#0oO=`$zn1{~xqI+7-R- zZ|3ieiX_~*P|VHUhp%araT%Yz$f**2Jap%9{(T(A7Z;w#Q|vFWZKo84QNt%NEvvCG zNMzQ>PAOnjw@rmyk#iR%a_Nd1ud)Lh-mx#^^o3t#ih^^;AR%mTKf}Wmgm+7h!QIXn z_C0(go5nw6byw3_{qzpej4RaCx>1hjP7YDPEmy+3?^^=)YT|c{T zlEGY+&$8>*`&s?%CBj~xHm=bqAPJ)hiqgIDbYDz%SoX%GZ`RcoQ*=Mdp}{vURC=U6uP^+Bem@fBP` z)(M}I=Lvd_Q-#s94zs2GU96{}i6wYGW(Rw_m~_A&7>BZ0{nPiX^~EK|Z?9o#x(dRu zIrZ=Fb@7P`Gg}<~}aOre%f1@!oBsKJz!eHaC@!+!}Ie)gqdBtd+!_qD1bT z6~4Li8Hw>ePs+sSwyxcVCuTBo^4VWvcV#{4A8?TD4?IEQROiv>#Y5;TaXx0Wu9A3o zdgGU`3Q4bQ3Lz)9Vrl_OyAX&$9@ThAlWZnlmvg7_8GCS=y?qS17Z>Y%0?7`&J#cAZ&wUb11Y8L)vkw~uH zTZLtV&G4_{8~F3s1ytr$12GEKC->`(u$w|Qi8qxOoh3&}_2@zP*~3osXXz)L;+0JP zop!)WMaC*#@RN)Z=UxM!^^?D~?(0arw%FO8Pe^%U#lllTQ!s4EFX^3PfHlfO{*v}*oHK>sk&(SPRemTQ zmEnqKd6{w#SM;I(x`uF%J_aF|l)-qjml^+kbAb6;w?F)pFWP9fL5O6+s%6~qC)%7V zHxKPLyepB_ZZwbXmcki6m+_w!`aI`6pL5Qe!ujT0LuDYFW+<8}VN2L%5F76HxlY75GQqLZmcD3%^M!#BE|Wb>zl! zWL})dOC5g9XD&(M!V_}22}|^NmQsv_win#Aq*UD3Fn}B?tmgF!EBL`zb#RdNGs$mu z2nFk<@ENZ{BypiNT!X*2q$`n{_i4>R`Sm~1uzU6Bm?B0V8!Y%8t6odqAq(x8$93w_kH6+5b%ySKYU4^8g86Bg>P!m=bTTgp@3O-{27%r{^lG9ezM&G z&Us}Nck}Ol9-BmSxlNU5#G4pC|Gg^TUNIBd#=PP-`Hka^XW!tSrI=y)0~fdf@!`DL zD;w^nT?m(U@iaf{s5|#bDUiSZU5CGY`3$%Jc_**ln$AyaQRbDht;Dmo4ML|>`H|;U zkaXTwPVxF({(5IM7pYUk4PT?oU!I-F7d#q${Q zlRZ-0mc@SzDCS1DUgCQ8EF!j6a-3E52$Y1wIH{vbsAJQfpUYXu> z)iE`!(yE4Dt_Y=}J8IF0e_wFdpdb=IO9O8)Zp1@!)zR}S1908g1k_9ANbqxQ^6Ixl z^h4do?wR9IwypuL>X9Q&N6X2$&wq%`)k0Fc=s3EcYC_^C<{~?dq2&AG+x(Aaij?#o z(867j$Zhl!l6ut}2iL46zm8;J^-GKJpc*B#=*~Utzbu1vPfa4zzgl3YP!oQ{ycooE zJc;V?Fr0NwLiGFW$&=U5X=b%Ou3eUim-qk1hwm%k!7Dn5R9X*GJ@%A%{xhRaQnCD{ zVePd0#Bj=OzC}kaJ;*tEO~!qj(}{fH3!EDHAD5wYRYK23;@Z}m-0``^TzFHXuKD9D9MDMe6x@)Jbjm>8k`}1hZgcj4TlmfnJO&h8%+}9 z&mslObNEAk1gSl4LY`*KrnlU-(iczSiEZmxy4*FLR{hnY7MsFIi<=@zzpw>y9`#sn z@I|_;@d~+kAr6(?PDIye6n$7j@IvkxT{X!H#-A=n!#SezO3p%i2N&_nO38xp^W$2u0AfwSge6TSbSw=kIBqkxaPiYZdyYd*VUz|#R zW=K=hjb4!CW)1~69MRp&_2Pf+dp;>mZPBVR(?cNCwA98h2sq86Q`HMxuH65 z={@Tk{H5ig+}V$bboYk?D0{mfZ@R?YHv!$_DUsaWa4QW@%;mxTRMv@y?Kj7 z?vI2{$3=9|*aPT`wFG^;9>x3G5$>X6I(c|(CSjrBWRb^yxb*!GUHfM;;^L0;g%4NI zbNMCIMa>kOa5)7CHi`s>G0 zk5Uc)bwoCPbM+;?mE4FQ43D_@}HcrtGM`Vdpo0r+7l!H%20pap$4*v5Sgr~F9;f#o-Dw89F0 zeXj!geJ6%fj0@xz#Ok6`Ym^W>rb|j|qOeAX2io!|jQ8rf#GgCj%$12#p(8VFNw1O@ z|9WNu=Xh}~w{(LvU!8QFyE@jJoByH(`RuAkbN8O*7n#-bKF@aJrY382&B~7-QXRvq zRt}K-yikUsR44EkY)sKe;QBu4DLb*@GD(C(8lyX zyz+Ay9PFfpo34uI@F&+$fzvdsICeL09H4+Ly_cZZ8&~7TTlQk!t_r`oy-#Em$MX+Q zC-ZrlD{zX5B1!WL;`dM9&*|Q}iQmrIi%QJj@ju<8`NrZ%?pJ6HZ|_~qwQURITzow0ev_!5Gnu5 z5bqi>AJ=?{>wN8q znP1cpwoEh>Mx+MW>i#QWux%+jd(=ZGsS>9&rsgv;OMHG8<-bm0{!V5-r zN`gXqKl`3Dj#+OAW$Q|NA^-9k!J}r9psgVYe}fa*uFJ1k%kHOa{IF+im)vWXul!H! zs3x$q)Mh4pxy;5dsA27NkkCExGPKNa5|Z=wGa^Ljh>nh~DP!gP!rG#@%57={U6=9(S3*~vz!jSVKNB`^(cD_hODArJC6F)8% z#*ArUjp_s0y6(5E|A3`XoN|y!TP2`~!33}@6%mIr3-aQ@W$6D#Mg+#{+mP|=4sO%u|uhC=X@f)aV9o@7KWuxeC9nr z8UA;jr0o6ms&6C$CPb;5mzd9F4IhS1k|WIrm~QKjI&H{U(b9)PEz- z$G^w@TDS21rK`zt_>I$FDC5h5AzoNFhxGq8ggqT2$)aYlrY%H;!p+TziO;Nd>Iv%qwmfkSCNyd+^!&NH# zki1VQueEt1wOyW!=U3H}3AKJy^XGJ0>Y{@06esa>UOvD-5+2g6PSVs-zkvwSd1(AD z9)FNgBjvaH$aj}pSbN-Q;zfo~lk4ZOQfUV5F^i=u!zCn4vYOtBctQW0zLzQmsZiMn z8`Awo9zQ$$4>Qf7FlLN4b$DKY1`IlmpIWuk^U1$(LF8cJROKw;zs6YBbl4e^f4B-g zx?Rk>dXEtJ-vFWL$}XlIrz%85BVo~#twLzVbm7gKS;FhTQv{PTCt>>IF8Hfn%hu*> zV5h(73(Hd8v0(5Nc`pqNJiUd=sB|H=JVUr^>L$En&g_R~J6rFN%z~4r2yI25*_aR+ zL00Z5YnMGF=tj1&%8$uHS6;Sop(8KQFRv7ql@acZm?NVXmNi>IkdvR${ka zXEAjfDZ%|y0c#7dWzvcr?9-VULK+w|EB_?6w$w}T*Ig|vXc;6_A9yL$k4%Tcf7xtq z{&}`!eG}75$zsYc^n{mFErl_+i2bKLNT!gPERlJQGVg0yy2;Hp@B8WMF4l2u zFFHSdDxPx5f(V=|HY)8v2C)~g&Fd0G@~)y1rPIi6d_FN4ITZa{6@hOT#gW>dkMQ0i z0o|Lo7;DzV2|Hy1hdA!_U zG_J|DAj95#!%KH3qPpM$Qt+r5e+X=(Z|=V)zE>{Lp!ib!cEl_)(=dl*?y@C=M!v2 zP;#BDc_BrYt6jx6oSm_STntum$|7M?7bC?L!?3AI9A3U*0b1TCi{p$AlL-xa*mqDA z`O>ox{d}v87ym_+sk+cwLWJ9?ea(0}E17>yLluA2%M~KAJlz$@S{e#IA@m#j) z(=+V3<0%$l8eX_P6NkZMf8qxBssrL^a_tMh0lX)VOzy4s5mb=YDIt4x8P79 z>k47y{Uoq7%!UOmiSS}_2K>%IbaU+>z-<@kQmFvAVKf@yR1fz{S8bZTTE{Mr@{8h89)YWFO#S)9BK35v(xw1ShRf@^afuxDne0b59Hd@1m2iV)G@47?&zi zz4k)U{%f>xoGi?gMA3p#(#$Qi3S4epfxmw0FxP1VoURIlP2t_{9%sY3CUDKBb>DweAD! zbreqD`V1zJ49nDF;Bw9ya9x`QrA`$PJ2M)FJXL`o?$KbpD_iU*<j|m&Gs|b2l>asyDXPE5j zpKO0~Cv)0X$TmODg}1dFn{oUpxRf1a-v?T<{rhIK8x7-_H|=9I&5GTh|ABS7^|2Xw zH%^cnb8C42w)i^_zGwUbxne7xAn{h10dJl7+ zJdeel9WC^a-pbzV3=poC2eU_h+APa$6U%O?XEU6avy(6H(Nj;u*rT!!Y~euzHswSU zQzlPX@uWPaxa(8jJNV>Wr}Uh#fn2kRKIn;o^@ z%O34bhL178ehHE6$+d-S%$^mjVa^fOp|ujiB!h*qwgUU8xRTl4Or`Tb+=8{Z4aVoX zvBRyy!D>l5v;Jw#BGS9ruK&)l&&>y!mfTimt5eG6&3?je&d6Z_VWU}VcoNg^JH;kC zp8?a;BDa2g5OXsZb5m0jn9u&VY@~!S{qOtOH`#~G+3+2_5xQxsT`Rj^u!}u4mJ^!S zM2ifuKQOU>EAx;qWk&8@%p&qG6U{msS;qWM*q&U&>i(`{R~ojlk_0!F5~w8X zUbT{qR`|`PJu(#JYNUj0MRP&MGl5l^E@okMWg^4zG7J7E`k1`JM2?{zbIgrm<6RBe z@6T4O?9^)3klx7nuURlIRfGApi2LmyU93252Ma#oC`3*wr=7|MZ2u@d_WG_3i>}sZ zZDVtp%j7b)qbi3P8^*BE)%Jp{aXK5`Gg|oEpT}zUI6*Nc$SN`%NBWkGASv~XsJBa6!` zW&xTxY;vc_u-}zRg(Wq9ZQSPr_XuA!KueDz)#wNxFI4aYCWLXBGlgks(hnVYx zKVU|G^c_cw%l@H--*ZXC@LkB!AxO-HeIi!Gg*?7@5c_65L^n4Mz@^bu^b7M^reR61!V1 zQsJ;>a6HK5>eIM{Kh#v^1PyFl3=VtLAaQtt7>AL85tXTcQXAlbRskH{8UQmBQs{$i z+OTSBHkG&94L!9ZVf}VvP`a%GvNEM$ymc5jtj~h6tDZpP{33|h_!IJlxR z4(^X1$UfI>CYN#^(c@$9(UeWUY2vddbbRP?P>9|HhvFB(4x{lfsacLK&YBJGBJWA3 zZY9LM83@nkGcXqS5l_2j06F4AxMP-(v9|?Gw+#TP)0v^ez_Zxzk*8Vr84})l&KGS$J&$gS;MYTZ0EE6B42d0(DQzkFw|7MZKy29#vYnhb$ZCG!!hVkj;?4SQ;HtX&_maz0F8&$0;2-iNq?7z-T zCrn>RY?~m=ioC_Fyp9NmHj3}ucqJQT8pbSkX0UptW$fsr*KCQMtl(zW#ZDfqW!VXb z1Xs6LY}L*k!rEW&*#qY|c0gpYjf3gJ*KJL#)nYLm?vfU`?zuwRq*P{UW-rtiI0P-@O z`VJN38&0w584HEXAWmqOQxa~Re#ORpFctEfW(gBb^@P=%)0mCAyij6oDD=M&IqM`y zxbyQp>mD?gJ>H=t^n>`8XBD#eiNl0dM)QQ5&GBr>jJdET*Gtg7^_`8FA0_N97%aSh z8Nr5sQx_6y=?t-I|lMwNAzOZ}uHyEH=$qHTtuqTVg3Wak%GT(?L z?2Jka+o7;p(Cp3>OuiiwLYka}4_O{8AhwG&i<|z{lV%BXHGi?MpJjzV?>ks@Wt?z) z{d3mu9w8jxpC@cvA0k}OyDf}w8Y;v!zh?_)Ga-ACqYynipS@qM#tz*(&Q@)d7oI4c z75RQQnd|Blb(t;rbcbDP z$YX~Wj}d(8Ckg9@azeYoP(dr^r6BXmNI13PqLAA>PKbM3&;DDeEbMXIB4mYW2@z!> zaPgp_pm*W0PT3t zo1TjE5ngBs7$d0EmV-~g+9q9*t+e;_jC+=R`EQbL8=5rJ3VB=8q!2^upDgsVo|1f9<* z!l+lvg}&YQSd8T~p~!Bv;5&6AOPgFSXb&|P{>HhpMq?&Kx*QceV|y9x>^4_;tRN}Q zOq5hRiKyM)G|9uyf6RY`T1e3EjgmV36!UPMPu$j$m*$oh#*&$`UJ@(oT*-ftyCuKA z*htRNFv)~1Ib6Y#5fb$=gCyB9Qrz|pHReYLUNt{9Ut2QgTZu%!uaTFTzMAVbwv}An z5+m6@O`Ypr8!Fj-vBz9QpmMpd3e3%0Ecg%RNOSTr@=VTj!Kb1L*ORm%^8+pzW)my(wysh*xGxm2zw={C7!)+3wF$LV!Qt`50t?sqCy;;$wziT8+? z{1@M7u52A^epq<~_cu>R@;7vmgsoBJtMz3i;a@zsE>lx}S!RgjS9T5e`NL6e&h5(* z-;s5ao*OsKN92S^v^G64Z=7aro@exy)BPF1%{^Nsx!&;?Ml7~w0cyVRyUU)AdNGYX ziG2p7-bdty|A28jmV?>OAMnRipB?_>!SXg*vQvX5vEDhDsfaw{Un$S&zd7f@)^rgR zgsZa~C+>pJwP_$3eIAOHXS0IVcy{b%7)w`}#IE~Ig|+7!;DFp#m?W|%lVw|AXRqkh zHoE~I=Ebscst+MiDwKH!?`O{zuVJH&a#`>USvF?F9nefPV2l4*usKo5;Bom69o&!v zs^hJ6jgX{!9wxfUI!v|Ej>Kc>N4PwBEr3(ev1gga1`qQ!>${DTd{1~Bcu3GCDvIq3E{#4OA1 z!lFg;Y<@7I3(txS%dugAo4R1>oRjp|TEYU~JcIUoam>!kk$sBcSShHm5cOHiV$62- zebIQ9-d+I~OHJ9gsSctW%?UnLrZeM5s_fG9NifO4kQIIj6@xp?VCrDPX1i=<`-BYG zRJDNa*cHwc_Q*4@joFOq7_#nwbVyz?mT^NCvY_hyEUVgweT)xcj~q8KMT1~gFh&C| zAMb(JRR`cdV+VF-#z5w`DjcpK`3lcKbGS9o9@g0 zyQs?k#Oku|Yo%GdTnP*68o=ySa@f0**I3k>R5rNaC1ZA`Y>E0H<_~U6OzE?lJ5^xz z*$l3jR>H{@28_8iz|aey;K*YoR;d!eE~VQ6k-Y%l_eHTn@%`Jjk7n@|a>CGShw13@ z>tL^a8~XfuVC1}7sFt;7rD2Pil=u#1ZyU2tMJWNwCbNkxP0V|&12cHt1LKxiuw~W< z*@`PXD+qC-y@r@Q8Bxwk-gd*WD@WMS4JX*RkD<)x>smJC)?pZU@H=!&UkrDCHL$p! zC)gpMQ*7Zt1*WNQ&xUE+GjhR>b*`PuW^1j3^FIc$GbMAFnUjR6D)21###Z)O*9cZ- z-(&j%hcJ!(g6PdzPB%Wu0_oi)@b;k!vj}`iGnD*T!7UAT=)pDCxiprQ4D)6EmQ&aq z!&nw^vVb`*3S=8z^ue$V%a~T$)ol4t!OM z>5aRw&>3S6@A?3YL@rHPX%*b=*N2t;MUYeQ1%`HB0kbQ=;9{{Wn3Wm9f$VVjaWDdC z-Fy1*tRr0=)kQxUIsww}qD}IHLF$M({46~L`ZJf)^WN>WpgJEmElr2HN5;d1=W1+z z+a9sc`-wh|c})v;D1u&8H{BDv6QV1^;Y8Xd5E7iAJyeyA)m#pSVn5%$eV5qb*MPe} z?cl6>A+)7?!aA$nWQ>wM_$GaVglogV(dZ;Z{k{lxG!@7sasK!B8nu&`frfKYRM}IS zUHW|uIK?Z#Jye4Y);{o`UJx`7-vK)BL|0K`4AnfY20MDZAYs2FD6E?g1JyI&SHMiV zC-OEd5gpgnBNu~hcQmo~yGrc_Jfv?w8AD@cKl#?Y51RY{^2@%!@QwT7KhGF2Ik5(| z{5k}!qblHf-Cl@MQH7r$qQNUP8`dn!rRq7|AY;7-?w;LC?}{^%6pJnWv%HTUP?_n`Q7eOBEFSazq|)GyF2hgOWKf!N+7g7@k&v(Rpj2HESyj z`F)oLHBqXn-$Y$pFl>=-rp{))G_6Df3<@J)xs3zueOyg{tV)J7{Y21uVglKQ16Wvm zII*79M29SBqMKIs(cN`T)P2PQ__BX3NUn)ox;P5ekE9u!W)Ix<`*6v^6CS6?K)@ye ztQTc~LHZ=PSQtSv-cA%53iYsiy9`YA%LKj4C!lOrB*gk}0>5h~=;Jrv>DGV^w8KO6 z61kT`=H?=praut;WadHMR}Y9XTL2qhdBBehe;QFV5H78E1cN;kJnJWlo~ym^+nv$F zx2j;Zg%YGLnhXV&0VG&BK{Jxe>9srB@Fw;h+2R}shjn#9HMCJYpGSdju|H^gIYC!Z z3@o=Ugs(y%s6Cg4+CD#sO^<_HB}ug2y#-!xp9O{`yQub)1#q_S419M}gOnTlL4JJ; zI34PylSY@5H~T(V&z^b=j#lDK_=!WszO+mY!O;5svTv zPJLZ##WiO$G`Iebv^S5YDtiCNk-3Z+qDUek_nzT-w((w~D56M{N*a{XtU;wnrYJ** zP)d>pQwo=RZ}Xr*l1gQ0(1eO+O8w5~^XKQg*7v)9pZ8tsEW)3X(cr&m20l%$V(1;?AidNCmUX+p z&Ku+5K|vXGU8#k+3a25ZFa?I_d*jXWeAqqI0?%nwz&Uk4NMD%<5AyISRNg|Plx@t zPr!oV<#6<133U7`hWM;2?5}6s|Go1->X8D4;RoUR)~C=~y`K&HqK;-ob76LQ9*i7% zi8&pq0E=^V;n24bQ2xNMtKVG*m5QBUoMwU7c@5z6^9mgNS^)2@p1?0k0ZR^F0!Dut zaHelyC({AB`R~{@ah9B?%W;U6yU4cX6#_9-LDP_x@Mg^rV(u}Kj5XVaXCp1)cDWBJ z*v{2;^LLP-MgQ>aqHx^ksYnife!x7}h!kd_9u#~**$|QA9LkYE^h6o(xh~dTO_%+U)+#AV~h?Uv+HbfCS2Q#o} z#UISxUW8v4i16m0cDxqmLSmFhQ6HI+yXoV|l{w3?Sy(s^rct z6X-KkAd&mh$YKu(`r2W&fvQIqhzOCI7#}rha@e( zhXspAkypk>MDCaYc`#^3NIjPVO?r%t71m_wc+MxwRGDacx{$_MvdBw6N`{?j#Xff} zqP}1}RDRlwf{Y}5-24Vt{w{|+3unTc`U#Ugv&fu1bBSt$kSuo8C%~*HNT}%iDi;>J#m|DWtpV3HBXaZc~3Wp0_?=5_N2I z883OaI;9pikN?|~&-Fx2c^@jb^Yd=x(ot=B{6{Z@yiyBIx}?sMS~~3KglTw?>YEcx zm&mCxN)1P;@ax;@_LaKSj?Xix$%F1x`LTSCWA>LmDb`{N;^XLZ!gBuE3@!dxtz^EF zAdWsceg$Q<@i}c8>qG6d^vP^@y6a8+<@t!E2;@$D7X$<~HK%t7Bb|DW?{#Y?wLN7%zceVC8e^ZkdzJv?g%RjZ zKLbm7dtt=e^Q=e>AZX=S+T`LqTO!nCAY^{nNDAU<=^h$l!-J8pi^6VgYRUc#Hn#4wKYJ{Q( z7ubmpudtejR&D0}Z|Gc)PKXV}HYLFDFx?2`f=wsk=VTm4cA z;u0d@`?e9xH+4Gu9x z1?42z6p#Q5=Ny1|nYrx1^?b+-I)vAbA4b(|1#GGqg?hrHIP6OzXunfr8ih~U^1ONM zqX13QG@YVa9@y z@TWTk+{WqP=f&l)rEC{CAGX8*u7AE}pDqbpB!#pU7BF7?8Ul+PS<4emtVBGGO<1lA zr)4rhI*!v2yL1w)qa<`t!!Ph#EM;%Jyu~~l5QA$sL8C-~l7FgXLuw2=yK@~IyMH5G z{db6Mmpp+D%SEudOaXmEmtX;JB&6DElm0(^v@ugAT?=a9ZLc45X~cCl>a_@{ucsiO z6AgLNGD3D?tU2EhF-ud;eBk35Rfk_`k3=K9#!nQ`f}7ZQmiRYY_2pCi{a@I+?#=G zJ&Uj)s~)wS)9{-d=acO+p0p^9AkyjmxNpb};;~ViOgVCl(B8TPR5}07NBTtL{SM-X zisWrk1~~2>OA^i}kRJ_~vG&t$(z`Z>O#A0SvV&>Tb|w_7B+WRwXgu~kDIg|Q=|tB# ziPRr$!^D5)q_azth>q!z+kO^Aeg=)dpS{BUzbwdLi5xk>^$(6~3yItk6|~-Vo^-r; zfz)(GqO(~5mCfrgBQ+M2{N%_^MgpFj?a9Qd4!k#SA8DMjj5Krr*-PsX6WKsw@jZs5 zi9N~ssyjIAniVnL)?1nP%LAP3zX6*V+n{%V>qk zGjFlOzE)#Z?My7lXhqEdP6sdL5sWy*_1}{ZVy@^O?%P?0cH__E!IUC2w=d(oY`kH{ zRvXNpaTjhCCgKlGXH2ZFhDv!$&Lj2;R<2bf5#v6icWNEJpHKxmjh(TL*A5OdPT->x zQ!r`jBHZlch@*Rz$efC4Xua_#zCsn^;PxCt>B#EMd+W^m_lyWcSL)J2R4c!WKp=VRm`kiXe2Y@&-2 zhRo8zoyHTebg~jo(@n&gn{%;z@;4HP>4ZO4{@w@9g7z)25|;?@r>oOU3m@iLGHzXEm14lP-- zDYh4-1rxdc)dBqTF#)G9*oX2jGjV*^Q7Ft7Vp?Gmit5+myZFsmkW`MRv?IYnSCh2k zWSn?l2Tn*j#V)OW4!e|pz?o;u&}+647~CsFvynb{-&CHYua%;sGKagE6Nk5!i8zne zZhYrniZBvU*q@6_Q{&m`vBwNL!td~N#nod9-rLLQs5hNbAGi@(>rlpX%p{c@NxGi9mwe#4blvwuhx9jxpBscc+GM0IOLs?DG zr7vGHWn#vMGkrF1=)4Ds?AsC6OjM4Dch1R+H^r9IN}sTj*}dZ)r-yZy5x-{GDJj#~ zG1(2Y@h~OsIHAOf4sd*!@+hWDx!-2XSrs;0E{NJbcQK`6a-M0=Sj98+CSc*G=A{b@TZA7fbocXIJn2 z3HXIw;hZ8#I=^#!8hy6Nm=@U;^Dq0`@YjC`;P-7B&Y%2aDrKj(ld_&w&A-EOk8i7G z@XbBjXpeUp{7)-___tPPQzMgQsRd!J{OY2G{C{U-XuBhC`GWbz{1Q(UDoFhUug`M> zPxgfzeK+YZ&%S0UC0AO`TU79j?>hewUmQD|I$J{Vf0Rz8d*@nEeX{iRD$YUzHx6fztl&IIXdhum9{vFx^`?fr^|DSPfTO!-v+9@QaxEJV`2|=NhqSX z1T|7#qxbQ<>iT#y7XIaR55!UI-?{vjwHow9mjX&tSBc;IZ#F+bUz^kOUe3$@X~7&% zvY1RkYDlWH2pd&ojP8sKs|kS zlFBPP&gHe8)G2-mHSF#&e#j~-PFo_Lue2(c687s+!KO=i=Z@A=jnxCxVEP-L$+>e7 z@mCIS2kJquSvO-~r;g5UX>gX~vL7}m1>p@Na2`AiPv5?TE4sQE{;?nOhAUxl^8ox# zRY0epEcO(vgYOqc!TxJa(0VHgeiSKz>f>-&@J$`pKbwe4bH?He-;Xe7*-+TjlmEJh3wk--(ZPzE^vbN7~Up}BcJxd;hvlD zYpx>RF&c*zx?jL`BB#Zy-2<+@%4n~t4l~#Kp_zL<=)`|wRkk;P?RRSoo0S4%2jpod z{wrE#a1S#&dJ)}j&ZpCIks-rgQZAWe=}&bu-L7$iY2Mz>d{x(EMQePS)}DLx!g@t^ zX6i^27fzsxs`^ll}6{_bO1!9AAV{I8BJwTfd_DUV{*X0%hCO|o?PfqT?oo`@M~vWMmv zbc}4M9rJs55~Z|nD!asNfH@T0LXV3!XFoig$KIVjlD+44fJt8YmJYV}XWEy<&=+H( z*sh~djM|_c)0cLH8DF@X?OO4XUNNKwcrMDQ_D~<(Co8h~y;_(Wn+y9nt+?Ld=V6h$ zDVX#gg-^ckprd^RE^HlwgUZ9OGFApP21&{Dy@VqSw zIxg#AS)v!t{AG!5Npd*xk2=_^W`f>)1DMz{0M=dE;Kg}V09^*9xe5;|JR!wt@j>fti95 zF5Yp6?QL~~?$bK>{-7@Me;$X>+!)k-`Gbicm;v5mA9!9D0kQFZuvzmNl+5gbOB#>i zr^k6H{7$)l{3+)p%upU?}5JGwQx~+40ayA40E(~*m#Q@u(NF%I#!M){U&rjKMx0$rC_0;f@c$I+57heIP%m!s6TrZ@;&}A-ZqwS*;D|%@3KK> zR}kCY+7El~9RV-i3_P$@0khuxfZfv?p!k|HvQCybT=ge-+>C+06@BokR1Nn|)Z+R8 zvyth$2eQ}xvb)q?f_FC$M-Iz?O1~=XIjT%XmyW=wrK%wLszEIC4xvW&1Y)Rv4ke2% zP-u4oZKw3$@x?~O$5o#AS`Q_WTZWKBy~;$UBL_Y`-Hh`#jK}F96F!p2 z#`}_G8s;SQ&T?X|QG>aYGVsZ`F6@}uhnuHFpq;J5hT8TSgjsv3Zgjke-)&ulzb zq(~xfHNn=NNjSWcieH?Jcew(tVQPC&?d9(70LaT8bl-D1n4~4i*ozN;_)FbG0^!iu9>5c&y14s z=!wxJReLdceAu33yck6m+|j^~g*oWU-Rs6n1=7gjkuUU?V4+S5dOipuhv^c`Tjxg< zUo9r)!-05vhLU5Fn>Z;w8|zbkq0S3+@>{wHk4&t9i`0B<8D5QRZ5N?A5L2D7M{h6YoN$ctZuEYm-OCp(fz+)gFPn6Ln^@1BpNUnk*O-aH&gY)8fAzi`Be z7ub72iUG2FNtnt*JZ%t2lAT`R?B2bY5cUM!9qq`Sf;+gCT?6wr^BOS)04L~Z zPUN1`Br-vb7?jJA&~-NW{BjbG-qjDG>08N!F^kAI6MGU@mX2RU0~qAoigL1@nD(&; z7wwhBgPc}p-SbBD;xJ>cD(|A^a}823?Fm0wEmzQF_j`;mHz9es%4DAHP;y|G3>mYXJG0L$gaI#O8&BRCR-{ZM371EX$fGX$3@cHv>JpHBwbsq#_)|cHF zlaqmea}>#{9giSS#tr4tw1{}E4cQ)3hk^Sth~Ga?piF1tzP{BcF-gXOJ-#UOsR?~H z_u|`~PtjBR92)xWC$F@daDMi3@?hR$oEZ|08EOx4U=B@UeoJwitv#5HdxeVcCzA~a z~gYli5KB5oJ=ZD=HYd-PL$jF0NdX_ z!8X5-n89gc-iXe}xfLIA>h3yB$iIY*W0Z;Iwo6dk9ziBG=3_pm{{*Ruu(#9-e{L3H zy({-#E{%ePz;UO4<>UL)p5*?RF@z_SC8mYVXvMu_i9Q128>2~{s-)H-pu) z2)xjrj{7F9LVvEVF}iIChCjInr)G`Ck0u1ewq}4*`yjh9>;NqL^c_mNv%qym87wGk zfFq^f1k`Bu`kK!L=YM_>%4ps*_-q8DT zxK2+WofrRsFDYU?D$qc5IfSv?ewg{I8k|H*c)@cy-fmPxAH`+tybl^EW3(Twi|XKM zYzPkYZ$^2miMaKq4R*a)1;5!UcojJwA`TzLE;ViqJ{N%^@0;MMKMH>t>fw<HB3c#YYjBgAnV?*%_e8w{AK2xd zixI;(?Al@>1d=hhaZWUjUHcFU=vMgPV9IezoZ-@ULsrQ0@Jdb<^vF%eZ~Gp@wQ@Hw zT5}s}T!-T8t@ijRe-u7_I1ZnM8)D>1Gknr3X1!NsL+~UQu&S2jvM^3pS9uh=O!qJo&x#WKn#~Fhp@Ar*moxa zcklJUUF#CDWNrtXC@+I7=}=sGNe?&N-T}?z2|KP}I}DlG44%bNP@0nodFwBLV8R&e z-Sv~TzZwb*P2+(T6e@kZ18;X6$JlIhcEY*{STMK?s;xN>!Rb5UvYQ{7>0S6R%y z^aR#=aG1T=Z!k1>H%2`hf|m`Bz_5icz+|-$GkxAc&<;~}k@5!^Ox}b(CP(0`n=3lF z``~XIGu(7>I0`RJh09f$Fnp{glydRxxMChwjGT#@6N|uku^e6=C5O2Kvba-|J2yw_ zK=hoGV89=M7yRd-b)^&bX^q8A*3Vg7xdCTwJPXHryFk53hvS!f!bGd3F#VMn&cEKr z8v2dE&ghGfWU~zoE{(%09Hwv$^9%kMT47hm4D75nKzxu7Eo$0GbAIg1Pzoy6?!gSZ z0Wixkgyd{_e9|xvZyh=Zio4r!-VrlGZx6y|w+V1%o)!7gd>J?7PbcfUA7j10H->Qg zRm~E0qL4G0Y&955I!r7G0V85#KaOnMdyCW;(? zGL4L`&mpziZ_stu1vKhZBVj_CY%qw$to&DCJ~awE*5AkXoG*NK*AbL0tin70IK2l2 z1zdfBtEXOMNr3Yd^3b*&PkLM+{w*6Ju6Z}Etxv-)%d_~jAQD$t%8)zDbjX?p1>(D? z4QEQvlGscc;{RqJIZ`G^cFj79DLrzeHzj}=`Mt;1`Wev4@zerB){?I5B2;o)Lh62o zkS`PYWcas{L}uAEgz!oXZy%2J(-KMPl$~VS?F|I2rMTZ)ov2v;!?f+Pq|Zg0>@*&U zk=j>r?@bP$?(zm#yzEBL5L0qx>N|M)>Ja&T@+vmB^+Gb4rt7M4#PiL}j{|X{+O_Q|UrT8pZpKNt%+>ud)C3!WP3Js2s&$Dk zv+3eddggg0=FOGk{0D<8sfJ<0XepCMTP-o9+74`>zj1!OrLi=nJKK>N5k)bBDzY?= zaAbC#+RF6LHDu=AFQQ|YzNGzv4Jg6v)zrY6Z07f_U-TTFF*W(7% z_9jf`JqrXT-h3SOG5iBV&+eiw{EDD|5BtdcHJZv4HO4R>R)(|b?|-xP1|!(^pKfqq zQzEU@D^J}peL(NFcuO&#;;4hqFEO3byO~E!KFrj*!>Y&RLWyP}yNz6D^AZC1);G7X zcgJ7ncfT}buX5h?J^h{Z3;%~aJ+C8-Y+fN_TNTFlcDqEoa#~SLpgH?)ekH%-lnH;# zMt3%Dc{r^4)kW98x1_hW`|$_5OlY~!{*2KLPVislnavqahoEy-EWQ1W5_Qw6i_zQv zi?_nif>ujd&EH`tWWKbvP+g1Hu#@a5;Fo`5ss=pSiZ)}=a^V^aO)UG&zm2)DM2QI- zGlkZX<$ON`ee~6_ne5XgGW6kURY*}whaFbBY-vpkv*SQMYcaHta%khT9>u5V$3G3} zK0$5Rx14>| z$&es>ib@st!~4 zdsb50Hd)ZS!fn~nJ2aqkzcO8P{RI>E^)v*H9{?pz`zOV#mHD?^8Ofd`UpuQWwF@hGrZgV52nkcvcpC!fg%MxSe;rAL;u9U%`jOw zY_tZ9!<11z(GC@t86e2ELr#hUj9;Au!kL;-qR;ul872cyF_ZI&+6`q_M`Oet4y#wB zj@g5*I6Kn-#b2hQ^NrI`w>%!A3!gw(QX9mtbcVG26YT4GE+AKS0=kVS!N~5VFi(3w z814TBZ{CVoX9HVMSf+w4u79Cr;~^;G>J!g9+Zd>Kg=LQfVEKFrP}e5G?v6Xq+y4ys zYBzxiJqh6%8&GGk7ABsYglmfKLCxPy;JxZNRF)1!rzw@34^#^i*IWcz<<2ClP@~c2w--W8P^{_Se zCj40Nnk`G;48InMz|pK2sAFY-HGcpcir9c?E0oqm!oi{{D5z*>zE_TfMQuEIT%QP5 z`~29TYwtmSbOy}4?22ExTEk8*cX%8xg|)VSfl@QVBY$2)_{4Q^^ZZL#wnGk|&QOBW zp&sadRmZMPFH95;p0*a{z&Ghowhb*S>) z1KBV1aP=G?46Wwl(jHliY0%`n1F}KP<;N%H$e?IV9_Uq`1oP$;SSz;2&r`VC;IeUO z{dhJ`Y_!CtkE`(X7YP^&Ih@DgkI-^$0G3d*ASkbj{rq(%)NelzsT%@7ShOA1KR*P4 zFO)G|zloju&jZF+>*1{gT{LtkffP6i_jGulAIv=17- zJOhUF7Rc0&M{mal7&ty3)$%*w=OE|hR#6M_FOBhJ`ZcJUqs`6{UITJ>I^LAT!39r_ ze^6(G9SN$~N)NzBUn?-3ya^Qkeq%=_h2WMGwwPi_VcVu8*fF;ajNZ0_zOW5!&bPy< z(tg$mlR%~HA-pUTLGp#mVDV5D*9gVz#WNl#>PrFE{wDMd>t`zUtl_}|7uar80ExJc zO$wGpdU^rC$(eYxP!)eq83f~9O)zIb9g9v-sKH^+?=Fsm(cM46;+z)JlXPKES|Iv= zdk7KZ}$8jH2s-q+h~Kk)^NP_JuVo$@drL!`WLB` z+xTJ1a8mMmIpzgW=<|=O5gt8>dK+ZXJbfYbSp9|P8>XYHnLGw@9uq?}81xH2hQ*qZ z@V50mn2oPM+u(ZqES`rC6>Lb`ymt1{&OvZ|I23axSm0cD5)^C+?I_MFiS{wGv zC`K)T@u1lQO9v8Hp2W z&%t`1OuXmVjpg(0v3h6&T)n1;=V#c!%<>^DHN^~vrJsQ4c2~S#cZ5{ zY)HHZ?=BU>!Vd0i`CJh*?uS6xr(3L6MhM`pn^1Rq9ZYdZ0>|#tP$Z{^UdP|EvLy?F zK5mXqzYUP#*FoN-EbhI~U@z#bhGvBjc*yzmJiEIV;O%#a@lwF`Azxs_!Fo8vWT5A& zPIx$e1IDWTg7xb%K(X{D2=XnlaCi$iSPn9iQ*Hyfwj7^?q;Y;I6wVnZz@%#<@XuKl zEL-RV&(fmdxs4K>t%|^2o->B?a4uz|N;{Gg9wR{6B zh4&!f%R^97AAzmXo9w7we|#i93_G{A!Se`3wlvKNPA>KbD|Jqr$1ajhKcI$I-z!0d z3FWv*`Z%n9D8?@3d?f{=P~K)DP751`w*6_)w@4YaHyNSrA&x(@eG`__AGmc!37mI# z!@5@)fvzwgpzHlwP-^BS&{PDuLFHc}+co^>H4TA7=2!zwz{x-`D#Rdz} z+Qk7+-gm>ZKM|jKxME>O2Ybb_8ag@`!|@X%Fm^)|Om3YDeMKVJEA++ik!kohGzNF7 zJK~%3Qy_o!Ll~I683z1VJZ1eH4qJVO2;JKtp0O9H4-X-=iR;0JWumvi8Y~c>M8-t{ zpBpxUBX`EG%dp35Bm**CWWh5(11vWE0@LeRkHX@)Bhbv$0HZ5Lp-O0=w^Pbx7o5s}bP^Pcj$}nH8 z^w<;K8m#fT^VIo?QA|bOYpQ3m7SrMMo|^W+nmN`si}_$*PMwXoPw7Q}VJ7YKVrLH4 zGG8LK*zHgE&>>^$=*21) z9$z_*9WQ#ugq-4h6{gfPgQv3T;K6!2SFM@;wWN{$te4NoG!@gSI@c&#Hj6($u$uAb z+tRwuODMOn0;b7v8|$>|Ayacrl`VC=M$a8vNAJ`IX5Ma!`4~BsQo0?==udh@weEaH zkvsv{w;g2Kj~LSX{&g{N!w)l4chpj=vVPLZsVA6O|Bf(^c^jFIgEdURGm5ivCd|5pxgkDRN{2FG4my+`JUt_FgWMpOj>zd&;L|#Tl zS(*Fee|$7$TxFJTUcGt|%`K|S7H?Y22iDzHC=>7>ePm<|CjZwMMqd3Q=58$WU)TR_ z48s3825@(E_z%XQDlW5gxVcx9$PDW@7i13HF_%gyeC?K~Ye; ziOBtWt0-d@M)ww++# zLs9FOIFYSukZ3Qb8JZHNWuHD<9}6Zwvpd|QV7DUttEg~-dX?bh9+94hmFyYT8tW-3=^s&h6vZ8I_OmC9?^0DZ~n$4mEKEsJ^MP_ByOeeT7dxG8O z$7e<9yD!@1>gL&baQ%zR9*U%3U69B%=YS|;aGPj(@lU%Qtp~Ajf4!~r?FEsx$6dQT zl_=4Nd;4r1i(g^zC@VYNWX0O76^vc5j}iL5UrIV2EUfxtRcQB4b}9K_I<)r4`?t0c zhs|n5HTB3qpr|yjNpzamCrX{7QspvnrfAubp|zinkFQ<1EE9u6kBhFpl8Eju3KU&c z@fP*^M~l{o&1!Alw~+JkX?9*N!|d{7jB2H0T17qWrFJGi_L1V^{i3y3f(el(i>{ti zsdam+QX4u#srDUpLSzt{D-xa>Uh6THu31>FN%rO>iE_@Qh+5Q}L{sl)iT*{L6loSO zvHh>uyD;x-po|^JCF4<*Zjd?Raf+xdVd9KE)!ugV%Vg5av!e%@E!)YJ2@wMnKz59YbWz~3tp5PG64!2B4 zGmnRCZ~I5q`|oV#M?A$_;r$XO{Md=XnN~RAGUL7*5i&Vd&WVJQA^xHvKHsC<=tP1VK`?C z+xi?fEpQ;g>&Fx0(64NNcRhqAT_H02UXV|IpZQD9+`xX%PdM585j@R$1-~}v;n622 z$o|TSjKK9W^n``usLX%lNQNUBA$ZC>ZKoNJG*7(zVi=q?4@A}IS;UB!M1BlAO{S#O zVQ_OY?)%INoH)!c1j>;{u&*SCT-8yDm+cDkOF7)4Y@$%D3 z;vOdt@vfm8#VZ2M#j$JS#Koln;`;BA;=mYHyECht#Ogh?c&ExdJKYtNYA;;5FA6?n zD>fgJD8B5uTYSsU%& zr;l1C9+B!J_NIcx?&YE49c6ane61Y2ZtIbD_eKcB=ZZtbdXEC^j+bn)tvan_r#&fI zG(T~z`0LWcHEWKxRA-x8*%jDX*z>m?5Z{^UCeF$573;037ERo8-geW<65Efzyv4TN z@uD#oR*1L9W!T-YF|=3p&a=HU9>iI*V{fw_DFF4CyvA{|E_!*PQ+Sbo56 znMR;^#g`!Qj87L6|GoZxx?SY^zlwjm|2+O>dAg)kM#1sVQd?4FUj-U*#~oxN>&RCA9@gk# z0>mZ+tD`}(01Kn63h93Z#;GYo>tCxTq1MFp_KQ-q0xUVS-eCH@eh!Q zZr3~9JboHe=g2u8^^S+tSN>t$1X)Z-xZ)r`V?628=zv34e{;SElgU?~QAGBRC3|Fl znS;P>191@?a*#XY#r3_%IOZgtc8GX$#X+#Y3!lJ3NAClmP z-JwL+-tqBSzGH1I&+*XF28Vg?_rTY=;Y3N8g#q+w2Sbf|2cvWu!ZX)lKXfQL9`IAQ zoj^4!_=Cci7eb%fVq)se^Pd$3d|2GI?=z0r>~t9kzM5IpjLLacJrr z;;495ilaUp6*!+i<>YTz>y+SAA>O@szM#*0mf+MdrMjsQBKWWQ3iz`92gRjJ|8@P} z@+Iy6IabQuRsDYq*1i28#EDKD;r~`M<^* z4o)Wj@A=n|8U8=!pWCW6{>StOcphvN@N1GhO+PChs@Y1ntY0*m^ z32*Lt0Z(bIF#kb_Aktncx#4m_kUvK##3mb|kw0H(Fmsgf$A|qw>*2oA$9{_?X(Ri@ zm$SwR+jzSr2S#od$kSPZ&abAz=y5%gfRlMnn_ESa54Jp~u?O4{hXXM?sSLb{)hF#d7kCcB$s{C;M4v>L;F_(@wRnB zxBFRA>y1`|*=79#>4CojlXapp-ccw_Xs@Dn=_3zaw z*!M`>E>{ZP_vQ<38kag8yBaMpGJYx$>vq;Pl+wboVj}$~Qz)Ih__D-k{xoUTEk$X| z&cBY@SG5Ffo|=NPQOCuvFiN=o$1TZehwoz7o-9G%R4)Nvjwh_BE|w^NTQ3f1+bq%C znjzq{v4xiX8zlYK4HALYVM)-2XrWwxl5l1vBiwVhNwDPWbwTyqT7grtg|KU>nRxEh zanjR+Zv;i_%mquA*$LMcju$q|7E4CWnJb*@6(_Y>sU|&f`h1=4b5`gVFiA3ol@TsZ zT_DZVC=#k&pDyvWkcfk9W(hr23MDb&?!w{WH^fWEDoRTk5RX&05a^KCPV@fg3tk+& zE7^W>ytoUl2<`<2N}d8G9%EE4Xm@OKI=Fw5(D7TY;84<8NpG20O4?sL-TC`la@FyT z98vTL3E(IAmzKVSZVwyY1r&S zNoGr?B-Pbhpa;!@jpbXVvcsb#F5jmM7M>6}rA1c=qBg}yj*UMrY~Q?JdTr_&;r)vj z#e<*b3V&Wt5}2Hlkv8QO3snn~#I|Ps!nsFegxc>{3d!1Sl8P-gP9p^CrB^x&g>I=+ zguZf4Qp+a}l8(();x~0EP6wE10sFqyY3l7Og4MDSf{db6Nx?-f{_PZ`PvbMidoEQA zmdh&$$8=w>os4>d3uzODV}4T7xyEslNpFvfWA{%G_Ds1hjJ-5k5bISWDR%Lcu8&?Q zY(Hl%`9xh8Y}(x_$V=7}I*p8zveg5U&x@u@dl%_R#~&#aoJ?Hp^kj*WR8q4|==?rk z(!j2i;DhIqmLK^}j?-hL@9af_h`W~rj=}X#qm<=@p%3=gy>8tn4LAMcWcpf3x~wHb z+Sr4VTPGSNt4Avc!vk8RS2phvezMN4JCU?kpt3SS`Z*?1&~##pq|KNwPWuxoY@B8& zwLWo566NSBs2`(btLg0^)OOL5y4?LMc1sI$YCX~|$Mi zD^oRvPMUWFdn5e>jcsEEzy3ec-u#=&Kl=X;nUbhb$Pl6l&4Y98jY{*J6s3WR1{y`P zc^)!ks1!-545?7gwRfdKr8!Mf-Xw*jNz&wdKEHmx>t6S|*Zsr!1I~55*6Z5)`F!l> zK6{>;n}<`zo&tJ){S??VSm97x3v6hJf@l5;oE2k<(v(aXJl>i+AEe;7)n#bYYXE*2 z)St%QazNGIzu@?b1=#=lH*uBlh(b2D!k7{z9;=s&p_`X*-*J=i-@>u5`TjkT-2A2U z?loTglKFssE=r{XX|u(cVb{p-#5pJq&l20L`_hofJ#fRIjpBfq0dz6^3q+Rn;Xf9M zq@FvO-$ooI*gOrwX1Zd!xhbyEb^wncQ~G5(9#17i@%9BGcu;R~UC|Fw<7p5&zBx>H z@^+$wf+4GBy@W?2U3r(SJJiIkfd%=>La@P0YHZQL&|Ar1uu8%qnh0HL^2yf97^Xd1 zLV4u|7;`(7f4{jaI)>#?EpEkY@n!T#w>J*!Q9|FwYH|IK6YTSSGwZ(mB+i^Mkc+f_ zLh7on5P#th;K%2*z`Q#@FPwm8&V#t0sV2Vsa!xdSn+KNy9#c|n8@-#CL^^Hrc%3AP zul7*F64NJA)9O29*-=48YCck(4F|#NxdNOp^I*A>R;k*Uf27bkj6F|nfUW%x!Pi4i zur_QLS%;kxN2I44fd%kp91&{hY zrLrR$P~JZaBf_qe<`q{+xo3^H7py=Vg)VS!Vjs3P3>M6{y%lV1jiBouUt!A5C9pE3 z52`qvqs3qE!X7I(&gpU(wtLT{fhk=vcS2vm+A{%9Zy11^wueJya3nUhIj}3KW7C7< z?05ALZQ4*mx2#|B`KOCu**Hz{Npu$Z=PTj)#!?!v^Duo4FBkKRhKfVx3H0lbGoAWS zE;J-)- zd?pJ$)P}+e_h#WgOT^=YOnH0PKQJt76j$HV<;Rmt>BLnvJm&Qi>Q}i@XR(r4A^T6= zKlGu^KM!!Ir86aumWlH3NAr?fZft>Vg5@tI-Ztb0W^0we-JCE|`p^$$6Vqbpwo7F0 z-48lP4a1fUF9cEA*N#l74&pN$F=%&P{R;u$uPlMe?Pn)WXP6%k_7ihf2eME z1jKEMqnl6SU{>iGakR!=Nk?`d9<)-oJ$!K&kJ!8&4_%*zZcj(j-*pu{Qci)(XQ*=N zbq9JhI-GKz{-BPj6GUUZ7Ff~bEI74fiC@q7u!@-#@AB+LF9wEVVaPdfE>;n())U-0 zFh+QvzE_yh_KK`7b*EEWm&Eybwe+h~k>UcgP-oaEUTI)~IwPt${pe|FWuF*Y1qozZ zAje^&QfY%?pr{lY$p_w-!MjQWvUpzzZJSqf$I@sTJ++50Jj)GrVv^uOO}jA7GkpB? zfdP=;R3yzWn~Z82h15lU3cl8I#AXPlOBVtK(_!l|_of}K=@}{1{VjnJ*Gftk?C!=v z8i7z|tpV3Ijpe90a&UPqYS=eq=tU^_&Fn z&ld@%f*E?Kyn%1Nv1qYyEPk{1MWvKr9%1oZY}M|?4|gAc9~%BRx%YY0@ykW~_@SI* zjA%T<1x&M-N^F5z}sb2(C5AFh+?JLO3NR58q zwnVLREu0v=iL|dYQ_Pk=MLqaa!wSjypx>m@JP+>+ z?c%b72~eHi+h+ZRiFm8^g>*Z25&eh0qrbhUVm1GR{!Qi7qV<$&-k+x7-fFz{L_5^v zU8TxkQT(>_0;CPfqP99^9Dd*c==V#7L;B^y?S;#vLsr(4ze=W1{ml~MlE&f3ws7{2 z&xCvTdeYe1p}2a97AcRp1TqDHBW6wl`#C#Mv-d;{9pnxtdo|M*-6XE>e}?|lyn*B@ zRbeIXq>`d8XtHVy534QUbc1i=x9^`|smf{)kM2SJvnjMRb0U2Vz6N`KCDO@-PB>+) zf*7G>f!oR_^49a39Jb${X5QP)jgbNL{`e`edlyCO`gk1HWX%>fmyW?dU6Ogc*Ii*` z+>#x5182Rq#sD9RF+@&XY# zhpVmv2Mk@nW@i;}r?Q=>aAGd6-jqa-Zuha-Ili~xzFrf&0(x_13&E?(qA zT-X`7lh92VsGG}~OD!;L(LCX@@S6roT|_^N50rJQ9Npw%al(x_F4;8;d_IoigvSx0 z+jte!AD+*1lFLQa?N&Jc?NJZ9P zxF#K=75${}s_Gh)I8@O3Zj(sk)p(8_^AE-(=!5<{TQt{6mWI1rg09ajIb)4FgqBna z8flK0{&h0yym4T&cgi?mjxF^${7{JAbeA6NwWne?I~3;W@#;I3w8(xqYq!6JKI5K3 zuSW_TaCHT^-b>>b<8ok5t~Iu_m(zTQzC2aF8&-c*z<0~f!y>znLe~67e)8f7=~~>N z-XkZGcb_`Z?{$%M%K(8>4fJukWvxVe_FiyND4~4X3lpyt0;*`?kTc!!T%IU+?~uoH zsmi>}yAu?a-AAXm{TLx}X8AC{G@m7CyuSnT-21VZIf^7FUPFXr3iOj3%VU$$g<0|O zl(@_vGx|KI+vh4t-ntatJoLiT57W_pP#SHz)m`wE4~5N1=P>O?Kdc*KL>p7DNNbz} zh3D6fgYh#nb{gWre-4&#My&>JdD$d%%iDy1g>0c#wwSz1XA(r8vqGcmMliN@G1>~7 z@%GVZD4+ZU#%L};fBh&i+qXe9usT7)#dNwc$^^%1UzL0d)5U1NiDqe?Gcq9#6nh6Wnk3gNp4mi^iaV?^tZoI} zj}JoKpkO)^X++<<7DJjOo*XBRp`482a4y;qysKL&R+1`YtuuonZ*^|jJ0H9!ttdTz z(TJa|F{i_uoy7$;D!kF&n6qOe=~b*FC|8HT_?@M6_pcs9VLq;!ql;emO6kuUfjqYz zW?_ZD;BKG8&(2$NpvwVBEC~_TZ|%)O&JpU~76nJk@@VpmyD&v-5T15gjOQlk;2O*2 z{3t()JYzfQ;==w=Xxtrkk6!`%j?LxZqze?i*pA*uw~)`&-FViy8-$@Kd4` zK0jhsUEfJ@jRWvYx(*bd$fH+|x_H#~Dcn4GM>O`&5jr&k@l9?J8M`Y=!={#%zF#X3 zPwWif>xFW0a?l%SfHGQrSe2qpw_Dxd)*1-H_ zPrbnRS7PTv8{Yb`njFk>u5)@a3anaEuWZknrKhNJGJow{EMK$9|UAjs^y%dPG3I{|4AnDtGWmtkd}*{ef81s)_0*u*7Nt> z6(YQNa|WN)D6w3&9asN+L`wUTagoxOOG#gU!^G%wqREvVoV;NRD(*Zi)g6DFGW*%F z>BQUQzswK(wjYE)>$>n8gK%l*mT)rLYmLjCzQKyKx*YcXy0|l~f+oiJ(YNuBVd&Mr zf`jjPTIiYxb`DV#eL@ADM;wHZv+zpBFFKiL3 z*1d%}wX%Nf*DUVQTLS-`vZoQrMKFBtSDIyU;!=#|O`$2~3GH5#0M}bP;H&KWdOrR! zO@C@e=12Ckk;7w&lGOp)y-^YG7gBFjUY@E~!-*u^n z{QshaDVkUDokA|PozN7+9wy_-p2>V?e-`$ep^l$MoDwqD`3n;V+@#+RytpCg2RO<$ za#qjmMKdKO7;v+djDPo|i&444*e}7jfxN8U|{-(zfEqQUni71Z0Z zlrpX>b1&fwwH3{TRo9|LpEnb*bGQbdGhW7BE0ow{WEvFB9Zn~kXA2eeo7p|i05_EM zMl&rp3hrtGPeN;j68W*%5GIaqxLC=6 z9Tv=m)@M2}F=Z&G8sXIiwjvlP@NfG0wX0yw)AdDZi3xl^x&~WH^x_ib3hnfQ$ zT@B{tzvi&|%Rt`o^av>}ehsgasz@=_{_HUvl72)oZ;J(b*tXJt zUlK_-NuCEQA0->tuj2fp>KIY=n#$C!!KH>BqWBgQBa$1Ecl`GIbw#^ zJN8H&*XT*ZER4{8l|LKXJL68RiEMJ;mqI?rV)i+Ljf#gQ=^gTTCSe8_y;Z^oclu$) z&+WqfSx;g984{H)7>W;qd(hz{k(98r2C8OvK({hY9(3z5UHLkO-+mg&y9}H--+vRz zM!8U?8j4F2PhrOq zW726k1wwPHU^Z?i8m5hArB@H(>ijr~m~(+*lY8+wjU5!|^9_dO1XII)SD5#qD+eyJ zL_@_)7&tH=HFqnsd5|GK3_CzquN#P&JJdL!GM#i2)H!}uFz%UBEY{1}V3atWM=sT2 zXAOa-v}&MY(j?wc_lfQd3#HvBi%AwzC@jf!rLQ_o^nT=An*HB8wpsp??9P_U&f5rV z8T_95%eBCopUc_40QpndSK;VwC02Qv1222%@&#G_zur5P1LG9giESw?7l{APwTSF-INGlwkxdLm}t>p>J1YEk) zjgKu>Ax9-uHW;;$&#t=(l4eiAZtD|q$tnv-4tfo?BjhRlfC8(^bo7#YXT{fDSK^b# zVvc{<2&PFT!YiL0;+ee*`P95-8vOSqv&7TGmsh|ZK0O= zmSFa2F@2e1z!{rU#KyZL`29*NTo}_KetEJ6A9PEiACqz~9*h`^n@`^pM<*oW-8m8P zH)t@b7;fU{-W$N&#gxsruOpS+EAaZ^-@fopNcc$#=C2=%`KR`o@k-J z#$5obpU`dga6UU}5f^(OhP$6yU&87oi=b-6= zTd*=`9S2(_-d2EF$PAYvgj-I@cjXGKTm;O{v)`YItsI9h4FwgXY?68h@nCm-|e3Yjluq~ zV4yXv@>j#d({kzV{Zv{!x)}V!a_Pp{e26znCQTPDGQYPJ3k@_dC*T;g1a{J(tT?)Q zMunRuMBwV1DRk7}2Bpq)62cqZQA7PQ*yMT=hs?!|@;^bxx(nfzZ20)zo0WeA6Z8v* z|Dt>1p&iv?=Hau1mA)7Co+NDUyUrqNNXZodNCr&h*XR7;Dd|^6d;WG+UyL zQzq(t=7ugJtW9^{>&|>_4#crY39^65!iB zIi9~y8@u{_Bz@EWAht~jn=1SBUvUBc(R<8xDsgmiQYaTEXXDSRYPwhC%yJVif|%Hy z^XBT|*{xcv-(pYw-^PN?wMB4uZ#rL?c$2;>rqIgPtEJD3HPC;>edu_#f_ApcbFh08 zIar+*#;ES+8}%db;?5VM{K){;F5D=tdNUrI4;GILKOfBH(M{wnX`x;H?XbA+2={+C z2z~2^3;$-gJoalR$QSfrtN+w(XLjBdjI8FOU6+M4 z?5-Yt=^e!}Vhb5=yH5khb%=j*n<&mUkNPEy#I~0eH1BsBojun^5t)YgVtxQv*=*uP z)k~=6_7S>u&q~_mzaP@busX_dItO`Ays=l5tamoqhyCyk4B%MM4?e?vhonp0j^2mx z>g5<_9Ysq&uL3IZVA)0~aQkprOfb{H+;xfcB2N$>EQy4kuS1w(tudp^Nlsb13HLT= z^XBXV)`$(mK34gBYNQd}E+4=%7w!lDDZTN-ZqPkcRe9az3n zgJ-gu?fj@N^f_k&bKpSgSoKJ7oQz_}LQ@1!8=QYIN_^gU8J_HFAxSYWNsOTH6`>(#iZ;e+^2OO5|_ zmB*v`di>4zA}DV^h9C1UL3>#lyr0;G$NJ{c4VOEh6|BhSMN+ZxVY#^Wzd*r3eGuM9 zGfr*l$*RjjQRoa6Z~vN!OBY?1PW$pw+*G!JeYC%doHzr;JC>+k@fen0lLK?(0$O!4 zhNhk0M{1QGvQ*8Nlrp|QYZW((xzh2H@z;Bk&c0;P<3kI4{~m$sV$4w~tOuU&7>9~} z2K-okEnW+LE38rZL#z9Lp@7CI;^u053=UFZljJ;V4k@R^N)wzV>__v)N>Ghg$Jg%R zo$;w~n$jCB@E15kzyt-{V&n`9)ZdbFMlkpFoP!6u z*zk|~Fg`cSR+v3bcK>C*rLHf>lXj6kF7Gy9&@#LMM`V3{{;3?vw39bQ#jVynd0hlA z)p&!`8qPwYoE{c>`|^K%Em2Y|^H*2Tfa%KTg*|_C*=tM&9J6>2r@og+rX4;;C7Fpx zr-P|$MWT58u7i-XZ5Jo+s1!6Ey|`nNfd7Ul;MKA|xc^yV>4O2KWSW*MJlH=SF4xZG zkSTBJ!sbFq`4J=alfBP}M^BT>0u3Bf6T;2?jIgi$5eP3e#u1hVbbgaFtRH=m7T+rs zlxB9)o8O`2^+g_c4ojibM@E?YCzYBy7<2|(!t`oWZrpCoD#t51ELj!zt|WMPPaAW- zy@l;(Hp832aquE%wj^*K(YC=}^yB++?3n2Rs)=U8lwZfCrQw~z-ZA~KwP-M!-0X!{ z?}WkH;|;KVa}>|^dn7rzX$;lee-3x={k8G%9t?(k&xtDOha^Ladh(HfvCt9Z48yms z;z-k0y#4MQtski<9qF&nH4oyT{!K1TTi*m?d84RQVGkb`T?V_zixlA46}9CSfy&>{ z^zuz0DbXdtYWoOUmK+02ns8imw^MZ4Xo%C~)I-OnkM=X5S2ir26 zpfSN#47fEPyZK!q=hLdVuJ$bTaht~z-erOL)T3;7bv6$9i?puaFu|*6xUeg!R`mZ9 zPoq5I+2^bV9&DNfxqnsBAn^rU?AHP}{yij*y+dGakO!C4&f)b2+Pw9q2Xq>mK+()1 zQ3wvAonE~-BqtW$pRGiL)7JP@-Hvr`e1@ef47jg>B7T-JC&hE4P}4tw`aUxj*L`e( zgBq$r`LC6zQguRfz4Ki%WaC1X&57{mKSw~f?-VL}uT1w|$T2JQg3W)8;Gvlv-+DX@ zA1rtU+l()R(aCsp8|=sWvV~r6ii-Jc^J1zmKPmh;u8MN@RpRY6>9T~=(oZV| zqdq#4%6calpee$2{ROaGVLgcIR|P?Dny7Z-fwX#yE-qT&P9fcYi;u-Pi1F~Eeaa!i zHzAX{{p%sDYhH$>O-!AiedxynK1BO6g*w*OU5HcL-=Y(dh~fXO4odcbS+D0 z7}cL&t9xL*I}5FQZb-}%A{LC#5p(P3(R8bgpr#VcON>%5aCJGptyn0o z&4{O;<@FS!TmWYa3t21fFnqEOfRf66^r1rzm;Q6Z>e)MK=k_V6;dT<|E@=@1Lw2E* z*79P-Ww1T)3-$QW4RhZvAW7s^;n1}M!hz4;FvVXUYcqRt<+Z~yUuFo--V=_3j6JBe z4TIK*LUD7yWAtw9cr;lp$E#A1rf!jE1C!Ha8=@^HC7uJ*k9N|#3%awF`6_YC>E&Yh zlc%uc+*hf_j#zlN+Yztjy`XysRWZyt8Z$m=!uU^{aAM~z==OIa_ckzK6>AIHVkqVD zHa<8cYcBkHVZ}Sril7yL3EfnSY03sCJm$Nc6dpW+OFB)0PUix|onNUjSys~z2A=!& z1>`s>U`YH5p|PkCPRcZe&hNch^Nb?Sc@-_RC|#hH52m80wi;`Hx`au7dP0H5X&7@$ z0z0�B5`7p&9S!)lysjr=-iRQ+4soeqwaZg3ROvxcFcJblo}zu6#KUed|={g;$HL zU+Tb*L$<&rLl2r|nI~f_I)u)iefWoV8QuuiC&#NYR>(?Axc;UZCJyMsLm#+t{tZp> z!J+Qx(3Hs2-!G9dV~wJPPby};C;&W}PaB#e>7~^HNP5{u6Wz?%Wm36hq1p+_H_sVD zb;}je%QFux?ZVKw=pyC1XA5upU8LXn(e$+BBKY(ljC%Vr#p&}@_^kO_@pr%)+WUA0 zymI+PVZkjhxK$1lvg=^;*ezJ_vL3Q8-hsjL#$XwA6Mj~o5rjdO3`YjQ`VT4eSfYoo zj%i_4H*M^@2%w;BFX{NUOKN-$h*}1&d}rb+Y}R+g3y(h1UzvCQ{>nO#JtnrWxhh0_ zOsD+O3iQcbru#ol6)V&33&$F6(y8wQao`GV=$JMFk7y1S8qIf-YyJwsTz?RL%KJ`p z{uQ9^&a14|7A!6qeUMMyi3P`3(QxWmE*%;Q;4l;T)vmvS-IBZ9G-DU7$=1Sg9v8%t zg>iIvgdbU@&4N*0hEx$fmCwEQhfmvwjZZD|VViY5q#mh*IM>?%u3gi{=|%%NMsv1w z+RY?rc59<(x48hv+eJm80IF^-;i2zG0BLu_?K9(1K59A?_P1oc!g-iK`Ya{Q*w67A z5|;Ds1M9XW@&2K57};FRuiZ_N>Rd&5Zy{zq8-RVc4xxP2Bv7mCD!98u!_Sano8jwk zP?rWLY&O)xJCz@WqI8hFTxUqd?@qwa>?Mr56wzPCcNza=ENx%OpB!Hc6my>n^P6e^ ze@&FAc7(f^Ym%ZuZwxJ#F*nD~LbyhRxcBW;KDD|x{`J2|?oy_ewchkfC_1LAaBT8?^L7S33G$#+DUz?|bjh7nwOx(eHKdPg0 z;WG{#uooNLi-i6EHVQvJ9O3w#L_ixaj1xB}_JV-e z6Kwi(7?{b5@TYlQ#8E@Naq6dslxCKJ`^~DTGJh+_Z1Tg0THT=2d<u}XabKb|vK>|v6}eI2s!qxvp!WYke1Bi;k+w2XMLRwNuMJ0j+1 zYV)K^j(FW94jgU-NLR|O2gkba^mnHj)wMhnLYLp7|4xiy$)p?-?scQ2$X^$a=bwh_ zVe7E*g+2PH&c#Q~JNUlKOG=+p4Eub$@ct2zq|ki>rbS&OD~o0_?`4Ql2j}w700EcF z{Ew6^xitFN4m6CK2?Hi-WBr70rFPLTDN{Q@rr$oI7^j)Iz9bYv(`&`W-cM<9dMcJK zoq+x_-d5pJU+!(cn7YNA;ql(HNu^gE)J@-lvSMCP|73)IYFdaMmubLaV_tdwoVe{z zGJZSciu?Qjp^nh;7!_4OpZ_b8EvJ*!mD{ZNp6fuaoZ;zl--xO%-S&w7#vgL-PS!5Mp;)KMqCIWqw#&6!Wl5*u7Tz86cKhrz{( z68_^ngTFcNg#4E~@#8r?5@lRVy!|5Hz0C@}9}Z)s{R?pJ237HvsiBMyih}HgWn!__ zN8xZi;ssAtA$X$}M=pxMvzCuIzRy%NIj=_+p4TYyc@texDTLkqv@pKr0tYE5p@EwT zk803{Keu{d!2BTin2`##C*RVcplQNg_a0)iQagpkTJz!h%eeK!8|bUipU_#hF5v))paKwGb9u7)y2gBH>PSJvF7#ZQ>rLzd*)HLtPxo5t zYjp~AYdyeO!5tP<&F6IQ@9<>eV+r~&CX+1;{Ctk5U0IEzmdwLlsbMtl=~!C*Ngg~` z450CI%6QfnhAVTXz)c+uY9D1RL|ZF!z^$Wr#XVQn3tT0K)UjfBUuT=qS!!sW-4C_( zC-FZ$dBG^vO>(GjiS$cI4U|V7=3z(uh58(SzGWCrV|8+c*k6X27X5--*DuDa^)fEc z_$oO4$%Wh>FC@=%Gx$9DVffFufHK{ z<-H^=?JU~fs>j>ar$g8LZ{Qo~4z;f4tT*impUezH3uj%K7g{2Q)dZpE@_d`F^&z6& z_Zk|}H%@Hmu;*@O@z|s3B#IaAOXUZeNLyeN{rlnqTjI*e?bB!+sT5e6uuYq^9Iq4Y zlFb+l9S_af=VY;&6JZ#c3P%EDtD;Z#5{~zC!*?H7@?oF5@N>m{^tYJI|GX73bbky~ z-f_jM@EBF zmsoUPB*GrKll(9@1w+pp@$;ep%vrD&$KL*4T3tAYMh69P?=%fwlCDj16b5FLM-ARi z;B3DGuLM1Xd)@*!b`TV{f{90-ZDn1^# z_4hNZOPI>f1FZ0w?KP?EQcDt6rL%*<4(xT>M39Tn=hIWR3Lonq()!AH^4=E)-{y{{ zgzJ{L+~bUBdf^he+Rb8%<-n8m=hFqN1b$t4P|R&?5Qq7!#Q9rg{L_gP_M=$(n#zYJh5`;FcqIaj<=*ope2)T6=`s}|W%=_0H zUR<)_sG;FJ?$IeMs?uaHrz22kbPm=3Rq$_(aQL&(PB4;ja>eZ;-N_k_140e(@33@1 z=UErJVn{FB1oN-8eXk!4Ka@l;yI|xs7tOh5G2=H*ZK~c5kl=4tT zHXAerk1s3Z@*#(Xy1IkH+Zq2TEk0dR`8b@UFAqWCw6lV|Uoy+LwZH+eWQBkIQ0>?V z=@!&S&odJ!)+3abK72?{-wk-`zX6C>?4WLv%mdxqNP~O66Soy4(%aM&Rv9!2jbS1E zQ_|qd5x;5CpFr%;HszR`cSNTHgXw;lCJs52N*ZyqBxSY%vTxup;nsz#!sgJm@a{$y zt?#o}V$(mIn|j=)iYKS&-qtmoYNW(g1BwXO4~N|2a@?;b8%`-%lilfjLHb3;TU4w8 zmuDtCY@$6iu0Bk`eWUp0QbV?#d62I3*oHd09^)?ODE2g&jWHFA@kbANGN08(-4}Jo zf7MK$Bb&)JaVffPkL0`=Utq?bmE7Z}6OGvJh6VnWf_SYC76+$@efuPk;jTff>iozi zcPygCktNXiUnA{0y$@PK9*9?lZ^3QeHf;9FlE0LRaBdBd7Guz1 z>tKF+M8-x}AA_ek>in;I2CiFi5##YG?HsXCn&@N&omKzH#LI>cO)rF3vx5YcUIfc} zo`(hg#lqWf%2=+Ejvhk~;*O*=IyJ+Lr$+rJ{>tpnrU%FIp~**JU6BOi2d$&y&jgA% zlmV^1O!@o#b|LorEebsPf=eBhc-Wa8+;y3|u-V5E$CULJXUCNa1Jy?GJkLdFTe2Dx z-WUpX9_^6lb_|BDxhMTS^fDbi-Uln{?o#2mZj_$d3=fARI?S}iWDDT$xv|nmnetNA zb!|fK&T;r;$Q@cSFJIg-V>RenG=NX(A<{YeM^xLZhdGz$lYB@TmbP}KC|P*Nq?&&8 zO?fTsdU{egwZ{g2${FBPuWoGi_a3xeHA1u6^?3Q{9MFHHfTE!qeY!Z46^%4dh;OH? z@q59^EuMe&IRNk>9J{_y;Q0^F3cn|}3KgTL@`1+zjJ=&8;y)$ay{sLAuC1cd@tM$g zc(*v>br0Dbp9UOlei)?#*87iN)W*<)j zUQ!_Ngbi;lO&Sp(e#|t$$um#T>L&>-cVQQ*XZ#U1x5=~wPZQX+wH%IgUo9DKZ-AGo z`$J+vHC>(F4NaO=;Jb?gyVU1U+@U@cv8X%O^)#m|{x-tP++3loI)@h(%dz5iWq#q; z2OB22;Fdw*{M(`#ERTNS>z8EO!;3${U!OEoS)jx_lyI7bby>)rqM20 zO}9`tMA+Ju!?bdE%4u)# ze&a7p*6_xC?Nf!$e^DTdafF$MSIO0}58Qci5w4jPbHCb!GOu8~5b$1Cu*$v*p>NDk zN7IXr?Hb4%_WlRGq-!Wn=LLV2y<@A|I1X>>iqT^{sM}8kRFC-}kyz`nd*(H9>h!HV zZgREwmhHLewh52kq)YPRIPR~tN$A)z6gwMBF70pfwnlrHRsA-`=QI zK4H%FEQ+=pj{mg+TF#cE`cEnx+^xS5^WGL+{+jTr$N4;|iwLygD4&+^iAJuT{QBTy zNG(z48PUp;zK70>I$zxQ${I~txH*(AZ#RPhiuLgGf2R9;c8BI}H>BITF2qr54wGt^ zCG_}3cOFM<1}dA+?gu01gtU2D5zxPvk8>88ecF=HXcb2;7Ero?W$pVOLQRoKxb z6}w~xP(=t3qqw&!)b6Q( z)525v(6T3F{UcF)7c_{Ed4>pD(hQmRe1IZ{C7@S<4tw@fhOLPToYM0LzyMp}n)W!v zPz}`Xbx*Ly`;gw~D4Y3NjDC^#p}TGtJ5*%j;PxXFw(&E>)>jBqQ|}6AL+?_+mJRf| zc@JL8i3Vr8D{y_y1oX&O!HBuP1gW?g+Osm8xD?QNiI7jDVPkPi8{6i1z}rH>UeaYD*C;h5b+7&{`ObhmCgHz``6 zz1MTn%XP;3DdTzB0*0-BiKrZ%5z!iBFPJda`^^i?9L7jNdg z#wx;B?KC+)8IsbQAf&z=VqZm*dV`9XblHesU(w^th)le9z!euw^#h0RzBE32KkYD= zc}-_4*jL5`wx4M&y`i^GTwhrzj*k_ z#*DR^is5ltf%3!~bi8LU{Ijc}@7Hy}=u0!GU0#pfWHmtlE&JeeViWAi`wkkd2c$!{#nI1> z9+JOfUD4g;B7_Vnq>A5daJI;hor;Tj&+P#Ive#SOBCUcB#bdJB{7?*!izYLJNw~=6 z9OkM{rqxUDkay@kh^-h1Yd`c6JWt%DwQa!H%x%Q*ZzjAtp-A%anGrqDo{rr{i=;Ph z4th);4wt4m;qAjQ)Ee|p2pJMdMvB!iV8})i777@?uLg$ZgyJmE0NQn96CYgvo4P2y z1dV-l;Jhf8*828>4*xQAI-Q4&zo+q__mikfNr9{0O~xHvztAT?V>l}RPUv@0U${Kq zmi=AQ0g--yxtslEvS{WhTVYMlt@tJFrsU4t@`2!p!T5 zptqq)X#6rk_$n7n%D1|Mb>$?8Rj3md_{#HEov-4{873_6)&@Z)XW*Z|vN&BQ2@k2b z>KpgOguPzeT>b-;js&n$h6--K7t1~w+xSxd7;^Sbq#haO z=sV0G{`8yx*XKE6qECi6IQkRx9%w@HJPJbwl<@R5$@FvE9Gw2#9ydMig$j#Octgbq zjFgSDhOL-G_G(+$t*;R#jQ4_$-BDyVvq})M3P7u>A8_XmRB-6UJ}R30Q#K#4JasV@ zr6l0cZ&RtWpgR?x>A{!QsDQ!7HFS7j41YVX$GX`=;LY7nwBq+HstJ!5^^UD#`O`yT zX!=?D2)oTzc`K9uT!=d=gXaGyo3~AI-dt}E*=rB7g)&yhXo~f`qj^|F#)V?3_hETW*W?gIA$XRF$xo5};yZ9y*^} zPoMoS!?#V{U|~%^N%GK8zB5-t(D*(_JeJoc<0aP7|Ky1Tv>BLmnIsEyk^TOk^ISB# zO#EMYBC_};+y9*>^8Ymq^3AXDcHY!4C_j2S3i zsW!$3?!$!LHHYw<{Crq(f4t~9-&I_%^As98^I+lSr||0jUSV!s9Q=6s9rQ0rVWjmT zeCgwa?LYNl#?nJF{dGUub?b>o-#XyRi+j=6^axbW9WHo#1Y>qyE!b&fm`JP+d6ycMbQ!CE`?yxph-4iHOB9 z#+M{ZmIYl>QPq}~SA@alLRZ{w;U}y*D<@-qD)7f97kq!Q4{g*9md(TL$E0h!z;^Fe zJRxIu9~mBiZ86pGxM(3543uD>-BI|(#B5wMtRF3Yg*Y^~N+^zK6UBxYw7c*|^vNBJ-@^t{=ua2Oiw%Gi zyMpl5{y_LOI371{bHp|N`A}3)4@<=aNOGKwvtKU6gYv^5duAN|T(t$W&R)QYC+4Ad zcnLgmor|j;2BS{$M!ej-1xuE>=5)XBJx2ScI#Nuc=DQC=FOvqDt*ro^+X zlf?f+(Rn{o_5X3)2t_F)MIsWiSBZOGFHMR{X(&oYLrRKhXM`jxWu)xTL@063>s^Ty z+B>BweJY_XmGAlf1Ae&fJ?H&?j>og_yFL1@5ps`a<6)S0Gd`VH2umWDGr!3`6xq=W zdmF|u)v7d#%D13^zEP|&bTa6Vt>E>=m-$VFZPY3~j*q(*z((a}vE40KpkwI}mh7>Z z8!ywwuRq`q-0~3i%BTmrhqsY+-C_P>q|ghSHy=hvZDMtK@5JW=1^@MyWbLfl@4SlE zUH;?uku+U<6|G1@_OQQ_u<^Pa-%Pw+t5VwIwRn4m543w(V(jmC8EX4jo7>q zf~S-*nteD`&!uh~4hN4JbA8LzQL(ie{QIo9>1fT47ry3dzFdXxYwX#Mi4wTSQVNq| zj)K>dJ1~A_3|t7+5&ZjgSU9Vf(q^PXFE~M)HL$3PPTpr|C}%d<01ECUfpXthST{=q zVY1OQqxZ0m#HJ zM~B@75a95aZ@W1eM@Pqqs@{Hu;hCzW^zjI0*Q|srCjzO(37o5^1m8Va8W-N#h#fl` zaaQtF^!j22viiT^>FUR@MD80TkQd+AJ)HgU3d76}B^)8-MrWOrMY9L5Ddb5XACof- zdxy0^Vg4rc4Do`D+uJ$2xw?>}sD;C)j)jE!AKXlnZ(M?@Jo;U-!0_us@P0r6UfMK* z_xU>?+X})lqGK3d44#QT&phDan{|BntrBbiNj#mm2_puzL-eh!Q0cbHULOSM z3TyFtVj(`eoCnd>MYtsW84OYjLeX+l+`M}hx2W!%NNb!21ycp@pG_ofsm=wDIsv+p zSzz8H&t^0Yp(_7+h;LYery7Q{Lv|zJvST%D>HEuhy>nvU#wn9bN3?Kvi@?3V_Ol4O z14Ee~UtqU|-}y=n+GWOr@$wV&qTv;^RD00+$H;eh|Da9If2grD1+=e4fZ42muJ7L( zTpo23GzR66-I4EPy+f1jbh%A_6AzK+m^~u5Wm|yVIb_={!x9*1}q4H<;BWXeA};q?$eihi2-rKbD`lBHcoI z_M{zN+S{@K@jn>(P!*h)3wM}}3c~Xxn-X+2*kI2Bj0+8b_=*y?Qe`x--R-2^R!-Yw z`bbhuV1hvtpYc|UHQi66uXE(tW33!0c{CM@T9c^Pyo`^CFNNb$<0y50B}gwYCnevb zaQ00Wg)6G8 z1KD%UDE_u_1P$J=fIbnu)F|@~(sds20kvQ44F!jFNQ8+>B!`S=ma0rhc!|TMF)AFaUsjt8g7cF+-iqkitl*B#U*)N&K(Og=|Sv8|5ZhK}V_q8R<9nx?2rH9cAk_G zEiL&ECeCTKfBLzNQ>#y9>JL0X(@!4D_np*wH^>39Sq~b?n6`C3xcmdDLG#5=q)u)_*=bsQ?-Xt555rlTiqN2<1Q-6& zhSj7xa-RD-p#cYt&BL&cZCJ<|qsQ)ff@j{sg$-x{ zzsd+maj}GfMUs?!=88yqNg=q0rh|FEIXgEe3ZGp3%$e-saDe*+*sYYwZ91WXqp$42 z|8~UF^J*!!rm+%A%2K!!BQ^0>+d_0K$mYFaFDUmr;PsvjWN<}=ZSLGEnl^0&f9>Qn zbf1-o5?L*eUILqC7!yqYF4%Om*LCo}Z_#-fZuh74Ni`sf1 z=i3L!KbJ<41rAVXI1jS!`r+cVJe)N@7KgRlqW-=d`fi{BTa{0sRbVpKZES^T|3zqi z)DS=AKZEg8>gjaM1n~Q_5SHt<^Hg4j61^ir%HK zVO2*do|W4Sb+S`&>+UHSxi%Dx@E>>Y>u<=l=z@K1lkxuWhkR3@7S79&V6JOE!7a^X ze)}~q(U`T-WNbfM;A}MTawoS!ti@N}=++cSPMw4`Axh}AMGl{8#FA&X;Ngt<1j9cm zz?7STJpZzmdo)m!IornZVeI2b^b>NChzE`lk#d$}(L3-P~q1$ZXlHr);| z0(tQ>uqamK4GUxGY=jaY{oo=69NCIptr@soIQOrgUc>Ldu$_M}*@4aa;tp!}teLZg z74z5$Y;a!}ya}`6T^{OS+~WiMk6(c#+2aANjpNy+vyr%2+7)D)2au~pKTSK90=Y}) zf~C|VG%b~4FRtF>W_7D$!NJK0FDAl}qcJ$oTaU$*9EDEVle{=14`%vbptUn4vBUlY ze>zm2)yz$Ucd4gHIcP8oIOM{DKKilvKo@xEmBtV6cqj5}4gkIE<$SHtBM5!H7`9oT z6f$AfZ0oH(g4S@3v}ONt_hlAS=|44gE`17ZGK zju%UW>_7|+d+3R7rCMywQVCjr`XsBm^^FL~TAft3Gu zagL0{-GAD^_D2}=aL}S_#>uRydOu8531=4t{?+x&%cOB&1RHkx6KA$ik$%HzUMfqC zZT&bC+t%09y5-~9gg#jo+4_!`Fx!P(WjY1T{lp)QiNsnTd9;$9PZx_v+WlRmD`*_) zu>Wu+Tc@>;dDd)UvTqhs;%zrJLeRCkR8`pDp6BFx*_A%~EoD1rNsvj|DE4%GIxq2W zHGiUO8_A9N%KcN~Y3rXNNPqsDS}wGM!bnBZU2n+txxSpHyPW7T3U`b{9*rxCbU7 z`SjT;ie7b&#>Rvp1xiL-_JX-rBiP(*Zw2ouyr>m;Da92PS;?4ddoq)+6A?<&%nu>^0=yO2rqw5 zlPn7lQIo+xunYRezaBpn^Lx%fSxy9r2aJOF_o|}bS0Z7wiU&+9-42semb2_*+u+*e zqnxCpC97K^k7MU(3p`_M~AM2 z{pPa$wAs`|b@oZBmK0iZ+2EID^uDhctR3{(i~|Aed|(^(EuG8ujXy?hKd;-{#0ohA zft_ZYZ2@NUZP>Wjscc$l1-a`zhmH~EkZLl7T^X~Db+%+tL9d+H|4Ryi;TWz^E}mZ6 z$-@42H)dvH$Y ze@blKGe=foTg%rsHgGEsT%jWu2Q%$2&e;Ez;O+7{Om%iaP5vj!kCO~@BGP^!r%s(pQw>_qAC&C~;52pWL5LO*Egw_?9Y$ZfRRpqI-8 zJXuTd{p%=neKCid+a1r(ELe(rpBzA=d|mXdG{rj2;bhY~AJ_N&;?7!D!s%=uEHY8W z%Rf)SLl0?;j>*FpRvj>9mKRLyxy!|Kz=HZyaQihiHfS1$Yw}-kgH(6IkQF~+O5p&Q zA!u@j$GV`x>^9VUO~Uo5jiRy>_24$}EwJOdc;j~tci!U_j5+w7nw=ZLJo&l|C+S9l$@4S_*4u}Tr5qL< zHNkt!OsM_$Rk$|fDHJ?eOM|u+Q42Ew!&$~COa)@ZnFw6vy^ej?`a*gqL-5jt z2Nr4oJo|YVY>N(nRCzG6rU1U$`CF~>Fl}tTvKzb>e6m$aK9*V$p-?xyXV~T}8ZJA?W15C)T<$V`P3OTD|pf~$7h8(kDTlfe} z44aNmtFGex4YQ%YJQsGgtimV1ZgXIh zHk#p!EnwLC4yvh#KipT&A2=}#KeTVaZ{{{wG~;Ccg%n@Jedl8!IKGj3hE!7GOcz|!I2^uRDS_k3itLX5b?9CGAE$WU1okB?fMFjF zqE&x9%x&%N_a>3sQE-4$lV`ZHS%yaESMmc5Oxe{hip)9s5t!>aev_%Kih zojmLXHcSoeTBpGjKV0Ni>B)deT`MOO_e`X(rHu+}b=WPR2Qc)mG}GHluw(dFSbFpV zzVbOjvrZ|{l8q-(hm#|}%OjZY@D$u*ZGt`R%^1Gzp?#RnQL?I-&zsAgq2eEFam{o? zkWF00g6lV-&4M5}Jd&e+>8)7%Q~@8F-h(K?iMcWq@NC{&Zq=e5SW@*4l*9Hgm$zjg zPD%r{mV>;gO9Q9qM_|x31uSaK0Zac|FzD%BNc7Rh(&iVGn{f<+mG?qLZzcp9k3eR6 zmQ(#Z7hhT0;`2oxU~+Cfm##kw8+Y2H)tklGwKWyny_TVQ;8Iq8c@5qcE`6Di>qus2 z8R`cFK*H4$;Q=rS0;D}5NbMuoh6_AYb9c14q=94|ALd^sdLkigTx- zQt~t|`D2NNbFCnAwgg_kun``_KZ8k5c3AuM2d$0YfTNy#<>$OFhr|da+-KYlx8BUh z%!xI4bAdHwExn3TE7fsc+)3Uf^fX1SJBLS&M`BsQBy{wzg)J2#%v~A_Yl8RjEqC;x zGf`j|{GCg0=3Ir|VlSE%6#+A@_i}w_l<>~*bSOUZn7bQufmc6R47VOWgO5JG*kB@$ zLxs=xLRlQ{tZ5RpYgBQHwKBM9S~IMxm4}9r&ZvB527bByK*;F6uTB2C&MuOm3)387*Y|LopLz>A9`u9rbXjIHNK>CXKsV+jPMH_L< z!G&1UAB}&d&%*874d83D9a@YNVb_XYe%sm4q!fM>4{GJ}spry!>_R4PS@w_gE0%Bz z-nGJ={c>#SdRv_5l?~PV-O*omG=BH@Lng|FExQHJ+rS7;cV|(tt_Q|maKdp4X4o*n z7yj&XfTUty9KYBKC8et%>qrE?+n!HOlRlxSs1%G&>?Q4tp%`nP&h;K~z}a=}WV*qT ze`zVf_KuT>>RWQ8x<$}zHt)rVo%^s(*&h_|n4|r!V|dcd7U%zGiuaFh7rskrs2h5S z8}Vm9>K>VeTp5SGQOBt|ke7N4nq*fl<=tIUMhv)xjO{|M8Aj z9dVbTB(w|txqscZaJO#=J{*<<7E-%#LPEB{*fzt!MIMCTw?S01I$rfVhMN3cxHLT; zTl)9mj-A7CYKIJNa4sN~F$%DGD`NJEC`>8Hh7VF#>0E#{{?1v03F~@jjlBZ=+1twx z5xAh4gSX(ZGBq@?EGPBAcr3LZ1ShsD(vHp;O03bxkvo&XVxA%Ht8|9nla%nq@&7=Y z525RE`{@Wj3EzLvXAg}2gBTf`+Q1Amy#4+aSOsrFZFdPaan?G>yW9_7bXVg(i&T&q zsEH9-1u#`D5qFqsk$&ndqz4=-r^(=^Vn1|Y?fj*kLMOx{4qorqr+l^J%9L7F^E0@W7iqH|6Fv|6a*T;IEZ z|5C`y#tq&?neta&-lE@Yj^hGVcibp#1>MUdvF&LjdZ>&CgR?JTSoB`3Pn2Q38_xE(fCb8fh|{EjX8Rpuxf9L9jo(sNx3}g(hWqLk4LD) zZ3*YN%nFaqD*#_}dE6uT1~W1ZxSEN-V9DO8*t>l<@N?$ivyTgKa$78JY)OKdud-*Oo>C<>#>V6dN4?T}NH_iv9)C_a3 zoF|VL3$aWjOQG+SaR3X(caGU;F~bih=#7Bw(K~SWDO(&DB7vR5?Xc9-7*9Xjg5Q>f zVMNs-T<4jHZ!$OIquMz9_os=Q`d<#{nGyEyGsL20d1yDi8GaWl)3x1?z;9v{%ItK3 z^G`}J;p|12SXuy^jCASFG81Te`5OkU7vX}jQDi%%1ct93fm3dLgs+D$qRvbO?Aa(} zB}0u-Yg!bjR0^GAsR_7j|4Obg;5>}GFb#hnO=kH&^0Bx~@Kem}2we23Ijs~=Tz-LO zyDnjkmIIn5Yk)O5(kPgUg{IY*kAv`@$q(+mC=kD&JAm)=D^P9jOgwya7nW7)veXyC zeNt%*7V8_q>d+BPtS|=u_DhS4=QZQ|x?eEiav9{h#o%j4fq9_l3i9R;Y06wNdR6Q| z&ej=2=RSs8)tgX~?qX|);P>h7L6$HVN0}eQ!2NgNMMF@H)`Vqv{dx&^J;?+=OT=Ku z;!gNl?~Yg7zVU-k`oe&p!SH_ZOz|u}6Yd@{$1_@Oq-U;xe}vrs!y;eO-c|*#9EM|} z`elrQA^2qAD>$g+kN1Yffd0A~e7|xaK9p9)hv!rZ~JlN zt6#A2lqnV;d@K5V;w7AQl7}MSVYn+k5(Cf5!$s>Eq|2G&AIC;<^TR{PJagf+WGX36 znvKWKXQ4}W3*7gshb1RnuuV&h`}3xu%&2r22amzK^%fjoUCi5f{e{WiBWdC7EELJ6 zqjC2ua{V-kxg;9m3$JdN8oUK(EF6N7$=%?bdkvx$eLy~15i8tnF)XJDzYT2z37KS! zQksg2+I`}V!%FxtN{uOGOQFNh^*A|j8gA%QgVB>h(OuyBxCgpogvoxcE%q%OdUX`f zoj2f5hP@&TJp_uUM`A=?I93T621!A0wK{bPN?qf@>yNNZym>qwSrH8wxt^=a2moij zQ2f}X3+n&H!Nb`p5c|`R9E@(FpIa8H9P>l*muSB083&JzXQ7p%8+<(Ki|YQHAW?2V zRz8t~KS^g0>i1D*loO_V3LWM7vM|$nf&l86O}FM7)1k#0toH6h+T=PCr+<3OC$ztV ztO5o%!Zcxy{U|Kckw6vwe(?vtEfA|c1GhX#h1OfkxajGb_^IwTjMmYI0vS1Unfa2F z-e1FgNS%QV=NsU|>`?LwI}J;&XJDyYJqCyuvAd7Wa831c{1{`0I>H;XAH6L5bqBx_Zcs#W&6}`L)>9a}`9LdYUuc1jusexR>{xk?` z3dBzak73-iR6Msm0ISXi(Y)ec+!X^|oS=OW2d}op=Kbk-bgj^NUoeo3cMZj5HmO+o zdpzDcIt|{N{33k`FSP!lk5b3K@Uy06!vK%LobA^>$OssRl{fqO&5MMt$?Pd`;J^x`!kkT5Ek7RzC5dq6lNnf)@)mba_rxAEX&f~xg?p3q zk#dTMU_oCX?pt>X4}Oiph3akd@HdJl@^G=E$|8N zy21gy759>HM-7ZEcg4tBEr{7U9-58av7+lJB#pU%DzXAMd@5n-nK`g7O8DKrx&@C; zeuRT9g!knm(D^D4oG1@m2Dl;3%Z00#O`z8#0+!kT#ue7qlxw^Z(`T<`TffQ)^!BHG z=gdJ&`=1r$eAFT9ab}pRe37mUX#oYHubSp6#Xe}4LiN*`Z0Kuwrv5RG!tZ~f^eGXn zxhsnPO0S`HujinL#6Wy9dL&*rGDBc<#lTZRgHpXV1}tulM$6VQU}qx5#yq$xT9EV+ zcFa>D&tH)&w&)L6uHwYp(r)ry^<^-}FPQS4Podk=3$W{aGT9j9)~*h>2QPnp;9YdM zSIT11gALZ$y>A`p{nG`N)-f!gPnyD3PGTA@$Dkm*nRKq)hM@3%sy)~UMrmJYK$8~m z_SUTDdoJD9_$Nv+3BVQ|6;auG6K2(`%G@Hn*#$>wFdzGdu20XPhaz`=z1??`HyA@U zvmLSLqylX`Z3|hoDqs`l1k=iD!11&y+ju{noFgW&1wBRFS)se9o2Jgist9^@{#JaD zR|>H^hOrU5R9J@d9-MtSmFmBY#)og(`8}P;mWd{@m0gi|(LhC1m3a_ahfSc`@Z+Gk zW*7JNS^_+FoIulTL&+c^hE1t!hVzDds9>old%rrExu-=#_9`nj<~mQN*6~!i+61L6 zPs4bv(d@|HEOu?IDS4k81E&@npyGpCYA_39G6~Tzp{I^Q4vG+qL+^aQkVScK1nv&F8VtH5r}V<>ZI27Xcmxk?KF z5|>as`}YHETpnb1Z|zHZY}^G}Cxbwu^cP=ddzViCiWjfV?}SUcop7YG9@5$YF#Loh zP9Js`D(1vd;~z~dx)CAL)~$xmxAxPG7l}8C+(S3O8y;TVD2{eM1zH9xguM?dTpr#H)i=Db zIKms0j|&}u01@6;c$Qa@WTLXJ^28JE4c_wc~Jj&s|d4x&gZ{ zeuBw!-cs4<3FtC@78b3Q#TxaIs2My0!uBkNjpv52oSnvS(cBRiT_1_(d#AyvvjPK8 ztpvs!m0{pbAJOW+J22MRgqfWU=1MnfV1khpY?3?3Yj+yrqtqfeGs1`u_wRsL+(_8e z{u54ZSSfTG4Dgv<1HJXGz?S+rQf$&jFNxpecxVIYE_w^Ht>@wFc!G1!TcLC5IKJZJ zCkv+v-XmC53*_bWEzjw`< z?7?8nbT|Nq8(Qf43>;eL#@EOn1mris#GP}n za$77eTTl-kW+PCcW;@JDxx;tN5pt;mrsB=muUyTjE%@_?DLxn%A|AVS7JA0_a=$Z2 zppx@E+L~AmN8fqj-W?L6cR_0SZ*w0EQjLLxxT)~wi4k4VS_{u2>Y@Df7H*ZiD#?1T z$Cwk%pncQ;1%MekM7!c$i3}{)o{nq%hhcZBEspgSvc)AfXeT9&t~JRxchFgseENh_ z`ku^w-k!of{Vo*SCJOulvuL(w<8E@j_?>Lb$FpZ%gCJLK6^r*dABlGZ_fnpYJK@Ks{rt9_WVQW-yMj5&FfDGQx|SrpH2foaStKJ2fs zGv>FNeG6a4#2@!lo0}E8*yD#qnmTMn;{r^LD`$c0>PS*>6&t=q(^sMAcPzoP*2XJY zl>GPrG$-`KGV4A_*n1G(t=rD-Cyl13rx!E4Jc$__q_R4)P3fs=f zX6j>i#ygt2KUUa*8OQil&ne6@miO3rjyDQC#NI4$W{1*8v40r}uyc~ozk4&74eO48 z`#-wiu#!59x+&ydUY-(ddp}J4V1=OhkuAt;+fmbwh3rweBQqL!oVR&u#ClT>h=zuj z!~U%CEHCdSMfCQ8`3G}a{NH@>?-mn!vdx#?{TGc@D<#4Gn>v2#eZ*N@?V#UF-_wZc zcOa&qg1S80VNK+1P&$jKn-WPf_dBLG(6C*blLdVpeko zW5`8ioS8I@qHS+cSkqwkZp3Ct z^>D)V*;%Zmd7DTxL_z2rPi4=l7Vuo0Zj3;F?VbIA&fdE%a&&Cp$Sj!lKt8n;G?I4bG_=A${i(C zySNuBe_e((`-_<8^JUz->}Y1_s0Jc&Jxn~WgqkC6u;^}{ik@DBCXGlKzvU=N$Be|w zcdKdIv{~$DSX@k3*;7W?xyOW%FKMEE?gQQL2^Pau(jX=INnZzcafJ#t)qk*`GXW*`DuJk0iEo`fNeOQFY< zQLH7Ok({GYDG<&uwE^+0s$wW>ykkx4Gfgq&cYt>6Iyh4o#b}%fyP156bXPBi zEdpofabhdD`(NZbnjP6_ktI9u>Jm)7r-`Xs4|A`iOChmoCvDXW7r34lOq63x84V-2 z+J-zxozqAq4MF5>J01_d9mq6S*)xsAWmq}$4$sDYq3$+YHcwzat$LIXC;s;H#oZHF zmii!koiK$a`E14vmkQA7`#^>(_Vf7#KdC)(E(Nv7Gf{Fc^=l1*xw67e&VQx6&SYU< zWZ6x~&~;_+KRdB`@s50r@SL}LIfOKnmSB5{z;nuM;MMbkxz5Eo{EV*+Sqqhl?zDb`|FHW;Idz$bUfQD7R@o=i%opZDB(0j51iR)2s5-zkMk z(F~8T55$lWv*4A?aHiQW8*PrKWO1Q`ncYPh1|IUj)G6vsD#p1DdLKXwUNL&6gWERSblQV@~LPH6N-gf}zCFEn9)h^Vjz6yhDVli}| z9@+>#o#c#1pl^PdrW+ncQP6VwZsmlYD`wOBQzG#Jqe6B`CX{*px=HG5k8m@EzT(GE z()cLZ2$|z1bTJA7E8RY^N>&!Ozdwmr#B0H6L<0V5sfTO5v(VY>4+QnBh4lB)Sh*~Q zZLOEVj&;e@nXD^3cQ*>#bmsWJ(g+`f1)-$tZj_Rogjz~jsOfNsT%NuGdBY7@lN}2c zCF{}pUMx58w*<o>52P z&V;`%>_ao*%;UDq2Yw_jz{PH>@wKp#MM`eC@S{6E4GKUL>ErzRjXalCkq>{e60!Ju zB_D4$0F|N~(KzBLs0!?wDHT5W`O^;a*s}v|#jEjt{XI_W*bI29oCZDV0<-&yFK!(B z0?vBbVW(XnK5{eXz5D-i^$jyH=lLO2%HM|fo*E-@)Bt7-}~U z#oN{gaj2RhmhaBva;zQk*tdM4FQScuK7WVB%`5Qtt(h>e>n>!d7~=kifa{js!J(yl zxnzh2wa88A`eO~`zA3=c<;iFkqmN$(O0ut49>UT7T&j7MgU5IsT;ULaPG+%KIBej!*qpc95&bHFE$RPotsD~!2ih`#&0KzfckTjRV{)VR+QgR0`O#(fL# zs`(V%t&^$x^HQvjXu^WC7s;{B1ecrmlhOA>!UpVOz9;+`u8~Y9wZI6xV`u~_`f1oB zEl`XL$I^-8kw!wZ=c!r0C4*a$RB^7>&uYC;nsC9e{?za`2K*fSFxD5%N&k)Trv*d*-XPGL1(^Ke}I4SqZt)EhoZ#o z?Qkm58QuoOqV+&~Fm`Bwo$VJyPdtTwY@s0y3>%9(im$=Ry+YUZ-zmJ$=fLD@MDM}A zFl|aCDrru^u6aCMc8@}{Y5kNtKMaH1w~^xE3g~uwFXXJ6VW+ATKFD8)3)}qgmgG1- z)!G)%oDg!sl7P*I+Gugb6XUMWf+3+>P{k?|&m8}NJBuSB)A0pJQUp%w*^PsYGV#sl zK`3P}>`40ocJ9!{F@`Ile6o_T0k#ew=D0JAYZG6s@n>I?A42NKE*LC35=Vb46rDKy z|IH&Ecx!3^A(&Mf|;_QaWrehwh=S%zcPGDzw#+&+lLsaggIkVRsC>0fN8z zY5*5MdMfvAM?5SW;6x9sT-nIZLu_)FGzCmw#F^D4fRkhbQ*v8_OTz1@7OVKT>8HUe za|Ji?)+e&~Gk|Vwc+HLb;0`5q?wn_NihbRH5Kz7OfIsnJ9;w-RP?n%~Za!HI-}WtL zqx_`VVX0T#mX*Gc|92@H7i`6fd*<<9>yL7S%Xh;zXrS&7Lt#Xk7am)A++MBPihWc+ zN;Qgh%BxIYHU~HG-%v3(O&D&aQ4eX9Ut44Q@f@CN~xED)XD{@mu87g1DA1{r@wLA z?MBi^=i_kn=2U+8@>AHB^A@gk#?rbihbgQ!mpkctfR9wrrzxLRX~_dmewx`2K1uzH z_+mr_uYP(fm;QM%bng>kjn7?J`JfbYMT=SI(^gK^bv#=?m4U-QGaUFlik#!+Xob5Z zwPz2-v*{1n_T7<`De;lCWDDp(bt*-!ilkX*eCgYq6=*vs5?g&nG8c^})V^;gt?Gzo zms*$Mu52Urc2FFJEZhPQXXfw|{tUo<{kbqr_a%3>uZm82S3|{v`(gtrW2S!Y1x!kw z3!z%TZu;JUJ9jJCSgDb0d!h~-Kj$j>Z1;r^T1U85mxZ46!iOZA@c_Q51~6%36*}6W zi2ip5VetFYq}^$b1DEL5%&^a8kG`t1cW;8B>dHpuoqS*PSWZFwpUWres-FVgqjXra zr7wv&REcw1)slJh_2KPkt21F z$Iw(X9L7XCGL>EK%zLOElgJp%lu{4Ct3wjZvd4_#BNUkL!#~h2_@bhUEwu1nJsdu2 z%vNx<)PK+&pZN$oc{)k-%jguo`Eiy-Y)|H_uK82#ur<)S*M=2;yvbSW?q~e4cQEB! z2K;y_gA-3~hOe(Q*^nDwIHjMTXkva66@G9;{lf8NDnF6+wKmX*kW~0yRL<+Y3>I`M zeJ*CfQ)rU#pux`b7T> z@@P$2CT??y7QY&-03u=AM1Elt?ozcTUAu7D;^PY!^qRmGX(lv(oD zYF;nRi7Ed{hm4z#Ddyx+`fPKR3{v((tum^widCknej?VT}P<*x+sDq(-cxM4m;Oe*3-bi?W0>R?LD{{oVp<8UE2 zmwi9q%{@KQMh{9?vixRcS~J0o$(H;fqY<+F2}^k@{+7#sPgFyTxj^=Z6zSpLCW_r@ z!nUvY3)}a;;Fmfn!lp)9@=rbuO2PA(;>=cBx+dSAuOE*q0<+lZk1Aw&yoEoi@{D_| zGl3l3jdAFD6V&zCC3Ha4=yJI|K7Mzc%p&B_YS}xQUoOphg$~Ffw_`x18mPM>hAw(D z*tsJC3@+BvU%x>1@J}PzUH`(J(Oyn7)a}9P?*{VeK{_&i2AfBJ=;ifALRRxAEROt3 zqc1FEA9oJLq3>PUOK}$W&{&I0U2zIJm#=1z?~N2M`Jjq3KE;X8O#RM(zW$8*_6=g4 zx)(vgt8^e^mxq^?e0GA0l>b$LXc#Vb7%`Ln5!OyaI z*=5TJe3B?E!H|};JcsO0hv3`|OW0PO1*+q=vRN5JYahQJhDQ5qXsT-j)_SM&pCco= zRpCm^D`yI<>+clbJ2H;XimF)BRB2q?zYV@RoTE~sGzxeRv~(DY><{ zj2WPc4KGgOH_tzCz%hfjkr<27rWx>G;xyEj+Ko+V!=OdM4M!$U#JG#=(dYOn&`FTS zf`#wEMd-LB-|K+ePk({!DSfP)7m7RM;_=SnZ~R*G0F15qOeL3VsCLwL&{L@gKg+S` zq7_e@CmbTfQ;FDCJ5gkOQ6B%j{3&L~&GBR9T70rK6bDKzr%`@)i2F|u9RiP|v)(g% z%aTy~HN}auPV4#=k9fnEO@O;+FTq7287a;NvTx zd{{&_hjpmDB~j1^l+b#uA7*V0!JbXaFnjVX&@Kx_ia5fikMD%Wwaby0o`xeHB%*x7 zY}{3K3>wo8a^?LR^ha+GDqC2xlwi#>UHr!$Z`1aCk=lt>V}G;c6^6J2vm4` zpn*6UefG>l&xw2SN0u}g|NF>K753W>dRxNhQzh86nK&J}CgJ?114^O@+~S>yXZJ?K z=xx@}yH!KvJv$yRnIl~H4n`NruW%^hBvb!yuv`*}6L{_zNW-%nh} z%i9z(Oq)Jwmcoa~V)j&hDtowNFKj(m3sVnIVUuN^fWNDdwG`MBj|ERRTj(|yPC6tm z=g}_#MOd*UPZreP$S9^jz?n$FTuYZ)x`2akx)l=$;v}oQwZ79*-e%3 z|4riipH8zK4mw=do+Xs(pMsZ^RpG1s5$3(W3wCr=qRHI_SXmxp|87Y?w-H_Ny;%Z= z%uA;Bg|g5)DISN^4TPvOcev+9o~WhO1d{T)c&11J-6GX6Brg#CA1uJXk2X=dzbctF zG;%@J|6}O9!>N43I4;T-kr^UNWkzM3_r9eNQKF1OTN#y>mWYrol93tNBS{J8eV(Y0 zNJ~pgLrN1RzchaD-{-o{b)EM*=Q+=Pf4|?)H=HQe%|O=~(I_~j1rm?c;is1=5L$E` z^Dc4cNtXrrwciH(LnflRtQMM-6+@)eba=br3Owv8K%LlN)R&XMkd$KV4$Ope-+uF} zIKPwjGeK%`=@nc*ydIaXd>|TT0)jhFT zVG{8a5JZQK#vth$iG^x6aN4hhxH&Wn19y0Goq2`$4aL!Z)-b#0%rN6~qzHfYv@pgo zC$ZW*8xH>`jlMx*^n<|${sgC3jM6e8$-~?ocTfn|-uMZ;#TB4;b0TlUfgi-F?hX5a z)A&V2_mE`{-0t#%2uT*?a)57QaFNIb^cEAxjItcWOWc0yq8OGQOUA?#kKxzn7(BVC z7=N}Ez@shN*tH`U4Zcg`;*Ya2%=abhv-lp=jcbG2(MKTDJ&rpX&!S|e99n3sB^}3= z@NY;DC#g3=D95H=75o5-xol+F?%k+%TY?_t&WZWEwle>QGGJNUOfSVY-f}LO>yiXKmB%K zg3cw78*?HPNdYW(S;RX)j8HPj5Kn3DA|KQ@fd8MBxH0-B=v~}I3&xZg1&4Gpb4N6< z?Avcc~r|D11kzt~^AkI>$TxJ_g?<_3%IIQ(%5eg;r0#0e^h5*_YuX zWY+iVWYf`Fu&VYZU!JH?+xeCx;JY<``8t=heOX6>5|ha3-kEUac8tY5qfz1?!=rqs z88F<)VC2^o_=a)8ciU#8i@!7;hHb3om05T(FPs#tbHYro^GsO#AV}{RgR`%%!wHX3 zw%9EZEb^RT;WG(Lb6rOcSlhvgO)WTT-32P|*5k}wFJYS0J^XKbES}^Tg)1lb!j)O6 zP^=n&#h<-VY2I<16~U5R9X)KHJ`0})oWmodPRusT?J)7ga?V3>0U+C$$rk05=m}XDB%#d+qgF#O~|*e@bY3fG~@`a9QUyUgmavj^U<;KW}_t zqOHzC@a6O-F_&BH?RPr#c)1!njfuk~^@%X^Wg;VAeg{$~B;cBo7*tpO2BMvt$cwkF z&~W4?qsnoF{%bl8sc+ih&rlHmeAh(0di69?=c^#3JqktN`PkoG4Z=c(xci+5l)m`E zK5CM{T7g&Wuy+zXh)l-`0^B)Rb`ZK}Y@^zi0-&EIhgK=6xZ%f2ykvd_FY0@vr%xuw zw+Unm9fOJW{A$v%t{5MGO~Y{6W2oHv7yNe)@a|9Ej8_cilZ!9nxa{X-YW*YwH|za` zetBIqQoP7m#7#qS^M2^xVb3i48ivXz0H1iqV2cZ<6Nrw&#Y=LS`fVwGoG=%En4Koa zJ~eV|R5kn~x|W1&+=5?Bw&I%~2bs-((-<`_AN{v-FP@H*pogy7;sqmleA#{kc-~p~ zcey2gHPFBuZ^C)F8zAp)G%k>H#63H9;RKqDMe}drP~Bg!@Cb*S`p@{?GaT`{StA^Y zEy5Smu0Y{=IpXIqo%~dnLEGJTNu0DHp4)r|U)>Kw!A4=!7~-DGIw5p%ii97Ume^!G z#Js+H7w$xIJH`BF!hBQ0!Fy%AwbvRz$5sZ#e%yjXtA_YaR!>2+D;rjpCt+7^4L&XP z#GYgM*tcObReT+R$9OvUhV!e}k58v2g|~T~1+wH#(;3+Kej#}}9E28r8&P`02CNQE zK-chAIG)M*pZ{yX_^D_B{)lPeDI){&s`nxc|FL8DOv=Say94p& zUn{g7`o*-~J%N3d>+t+lC8Cr%4F^n)p>y3Vl&?+0nmhUM>97y>-7H5ReKSn8bAXVG zU*X;NdUV%u#pVMin1;kOve17&-o2xXBe|ItQE3+J>E2~16R{X)rbXbrB`L@iMPa97 zF)VpOh+(Q6x%V32+^>Ul-5Ezzs5Qg7cmZ%PGNk?jm@q{WD_X_z z($Y9|yZDOfZC?$J%VThXp968)q(zMLci{I|HuM;0I;o2BBX}bTZ8?UvpVt8RUps{k z{+vIdd>`7hzGhch--2FhL!P)VBG0EAlI3;V@p=0u6e-+`*;RLlgXCN~(Nhj9`i?-h zKnQ%4l!j|(jnVv%AF4g)w7biuq%>F`UucEllm3Me5>LtZp)rV0RK?KksE>0U+A0%Rg@S6>@gu>)G2}2YF6_V@ zH#MA8&ScIKGaYH9?*nEQ=`h1(U6tKfcPE)*|l0XLL zY11FhkudjQ8Go6@PSXE+IpnLSF<@Q+PiBiT;PjX=jE0`mFf&~Q4K2@7!I?35XMGj8^-sdm&>FmxlgjS<@f9*p43Uw# zI8<&KV!h5JgZ|GLyiuUZYDP`RQnyLC;H4{e_uXW!E*}S7jTM;rC=%#hCo=Y=hotLf zpu>%4C`StrwWOQI{kw5sGJ`(S>UjQ_8kQOI(eQIEI%;z{lD&1PuP=m`C&*zyu@YV$ z^hJ&00L&8k#Vq*}2MWp8;81HLEcz9XdBSpFJhK$GE?)#Cg=a9>Sr?q&lmatpDQ=AX zOtK7Buw&c#GkW`utS}NnK8eiYKsu&My24a zH7z(WK@N&Eevur}5lHk?z(7?gVzo;GDtPJ`-pqBt@nq2Pq!)drcM9W{E~Np1xg`1T zbD}CCh`bJIRP8dwJEx^k;Qc<-bCE&w6C7V^-C@i#odV13SD~%Me0(tYm3=PM1^@hB zu_K;88MozmXn3KIH+i8Z?)aqw?u$cEv{)B?3}1u$rA_!TdM((YHCoH1!9YHSr!pa@-6c3C)ey5o){iNf zHyPB#oJpU%D805?l2nGyrS*%tStX-zdb(p3KF>Aft-CUXjz82Si^gWsD3i6|X>%A9 zc0VPVu5+oFL=Ty06-$d|c+*cV;beQb7;U}u1HKq5(t55R?C)M%-o(giMt|}I@XgU8 z{d-=Kjbb^Z&?XS{FD$2Zr?}1zj*)ui{B&yDz7e;;EpqL=72aJbM|1Lq2x~XW81!tR zMnCyXz4i@`Ctrv8*K&v_m*b2V@#60c)2AV>3SgSOlpfZ3#|U444g#x1FtwNCI^}O7 zw(}NJ!|Ymgo&SuH-6@ZkSGdDS>{CXO%hUchqnyOOT}gjcJ%{11g7o^~|9HU_^HIM* z05Wx@z&Bq8RKDoZihT)ycOuXX)M`&aEP?1dy)JP z;TED5-q;y6lQA-PK&vHv{K)sVAe<~uwtXBWKDdltbQvLm3zV=rKaDLt7C@i(I?#nK z8%V!&9`k6l8y1=WA|01g$V88;faRQDVWJs*W?uux#W*IQiy~d-lS2P}l^~lACXmg- zU)UULGYE}6Mpk^xp__l@(O`KlV;R00XDiQOlGZ$AhhCmwmxw#kosr4(#r+02u6dSh zx|%}vY>xvHIFYzTpMf!@5}1B+D!X`^DwwfTY$(&5A<cz${`z`xG`e~(r{X204rAYnp8F< zgW%9?dMrSlEuJ^d+u|;cCBi-A(nJAlpD{`-+%sv7pd>^E&!F3lE|W}Q2W)m;MZeen zW~&~RvnDT#>4)QCNIp3rO05QYn_cXt<)!3i*mPQ4(gC-ctI5+&YcMiXrym8+vMwJ# z!_fOy(A>U~ByeTwtFK-lx390|ej8PUf+`8QrHSHK>xg{SK*LGjRTz=*n!Rt;!fKDi z;KwU+#K?s}fp$H1I+f9H)9YDBPivgG>f37a>q;a9z0qkJa~NYC(oEr0XE_8Lma!uXcywRaOW>bPuX z-05%-U+oKFqOVEe1#WK`We#Fm1C%O*N(8^kZLZdz%*SHVWpC-}Q z4pX4kq#cy=h3Hnx*|d9KB9nJWi+x=m3%BHU@gyRDGY_wekgNVJFfSvIp7p9Fb2eaR^qV}kmB0&kW`J>x3nYEnLhi`ugId29l`5+w`**iOwDdI-UxlNv~P{!{1cg&AyA;xafTc+!zA8(q)Cy-rRjXOq`)3qPW$g^#kaLJ7` zvz(4Vp`06x57+UQo_7^)yvxB2XC-irSvk|C9N*C?fVaN+EMC+}(Tn=C|x}6n7 zt5g5LG?+8L?7K<2kN<>nmsI%h_9kQgb0 zwDTHD?#;$AD=7-gCGZ#D5ax%J!%oHh?2)$H#B9wf91m%LTTQ(vsp`mc;PpVNK|Vf< z`a$F-uyC)ofhd+6=e!gKmZ z*(Db*gXOq6W;y={MK$*L`CSHohJ_UNC1qj9>lm^xNy@a(w-pSg6u_|PWb|C62-cNN zu>M>HY+Rm7_LWG`mp6`(tF|$areH+!t!0&)y9qw{;NaC&z&(iQrHCaG2>S6^DZ!t2dx z$U#cE?$?ueLw^*$D&{d9Tp#t`8Z_;HxPuw?EoSzMtwU9xC}=L_cnU)*G+4?Wt$Ed0 zFtMCkl)3xug+=6L7f8EOjiImBVbz^A z=(l?umUp~k6egU;EuPkF& z4t;F0$Z*LCW})jsygFu!Hec8B^IN!{S=Yt5qSpiu?^3`tvvBsbZx-C%auSPC0S5%X z;tu-~m|v|1npdV^-s5uko9clY>(6k!bsi1gyPw(U*hDOYX5*B(<)qYd3+@z6V`rC2 zqurFf_&huuDz@ujzrj+>Q)pvmACKd*vntsCa1#uad|}&_&k(Lhh*3)CGsX@LuXgR{`YtTEbsBd zpieB5zQ_r?PZxu{v^}Qh%hQ(ZMEJIO2VRzSf&eR5ykhBxH|ITrvc=ggm<0u8H=K6(0cuxffP&k4*eKCPY)9w9-n~7T1Pk=-JwZ;3a(B;mQJib=0{OerF>+EVCV4lb$EjHmGw1?-&8P9| zs2t`ToYwTB;XXTHqYsyla@ix>-~5o3m2k8`3zk&Nz%!*GP$YAmylz4(-@g9HMz6xgV>JfHogEsE_ zH3j9iUWA;dCgd@f{Y_G@gf&}7AtJPvU3=;QIpY*>5q?#c`0K?%?#);dS#zBIZ^r@h zL{Ss8uDId+$B{I6Ni;M4<4kfO%aDDAA{IHO>SS@B}{IWuq%@fZq;=j>c?e`y}s? zD9zdAkke!S?^Z8jHC2k(cFC|6VR5KqHiZs5S%dvyGsdlKGA?LcK;3uekv03&xGb9< z37T}7NZgo5UsqiR?Y4a471scj>2i25c`7vuDMXQx#Z=cMlk|JsB~8+O^9DmK`N-^|_`{SaaD&}`y2y--LGWF5#BO6ZZ(83+^)XjAY4be$p zBDIrATu3=F3cAF5`gld?RR z*9*{SuQOz4w=q^WRe(b6LuPnwG=$ivgY1(DSUA0&94{SX+Lw27xzZbqq= zdo4s)Rgm`Q%VLT_KbyMt6>E9m2VYM+88xO)!t+a`@zMt|2#YqwsKDuD`5amJK@c^n z&SG4`RLF}Ah7WyCMDj=xxuPA0Ui+%a!U!c|dpwv-@JhzHM<=8HEp0q{b^@G=Q9@yhFb%?4kXjj@_S z@i2Q}9>kf6p>wGp%oIDvzVP9C+&v~hFt_tCUhcyxZJ&b%t1rRFxu41Ep>)(YNTmVW z%dpok8wzHfg)zdhuJ(JQ#6B$|Ri6l+>I<>M@F-usU6xMVvl#E!bn|+i)PTd`Tuy)Y zhl)GqxTW$dm{f9C1ci81ot_Eneyt^rq8ey_;3*Vkr!(u%KZ5v5AqXAbhr-1@+)jtV zhe!CJL9{TP%lX?c>H&$WSf<{q3e(Rb&e8hEz9mw)bsfv?p8LtPztJdhX)ZZ_t^@>3 zdq9z|gb`0X@o3>5@R@0W11&N*Zmfm#&c|b^-W+@($mv}LTiK(3evoKMbu44`ai`i5 zG@a*1g1MZ|FF7^r_NYO=i7#jrWN~+sLOiv#sA)ry3%;I}59wz-pwwuH{W-ac<$?fc zn3RZhyF_ue+G*4@m&RRvu6S#@4py!|j3JR4Fev#Pi>1WqOY1b~{89iBqQ1~PehmG% z?7(a01k*3w4j~dsq~^6R$BF19GBI4AZQ?iPnEQ2{|8F^{JlKsAcH>|wlmczreekTE z9PZ1|#5<;I@tN5Xd~x|BJ5|RF?c?LoEOrSVQsAM=+$Nl?ZHT2O%b2Q|Uhs4&K&iA+ zR`JbgOt;&}F3nzonN|fDDQgT+B7}2FSHrUG-8hxlVKaLbuPlmVs~^@fc{Chvxm<&T zR0FFW%<))XCOf0A7~gW4^G_-tV0b|xOu2cLX_FTOArJ0<^xFjd9g~Xd9DlOQ%VN>t z$6YwXow>E?d^{i^hPT^mh}-q2L_ahay-IYjaaKDS==si@ysHBEo&uIn8&{)(T_dU` z`~>?=`8;inA$I=X>o~Rd3`QSnhaBmpsD8|peOo&UBSSqREdpYA6O@aeDRVZ@)Bs8$`7~iIf6aE}vqVX$8sQckZjVb8e zG!tXOzCfzA5(=;W#5!AQVZ%pT)DIVi3*|{{jE*g?w9MkP%jqOq#Do9Jyav^`dSFnA zIlf8!29@{I8LzK3War&w_+qscUhc2Q?1WJ8nYEp~nWTVP1|Q(7wlGfR_*f@7T|k!e zcUic*Al21Ghsi1EU$mC4+IAebMT`?4lhc^p<$x}(K^W_nhO?ZX5u2D&po2od3%g1V zSue%u2d*-sa%1qeNRRw(*?@0V<8kGkm8d(X1A0r=VDhm?;H9HRJdgheJ9c$rCrQMF zuW@kpc_~|N5=XL^v_N3|Q&3r}f>HD4&^bqsld#)s$a+f)s1P@UPm2h=(d4@Orf~YZ z{$vcRPh_oL-GP66Yh0^hfESc{;Ipa}?hP-(i(Ibb74e0)>upfwWh`OuMZ$?H2i|tr zMqkQnfbEVw*sv>wCmQ_(n)Ya;h;=Evl1U()0}{w=*ouLxiy@Y71M@l+oO|aCxMf7) z)PX{@TKE!Xi3?-XnTaGu*c>lBjfQouZm1_2jrRsJSl=;%4d{rw3er$ybscLM>B9c^ z@fwcJx(fT9XP`j$Mcgf5Ns26|VD|zsw5Uo%)vsU3@1veLLCKFTQ~Ak^54{BG+*UF@ zxP&}SmWQ`z71&%AQF6XJg~%i&WBZF`*s&u4|7Og^!gngD^7%aMP&p41RqsI)2*4Lt zU3fgLnibq@h6)CInN$mTTqoQHaZ{ubjBmmN#bYp0=@#i5(7=b&uYn0YLmn%nV!*-< z$bXQ84I;5ve@POLZm%TMS2E;i;C6I#_ebYP7jWhZE*om)i|-%ux$c8kOj_(x>^qr; zm&a>hdteH)dR`B1u=PfxqS-Lh`T$J(_nsd-SqmD2%rR!oGJ5SuF6kp2>*W18e4}s{ zT!m*~V?aDcN{vGFq3Jv|Y=DKcyP$DyG^*#uurdExkdl8l!9&dqw;ApsHnn?DvT7b~ ze(DW6tCZQg-48)fcMinAiv$^+Rm{$VtGWHEFJ{TtK_r*8n>6l87KF}5DUClc*v4^C z&hEsv-TKVUqaVOf^eww6YJ>z-Or&ETOTg{kZRmS^l1K-QFs_L@WPRH`P)ZfY(Vd&I zH{AwTxER96)?{XN?_9JGT!c$3Gx#23hVUQ9c6-g~pP#2^anB|JM#(oAx3$HCFNYvT zv4rb)LA<-=DOgp?07hQMsp757-Lyma^j!vOc!Z#e`#o4Qe-fU$7Yx12zp!i4e?eH` zF&sNphZkSe!Y-~yBYKGlN+md>;>bc2lzq!?Jb42B{%iq>%R9kCVg(i-i2;?)G>es4 ziQqN$32~k~#AY;vVtj-<%rJMu;~<2!@(5k)3t`krk}^u`XlJz>DrUQ2-jo1beBTUi z3GBqq<%`ks!eJa;5=Knl=3_1Ag7lq%j$q_ns$tH&+O!>g9ql~Vxg zTZGX>eMXogON9$hLSP_y1SV;1C0l2x!_ilWHOpV3SmFZA zoU4gpJ+p99Y8yUmlfXTty%>5e59bdr=YC&>czio0@L#+aIzrF}9&v;|{XJ>Y3;}OifQ_RlH%fyUR2ia|V zG;!+R)i6!?81B{42bIWExaO!d6eXNwT|$@REA?#F;DaX1M0=sDmlk?FvuC#XN1*pv z9dh(dD6Z~R#9%KCq%+e_=>l|yoL~lLXrl3(9D6oGH2|Hp{y`lHW|m2j}o9WO?SV~mh54)l1__C433 zcxnvla+>=89z+8=;f85`#8ILdU>f-hqV; zD5+k=9y1ig4DCT?lhGo4WGRVHqtJNs2q z3BSJxV&7$M#Hd<*>Um%-qWvTcvaW%E-_77FZHIR>rs9n|L+tAKB1n^4h5L8g5bZ7A z2r8*O$HEe936?=AWqah8Zf!EV5sto^63lD^#Hg~FXs@<|v^ERiuf`yfvgj!01c_qx ze_F`jkc|I?_h7Ph5_#3;3Nl)9EKk>k-@Dii2Q&J>c}$OS=LmSMx!yQmt{xm!WSH$$ z+d=575Iz$k)u{xo>VFC__EnSU%o(ql z`mpD)K5hpNzRH2wH#Ra#UXRJ4!Vz-l$1`^4vPJMV=?KpxXdl_wTL;N&S5Waw<;2j- zoQk}0hWVPhX!AFKm^^ZZhPUEmdEXTF;U*cH7@~n0zs+dQTO}I0YCZWTI1LX^oJb4D zs~EmW6cza{OJ`n@1t8n7WU2hjb-adzFa z|H!0HMRtF1I-BuGfs~CE@JhDJ;aQGZb+^Zas`iBN|NN_h;cvzy?}{{CxpWnb{D^E~ z1;lS?au*>5G>3Np`uR9qMujfHjsSOOC-$2zI^VrLW9}>?QCsFkMO#0ld3|$r+ zC97t+zNQS~7Yj>=P^W<~Zg(MNsowzw@#YnEXoR-I)7xIN#Y6mO{K zCZf;x4H*m5*^ph3&zv9zG}-kuyi}S+wzotPleQBiW?3|u^miIY36GPh@P#+L?=#u) zZ!xZ$?S<7=`$$0QQ}8TNfsWro)WKbmMj5UE+lX6?%!Xf#N!JwkkL@Att1a0xJ0r0_ zY5{z$lBF|VFXb5G9w_854_ya!>7i+Saz0srMkFSX+x1V_;C62A&-w=wgAxi&H_}P-V_Wmk65 z-809#_N~NVT?G@$7Bh`X#UNHWg$nK+CJhY?QT!tS%IA|P{rG|Xm&1}B&Aq&_F>6+x zf0*;+8&jK?pZR*#F&LHE1z*1ekRi=`{HV0G?7+}@wkvuUwJBZ3?&YacM!JD{)xCiP z=By#64bAYBIY1;fzXzGpA@<~IXFB9Jg?91}z)g1#TJKm2Nr9u}5MKsQcTeGR7DXgf zI-fPK4{7>un>)5Ueq)2)Y0xpR6k3qDmlv_8jJ@A~4Wz2p(+0%~;;_7w5xVO{xsCx~ zRvmMB;c5%^&0jt*DD z;P@tAw#8@$@5D?=?4Py_RfbZr`CbEA>fXWD`YZwA!*ghGO&f%DEyu1|Pas?`0)K@| zlBeAruywEvo>n;H+`wpVzVpOg()Unj^>MZ*@iZPwTuN42ia^JkwfM#VGNU&b&0a1a zhGOTb7%)W~4|jxl`_l`p+#t4}K9*rJD&)wuHmQRhoF~$_G*vz-f#P>9`_) z9SY2T4ogxmfkrbAAMXn%%|)j;?qxRD!6$$l0>faA(j!=56o4lGNe~3|Il5 z`^(^@;xzP47AEVTas7)87WBs0esl{ifiEJ;7_M>-izG@oZkz}ak*pxri_b8E4yyQa zaW2d$`vGyB&-vl$YKV(2!PlOO=*zKn%)PFm*=P}{T8N|6Z~>%VG={KLUz+$(o7E4D z#FH!LVZmK%?#_A)2JXxUsH+C6Py6xNk{fVC*%fbBjj;PpRAPnqd3bU{4aZ+UgZke- z>|QS+baZ$R=C2z$R82mvP(Fu~cI#kLiVL>>34sM)?l6{pHkkXV1oLdJk>9*g@F_nC zSECltl)1}T>JM~xYzi(cA0S4n2b*-YkAUWa%g}1hvBJA!*ekZ7)aXhg>7Bld#B&~_ z4L*B`__b_mXMUD!Ziu40G*e;2jYFU`U5y#}P)>SZlta(Mlknn+1#upaqUU<=k!?1Q z$=cjhYW~XuPpDbakAYVi*Wm#u>aT{WA$F*+;|CG=ri~#wTyN3crL_OWRFGLXgE;i9 zVO5Syp_!9-sC6tJW++`F>A?lWfC-}3?=84p!5T74B8m)Zy3>X!I$-t9l=GqycEo=& z9WijBt*L?}X~-7hPH6J~NUs2q7aVUTA0dkgB2NTBfC_Q z+BAfc`p7oWkDpI=>rbQ4A4}6%nHDluxr8-(a-BpQ>r=~cu1_K?u+bqVkpJp-95vSu zAVGgWkOA#{qMG3gd8>zhQ6ezqom7Rys%Gbj4E*_)obo=S8ETFJA< zE@Jq$AI4XEG9m7_U|neeGab&-N83$7&{5L$>MEIJ+RU7f z-cI@iQ^+Ph$9B)IWAoA!Nc~euT$PU~{=l3}-m{DpWQ4G)v)+;g>7hu&4QLj3H?Y6b z0r2=N9hX(ZsFS-n&22xG`Cbp_4LNN2}AxtObXR-ldZ1@uS4 zz6HkE{6UqTIxL0~UoJp&X9d~5NRcMoP9v(b%ArJXA-yn`Pj+?`k^F<-2|cI)`|f0; zbbl7`SCueRzqXNoM)4$M!Xz5)W=(E27+M%TZ3Ksd3iKHe0>72$@|X(d;X`Nsr5)~c z(e7Gu*x?U*x$G2i(k}*!m$^)smmkwRPn2K!pBUWa=CLTUl-!g|C2PEe;pid6fm{h_ z%C(_icOHY;dw-I_M@NX=QA0-M;B4G0Y6eBZ_N1jNi8wkOAfo&BZUk9H!|B0_hh=) z>LCfxVxdg#9qG6+lOAc4qgVX}>1UPcv}ckwJz%ni>)|$~Sm6rC&Pia^rPX-x$TI5Q z{D+_Wg7YlQoX0;pQ3Tq~oFIN{B&ci63noG5G>P$zhM+5M)IM|xOnmT;6g|0tUI_PVSPiFq;^wMXrl zV|yE!Suc5{==vvqkl^W_Dvco-jWn^fDEuC^H9?SOM z0Di0z?TwV72dwLf&8K8~C5Wq<+<%++r8R(!QYqOf!u@ybDuS!=X5>xlaq7eqq4I0f z;bu@bF@g)MQBXPY>6XE`+SaD0e?6(RUp4GMXalQCSvK!d6^+%NPPDJ(^5sXkzUEGO z`k?s>WT+Uy;i!9L^yd_u!_95U6O^fCt{cgGpg=qQkKxdx8K`-Xcd|L1(3^&HK5qs4yghh( zNhB?Dtb&cPHM}c3O=&!1LN&JskOYp!;a5L_zG`nEW&9YpHg3fOI|DrTM4g!4d;?xy ztMPTnVy5a{A9%jgW;-}Jm=E4VCpMt&?^2?4!F$k$^zJeNBaFzzP>InM?;=BO=3`>*Fe>##xr{b)8x zy^Cad#Pcp@8IZdkrwDhN!8+L@7z~xBOQh%U-@Z?vQ{5C`Z{B>U>J1}DMm`do6$51E zu5Qw_Ntrfnu*FzO71UI&q%$(OES1q_s8bMx2bStIYW!s5kqO$IW@^if{>vvZ?*hQW zd4TUSzYxBZ3enH4?Of)54t-gp4jEk6*`7BKVY5I7m*Y8#26w)Z(1!cuBiAFLCioYU z)<)o}hz0EG$sB8Mb}n?U-^I5XybU$am%@XFILhHG={m{SYxfogIg{t$}b znQy*I>;#{Iu3-z#c~^wfzCB_8yjKI2fT?(}WIrz1DTZs+|FF;hXyfkh58zM!B7A?h z0sg+;fv?vlk%GMskl%Hk9a}ROWk0!cY=CU`j&uyH=DN^?pRdBX=ksu&SOCBHr1NSx zmes+uE9l|8jAob{0dTurZy9Oq*dT&_HQ6{L*a*EZ>yqelKiqt#5boTYj=g8O8QD+) z%igELO=oS8R#!rYdM_xq55TlQMf|0-1b3*1G4VT2k__EO5LvYca+Nah(`iTS-Qt4h zBaJbA)*2k)a^(5}!%(mPA7jw4hNCB9+M#Tyc+qQwHbG}c;UM5A4s>cI_kOh zK-eu`czNb3W4EQ4S1_pvYeLhpRQV|R^-&#Nq}QT$TNw(gNPz2}TDaOg6=I%j!Cf+l zQ%we0oj#T`%ES{P^#;iYahD>k14?$|**+T=twD17kV9hre_ z-9JJ67_x|eZ7iSu2;_YE{b^Kw(MLvVd;v@fzXcj^Z-K7hPsVQi8EkZFB`wJ9tx`8(fuEvFdd;d$?7M-d*BD3>2q=>6KN4>Q%CWM?L>{MDKkp8>>H) zZY{OL_Z#*TH%nippe-NNA9CKJrIE0G+=dv(F9H3Q`(*XaHB^3MD`U^`943#b;h_`@ zOpD@jJWevy?Svowf$ikd(KJ~3LV_-esiWq)H`r9$n-(=&##w_}AJA(Qq127r=MQ$U zXH0$(y+|>TsBy=naV7fUTR-d-xIhN2ENJH*Rd_L@hnQ$xpo&TB$k&JJc=^NyB7LYE zG+#N8xR!3Z#UqF9Upy0oq#aR8ZU#a|US>4~D91sT!k@cZV?R6Ii`KnMlsp#AX3=s9M=;QTcC()c5kp zH|94vE>zC^GCj?c^`C-=Mhx)d!Fo`Z_(H~)>a)3KQ^;h8Vn$Ohm3DYafyGuIT0JkE z9mYs(H*p?D8(-S%Xum}??z0X8?E_hO`ktkrjb#1iAY5l$(U`x z94qM|rnMiTX4r#c=H`-%)>nvJxD6SQjG_|q4;aVYvx!k~2a#ROsghb;|5Zda>(ZFR zRG*2Y1_pdmII)IfnR;?v$)_y-e*4JetyoJ3X)f8Dbe=5#@|j)vse{G+TVZdtGlcot|BkV;hIp|meCHYYhuX17x|=N^BgX-C`#*kv&qTIM9`jT zOPv%9Q2PNlt4r-*g~JWWzL6@|sQc`6IwPnRrVRV#8s-K4a@;z)-sxIB#S3&=!3sK3>+LW@k z)Fn`bI=jfy?S_-+c#td!U!6ybWweO(ievv%bl%}yy>A@1_iCt6vLc&opL5?rLL?y+ zr9G6ER8+EOD64Fd7D-9P=R6N7X;Y}aq@k!(Dy2pGo!{TMTt3&ij_0}W_xtrC89POp z@tfJ8^tXxcbubGiM&BobGmB`$tHY$D+l0Sz#0__CG^fLIoU{7QCz84_hrIAIrG+zf z>A_VlBu6-kcKyzzkrm^t)7KeftD74A9`>BvIqgSx74(tBcoCXC_>EZl19cQzO1UyD z9Q))z?E_h6e`5$4zT!=JbC1w~R7X9Npk+i`^a{qG$$+;B8 z=85ef%25;P!q1k}RVI-7$ls!E&K9&Ja1W`{t07BYUnC9VkBF5-480iEN_S+I(DZpO z)c3#h|I5$;^3VaQv8@aE$S6fl5dM$b}6lf{ul0MKBO4l=4bYk0dx_sArc4|^3 z=WI@_x3)b%GQZ1EnQ<#Rq#nunc~_I5?|$U_#w;?c^*7l4yhNn@KC%i zFsp89+8w>)Poidv+HGwPVa@m|T$iB~YxRG_@Tz1CJE8@44oW!K9D;U2`b5_B5xkzJ zf$lqQGCg;%fvk}-wk0isfOZp%l)M5n-AwRqR~(K_bj0ROvE+z(6`J@T#zL#3c+t3$ zAE+M-2WPzjDd74erB9irTrvF6&IzK~hQ@lvlkFai&I!ANsGy8edFA3C3G{Qt^D=Rt#Qv8;;8_!1^bgukemEo{m_GtG=AYsNdqq|M85G+7}J~ zB?@DBQ~~@7KZ*I5HgjEZUsSjvg})gVFeiiN+tJp-N{tX8sIje{y%m*~uCB zRLmOd23>J5sUE(IiO`>_Tqa}NYuK?-4}JeMVSIW4Hm~agl^z9bx}1wX^9@ntOd=|& zZ)S!)&O_48N_77oM$-FsV)3V|yonN_*gvR^R!XbM#MgdU+tUp>0~2}>;5wg_V$ z+(E;6Z;9Q0HCPcYh1zr8fV74_*>A1Fb>HnUNj(8I6?HhaYCg){nt`i7Pr|CdEv&qy z9yJoB zY&4`?=UfgX6}v4*A^NWw+{le%c5)0VUHdCodMJm4tl0}TO+N5;ku#F(dr_&=2K^NT z@j%;4rmw0Qwz*t|r32~gq5N)~JEaNI9u_jCa&KYH4G$>dyn&ai6R~)O79Nv&2^m*} zn2#ev(4g=SCY{s6$J;i*58hNNn|T4k#wVbJVKNHcxj^n`4-++MIrfOhTehLrm<_7n zazC@inWhKAAjhV_^8G2~>fdxYeax5D6bnVaV;r}|dJN74bKm#J2kqsJFlUkhhFv($ z?NkO}igpEgG1C(dD)~Xpj4`t4pA)P0wHL;e&%?4Mt&rn7gexCBh0G~Z&^q9aVdna* zV4)o9oYccJ?F{U%cOd3-Y*+u?`*|t1xIY+?wm&*%kcZ6B0RRT4aUyI z0U0$;0)9v__S~PxKiRhcqK68guetyq#R6=ZXF*@?D=bS`g$h-V*{JB5sQ=>- z>^ob7;^7&vr>mX)_V6w%)D}as#d?^B6YC+N_$K){s0KBsLvVcBL=-Jwh3zG-@M0u} z-u3K+6`$?dbB8O~*ZD3|z;QZi2?r5SCPRaPhug=sjEk zT2o8llzJdvGfxDAmpIaMCFXP_y_+QFyl2G&Q}FNQIJR$HHuT?&w0(|tM5sWBPT$zX z=#*8Fhwq)SwcP@qXmMR55o2oBkOc=npCUDFNMl=iN#2v)Xz)vw)b4j8-UklDq)Fm< zYKt`eqaaFacgNFx@3W!k!BL)3b0|1OZ9ubRAv$mCdsyOVK?64YM~tm^v*$kslXXu| zk`P%}AgpwLIDR&XK&O^Yp0EvGdUPED_&~S)st=i9~KQ z$F#L@A+`3+;P~q}iQYXxvX2_Ds}lE;eb=jjzjP9PzhWD^?Xd^3FkVM^`y@!YK{gTZ z9VZ^<%W<8QBpIK$mEl*8vlfefK>e~=^jP-_a?5x-y~|3{Zbv(^t6T}CY_-jMxQxGz^UoCh)C2DqRpOQ#ayE3A)!ws(A<_Jcld#inLaLKzBAn){Ky}d zlT5RUEG{^^pM8E7NCd;>LEdw-$VM%Y(5oe;i7yJD&2vs_-8@+`WAy#p_@v$?%t7J5Dj zfu_NU80vnAMrH3|TW9Oh9{*-`cG*(SVX~br&R7nPdy(Tt9ws(kCbYFN7kpbEk@WC; z{0Ud4;tlDQFd#OMb{1*kVcRig{fG)}pLd^ZIT}y(?w2y6S$$-cy9D{t%jGABjObvw zFj>eOB=VDtu|DJp>`39^@hR&e?6W-CxiXv?RguB1b&)_rJn3rgUhT$xWQ-&F z`NC=q1j%tCIa`bH7b!qmxjGTN@&byPTV!~*06h2R{IVhA5OU6yJhPIcBNj7o#i%bi zxa1B@Um}E;l5>Eq%I0Uhw*~RD!8l^~fHH;;y8*i!MViS*U*fSBM4Q-`a zB=Niw25p~Bm#mcLKFeO_Zpa~0w6Kc^kpWWacAGh^*FavcuZD>17i1|fiNe}!re}jC z1ex9?#kZsBQso6?d+JUc&3B`BSH6V*#CO1@E~Gaz5{hDX4youV?CJn@gr7S%(1yB%_{#4CaR_sR`_ zri-vLF}CDN`5@c4=N|LRBaKb>A7YgaOJF~)JumtV%>fp^< z27Rp_G67E&$X)(pI63_YPT+j+HEXKiUA7WhX^)Xj0bL|ZsF2lsG6JDz-$Pz)FKcq4 znCnC6gQfx3nKnuX%c(s~%*z9CiR+8p7ir_}B^IpnZew_(s){NbO-b3C*=!rPyE07w zi19ri;HBFp)J|T5wU;+jNB7N`>z0dy)0g9hjKgrn_7<=0TMMJXeZO;mBu0pR23GeX zOdfm)(_B43`I{6@&B}zZq*DB|GXm$CzaR>DmRsG8Tn{DmQDAs z%p!`f|B(-OR}$Bfi{#`c6?8N-MID7}?6s&b%)4Jz{HF8->Uo~=B z?p|q7ZmJo0lGZ@B8=mLhS=Y(lan3#QI30$L2Ezy%LrcX$TDaO4k~A05 z#ogzisqZet2kfTwL@Kpy7DWHPNp#NBrLg7hRhZalMZ*V;S;49cO!6y7x_O@{y&n=l z%Qm%;&A9@2HuEd*l#3OkeYzB%ZkMCd1tUaw$#q7iyOiJD`;W^A2jGK}+c>Am5S@Nc zLARp<C zMHjrB;DXye#=sP*FjBPU0H$qNglFGOBbtw9LgDd!IKyEsxqU4YgBQOcm%8Kd56AuN zs*mHmwe#pTZm*M(CXW)GA()YSn4L8^L_+nI>3^0Z91lMRjo-|nKR7PN!M1&%^wJ8| zZ|uWNt|t_cxED!TuwjcW$JIC%ykvl(z;6Q}~+p<53yqFTnu}8#c zg&vZN+L!TOr^nF? zsfQV%L+NlrR01Bv^T~B>L7Gs_2dyhnRCCcd@tJSQZW&(A-kduZE-%nxUmGqWd;13& z1AY=;mC- zfz2ybvUBJ#ehK!cO3`i5-FgaEjI@$1zh{t#-4p4(+^@tZ?K{ae{YBRLL@+y*hDo2= zU-IotBYFHNhDr;)XRfO>llZV;Rw@27D-b4+B=rfoVyHz0d%6B>hrKiBmz{AnN*M zEt|G+3X{6Wi#Badp{Xl2fFgci2h8h9SYrlB_`D5F2DGS&`w;6JW(r$o)e| z%E%-ZK#oBth@_Q) zu{)Uyr>0y72W1a9rkzKw7t~M=J3+r;9oU|7g?l|lbkwc~7SQ=nl%NELt@H5nHE$~W zT!LOH&*$s%+~K~#aw1=Ni-c9&;^}B?q6Ly~h~CEC%(;C@G*CX7Jy`XG+|;dQsC}Y>o3}<{l>q2#G8j<-eLf)PI$IQ_a z0KXJb@-cTiIgqv;oc`MZg0k^={9p!op3y+Y%&rin-6vpTVjgBmClRF&{mfo`!K}{Z z?uR*!^vii+EV#CjtW*00ZNFBa(93DK(C~MI#WijR*8Yopz3~A=GR5fG%NN+Z6MZBt zV*=?5o{I^C#~~(p3XxTR$6jdk#)w(FXpsFzl5s_WCL~9*)#1`~X4)jyg|Q&Pw_BNe zgT=H^-H>d{-?=k2ZK?OsX+$?7ss&qNA*` z@dt1&>wvjxqwI>5TF`mB3S$H=GjfyPk*eM6Xp!n%`c?cUsQ2oF>unAA`uQUa*R+yg z`+4-dj~2P@)dyFkn;FgRci5gsakTVF9+Pt41v7c)AguNU{0#a_40aTn;Ym zTn^b_!2mPOT#8l%<%L*qjGp_m4 zIDK*2cbIEmcdVlR_$MmZEXI+<>}kxXZJKA}?A7Gqk=E%;2`32A>t%Kycawel0` z84oXd?9@jX{j!WCy}S*l58q=lT{Ust@n1vFM-Dd3i1}40h#pUM;nOgTUD9;SyY&hvK!;gUr{f)fwHG^;>&;s=vr{c(UPrR=5 zljKIKW62v|uAjXc*B(=XV5^1nbGig}GfS{L(iA2i8-Ta_{ZaDNIh>j&02cS|k-uNu zFixTrBP$(ARhZ>byRRetVp;v?>bwuUTWsurS*yZI5ZC_sPXu+fmJqW3C!v)j5K>sN28rNXeBj?21jqj zz`X|adin(VFMSIt^|&!nT)*njWIGI%w?;p`c__ba3I9p!7z%DOBmU*e>_jDsPZeUY zB`%PZ)%wDzC!dMR-DB{da2(mQ-<*Dj7QVLeRgzOz3H~bxt)IP{3?Tciv(By6-n9cR5+Hbh&8d>LEY~;S+LTF|qeAq8-vVmwABi8F){wXiHM*&DEt&kUjVvtY^Pi6{g^|{?o#j5v zTX@6?;yYAupOXdssyYF8zV-)V&v^(t_S03i!{jlSmlv&EiU++zX_$5qbnzw0#tr%K zsguC1qIPm?8trq)9Er$2(5 zwhAr&_Jkc2W#C9h2ulCpY8K~hFwjk$-ZG2=VVU2sUSE&CaNkc4>!q{Z6(MZL2*;GZ z@R2+}n@-w(rlaA(KP2RL8&hGHL?<89XRYlg(RFV!h||}bME6`j+xct>T)|DE+P5H4uiqundlRuhQYH|LDzsZJ>Oo&X7Ku%G=mM4 z_N(#rZcEV&l`$e0y@A;%eT-JgPQ?U&1?tAR*k|R|lS?L9j0YRbOuO62uIW9@GweCZ z)EdpAhfGw^(~tp&>7le^JPq#6Rj0QKs(HVUEu{h4<@DJSRVtk2MedY`LDr}&e%N=N zOo=_m%e^y7=pjpNn{9}%Z`hI@VOPLDm3r`kv7gNa!? znct;EVvM$6SeyV&(AiA;-4&jvO8~qdui&5H`mTG|2&1uWPD8<&d{*4- zIyj5C(+zLrsX*u?S_J<<{*x-4KJQG=NzNwXqrIe5))#r9MeJ!+9s1yED11~(C1r}a zkgQh$lY5s!!}LM8b|LDjs|T^@4Xu#}rYLcOs4se5qs;ZI96PT5sTF+Z!fB_y&LPjpxKj z+8j)O$C5eUL~)yo2z!a62`sWX&;G0Qp*@@8(Oq60-#tj8PUqeLxxbuLz9=MV(kH38 zg(}lCtV1_%Ob3zJUOq@~q#HD3>H9<@qF=m=DhPdre7`z=NbE#bmUF-<^6H?xc{X_a zi_+~+bTQPV3^nwFfz_Bw=T%-JksE-99@3?CoEvP{4qKY@ma1xVrtXK_U&6q)eKAe_Qg_q%ifx1svl#LCfL%wM>!8z z)Hs}5p@K_$)tI=<&urnICbmMUmXWq!N=E-WW8%_O9ur_nkL|w-%L+Z%%a2S@L+LTc z+)aZs15(s^K?n-CrcuvEchH$UMouZWaOas}SpDU*?e05@bfTUaooK+&7Zm9NrwXE!Gz)Jy`=jm|mTd4d=YN`DLMnay*eA}_WH(WuixXW*I5!J@`azlc z&yu5?KW(F8@4eYIIbYbVMU&`A*f>~j7DMw&Q*8M935tUhxc=Q$a$dC;erG-+KY1PS z<@yd#+#O9Wz7V3fUx(0tVK>6%5@P;fs7G?K2M}CV!NX zAH-)ov}@U&jndTgq##;ly@3TkGQe#XpE2oIqq%R_0UNcg;cUkIhb2yo zUPj37t#ngd7CH7Po|Z10f^B(+*^T#RvA-R;`QnRgyzQY&Uumnr6Su`=ZsKfuarF!; znE!{j^~)$<<#H^!=TuGisv~MF51>1CxY7e*lNk5@J%p>t!xxK9Bhy7Dck}-V8L_Z%>onWsuwZ6lf7Uh5q7Z4tu>9qVwiyOc6=vUtonIDH zP0dAcMj#oSCd}hzhv`huHwhYeA&VaWv79*f-{JOCVe~j7#`*cwu*|rPi1}Ke_}mku z`ldYVyMG5Um(HiZ$zN7;Wj$N4SA|$DaDt2}3y2n96VuMg(fVhvn90op{0@#yWmhSS zQ)-K#a@d*rtvQP!9!c;~afF#jM{OBTt|x!)5((J3f)*!u(#HGK>E+j14GsTkWBgan zOLV=Q**5tdocNhZ4$H12o6j^t0VyVf3i5PcayJ>YQ=%>o2J}Wn7x|$ki{=#u_>yB% zI`Az}^uYr1c5)^SR~4c6ri}7`^_9TECwCc*C~KzVnmEdhCqi&uChOhekLs>haQ5u2 zTt}veXo_Vs@6&woL;on7bh{pMXLpf*%~lxOIKm3_8ByI!S#&%^2bX&MgvF_uB#;rL zOA`LVPqhJJ$mjEx$sL4%aE8^q?ZSre7%W;KN#+0EWDbp`6I-t-@Pd1HY8XtXQ}oR6 zUZO1fzAc?jUzbK5zp3FWolUq)^do=RON8z^e1JE3rZ+gdM^oJ^;%M_Yg%oyrFfP_Y zOz*AxEDf_)uYJ$hli+}E9U~$*~Iw2_orTqp7B-BJmT@5 zN|7r;f%Mb4b7WG!Ba^;EhdNto(7BrFr1qW^`j36()ANyFIxq+PyLqrysh!JTIn$5@ zF4*(hmVUqb4eB0HkXfljosvhH3A3CT$FS9m@#9+K|LQ8%HXp@MjV|C^aK zV8cewk-+fo5mG$s2l?$MNBz}XsjrL%z2Q(rGar5jJ6mqoQt+EiPFJCV_g9j<$H}B7 zFbJLx2-4L*Z?Z@0|3Ga00G#LewUhVWBQsyDrDLzf=!(1P#E4^?z5c!f)|?z;_5Rt= z;$TDS5ORSI8vP^^eX68oYXOfevLaqN$z+%I5i+)M6QRpu;mXB#&7-&0jfo5uQ zPAgB239_OXHapdly5fgW?-NSoey)HUiqXvV*u_*NVhpyg;MfjYzu0LZDNKjnWb!;q z730Qtv5%uZz{dnlT%t9XCh?C0bvVnOfth(8KIfXJGm$bmtpA3yo+>;;v)K^XC3)&=f!mPmXa-RGuX)dRKihSd9 zEblrG`sNn*c?<4h0!{3par~2QXHy#tZ_~o^zsredoigT3G{UI^_sGzn3@G^$h^C+G z*wD;aoc|?`{a`MQo;6RwYVLoa#vaA2!gx|_JPr>ZJcke5e4^s72kc5S!rdCLm_NT9 zv3pbwUq?;F-7{7|!o*5^__7t<90ah4DDo?hYr$CB8ytig==AI~7_=WGm&?21l8-5} zcW*J;yVUXQ7X_j&#OKw>WniU9C-`nHhl?e-xM{r?{)%Z}!dgX$_S6l~t|x#>7q}f_ z_iU9V{Cfxwr-0V<`JKKtBe1YyB&S`f@ z5!d9*!8`6}Ns7HIef7_dxQf1Hf8|=ME6j0B37eLzn3b8z8juDcYP_8FTAM|PvV~$(g zcJevgeZcKHHcUqi+YRJbsy>Xo+Jh_NE`f&vL(7|a=pZV?oePHMVk_!z zwFZwL8s?t&MSO>k`}hZ2e2^Uo!Csj(R`XUjTQFM^hF0q0_UW_P6CvqvNlTAT40%sp zTU&!ma}Qad=SO9BYT@+x%BT|-&xY-HAe|DjkXpD2-i=HEGGP^!+2Rd(Z`1kri*LdI zIc*nskKn^91|~LrV2{39!~Whj%-W3Ag5SNDe3Knq_rperZdfx6*Yb>Tm&ZF^*Sepu z=b|VCOa?NTGKtpf*29vZAuxO~gYFn^B*8q62^?PlKNt9d*iCU<`N;|%HII>7Dh{-k zV`%4_>0;R6RQUZ)j~+~yhL`egBm2l@av;PgJz9 zf!Fe@aZ8&C_VIS0jJ+0C9{kLn9k~Wi-fqJFMX}6gv!7(A)l*!ZFGV&v2EmWS0Z`_; z4OzEuvzHfj!QvZBn2zs*aF@TGbTMWFBygk*zTN00Y_Azk7m~nWgCh2W^fmIxh|B4vulNtBhzjC^UE<_rpC;_QVFA}?on}9;b|W?ox8balI4ZB6hZpA^!PO7D zKw&~QOfyv@o^PMPh9V<0D7%80&JVHAw;c@QIX12u0fE?9np?92`0J(dVel%PHI{`c zGVS2pG7-;KTT`EfXLu$vFXOkZg7k@@6)HMDg6B*YJj#8{%-QLSwHlj2!1y^)6ga|= z>JLymq=Y`ovw7WnG;z?{3}viVftzF$zU6vQrQ7Gyc^@W_VKk*VvxVTTk{ET=5v9#5 zEGb-QCHo>YNO5)x(MqZ%*UO`@#PK#2dK$$3jhshA1}4$DAsvt&B1zU8^s^t=N`iPn zI+Gf{gz>DgVMJA&$%-%HDD?3fXngagBbO3T0ZK{qxnZ!|*-aWY$&;4mPw;(D3~^K2 z17|PhaCL{Y#1Ejn`%D@jvx+Qks3#M@3_|RhHnOL( z11^g=)3E|~?ySv&lEcd(DDD}v%XTmIRanht{~2Ms;v1OnueE8+F+1v|dIp|cP2+X_ z8)Em>-6J8{YIvbvk}iL-j2~m%NLpumP@k{MFi}gJ+68FCzUCH~Cl*fr9@tK%?l}TI zUFOW$Y3Wo&$b~v~Hu0B>_ygiP9wU%TKV0REL-~n=QUGznMV#Sd`HUN zJc#kvO5&(`u3?iDmy1bTLWBmM5}Si*bSiHaJ5a%$O&eOE$FP%x7tDnK?^D>cx&@bi z=^$*3Gm1^$3)aG%6K;h8jtPm;Ka|T`3Y3yles9>?HL{Fd%SU+Nx)mEz_Tj~M|JV_Z z%M|z{z>N8upheral_LOJ+ZH>9b8?D;btw1Y+wy8 z*v7dW#1z3rR~z4RoJ#kE4Omgq0IwDv#Ub$`?7xM$&+{sCb@_bE==%nx2dn9;Q>D1U z`Vy=Y2*U57x+L+s6IvL4gL=8^AXeyrpMuu0`%Y}Y_UT3VZ#15bER$mH9O}cT*5_bd zTH?#+(tKJe4)>(wq5noU#`u}Qk#aE^(cx)z-y z`Jmfsg;^nYag|9T%FX==neth9zjQ8k;c~2at3e*#JPQu{24O7P0;e9f#nT%&|KlEx zn=^9~aa5R2{uT|9x|VRVcGP(z#Z zZ6`?}VGS^z>t?F&Uxc^J((w3uLd1>c;j=ZNWt`7kMvgwP^dW5-K(df%oVFym#g(^Xc&6h7q-7)OR{e%*W24 zSe&=P1qN4F!FI`HII++LUkq0<5|70|D*W)LtpT#Zk^f?0P_nNCEn!`U=xNe+T*dP!WeJh4FV}I9_fMrSadQ$()lb zVdA-4jClV}s82eGy!ck~C*uqozfB6Cu2$uEV}!&GoPg_ahOEEyALfM%qTA$QcDh|2 zn$%CAzn{5LmzNC?T6+ZTTIb`7W-GF559gU4C?IQ1YH@OM3tu*#ho(}Rq*zn|=elix zcbVMIa8#eyS)k1IBI5AM3(o%-B!L%CZ9q}2-B@fC0=qVFoxN=nc(3QAf`~;P&MJAz zjM+|rx{>*~d9g87Ym}l*Hx)_!urI!=+DL92FTr2CwqaQ1G46cAIg0okV`$GbwEEQr zck|X_-l5G<{%=U3U2X0>Ys z11CW>i6dig#BpzIG9*uvgKO*&=IH%YCVsOKxCrGE-hp@+KQu(%23VnJs~Ju4yTP6c z-bW4oyFv=ur0Da+{Y2q@ENnkf!tW8DPA{F@33U8B$p3Q$OYh@!c`TPL?y*LRn1%eC zXZ+~N0y7%0aSDpvYhjcZnUN1GSnLSB&UsI6k{o6-KJ<`c1o@h@WpWy0>S#>^UsZ7( zmnXcQ%;)URu9r;y-z3Pj6(ZSrZB%e%gn<#K=-89pFcknTxVWh4)4BGOrf4thZy2c8oM+$n`J_>nD?uv-_xbvlgAPQMKXp zGs1*DRL3y0O8%F+r?Am^3wz7C2Kz&!aWcp6iEFQ8o|G0a*15lVPZo{9pVnSrBMe}( z?K!w!Xo%b0MbPIUWhPBq2(>|1VEMN=%;QO5%lS(D@-P77JcBT^vYNf6ZHU@*JvzK_ z1l_a8@ROb$CdAx;#2;>Gt+Ne%(wvyKVrLwgnMc-KaKZrVAbeL=SM>2<=ly$Uiz3SlZ!643~D#rG^w)JrT zaSyx{&B3W^1r7A+F_1mh55`cYLK-~|!*EIl zTJXjg8AUEP@Ff)dt@3e!>>DP0Unco{VFncYAH%miM`pHYHtc*)Fx8?44h)ImCJ9sI zpMQp-Z|#U7V-L*JP84X>N8Jj}bL(P+V>i{X>xwJ(dA?-KWM%Q-!y?WNB1jKh%Ek$a z)_Cn|I6BR|2fq6+;2q&Q=F{ezTpwjMQ>B`Y*ExQHxl|0EG$IobJM4$Cia`GTMMm|wk&#FRNQ!G(ve9#59VQ`6osp$GS3Q|B;qoSG2Bs(8-l z)I&zhwdmOeoWDXh5ij}IlfD&AAQ&1zi+a=X&7CtaU_SwC)|av;dpAK-${KR+r6N?s zo`KO@vdGUm0QmyJSiK1`vyY~L zT<~X@zx6WATRacG+eP6}S1P8Eg*1(w4?dS|NJ>~3Gj>Lez` zRs@oV8{nNvB(4+r1|E;q`3FzOp>*|PjL{Fl)LaIgidJL9P7%!ZZY8E>k<8ikGRS(y zp=9Dtvgh^+{4!ASB6QmNz$-cfWt!HIQNJ{FP{<{Z zy2ZHX|0O(15yH2Z^L`+^A3VQ+ahUyPfNzPo^0FS9|~ZVIk<3PVuWMXADk9P(&| zwB1th^sXh8NZsdLxWd?1*-X5)aqqDu#&~r>I&6Gni2BceF~_*>lWT?;QmTSmzMKOs z{S}zoRm$A~#+Z>_d2SE0o-ZgSjPe4(aHh70Y@4FSKXQFCz7O@n5~K6bbtw_oxknKL z|Fh)hxeVB}Y$JRa48g`{!LTg36P2^x5OZ$>l&ULdCj2K&<1!{;@YfThy#vh#Df0L>=oprDETGStEbx-NG2OB38;R*qfktj0(>)`AD&Edzl{rytxYhwGsHBft zZx)aS;4)OFkI?eXhlqqk6`9l9!QXc16Z?E$1G)cdHeETO1p@)%RN`G)gTGrI`80D9 zBl!6>8(dXR=IEsJj51G?^=s1TUw=p3n-K=B4(gEl_An;5ad+-nX>8!b78q==Wu1FA zK+TSN(B0{cCyI<|sB|c^`ECXIoZmoN?H4e5T;9~CW)jw0&7q2FtNEU}X1CmFvQ&tWqGorh?4Jm8i=*kp%NjJ~>p#*g zV1u_+l4(GhK4}bEh-yv?Y3mJRVr_e!QPGgH)w%SI`P`k%3hO?D_l^>Di$-si@FEFQe%|8Vl@W> z#@yJghWRj~uaZVSqGa`Dce<}|3ezRzOtt4k(^?BntmF30d6rJZM`nmWt4o|VYY5Q4 zi>2u=bu0R7M>**Fgwp8eXLyaVa<<_L2jG6O4F8qUOSu2u2@7I}p-s4v?RdvIbzY}{ ziJKNaTBpYr>My`~%9*%p8{qwSZ(*_9cj#~a$ygq*#^z~9VE?TGycMpG_g3b^@?8h; z@*_zczxo%(Uzp=Jvvd#_wI=qYmdQMGrrwWpT3Gq4$4$~NAojf}&gZfL>K`T&qb(eZ zQeqgCIUcpq`UD(o`VKBHC-Y=had*ML!u0DvHf-LTge~nKpke7GoVx!Rd1Z4H|44p; zging7xlx|XedfjWsZ*H~k2}Gs=OR?hIK(LCuZAx6Ei>s*8s2?ujE|?x#1ergq)}}r zj-9=L%*{yV$xa#6_Pzp(H+&?;KXOq&{1}SuTZhdjWgA?g9Z_;+A|C4ZLi5N~XfOSp z_b0E79p^YA0d^8p$oM$P`85OdTXRuDf}1z4*$>5>kL}9iJUl0nN(?wo{Nffxd|Pq~ zQi3aCRNepw{r+QlL)n;^?@l&O-;Ixgd%)?k8GZ9w3UjK|xU8rQHtWT)Z7t8>yrV2= ztbGfbO&&lu6=L79Vg98jLC%y$7Y|{Gi~g z3xvp6z%){EvicnA#jv4$syu9ZE z>M44lYHk$B+z79cUhjM0sO-=I(+o@E|pfXh$%3kA|FUL8F!;<@AOjOrWT(W;RWc{zSH;>Ed`~HS2O(M;ys7M2mq*0x;8eIFEZS znY?Blamw2U+4j;*>gprpvG_ii=9!F#j_$_aiDuY7DIH=B7s2@6EIg`tl7w6k;_Ca1 zFiDs}L4OmnO??|NotnoERk*<8n+9mqyBG7P=wr{6YPRdq4HC^uGizHl0D6jc_)$v) zb~Ia4dAYBUA*7C4$2k4HdpEJSt_Js~rQ^2%gIOg)v7BD5BW~+^0Z%T-;E>xv93K>k z(7Tt}=C8vsQ*!!v`SBn#s|_ppyIHnjJo?olo_CDG&6mPJ?{Wexl;?P^T5|C~yA<(l zQb3u^9Zc`(%jEK*M{KobBt$J5LDh~OVGi}VV4>|QwzFd+2wy*nc1f!+FDn-vI*gF% zScYO;58y+~n=tzK6*w?ammHZVk8`L94LrF8uh$0RCxuCD>o`WbQ`1US5tmFcQykd4oKTckYv+ z4qiVb4q9!wI79jfESI?h;q7l>*E&I5FXD{yKm2g$Z8l0jQYBg2rr-kIRXB6YTKvGz z>8^a$#1E=md@GvcsaFsrT2DAG+c>;;J7H!I|Uhw4Z8( zGMi1X#8V3HZ&xEHXHG^1zGD1r9DwSDHSBEX0f=(q;wlq^V9bFDq~=*BZo7UGd+Mek zmk>bP`m>DfhsugATvLeg>?;`SmxRAQd7$hAF-0fDNBEavTIIc-~|&X2$z)nmeh`_gE7pNC) z$|F1UcEKYRLALsvF$5n!04A=7(a*LEzKoN>n!5*K-l}c*?y?!P)@>4I>H%JKv&Hij z(P*UOhpi_8l0>$e{?Pc$_-Ahk;rIV%1!Uvu6!Bj<}H^DkqFWZ?egOYwqY8uFbZ$bV2k$3fP+mqwlmt4BwH59BD2d zTYJa!P+cA9WeQ-*;RU!h-V}#a6!A`a5Yco#hP)jTT%D5$e*1a|gY&{r(h|r<*MsOQ z{2J)y&9HZm1qvS9itSy8pgKYlBYC>GQ~f?>1Q^oGJ$IStpmF%w?*qJS3&UOJp5SaZ z8K>P1r876X;+9W2v*H${4tm7eX@y1{^dDH&S+v>3KzRHki|9oO2Ns6>j99ggZ3XG zq&)N$M7bkAbF@Zz^{x21RtoR^`VG+!tuT<&9$c_`7x9WJ!p|G|aQEIEd=PdDwTu>! z0COE2bw(ZsT@S&a-cwMm)qzcCAc0aAYFv9@G)(Ik z#84t*rmgxNw!&5}6JUcAS_5E>T^e*I24j0z6kbW11T`3H-*|;q%}Qvn1<6(3XhBwX5TB z5vjo6zZbv;s|h$mVgfzD)y^*n?}nm)+eBf823F1s#^uirzd=ggWRQaTtUx7LwaF0%zY%gNR^$oUif&_zp*q!NgELFy_vu+rM0}%Ek%vZZAN|bP-a#Lk+t+I!O83m87w#9~6x4 zlQn8a4A+drY+PiEJHBqi%AI4uYa7Qkk`)V&wjYJY)ZeURq6)s2eMx@pF~TnkeIP6* z4;r|7<=YKncsy)8-RV${y&g+ZctDn#$g7jqV_S)tR0KPaqd_es@~HbnEl`@em~>>+ zGKZ!LWA5X8Qk9lL&BqI3?VWhuz3)QcH=sqanY*7Y9)h>Ng7{&vFNF6+g8s22Hhza4 z6}bJCU83bqBJ_8`e39S4H^YlG-8MC8J6+Dcd9Kck z<~TT@MYQ?GLH%A$I?pPRJn|Hz18NFXslNmo?+IhqwG0ySp%}K-hoNqR4$XbRaqO_s z*rF87S|6Nh7Vqv(Of)xfTqjlJsI(-d=3kj(YmCUbylv!Nw=69S)TF%}hriokSA|p0 zWwJ(bIj5g=fL!EszQ=nhQ;WDM9|RDs;Av4(j`X)s_bhU%jRh}`&Z2mtfld$m3O0-#N#xj#iNldyTBj|seUJ{h0x~1)Gko*9d*-%G{dDDpSFR80cetv4*{r zu8YfZH?TToZ7@f=ozx!lq$?CSe%>Rqn9t)KlD3IouyS(fGjq6bq{RYyukBIod z9_Db1FI`_C!A$ygo)=m%jnTOE2pY>GnYWT=kmsdF2mMU2o#SH(%9Nqe8Rto3fH@r# zSxBm5OGusO1M)U|BC)FpZRd* z=ohwQx)vGhEP(am>o|^#x#auo1CZr7M5J@~Lb1#^SbSWGB##?OBXlC@^=NbAQ{M*^ zd5nEWDFku)WJSrG#`>onU}EP6d*$!4fxgGVe2zPsw4^YvHd~>aiYzUCGm(AQFHePI z65;)76?&)h7US@99LBi$&}R!?lJpCX_u*T{nbq%K0WWF6l#Hg-`kg#XASzmgxr{K7H#!B83|#dR|Ws|z41rXz5>NYrCy=@K$I_h_&4~KL0mi)I0UQ#bq;KvdP+ql( zcD5cM126s943I+J)6+y{ek!^8XbGI~L-xmoOYGR+w)E;!BjDe1pT0aXfn*jvWVdcw zNNgN-!po-;7~;?M;cTBlACgA$CToav2AD95f63B|0jHSTMVsixTmkI2T1FqWZ^qr4 z+h|Zw9vn}93JwBevDjK16Rz!risqM4`$CI+ODQG~IUeou*&}Jt^>fhZl1^Tf%i)R! z4b-*0Mz%Q$g2drf?8dJG91n&*eZ6QM-Ezc+&hacD&ilOaT!{r)ts+O?W+f2c<6%tx zMO_m4DFBWiD}sr~gBj`WY?3lK7AC(Njbx@C#yRf=mu4AU(K={$TqU0QYPk_FbMfTe z>$`br)w{4Z?=U%{n293gwM4Fy)9&JQ-=u3LY0aq=_G+Riu7B5oYxSQoE~4vjuu6w1 zTN{tX>Z34e-E7_$sW`avO#ttfF2HHD1V*fPH(RKqY`WBG9oFk|Jt&8-;q|;m=8Ud1 zR=+AUle198m=U_D&Goi#OOM18%Epk$XM(SLIsUMnDwx(LkCSUHs7|yY^HTX4S#a(N zNa`j+i%cXsvnI@4L+*J@LxddE&)|3#DsiWSG-h1Y#0PWEkVl**hsN1>NQ_oPTKmZ) z^?oR;qk9$Oy$D6$-n0Eat*&v)! z`E~RYsJ@tug zZc}G-I*17{vNIHWjLV@gb2P@5kA{|YHpq^O08gPG;P^xxN7^4Gw&rPYDrz>0${XU- z6Z~ZSBWr5SQErmYr2_TuX`TVO5D`CY|H$)#l?ZX->e==PzMZ zPz$th9srPRuoRqnriVMF4uQA(+_*@LVw_qToZ0BmkC{4B{11> z7A~kVMY-=X}#*`v_C@&r^hw~&QZb@2GrJeVW+mYn;MgpVo5VRP^_xY(O={ifR3GvhPY z%btYJ=j3Uzm@t~})WvUAEZR<=iRUlJqVY--s1V_5txt0G!>t#=#cUQXT`mK+-;QEO zar!p%=WQh)HDpw1d!n$eqGSB@ju($j*^HMDd z#Ko^w&bm{?DE4lEYh1kAO)s3>`YJ+S@$#8zyKCV0uQBYVXW5Jk*V8Gje1JJ0?X3Ili<-M#J+VQjk{FE*w0qOy8Lu{?8{}? zeqIQ7J~YCQtNrM6*F|)9vLYI6ri`bBJnFxygnPPaOjfNt)(}=R^yw@(67Tx zAJ&t`S>e=d=nEXrI!1oPl|V_+J2IiZh(t(8ndww~ApDW>cxk0GKJryVJ;j^k>Dx`1 zcrlh3rq9Evf`@7K>k9I&7^#-i8M41Mhgs+O3wS@ONcEX{#KKjEcJJ*W7joq37QtYe zGWdoOEFOyollS3(-4Pfg!s$mvHWKf<8uU25M!OP}adUbjoNw+UT4htvTjvm=1|CFn zvD5JlfG}#EFaOo5KeqqN9$&7!8KnLv1|TL z_I2$G(}&N3=}(jF}Y{B^I@wAzSv?)kGxYLJ!Ace`t;q5^apKv&cB|#<>E^(6lTB!AxnH}Sq%~w z1L<}fah&k!3>!T+o^Jmzj>d#MX5{VWVg`Jx)Sq;K#@2Q-dvA=O4!4b|L#`^aUu3Ae zlO}yT@hSYW%4V{$zuOjCSKlOwr~RqJf`?FTU`r13=2NAj zLsY)AjX3295WL^OCJynF?xEw4){ZrV(ZC zdH&tq1~NCUh1`H0JinZY;CnlPc7NV&=Au);OlW<>sD?y9W@8%1F?*LyYG1}i%?@Xc zH(C-!(_EH0#ntEcNn*+Tb2NpGg&Xs}Gxu{0i9>l$9W}bTsZ3n_(&gn(?PR0rra=GHyOKzfrU;%M4kB2!2 ztWd4t0aK@%iBb(^W)D^xkdYcaAoXT4Iy{lbVD&ZF!ky2dk|#{cD?^BPKMxw1?f8^0 z8#yUx5O{MHZp0YC`=SQeRbGGsW2-?r>Mh4tb^u?_oI#B?_rbxG#gK946U!&k$u7MX zMkd%U#uDda@Kf|2_`aM3yA#i0Sph#QSe1tF7;DDrB~^OLa=o^4Cao+pmQllLetxsvN=}9p~!46wqk=9P%jE z6qStU;BlTXS1+260~Pb|ow6Pt7hccW4MfwcZG2c=DufqpbBVP2RT5Rs@zmL$g&q?} zoFTJ-@p*BAw|?#(di~x+TH5uU`auK910hBm;gWWlss}XEgq~k>*$l4#Ws45>xzBoD3 zxn2pxes(JAOkBytc^!tpz-vsCwLRv|xedaey=K{pGq}2Eb87ySh5jNB{Cc(oBLl|6 zB8hEqruQtY@4Cfk_axvgqjXMFUW*w_b40!o^)N7R5*BgwpZjb|h+Kaz`tRZ5_rFZ= zCI0|q<+`GT=^A$3Y<{|Z-&F=1q)|Hi^(^(hQW#OW$i(_v1o_6*qSh`Iq;3v@*b@Qx zGu;m@xV%fYJI7(S*9B}Bt-$ry@31FF%)oPe@|f#>pIOhGLi+eH1R1DfwADzis(2i# z1XN;Ko&sJG;7BbbAH&d7MdoMxGAP>g6>I#q;NssQ_)||3vOnKuNm;d7vHxORr|pb< zlH2i2tuwAi&c^-1I5HeiMXHUInO9)qrNbDSy$O@lW8i&9uBoY1FuV-@#AF6IV@UoQ zd>G-2*K0=O-WLKmIb#toZKWpewARGxvkaO$#jx_?4BFN$!fiWuV;&cqJ!&F`(j$yO zLXaPK2p_MkH{kk@#(X6n8W;Taetsmk0HK450w6b9{8KcMqnEt|N^AHxMR z;n>(Xm=fTEQ6}bi(5oCK`)kvzptCq;gFXoIH9&la2>O)ufm_B!I3ptlohk{aFw!2A z4;x{4`dl{fEz{(lH++CkvmVCn zX~MiCBT(|rX|mAj0BF3QkB;^X_O7@Nof{b(vRng_I-kkZTah?7(i4MJufoIJL8d@K z0Gn=#Qsn~&vBT;GWF`-Q`f@MG^8qxRy^9Gj)I-B3H<{K4(=qz%UB>g{2uw)o0Mk8# z(Ee)~c5<;%YvUKp#^t{VuTYQ-hNQzD*BBgo(vRs2G>59wQD*zJoXpDkSUAon0E+%E zVDiJKyi>#%?9&kU?K1(J#xxYSjD~R%Ml|AzKO2-4f>(B2f+ULsJa9=B&VUA6>5Z z!5bu=O{EWhd7#ZJRorJCj$JO^IAL)(*xz+ToLGg2UVg>I9(U~WDZie~~exo!!*&RGX9>csF<=?&9ezD6j9O4$7&7F*UHVy`Vz zV>+8T-Kmz%q|TrkL^UI^+0Freo#k}So9*!1`$gbqzk)d2JjC#pr-0+SE>ucW#52_g z@a-3l2kyHbb28}|n-Ud{viT$Mev@Z;I+M&q^vB^u=`uJPu486g*Th?;+Q{Vub@03N zFVbowiZeD^;UnQp)L5>|>Xa6M{4!OJqs|K-b$Sz@_lLo}U7B}HiqkX7xCQbH9WYHY z5B)>9n7eKv$T!7seW$u~?Y3aHcxoCZHF?6rvJ-f4o-x<^UIEP}`KBA}x1$6*1*&Q| z4e`f!;D+^fj_08qcKh-}bNXoFGqe-sgpLsjz0KHi_9fhVy#miT6HwUXfyax!GiPgm zuy&I*aVYvSQ@X2+cyvDi1?9~+`CtmZp26U_39;}-XFns=DUGSS9>CzqB3RG=oCt7Q z6I1-{Fz{|Pu0FwWN^M5CF)e|J7YD)tbq`#6(Gu5)uA+XcT(G!86RS3ff^J|jOiHbR zeZ~ryYVFJTo>M2krMzLOR~d}pbm#1H3&vPZDD?0Ms`(G03JwsT z;udD%(L^YXXTg-?^-6f2hDUhr=$>B9dl@l{>+RDd`z=h#fpm@&=+PvuW@9U)aJ4sr zpOlD~3qKxh_rSrQXrK3Lk`J$VPvx_D&<#zUDiox9LvQtcU~ba-1X#1!b&c#4q&o23X`3ep{aQp z*j*S4mUGYG_%bQD@-2mI=q`furULv_QUGFsmTY5%B8uGH!JaN`V}82*1pm!B z_-pSurxqDYFCnYrdfa~HH-odB zhVdm3n3xDxI*PE(M~00Sw1Do?5ZqB~#c@k5#O&D&{M7i#o|}<`k?$vy=zwUna;pOW z@Cah&{gPQM;)+@&^`!6qM+jJIi%K?)IONblc5E>wZG4;_@79CZI;o)lX5#-rEa&v7snw;ET1~8tA#` zRi?gL86R|5GXirWn7(b>Kzncz%&m>(joW+#YTg_)n|)P*Fg=FU^IkmD9F#@GHZ8(k z#%I`2k62=Ixdz6iZ8H_$B98eh3SrqE189XY*zamVCWkD=-|F>fo6U#gjTz__8HJ+* zXQBV}82FgS^@{B6f$RWz9HrL_yF7k^$oUxF_W1oQIk^Fr#ED^zvpSy1?}v$sacphF zb=Y@P1x?yCK%3+3l@ayDUj-cRkxec>JdU{Y`C&|6c^*X9OVMv@EO6;EPgZv81`=)_ zg8t{Gg6KdUyfc?YvGfgSo9Ksos-3VO%*ZY!*;$Qu>xlU6WVCs1$o3IOyfRl7SM|#g z+XKyvz#AEqmaB!Zd-9~@%w(LRe-ihZ^^y3@P3ZaiCp-F^HnY1Ee_9`aO;y zk?7{*U|j=wvWyR(F4&1-zvVDcpbk2gS<^D_DR^pcKK0zVpH;L9WXz=8VCcsIm>?+x zLBE}$+td$vraK^OgEZ=gD`MuQk8me)G``Gn!V`lnkP@@5+_`}tPdLqHg%|t)r$QmR z)4vpZZ%o4W3&v=>=mhLuRRq7XHW3SY5~h1j2G7_m?B(j$zPz0bO5e{BzSKClt*OHJ z>Yp%c>n4~qPYkEbj=)}ReYih?hS&B>VA8WV-jT#qHZwn*!`1jgS(c51N^Ri31a+cwXK75-D02`P(Ff0G%e zuc`*zq5_NGFUGRmWK39;0RC>_q^BW{JmP8|PCpmL#F1|p|EVEh_u&hf$*t9Ht>oG- zUv7X*D+L?~+lTA60mfY3%jEAoOOEwf^6uFzM{FET9+b(V57!UqwRkhc?QMstH4}K} zx5>bEeF60UehG8s1aVeDI^1%624dQIhs!W^HLsuxQ6j;yX)%8F^Eav2f5vuP8;d(w~HeYpX!@ zc@lQ95g0aS4K6uujn{l!QQOfFhiYTt@fLepADha>ceU{T@gO+Uqr*tXX`<|&k#vrG z5(x~O!TUl4ajLK*hKU=3r3i(qz7C{4eK}1VXaLngKeG19D(w3x3BG|P#8!D8IXQHj zY*_~2RAs;@l)oSe$0!Bo625sX4QGW5z$IUJp%jRU?M-&77mGul$1_+$WewKAoj zD!INC=^Xm4xQI;Qaz$ zqa`~T^&%lE5^qHp?~bS4GeY2U?RA)Ixt8`UA3>j){eZ)dGZ=+9)P}^y4tvZzYPsHYG6B8BE7roWK?yQN_*g zieZ#y8|#vt%{b{t!Sd#Cs`H5-%vwu8?bjqYH!z*7EKltKB zY>u(P8z+Orne$xzu^1z5u%B_gIfA|%!)bWm-ODYw0@?YtYBZ|dn3(FhVuo=HX?ND9 z;zzaV_*Z^p?%@cU8=hraa8#VrAyTEO>O5x0!eC~<(qquU@o?oY)NoqHO8lb|4wtV+GrUO^11`rKjdgmQ#shx^bw=dR#S{v<7}T9zqsue$TG$kfk!-nM7&BYB+7z12OfooVbaZ=jKsl3cWVl!!C?9l)63Vrq-uqC<~3{_cMO_P0IIp#3^X z>m6l6B^>Zpj|ujyK-lFNirGES0l8YsbKLWHB^AY8opaEvH4|Qo_CY+yWwYpMILyu7 zjuWS@$1%!PVBF1d!Wi^IXwGPwFoVzF}vZ z5{|UkgwOAIV#|XlywP|ZUp;ii(E3meGSUP-!R08rx}1?*IT7!8gkj%vF&sM92k+@n>Vn!0{9CnayF=hlj8pS3kh5*%L9)MvEC8ql3vJ^Wb&z zDZF2_3i;$mv4wd8xN8%SI4Yg)llTO*E^fzXr+qP{Ad%6c0bsS{HauVE zi{4TOAgol)8mWDU%SqEQZOd}j?A{NvOB|=d(-%we-LKO)=b$p`%w1#V=OMz?Z>F>U z5%w6kFP=R#GlDlq_&Q7<8jS&I@_3=v0=cXxXcpPxEuY8eG~h{kzp27I-$;0TB#5`J z9Y8hx3oPsoL8(a_@!M3c-$5ajxD@i?=0$7J!hHg+xFU=(euSyxVo2E~OUT=-M11{I z31#@+gYGGQtiK{d@|BEeQqg?8>7b8hXZJ#&^;%q&paiVjGv2b}neeIeJZ6;HGkSG% z@t#{A<6%7y-N!G+UHfFvLg6wvOfkl_fq{&c^&Xy(l@BxaR}j9>Q$nHo0$khb4qe4> zFj`_fUilV>6JERHL?wGv6yP``nna1n@daqT=`M(wq+n818(Q{Qu`8eWku_Qi@y@RZ ztjX-=xQ1WwEH;Lc*gaApG}i-0Npkm$yAQFbUIpK;ki_3-t3gF~1gcl%V_Kg*9;uc= z0TC_+$62gIS+(~ZpVcQBJaud=j`&82 zM4AaR*;Iut81%*;uIXSn?I$=!g)rX7t03=EKT+-xq0e4bGOp8g;Nqw8cz;L}*8La) zp>e`E=vBhB2v2~8!Shh=(_5&mcY?y|=j>_e95(Zs0IXch>DrluqTlEo^jrDJbWF)D zMni2mdfl6VsjtP+?^*}wsB=6n4`qPwkPPe;OvcRHXPDJ#^D!VboCG#bK+zW&kZy5^ zP3Aar7G2ds%eUJ2Nq8}uyb2-5WR9}6PUD!3AI$OUC`as*F~Zm$15|YF1F3cEFwad8 zP38yTfl7HOp86YdZdnrHH8Pn0-UW@djq%JhOHA7sjkg2UVTN@HBRNNpoZEj9H+;Je ztGPb50quDxq-ls7`;u|Ck2^8SDuEBPe~|Kn>&acH1LqV);;o+s8FQCo=dB$WJVG2Z z@>I~KvI;&X2BG_row#JNHH0_y!<0BPRM=~VGCrZ~Yr33Iw#dz5HIE%bYd5%1%1sGl#fc4BJ(Cz4BZY!6d!HPg0Z4!s6vh&fxc?nK$ zHNbI7Lr|EU3hnn!vR={rxHG^Dr$(J4>u;!|uJ~8B^{Y3Tq0$Szzy0y~wKQghRuU%d zSc4T`T;b=P5PWm_JQ#&^LuI)jI{DAU$}tPz5M}jzXaQB4sYvjQ7!crXLcMvxCaJ5iUdk|C~Fyn_J zab=$+I~3uKF8xAu^9D-pPYg$1=u1}h%mKWkvK31j3doU*Rp2~-0frzSX8K>o6(Rdz zqx)y_cDyLL)SiPcjI1&EVhY_C%tJ$gG-x{*jmEiQc<}xscp4p!mFGh7_7P(&3~B(C zre1inYXnT$?B+9JjjX6(SW*>|Be-V#d_+flZq5oDOxutK8%jB}(gjjPeh zX{#VvFEqf!xF!>faEl&NNqyX4|DPIpbLy`5hgP7 zTrE4tl@=zy6o;%Q;1=zfW?hxu_!ng)zbuV`-|xuC+u%%%jRNwpA2!1@{o1Sx zE)%h#9B@><4hCHtk3)go&?D&u7HYDnT%W`&cr+2WI$Q@Uh(V77_h6SsEV=b7p4ZOx zZ)>o{ihF0H{hd@g;^z#IOgxF9y&pmF@=ETx=NtIeW|6fV|LLfU z;UrbP0!n|Z$2`?2)<|B3`8+y-_ypZ1#Rmh)DGwLOE-QjAt8gODaenn&xJOL;U$e1q z_7ll@OPLXUKJ-9f1KA}ILQEafV1jERgn4l~+2XS}F2qDoX`M;8irrz3Ykq}OTY#OG z+zm-Q6;`ZrGNiAZ1`l;IiCkq4SV=~s_pfk#t*%cLk}va4-HRZv6vxp|15+>urqIJT zC26a)8Z)G2IWBsXTmqp8=B_ zA4AX8a8kKC#Vl{iVU+dVL%dFiQH>>|VfjZhjI-QD{m&J#l4I>L?jl!DzSkTjr){N{ zcVlR4>^5>$h2`0w^(76-swg>&4->3n7#q8M)`vfVv^|ZaJ+F_!tIDfn`Di(soj8$- zialVGytwte(ozsGKSBmF_m=iJh!~ z*;9v@lmsLT$~(xF7x{2Cn-V*Xqul*U52sxhrCN1MU{$ISO%vJ9&fJmDO3rqrlT~v` zZMiY-Kdwwd{XenETjo>GmI=gc)f2PYoLmz1TNiI;h0_i_jw4MarInrsK*U-a zqlgFl{zW;N+!BC!3xlxq;u!i^OpWed$?<5|h=?wj-E)bLkDu?K&DLgwARnKoDEG}D zFG)UgK92w&pEY`hGj(@t*t%`gWip+HvIp*{cjt( zmZ$vElIG+4XOsHp7yo+wZ;Ra5ZC^Kii?`38a2q$rt9%w5hTA0m1>MPg;J@IyGyVi? z&vR@4e~scS`Zu_F*`Hv&KfznuZ+89%EcvgIZC!?ehYejidD)e}qnlR@Lk}CZoBxiseLHMylRwe_-SXyl!_c$- zMBhDKBle$D_}`A|*!L%T*x^3EV#S^Rfd75Kn)~?wI7Ma-b5xZ@t2+OVw(S@A6FtmP z|1Z1UKjKgHFw4c;)l>dH<&N)%p@%u@P(wWb-_gwVLP~_RBEzFh@m&$R0ig z?(F2Yf6sZ_aP%-oRk~L0`FFJK7{NbhZJ49}cgveKhoOf#YNPOHy&0V0|7`!Z+)-;7 zdYGeH?;n`{pE>`xqw-Du6FuyJwTP#YzYlGzJq$d|QUCjH^GzLw9_Fa)qfD3meQd|! z=wXg}sq50QzoYr44I6vde*bsNgNLJsIcnhVOtHUTQQL;2hdJtjw$C5_j<)q5X8ABj z{qL4HmkmP?bJUv;kB0omS^jXfOT*B^994Ph>g|6=HK<*SeSg2AI<^f%4|CMIZxg5f9o^g}^vAWqV3?!+cgtM-0{&c^e{(_ z)-aC!JG%MFF!V4-{qL6Bb`C=ib5z%ldj|ed3#N+lHfuIqEJ0X2RbMcYOZm*u#!j$QNa`|6G>-z1MtQe}ab{uAxiM7XRmP z{TpnnCGv-p4?9}_=W6NS;N~fRf`=Wf|8t@9?<<#P5~j}rf%AKc+S int: + return self.ob_dims + + def act_dim(self) -> int: + return self.act_dims + + def alive(self) -> bool: + return True + + def observe(self) -> np.ndarray: + return np.random.rand(1, 34).astype(np.float32) + pass + + def take_action(self, act): + """ + upd recv and send + """ + pass + + def reset(self): + """ + how to implement + maybe to be implement with stand + """ + self.robot.reset() + + + diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml index 5f0f14b7b..31b3a9919 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml @@ -21,7 +21,7 @@ environment: learnning_rate: 5e-4 reward: forwardVel: - coeff: 0.3 + coeff: 0.0 torque: coeff: -4e-5 Stable: diff --git a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py index 123cd1fca..9eca4634f 100755 --- a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py +++ b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py @@ -28,7 +28,7 @@ def tensorboard_launcher(directory_path): tb.configure(argv=[None, '--logdir', directory_path]) url = tb.launch() print("[RAISIM_GYM] Tensorboard session created: "+url) - webbrowser.open_new(url) + # webbrowser.open_new(url) def load_param(weight_path, env, actor, critic, optimizer, data_dir): From 82615d8203e9da039077d29ce638be9ab940afa0 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 1 Aug 2023 13:56:26 +0800 Subject: [PATCH 09/62] add deploy part --- .../raisimGymTorch/env/deploy/deploy.py | 142 ++++++++++++++++++ .../env/deploy/sine_generator.py | 43 ++++++ 2 files changed, 185 insertions(+) create mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/deploy.py create mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py new file mode 100644 index 000000000..caa5c4cce --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py @@ -0,0 +1,142 @@ +import torch +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +import argparse +import numpy as np +import time +import os +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.bin.rsg_go1 import NormalSampler +from robot import Robot +import torch.nn as nn +from sine_generator import sine_generator + +robot = Robot() + + + + +parser = argparse.ArgumentParser() +# parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=120) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +# mode = args.mode +weight_path = args.weight +weight_path = './data/full_152.pt' +if weight_path!='' and args.cfg_path == None: + cfg_path = os.path.split(weight_path)[0] +'/cfg.yaml' +else: + cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open( + "/cfg.yaml", 'r')) + + +def update_dim(robot): + """ + update the dimentions with robot + make the mid-plugin to get the info using python + + params: + ob_dim: contain the basic info ,which is same with the ob_dim when training + act_dim: contains the action_dim, the number of motors to control + + """ + global act_dim, ob_dim + act_dim = robot.act_dim() + ob_dim = robot.ob_dim() + + +act_dim = 0 +ob_dim = 0 +update_dim(robot) +print(cfg['architecture']['policy_net'], ob_dim, act_dim) +actor = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + + + +def reset(robot): + """ + reset the A1 robot with reset the basic info + robot: to be implemented by c++ + todo + """ + + pass + +def load_model(weight_path, actor): + a = input('Are you sure to load this model and run? Y or N') + if a.lower() == 'y': + checkpoint = torch.load(weight_path) + actor.architecture.load_state_dict(checkpoint['actor_architecture_state_dict']) + # actor.distribution.load_state_dict(checkpoint['actor_distribution_state_dict']) + # critic.architecture.load_state_dict(checkpoint['critic_architecture_state_dict']) + # optimizer.load_state_dict(checkpoint['optimizer_state_dict']) + + +def init(): + weight_path = './data/full_152.pt' + reset(robot) + load_model(weight_path, actor) + + +def cal_limit(act :np.array): + """ + get the limit and norm the act to the limit + param: + act: actions to be clip into the limits + """ + return act + +def act_concate(act:np.array, sine:np.array) -> np.array: + """ + cal the act to the limit and add it with the sine + + """ + sine = np.array(sine) + act = cal_limit(act) + return act + sine + +def run(): + """ + run the ob-act + """ + cnt = 0 + angle_list = [0 for x in range(12)] + while True: + print('running func') + if not robot.alive(): + break + + ob = robot.observe() + + act = actor.architecture(torch.from_numpy(ob).cpu()).cpu().detach().numpy() + + angle_list = sine_generator(angle_list, cnt, cfg['environment']['schedule'], cfg['environment']['angle_rate']) + + act = act_concate(act, angle_list) + + robot.take_action(act) + + time.sleep(0.1) + + cnt += 1 + +if __name__=='__main__': + init() + + run() + diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py b/raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py new file mode 100644 index 000000000..1aefb1419 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py @@ -0,0 +1,43 @@ +from math import sin,pi + +def sine_generator(angle_list, idx, T, rate=1): + base1= 0.82 + base3= 0.0 + base2 = -2 * base1 + ang = abs(sin( float(idx) / T * pi)) * rate + + idx_base = 0 + + if (int(idx/T) % 2 ) == 1: + angle_list[idx_base+1] = ang + base1 + angle_list[idx_base+2] = -2 * ang + base2 + + angle_list[idx_base+4] = base1 + angle_list[idx_base+5] = base2 + + angle_list[idx_base+7] = base1 + angle_list[idx_base+8] = base2 + angle_list[idx_base+10] = ang + base1 + angle_list[idx_base+11] = - 2 * ang + base2 + else: + angle_list[idx_base+1] = base1 + angle_list[idx_base+2] = base2 + + angle_list[idx_base+10] = base1 + angle_list[idx_base+11] = base2 + angle_list[idx_base+4] = ang + base1 + angle_list[idx_base+5] = -2 * ang + base2 + + angle_list[idx_base+7] = ang + base1 + angle_list[idx_base+8] = -2 * ang + base2 + angle_list[idx_base+0] = base3 + angle_list[idx_base+3] = base3 + angle_list[idx_base+6] = base3 + angle_list[idx_base+9] = base3 + return angle_list + + +if __name__=='__main__': + angle_list = [0 for x in range(12)] + sine_generator(angle_list, 2, 40, 0.3) + print(angle_list) \ No newline at end of file From 1de92836cb94288310d02c043aa2410a627e1e58 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 8 Aug 2023 14:31:23 +0800 Subject: [PATCH 10/62] deploy part --- examples/CMakeLists.txt | 1 + examples/src/maps/anymals.cpp | 5 +- examples/src/server/go1.cpp | 60 ++- raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py | 7 +- .../raisimGymTorch/env/RaisimGymVecEnv.py | 4 + .../raisimGymTorch/env/deploy/onnx_deploy.py | 268 ++++++++++ .../env/deploy/sine_generator.py | 2 + .../env/envs/rsg/Environment.hpp | 466 ++++++++++++++++++ .../raisimGymTorch/env/envs/rsg/cfg.yaml | 32 ++ .../raisimGymTorch/env/envs/rsg/runner.py | 221 +++++++++ .../raisimGymTorch/env/envs/rsg/tester.py | 76 +++ .../env/envs/rsg_go1/Environment.hpp | 177 +++++-- .../env/envs/rsg_go1/Environment_ylq.hpp | 427 ++++++++++++++++ .../raisimGymTorch/env/envs/rsg_go1/cfg.yaml | 10 +- .../raisimGymTorch/env/envs/rsg_go1/runner.py | 62 ++- raisimGymTorch/raisimGymTorch/env/test.yaml | 32 ++ 16 files changed, 1776 insertions(+), 74 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment.hpp create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml create mode 100755 raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py create mode 100755 raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp create mode 100644 raisimGymTorch/raisimGymTorch/env/test.yaml diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 87dde6f72..24d95b4bb 100755 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -78,6 +78,7 @@ create_executable(inverseDynamics src/server/inverseDynamics.cpp) create_executable(dzhanibekovEffect src/server/dzhanibekovEffect.cpp) create_executable(go1 src/server/go1.cpp) create_executable(leg src/server/leg.cpp) +create_executable(quat src/server/quat_m.cpp) # xml reader create_executable(xmlRader src/xml/xmlReader.cpp) diff --git a/examples/src/maps/anymals.cpp b/examples/src/maps/anymals.cpp index d4e48882e..c55e2b3ed 100755 --- a/examples/src/maps/anymals.cpp +++ b/examples/src/maps/anymals.cpp @@ -97,7 +97,7 @@ int main(int argc, char* argv[]) { /// create objects auto ground = world.addGround(0, "gnd"); ground->setAppearance("hidden"); - auto anymalC = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\anymal_c\\urdf\\anymal.urdf"); + auto anymalC = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\go1\\go1.urdf"); /// anymalC joint PD controller Eigen::VectorXd jointNominalConfig(anymalC->getGeneralizedCoordinateDim()), jointVelocityTarget(anymalC->getDOF()); @@ -162,11 +162,10 @@ int main(int argc, char* argv[]) { // std::cout<< i<setBasePos(pose); + anymalC->setBasePos(pose); angle_generator(angle_list, i, 30.f, 0.3); jointNominalConfig.tail(12) = angle_list; diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index 82374d562..10b7b210e 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -4,14 +4,22 @@ #include "raisim/RaisimServer.hpp" #include "raisim/World.hpp" #define PI 3.1415926 + + +void swap(Eigen::VectorXd &ob, int a, int b) +{ + double tmp = ob[a]; + ob[a] = ob[b]; + ob[b] = ob[a]; +} void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) { // todo ang2, rate, ang // std::cout<< "size is "<< angle_list.size() << std::endl; - double base1= 0.8, base3=0.0; + double base1= 0, base3=0.0; double base2 = -2 * base1; - double ang = -abs(sin( float(idx) / T * PI)) * rate; - double ang2 = -0.15 * ang; + double ang = abs(sin( float(idx) / T * PI)) * rate; + double ang2 = -0.15 * ang * 0; double ang3 = ang2 * 1.2; int idx_base = 0; // std::cout<getGeneralizedCoordinateDim()), jointVelocityTarget(go1->getDOF()); - jointNominalConfig << 0, 0, 0.30, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// jointNominalConfig << 0, 0, 0.41, 1.0, 0.0, 0.0, 0.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + jointNominalConfig << 0, 0, 0.36, 1.0, 0.0, 0, 0, 0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976 ; // todo implement in python using list // jointNominalConfig.tail(12).setZero(); - Eigen::VectorXd tmp(12); - tmp.setZero(); - angle_generator(tmp, 0, 80.f); - jointNominalConfig.tail(12) = tmp; +// Eigen::VectorXd tmp(12); +// tmp.setZero(); +// angle_generator(tmp, 0, 80.f); +// jointNominalConfig.tail(12) = tmp; jointVelocityTarget.setZero(); Eigen::VectorXd jointPgain(go1->getDOF()), jointDgain(go1->getDOF()); - jointPgain.tail(12).setConstant(120.0); - jointDgain.tail(12).setConstant(3); + jointPgain.tail(12).setConstant(2000.0); + jointDgain.tail(12).setConstant(100); go1->setGeneralizedCoordinate(jointNominalConfig); go1->setGeneralizedForce(Eigen::VectorXd::Zero(go1->getDOF())); @@ -89,21 +98,36 @@ int main(int argc, char* argv[]) { server.focusOn(go1); server.launchServer(); Eigen::Vector3d pos(0,0, 3); - + Eigen::VectorXd ob_(24); + ob_.setZero(); for (int i=0; i<2000000; i++) { + go1->getState(jointNominalConfig,jointVelocityTarget); + Eigen::VectorXd tmp1(12), tmp2(12); + tmp1 = jointNominalConfig.tail(12); + tmp2 = jointVelocityTarget.tail(12); + for(auto i=0; i<12; i++){ + ob_[2*i] = tmp1[i]; + ob_[2 * i+1] = tmp2[i]; + } + for(auto i=0;i <12; i++) + { + swap(ob_, i, 12 +i); + } - RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) -// sleep(1); - go1->setBasePos(pos); - angle_generator(tmp, i, 30.f, 0.6); + RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) + std::cout<< ob_ << std::endl<setBasePos(pos); +// angle_generator(tmp, i, 50.f, 0.3); // double rrr = 0; // for(int i=4; i<=6 ; i++) // { // rrr += abs(jointNominalConfig[i] - ) * stable_reward_rate ; // } - jointNominalConfig.tail(12) = tmp; - go1->setPdTarget(jointNominalConfig, jointVelocityTarget); +// jointNominalConfig.tail(12) = tmp; +// std::cout<< tmp << std::endl; +// go1->setPdTarget(jointNominalConfig, jointVelocityTarget); server.integrateWorldThreadSafe(); diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py index 0cad97548..f50835a61 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py @@ -76,10 +76,15 @@ def __init__(self, def act(self, actor_obs): self.actor_obs = actor_obs with torch.no_grad(): - self.actions, self.actions_log_prob = self.actor.sample(torch.from_numpy(actor_obs).to(self.device)) + tmp = torch.from_numpy(actor_obs) + self.actions, self.actions_log_prob = self.actor.sample(tmp.to(self.device)) return self.actions + def forward(self, actor_obs): + return self.act(actor_obs) + + def step(self, value_obs, rews, dones): self.storage.add_transitions(self.actor_obs, value_obs, self.actions, self.actor.action_mean, self.actor.distribution.std_np, rews, dones, self.actions_log_prob) diff --git a/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py b/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py index 882d84873..0aea66510 100755 --- a/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py +++ b/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py @@ -45,6 +45,10 @@ def stop_video_recording(self): self.wrapper.stopRecordingVideo() def step(self, action): + # print(action.size) + # print(type(action)) + # print(action.shape) + # print(action.max(), action.min()) self.wrapper.step(action, self._reward, self._done) return self._reward.copy(), self._done.copy() diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py new file mode 100644 index 000000000..ea541c9b0 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py @@ -0,0 +1,268 @@ +import onnxruntime as ort +import onnx +# from mlprodict.onnxrt import OnnxInference +from math import cos,pi +import numpy as np +# 加载模型 + +def deg_rad(x): + if isinstance(x, list): + return [deg_rad(a) for a in x] + else: + return x / 180 * pi + +def rad_deg(x): + if isinstance(x, list): + return [rad_deg(a) for a in x] + else: + return x * pi / 180 +def ang_trans(lower, upper, x): + """ + trans the rate x to the angle between lower and upper + """ + x = (x+1)/2 #todo for test + return x * upper + (1-x) * lower + +def norm(lower, upper, x): + return (x - lower) / (upper - lower) + +def rad_normalize(lower, upper,x): + if isinstance(lower, list): + ans = [] + for a,b,c in zip(lower, upper, x): + ans.append(rad_normalize(a,b,c)) + return ans + else: + ang1 = x * 180 / pi + ang1 = norm(lower, upper, ang1) + return 2*ang1 - 1 + +def deg_normalize(lower, upper, x): + if isinstance(lower, list): + ans = [] + for a,b,c in zip(lower, upper, x): + ans.append(deg_normalize(a,b,c)) + return ans + else: + return 2 * norm(lower, upper, x) - 1 #todo for test + # return 1 - 2* norm(lower, upper,x) + + +low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] +upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] +u0 = [0, 30, -60,0, 30, -60,0, 30, -60,0, 30, -60] +u0 = deg_normalize(low, upp, u0) +# u0 = [-deg_normalize(low, upp, u0)[i] if deg_normalize(low, upp, u0)[i]!=0 else 0 for i in range(12)] +# print(u0) +history_u = u0 +model = ort.InferenceSession('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/deploy/new.onnx') + +idx_local = 0 + +# 准备输入 +input_name = model.get_inputs()[0].name +# print(model.get_outputs()) +output_name = model.get_outputs()[2].name +print(input_name, output_name) +# input_data = np.random.rand(1, 34).astype(np.float32) + +def sine_gene_test_qua(idx, T): + angle_list = [0 for i in range(12)] + if idx >= 2 * T: + idx = 0 + dh = 1 # todo for test + if idx >= 0 and idx <= T: + tp0 =idx - 0 + y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y2 = 0 + elif idx>T and idx<=2*T: + tp0 =idx - T + y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y1 = 0 + + + angle_list[0] = 0 + angle_list[1] = y1 + angle_list[2] = -2 * y1 + angle_list[3] = 0 + angle_list[4] = y2 + angle_list[5] = -2 * y2 + angle_list[6] = 0 + angle_list[7] = y1 + angle_list[8] = -2 * y1 + angle_list[9] = 0 + angle_list[10] = y2 + angle_list[11] = -2 * y2 + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i])) for i in range(12)] + return angle_list + + +def sine_gene(idx, T): + angle_list = [0 for i in range(12)] + if idx >= 2 * T: + idx = 0 + dh = 2 # todo for test + if idx >= 0 and idx <= T: + tp0 =idx - 0 + y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y2 = 0 + elif idx>T and idx<=2*T: + tp0 =idx - T + y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y1 = 0 + + + angle_list[0] = 0 + angle_list[1] = y1 + angle_list[2] = -2 * y1 + angle_list[3] = 0 + angle_list[4] = y2 + angle_list[5] = -2 * y2 + angle_list[6] = 0 + angle_list[7] = y2 + angle_list[8] = -2 * y2 + angle_list[9] = 0 + angle_list[10] = y1 + angle_list[11] = -2 * y1 + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i])) for i in range(12)] + return angle_list + +def rate_to_act(lower, upper, rate): + if isinstance(lower, list): + return [rate_to_act(a,b,c) for a,b,c in zip(lower,upper, rate)] + else: + norm_for_act = lambda a: (a+1)*0.5 + lerp = lambda a, b, c: a*(1-c) + b * c + return lerp(lower, upper, norm_for_act(rate)) + +def add_list(act_gen, sine): + global history_u + kk = 0.9 + kf = 1 + kb = 0.5 + history_u = [history_u[i] * kk + (1-kk) * act_gen[i] for i in range(12)] # todo the act_gen[i] is to big + clip = lambda a, b, c: np.clip(a, b, c) + + + # f0 = lambda a: a + # f1 = lambda a, b, c: a + + ans = [rate_to_act(low[i], upp[i], clip(kb * history_u[i] + kf * sine[i], -1, 1)) for i in range(12)] + ans = [deg_rad(x) for x in ans] + # todo swap the ans + # for i in range(6): + # tmp = ans[i+6] + # ans[i+6] = ans[i] + # ans[i] = tmp + return ans + + +def run_model(observation, idx, T): + # todo idx should return 0 when fall + # idx = idx % T + act_gen = model.run([output_name], input_feed={input_name: observation}) + act_gen = act_gen[0] + act_gen = np.zeros((1,12)) + # [array([[]])] + sine = sine_gene(idx, T) + sine = sine_gene_test_qua(idx, T) + # sine = [0 for x in range(12)] + # print(sine,act_gen) + ans = [] + for act in act_gen: + ans.append(add_list(act, sine)) + + ans = [np.array(ans).astype(np.float32)] + + return ans + + +def run_model1(observation): + return model.run([output_name], input_feed={input_name: observation}) + +# 运行模型 + +# outputs = model.run([output_name], input_feed={input_name: input_data}) +# print(outputs) +# x = run_model(input_data) +# print(x) +if __name__=="__main__": + # test_exp = np.zeros((1,34)) + # test_exp1 = np.zeros((1,34)) + # for i in range(12): + # test_exp[0][i * 2 + 10] = -u0[i] + # test_exp1[0][i * 2 + 10] = u0[i] + # # print(test_exp) + # + # ans = run_model(test_exp.astype(np.float32),0, 50) + # ans1 = run_model(test_exp1.astype(np.float32),0, 50) + # # ans1 = run_model(np.zeros((1,34)).astype(np.float32)) + # print(ans) + # print(ans1) + # print(u0) + + a = [ang_trans(low[i], upp[i], u0[i]) for i in range(12)] + print(a) + print(u0) + uu = rate_to_act(low, upp, u0) + uu = deg_rad(uu) + print(uu) + # norm_for_act = lambda a: (a + 1) * 0.5 + # lerp = lambda a, b, c: a * (1 - c) + b * c + # print(deg_normalize(-10,10,6)) + # print(norm_for_act(deg_normalize(-10,10,6))) + # print(lerp(-10, 10,norm_for_act(deg_normalize(-10,10,6)) )) + + # import matplotlib.pyplot as plt + # x = [x for x in range(200)] + # y = [sine_gene(a ,50) for a in x] + # y =np.array(y).transpose() + # + # for i in range(12): + # + # plt.plot(x,y[i]) + # plt.show() + +""" +def test_rad_deg(): + assert rad_deg(1.57)-90 <=1 +def test_rad_deg_list(): + assert isinstance(rad_deg([1, 2,3]), list) + +def test_deg_rad(): + assert deg_rad(90) - 1.57 <= 0.05 + +def test_deg_rad_list(): + assert isinstance(deg_rad([1, 2, 3]), list) + +""" +# def test_sine_gene(): +# for i in range(0, 200, 10): +# a = sine_gene(i, 50) +# print(a) +# assert max(a) <= pi and min(a) >= 0 + +# todo +""" +todo +1. on action 的范围 +2. 似乎是角度问题?应该是范围需要考虑是 角度还是弧度 + + +老师的输入是deg or rad +what's my output + + +using deg to get the rate +and feed the rate to the env + +""" + + +def test_run_model(): + ans = run_model(np.zeros((1, 34)).astype(np.float32), 10, 50) + ans1 = run_model1(np.zeros((1, 34)).astype(np.float32)) + assert ans1[0] == ans[0] + +def test_norm(): + assert deg_normalize(-10, 10, -10) == -1 \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py b/raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py index 1aefb1419..bc4ee142d 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py @@ -37,6 +37,8 @@ def sine_generator(angle_list, idx, T, rate=1): return angle_list + + if __name__=='__main__': angle_list = [0 for x in range(12)] sine_generator(angle_list, 2, 40, 0.3) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment.hpp new file mode 100644 index 000000000..82a196374 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment.hpp @@ -0,0 +1,466 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} +void swap(Eigen::VectorXd &ob, int a, int b) +{ + double tmp = ob[a]; + ob[a] = ob[b]; + ob[b] = ob[a]; +} + +double rad_deg(double rad) +{ + return rad / PI * 180; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.82, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1_description/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_<< 0, 0, 0.41, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + +// jointNominalConfig.tail(12).setZero(); +// Eigen::VectorXd tmp(12); +// tmp.setZero(); +// angle_generator(tmp, 0, 80.f); +// gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(2000.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(100); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling +// COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); +// Eigen::VectorXd idx1(8), idx2(4); +// idx1.setZero();idx2.setZero(); +// idx1<<1, 2, 4, 5, 7,8,10,11; +// idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); +// Eigen::VectorXd ttmp =action.cast(); +// map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + +// angle_mulit(pTarget12_, idx1, action_std); +// angle_mulit(pTarget12_, idx2, action_std); +// +// +// angle_list_for_work = angle_list * for_work_rate; + + + + +// pTarget12_ = angle_list_for_work + pTarget12_; + + + +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + +// / if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[4]-gc_init_[4]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[6]-gc_init_[6]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml new file mode 100644 index 000000000..deb2a0029 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -0,0 +1,32 @@ +seed: 1 +record_video: false + +environment: + render: true +# just testing commenting + num_envs: 100 + eval_every_n: 100 + num_threads: 30 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 8.0 + action_std: 0.01 + show_ref: false + angle_rate: 0.3 + stable: 1 + reference: 0 + schedule: 50 + for_work: 1 + float_base: false + learnning_rate: 5e-4 + reward: + forwardVel: + coeff: 3 + torque: + coeff: -4e-5 + Stable: + coeff: 0.9 + +architecture: + policy_net: [128, 128] + value_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py new file mode 100755 index 000000000..41704d49f --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -0,0 +1,221 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg_go1 import NormalSampler +from raisimGymTorch.env.bin.rsg_go1 import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO + + +import os +import math +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse + + + +# task specification +task_name = "go1_locomotion" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=120) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +if mode =='train' or mode == 'retrain': + tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update + +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=4, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + learning_rate=cfg['environment']['learnning_rate'] + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +# if load_best == True: +# weight_path = "" +print = logger.info + +mode == 'test' + +total_update = args.update +if mode =='train' or mode == 'retrain': + for update in range(total_update): + start = time.time() + env.reset() + reward_sum = 0 + done_sum = 0 + average_dones = 0. + + if update % cfg['environment']['eval_every_n'] == 0: + print("Visualizing and evaluating the current policy") + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + # we create another graph just to demonstrate the save/load method + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) + + env.turn_on_visualization() + env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') + + for step in range(n_steps): + with torch.no_grad(): + frame_start = time.time() + obs = env.observe(False) + + # action = ppo.act(torch.from_numpy(obs).cpu()) + action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + # print(action.min()) + reward, dones = env.step(action.cpu().detach().numpy()) + reward_analyzer.add_reward_info(env.get_reward_info()) + frame_end = time.time() + wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) + if wait_time > 0.: + time.sleep(wait_time) + + env.stop_video_recording() + env.turn_off_visualization() + + reward_analyzer.analyze_and_plot(update) + env.reset() + env.save_scaling(saver.data_dir, str(update)) + + # actual training + for step in range(n_steps): + obs = env.observe() + action = ppo.act(obs) + reward, dones = env.step(action) + ppo.step(value_obs=obs, rews=reward, dones=dones) + done_sum = done_sum + np.sum(dones) + reward_sum = reward_sum + np.sum(reward) + # take st step to get value obs + obs = env.observe() + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 == 0, update=update) + average_ll_performance = reward_sum / total_steps + if average_ll_performance > biggest_reward: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + env.save_scaling(saver.data_dir, str(update)) + average_dones = done_sum / total_steps + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + # curriculum update. Implement it in Environment.hpp + env.curriculum_callback() + + end = time.time() + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) + print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) + print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) + print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) + * cfg['environment']['control_dt']))) + print('----------------------------------------------------\n') +else: + env.reset() + start = time.time() + onnx_flag = True + if onnx_flag: + cnt_onnx = 0 + from raisimGymTorch.env.deploy import onnx_deploy + + # load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + for step in range(n_steps * 10): + time.sleep(0.01) + obs = env.observe() + print(obs.shape) + if onnx_flag: + action = onnx_deploy.run_model(obs, cnt_onnx, 50) + action = np.array(action)[0] + cnt_onnx += 1 + # action = np.array([act for x in range(100)]) + else: + action = ppo.act(obs) + + reward, dones = env.step(action) + +print(f'biggest:{biggest_reward},rate = {biggest_iter}') + + diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py new file mode 100755 index 000000000..bdea58d30 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py @@ -0,0 +1,76 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.bin import rsg_anymal +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +import raisimGymTorch.algo.ppo.module as ppo_module +import os +import math +import time +import torch +import argparse + + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-w', '--weight', help='trained weight path', type=str, default='') +args = parser.parse_args() + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# create environment from the configuration file +cfg['environment']['num_envs'] = 1 + +env = VecEnv(rsg_anymal.RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper)), cfg['environment']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts + +weight_path = args.weight +iteration_number = weight_path.rsplit('/', 1)[1].split('_', 1)[1].rsplit('.', 1)[0] +weight_dir = weight_path.rsplit('/', 1)[0] + '/' + +if weight_path == "": + print("Can't find trained weight, please provide a trained weight with --weight switch\n") +else: + print("Loaded weight from {}\n".format(weight_path)) + start = time.time() + env.reset() + reward_ll_sum = 0 + done_sum = 0 + average_dones = 0. + n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) + total_steps = n_steps * 1 + start_step_id = 0 + + print("Visualizing and evaluating the policy: ", weight_path) + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], torch.nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(weight_path)['actor_architecture_state_dict']) + + env.load_scaling(weight_dir, int(iteration_number)) + env.turn_on_visualization() + + # max_steps = 1000000 + max_steps = 1000 ## 10 secs + + for step in range(max_steps): + time.sleep(0.01) + obs = env.observe(False) + action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + reward_ll, dones = env.step(action_ll.cpu().detach().numpy()) + reward_ll_sum = reward_ll_sum + reward_ll[0] + if dones or step == max_steps - 1: + print('----------------------------------------------------') + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(reward_ll_sum / (step + 1 - start_step_id)))) + print('{:<40} {:>6}'.format("time elapsed [sec]: ", '{:6.4f}'.format((step + 1 - start_step_id) * 0.01))) + print('----------------------------------------------------\n') + start_step_id = step + 1 + reward_ll_sum = 0.0 + + env.turn_off_visualization() + env.reset() + print("Finished at the maximum visualization steps") diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp index 81a9d7751..1667903c1 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment.hpp @@ -14,6 +14,17 @@ double cal(double low, double upp, double now){ return (now + 1)/2 * (upp- low) + low; } +void swap(Eigen::VectorXd &ob, int a, int b) +{ + double tmp = ob[a]; + ob[a] = ob[b]; + ob[b] = tmp; +} + +double rad_deg(double rad) +{ + return rad / PI * 180; +} void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) { @@ -86,9 +97,9 @@ void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1 // std::cout<< "size is "<< angle_list.size() << std::endl; double base1= 0.8, base3=0.0; double base2 = -2 * base1; - double ang = -abs(sin( float(idx) / T * PI)) * rate; - double ang2 = -0.15 * ang; - double ang3 = ang2 * 1.2; + double ang = abs(sin( float(idx) / T * PI)) * rate; +// double ang2 = -0.15 * ang; +// double ang3 = ang2 * 1.2; int idx_base = 0; // std::cout<addArticulatedSystem(resourceDir_+"/a1/urdf/a1.urdf"); + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1_description/urdf/a1.urdf"); anymal_->setName("dog"); anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); world_->addGround(); @@ -176,18 +187,24 @@ class ENVIRONMENT : public RaisimGymEnv { // gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; // gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; // anymal_1->setGeneralizedCoordinate(gc_init_); - gc_init_<< 0, 0, 0.30, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_<< 0, 0, 0.41, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; +// gc_init_ << 0, 0, 0.36, 1.0, 0.0, 0, 0, 0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883; // todo implement in python using list + +// gc_init_ << 0, 0, 0.36, 1.0, 0.0, 0, 0, 0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883; // todo implement in python using list +// gc_init_<< 0, 0, 0.41, 1.0, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883, 0.0, -0.4, 0.8529411764705883; // todo implement in python using list + + gc_init_<< 0, 0, 0.36, 1.0, 0.0, 0, 0, 0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976 ; // todo implement in python using list // jointNominalConfig.tail(12).setZero(); - Eigen::VectorXd tmp(12); - tmp.setZero(); - angle_generator(tmp, 0, 80.f); - gc_init_.tail(12) = tmp; +// Eigen::VectorXd tmp(12); +// tmp.setZero(); +// angle_generator(tmp, 0, 80.f); +// gc_init_.tail(12) = tmp; /// set pd gains Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); - jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(120.0); - jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(3); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(2000.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(100); anymal_->setPdGains(jointPgain, jointDgain); anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); @@ -242,9 +259,9 @@ class ENVIRONMENT : public RaisimGymEnv { float step(const Eigen::Ref& action) final { /// action scaling - COUNT ++; +// COUNT ++; // std::cout<(); - Eigen::VectorXd ttmp =action.cast(); - map_from_origin_to_limit(join_limit, pTarget12_,ttmp); +// Eigen::VectorXd ttmp =action.cast(); +// map_from_origin_to_limit(join_limit, pTarget12_,ttmp); // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); // pTarget12_ += actionMean_; // pTarget12_ = angle_list; - angle_mulit(pTarget12_, idx1, action_std); - angle_mulit(pTarget12_, idx2, action_std); +// angle_mulit(pTarget12_, idx1, action_std); +// angle_mulit(pTarget12_, idx2, action_std); +// +// +// angle_list_for_work = angle_list * for_work_rate; + - angle_list_for_work = angle_list * for_work_rate; +// pTarget12_ = angle_list_for_work + pTarget12_; - pTarget12_ = angle_list_for_work + pTarget12_; // pTarget12_[11] = pTarget12_[10] *-2; // pTarget12_[8] = pTarget12_[7] * -2; // pTarget12_[1] = -pTarget12_[10]; @@ -355,6 +375,7 @@ class ENVIRONMENT : public RaisimGymEnv { void updateObservation() { anymal_->getState(gc_, gv_); +// std::cout< quat; raisim::Mat<3,3> rot; quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; @@ -362,16 +383,79 @@ class ENVIRONMENT : public RaisimGymEnv { bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); // std::cout<< rot.e().row(2).transpose().size() << " " < left_q(vec_quat); +// left_q[3] = sqr2 * (quat[0] - quat[1]); // -w +// left_q[0] = -sqr2 * (quat[0] + quat[1]); // x +// left_q[1] = -sqr2 * (quat[2] - quat[3]); // z +// left_q[2] = sqr2 * (quat[2] + quat[3]); // y +// raisim::Mat<3,3> left_rot; +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// raisim::quatToRotMat(new_quat, left_rot); + Eigen::Matrix3d left_rot(new_quat); + bodyLinearVel_ = -left_rot.transpose() * gv_.segment(0, 3); // minus was added to test todo + bodyAngularVel_ = -left_rot.transpose() * gv_.segment(3, 3); +// bodyAngularVel_[0] = -bodyAngularVel_[0]; +// double tt = bodyAngularVel_[1]; +// bodyAngularVel_[1] = -bodyAngularVel_[2]; +// bodyAngularVel_[2] = -tt; + + +// std::cout<< "left " << left_q << "right" << quat << std::endl; + + Eigen::VectorXd tmp1(12), tmp2(12); + tmp1 = gc_.tail(12); + tmp2 = gv_.tail(12); + for(auto i=0;i<=2;i++) bodyAngularVel_[i] = rad_deg(bodyAngularVel_[i]); // to be deg + +// for(auto i=0;i<=11;i++) tmp1[i] = rad_deg(tmp1[i]); // to be deg +// for(auto i=0;i<=11;i++) tmp2[i] = rad_deg(tmp2[i]); // to be deg + obDouble_ << new_quat.x(), + new_quat.y(), + new_quat.z(), + new_quat.w(), +// rot.e().row(2).transpose(), /// body orientation + bodyAngularVel_, + bodyLinearVel_; /// body linear&angular velocity +// tmp1, /// joint angles +// tmp2; /// joint velocity + + for(auto i=0; i<12; i++){ +// std::cout<<2*i + 10 << " " << tmp1[i] << " " << tmp2[i] < ob) final { /// convert it to float ob = obDouble_.cast(); +// std::cout<<"observe in c++\n" << ob <0.3 ) + return true;} +// }if(abs(gc_[3]-gc_init_[3]) >0.3 ) +// { +// return true; +// } +// if(abs(gc_[4]-gc_init_[4]) >0.2 ) // { // return true; // } +// if(abs(gc_[6]-gc_init_[6]) >0.2 ) +// { +// return true; +// } // if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) // return true; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp new file mode 100644 index 000000000..8d582f19d --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp @@ -0,0 +1,427 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.82, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_<< 0, 0, 0.30, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; + +// jointNominalConfig.tail(12).setZero(); + Eigen::VectorXd tmp(12); + tmp.setZero(); + angle_generator(tmp, 0, 80.f); + gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(120.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(3); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling + COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); + Eigen::VectorXd idx1(8), idx2(4); + idx1.setZero();idx2.setZero(); + idx1<<1, 2, 4, 5, 7,8,10,11; + idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); + Eigen::VectorXd ttmp =action.cast(); + map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + + angle_mulit(pTarget12_, idx1, action_std); + angle_mulit(pTarget12_, idx2, action_std); + + + angle_list_for_work = angle_list * for_work_rate; + + + + + pTarget12_ = angle_list_for_work + pTarget12_; +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + +// / if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml index 32a0b24c9..15ee76666 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml @@ -4,20 +4,20 @@ record_video: false environment: render: true # just testing commenting - num_envs: 100 + num_envs: 1 eval_every_n: 100 - num_threads: 30 + num_threads: 1 simulation_dt: 0.0025 control_dt: 0.01 max_time: 8.0 - action_std: 0.018 + action_std: 0.01 show_ref: false angle_rate: 0.3 stable: 1 reference: 0 - schedule: 60 + schedule: 50 for_work: 1 - float_base: false + float_base: False learnning_rate: 5e-4 reward: forwardVel: diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py index 7cf3010aa..880a89c12 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py @@ -103,6 +103,8 @@ # weight_path = "" print = logger.info +mode == 'test' + total_update = args.update if mode =='train' or mode == 'retrain': for update in range(total_update): @@ -194,11 +196,63 @@ else: env.reset() start = time.time() - load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + onnx_flag = True + debug = True + if onnx_flag: + cnt_onnx = 0 + from raisimGymTorch.env.deploy import onnx_deploy + T = 50 + np.set_printoptions(threshold=np.inf) + draw_line =[] + # load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) for step in range(n_steps * 10): time.sleep(0.01) - obs = env.observe() - action = ppo.act(obs) + obs = env.observe(False) + + if debug: + angle = obs[0][[0,1,2,4,5,6]] + angle[0] *= 100 + angle[1] *= 100 + angle[2] *= 100 + draw_line.append(angle.copy()) + + if cnt_onnx == 100: + import matplotlib.pyplot as plt + # print(obs) + colo = ['r','g','b','y','magenta','cyan'] + # colo = ['r','g','b','y'] + # print(angle) + ttt = np.array(draw_line).transpose() + leen = ttt.shape[1] + ze = [0 for x in range(leen)] + xx = [x for x in range(leen)] + t = 0 + for i in ttt: + plt.plot(xx, i, color=colo[t]) + t += 1 + plt.plot(xx, ze) + print(ttt) + plt.show() + input('wait') + + # input('?') + # print(obs.shape) + if onnx_flag: + if cnt_onnx >= 2 * T: + cnt_onnx =0 + action = onnx_deploy.run_model(obs, cnt_onnx, T) + action = np.array(action)[0] + cnt_onnx += 1 + # action = np.array([act for x in range(100)]) + else: + action = ppo.act(obs) + # if cnt_onnx == 1: + # print(action) reward, dones = env.step(action) + if dones[0]: + cnt_onnx = 0 + + +print(f'biggest:{biggest_reward},rate = {biggest_iter}') + -print(f'biggest:{biggest_reward},rate = {biggest_iter}') \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/test.yaml b/raisimGymTorch/raisimGymTorch/env/test.yaml new file mode 100644 index 000000000..21cf408af --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/test.yaml @@ -0,0 +1,32 @@ +seed: 1 +record_video: false + +environment: + render: true +# just testing commenting + num_envs: 100 + eval_every_n: 40 + num_threads: 30 + simulation_dt: 0.0025 + control_dt: 0.01 + max_time: 8.0 + action_std: 0.03 + show_ref: false + angle_rate: 0.3 + stable: 5 + reference: 0 + schedule: 40 + for_work: 1 + float_base: false + learnning_rate: 5e-4 + reward: + forwardVel: + coeff: 0.0 + torque: + coeff: -4e-5 + Stable: + coeff: 0.9 + +architecture: + policy_net: [128, 128] + value_net: [128, 128] From bbe4daf67e624a5649a2f34e2d69efee40de6cbf Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 8 Aug 2023 20:14:32 +0800 Subject: [PATCH 11/62] put the sine generator to python and change the file structure --- examples/src/server/go1.cpp | 9 ++-- raisimGymTorch/CMakeLists.txt | 2 + .../raisimGymTorch/env/RaisimGymEnv.hpp | 2 + .../env/VectorizedEnvironment.hpp | 7 +++ .../{sine_generator.py => angle_utils.py} | 36 ++++++++++++- .../raisimGymTorch/env/deploy/deploy.py | 2 +- .../raisimGymTorch/env/deploy/onnx_deploy.py | 13 +---- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 7 ++- .../raisimGymTorch/env/envs/rsg/runner.py | 48 ++++++++++++++---- .../env/envs/rsg/sine_generator.py | 50 +++++++++++++++++++ .../env/envs/rsg_go1/Environment_ylq.hpp | 1 - .../raisimGymTorch/env/raisim_gym.cpp | 3 +- .../raisimGymTorch/env/utils/transfer_act.py | 0 13 files changed, 150 insertions(+), 30 deletions(-) rename raisimGymTorch/raisimGymTorch/env/deploy/{sine_generator.py => angle_utils.py} (55%) create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py create mode 100644 raisimGymTorch/raisimGymTorch/env/utils/transfer_act.py diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index 10b7b210e..0b3ce6deb 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -100,6 +100,7 @@ int main(int argc, char* argv[]) { Eigen::Vector3d pos(0,0, 3); Eigen::VectorXd ob_(24); ob_.setZero(); + size_t dof = go1->getDOF(); for (int i=0; i<2000000; i++) { go1->getState(jointNominalConfig,jointVelocityTarget); Eigen::VectorXd tmp1(12), tmp2(12); @@ -113,10 +114,12 @@ int main(int argc, char* argv[]) { { swap(ob_, i, 12 +i); } - + raisim::Vec<3> acc_; + go1->getFrameAcceleration("ROOT", acc_); + std::cout<setBasePos(pos); // angle_generator(tmp, i, 50.f, 0.3); @@ -127,7 +130,7 @@ int main(int argc, char* argv[]) { // } // jointNominalConfig.tail(12) = tmp; // std::cout<< tmp << std::endl; -// go1->setPdTarget(jointNominalConfig, jointVelocityTarget); + go1->setPdTarget(jointNominalConfig, jointVelocityTarget); server.integrateWorldThreadSafe(); diff --git a/raisimGymTorch/CMakeLists.txt b/raisimGymTorch/CMakeLists.txt index 8c9901416..ba4faa5d6 100755 --- a/raisimGymTorch/CMakeLists.txt +++ b/raisimGymTorch/CMakeLists.txt @@ -76,6 +76,8 @@ find_package(raisim CONFIG REQUIRED) SUBDIRLIST(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR}/raisimGymTorch/env/envs) set(RAISIMGYM_ENV_DIR ${CMAKE_CURRENT_SOURCE_DIR}/raisimGymTorch/env/envs) +set(SUBDIRS rsg) # only build for rsg + ######## Env ########## FOREACH(subdir ${SUBDIRS}) pybind11_add_module(${subdir} raisimGymTorch/env/raisim_gym.cpp raisimGymTorch/env/Yaml.cpp) diff --git a/raisimGymTorch/raisimGymTorch/env/RaisimGymEnv.hpp b/raisimGymTorch/raisimGymTorch/env/RaisimGymEnv.hpp index f1c4914cf..343069354 100755 --- a/raisimGymTorch/raisimGymTorch/env/RaisimGymEnv.hpp +++ b/raisimGymTorch/raisimGymTorch/env/RaisimGymEnv.hpp @@ -28,6 +28,7 @@ class RaisimGymEnv { /////// implement these methods ///////// virtual void init() = 0; + virtual void init_position(const Eigen::Ref& posi) = 0; virtual void reset() = 0; virtual void observe(Eigen::Ref ob) = 0; virtual float step(const Eigen::Ref& action) = 0; @@ -48,6 +49,7 @@ class RaisimGymEnv { double getSimulationTimeStep() { return simulation_dt_; } raisim::World* getWorld() { return world_.get(); } void turnOffVisualization() { server_->hibernate(); } +// void init_position() {} void turnOnVisualization() { server_->wakeup(); } void startRecordingVideo(const std::string& videoName ) { server_->startRecordingVideo(videoName); } void stopRecordingVideo() { server_->stopRecordingVideo(); } diff --git a/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp b/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp index 6da980fdd..94d3049d3 100755 --- a/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp +++ b/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp @@ -78,6 +78,13 @@ class VectorizedEnvironment { env->reset(); } + void init_position(Eigen::Ref &posi) + { +#pragma omp parallel for schedule(auto) + for(int i = 0; i < num_envs_; i++) + environments_[i]->init_position(posi.row(i)); + } + void observe(Eigen::Ref &ob, bool updateStatistics) { #pragma omp parallel for schedule(auto) for (int i = 0; i < num_envs_; i++) diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py similarity index 55% rename from raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py rename to raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py index bc4ee142d..01b6c7fbf 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/sine_generator.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py @@ -1,5 +1,23 @@ from math import sin,pi +import numpy as np +# from onnx_deploy import rad_deg, deg_rad +def deg_rad(x): + if isinstance(x, list): + return [deg_rad(a) for a in x] + else: + return x / 180 * pi + +def rad_deg(x): + if isinstance(x, list): + return [rad_deg(a) for a in x] + else: + return x * pi / 180 + +low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] +upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] +low = deg_rad(low) +upp = deg_rad(upp) def sine_generator(angle_list, idx, T, rate=1): base1= 0.82 base3= 0.0 @@ -36,10 +54,24 @@ def sine_generator(angle_list, idx, T, rate=1): angle_list[idx_base+9] = base3 return angle_list +def transfer(act_gen, sine, k): + """ + clip, lerp, generate the final action + params: act_gen: [12 * (-1, 1)] np.array + params: sine: [12 * rad_target] np.array + """ - + action = act_gen * k + sine * (1-k) + action = np.clip(action, low, upp) + return action if __name__=='__main__': angle_list = [0 for x in range(12)] + sine_generator(angle_list, 2, 40, 0.3) - print(angle_list) \ No newline at end of file + angle_list = np.array(angle_list) + act = transfer(np.random.random((100,12)), angle_list, 0.3) + print('sine:', angle_list) + print('low:', low) + print('upp:', upp) + print(act.shape, type(act)) diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py index caa5c4cce..239ead534 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py @@ -9,7 +9,7 @@ from raisimGymTorch.env.bin.rsg_go1 import NormalSampler from robot import Robot import torch.nn as nn -from sine_generator import sine_generator +from angle_utils import sine_generator robot = Robot() diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py index ea541c9b0..c20f0a074 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py @@ -1,21 +1,12 @@ import onnxruntime as ort -import onnx +# import onnx # from mlprodict.onnxrt import OnnxInference from math import cos,pi import numpy as np +from angle_utils import deg_rad, rad_deg # 加载模型 -def deg_rad(x): - if isinstance(x, list): - return [deg_rad(a) for a in x] - else: - return x / 180 * pi -def rad_deg(x): - if isinstance(x, list): - return [rad_deg(a) for a in x] - else: - return x * pi / 180 def ang_trans(lower, upper, x): """ trans the rate x to the angle between lower and upper diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index deb2a0029..32d37f3c3 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -10,7 +10,7 @@ environment: simulation_dt: 0.0025 control_dt: 0.01 max_time: 8.0 - action_std: 0.01 + action_std: 0.03 show_ref: false angle_rate: 0.3 stable: 1 @@ -19,9 +19,12 @@ environment: for_work: 1 float_base: false learnning_rate: 5e-4 + p_gain: 180 + d_gain: 8 + urdf_path: /home/lr-2002/code/raisimLib/rsc/a1_description/urdf/a1.urdf reward: forwardVel: - coeff: 3 + coeff: 0 torque: coeff: -4e-5 Stable: diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 41704d49f..c86e686f4 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -1,12 +1,12 @@ from ruamel.yaml import YAML, dump, RoundTripDumper from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger -from raisimGymTorch.env.bin.rsg_go1 import NormalSampler -from raisimGymTorch.env.bin.rsg_go1 import RaisimGymEnv +from raisimGymTorch.env.bin.rsg import NormalSampler +from raisimGymTorch.env.bin.rsg import RaisimGymEnv from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer import raisimGymTorch.algo.ppo.module as ppo_module import raisimGymTorch.algo.ppo.ppo as PPO - +from raisimGymTorch.env.deploy.angle_utils import transfer import os import math @@ -16,11 +16,22 @@ import torch import datetime import argparse +from sine_generator import sine_generator # task specification -task_name = "go1_locomotion" +task_name = "rsg_test" + + +""" +todo: + 1. init model + 2. change p-d info + 3. debug and add_on sine_gait + +""" + # configuration parser = argparse.ArgumentParser() @@ -46,6 +57,7 @@ cfg = YAML().load(open(cfg_path, 'r')) else: cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) +print(cfg['environment']) # create environment from the configuration file env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) @@ -78,7 +90,7 @@ if mode =='train' or mode == 'retrain': tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update - +num_envs = cfg['environment']['num_envs'] ppo = PPO.PPO(actor=actor, critic=critic, num_envs=cfg['environment']['num_envs'], @@ -99,14 +111,20 @@ if mode == 'retrain': load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) +check_done = lambda a, b: a + 1 if not b else 0 # if load_best == True: # weight_path = "" print = logger.info -mode == 'test' +mode == 'train' total_update = args.update if mode =='train' or mode == 'retrain': + # print('start train') + schedule = cfg['environment']['schedule'] + angle_rate = cfg['environment']['angle_rate'] + act_rate = cfg['environment']['action_std'] # how many action generated use for work + act_rate = float(act_rate) for update in range(total_update): start = time.time() env.reset() @@ -128,7 +146,7 @@ env.turn_on_visualization() env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') - + envs_idx = [0] * num_envs for step in range(n_steps): with torch.no_grad(): frame_start = time.time() @@ -136,8 +154,12 @@ # action = ppo.act(torch.from_numpy(obs).cpu()) action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + action = action.cpu().detach().numpy() + sine = sine_generator(envs_idx, schedule, angle_rate) + action = transfer(action, sine, act_rate).astype(np.float32) # print(action.min()) - reward, dones = env.step(action.cpu().detach().numpy()) + reward, dones = env.step(action) + envs_idx = list(map(check_done, envs_idx, dones)) reward_analyzer.add_reward_info(env.get_reward_info()) frame_end = time.time() wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) @@ -152,10 +174,18 @@ env.save_scaling(saver.data_dir, str(update)) # actual training + # sine = [0] * 12 + envs_idx = [0] * num_envs for step in range(n_steps): obs = env.observe() action = ppo.act(obs) + + + sine = sine_generator(envs_idx, schedule, angle_rate) + action = transfer(action, sine, act_rate).astype(np.float32) + # todo the transfer has bug reward, dones = env.step(action) + envs_idx = list(map(check_done, envs_idx, dones)) ppo.step(value_obs=obs, rews=reward, dones=dones) done_sum = done_sum + np.sum(dones) reward_sum = reward_sum + np.sum(reward) @@ -205,7 +235,7 @@ for step in range(n_steps * 10): time.sleep(0.01) obs = env.observe() - print(obs.shape) + # print(obs.shape) if onnx_flag: action = onnx_deploy.run_model(obs, cnt_onnx, 50) action = np.array(action)[0] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py new file mode 100644 index 000000000..fb0947df9 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py @@ -0,0 +1,50 @@ +from math import sin,pi +import numpy as np +def sine_generator(idx, T, rate=1): + if isinstance(idx, int): + base1= 0.82 + base3= 0.0 + base2 = -2 * base1 + ang = abs(sin( float(idx) / T * pi)) * rate + angle_list = [0] * 12 + idx_base = 0 + + if (int(idx/T) % 2 ) == 1: + angle_list[idx_base+1] = ang + base1 + angle_list[idx_base+2] = -2 * ang + base2 + + angle_list[idx_base+4] = base1 + angle_list[idx_base+5] = base2 + + angle_list[idx_base+7] = base1 + angle_list[idx_base+8] = base2 + angle_list[idx_base+10] = ang + base1 + angle_list[idx_base+11] = - 2 * ang + base2 + else: + angle_list[idx_base+1] = base1 + angle_list[idx_base+2] = base2 + + angle_list[idx_base+10] = base1 + angle_list[idx_base+11] = base2 + angle_list[idx_base+4] = ang + base1 + angle_list[idx_base+5] = -2 * ang + base2 + + angle_list[idx_base+7] = ang + base1 + angle_list[idx_base+8] = -2 * ang + base2 + angle_list[idx_base+0] = base3 + angle_list[idx_base+3] = base3 + angle_list[idx_base+6] = base3 + angle_list[idx_base+9] = base3 + return angle_list + else: + # tmp = [] + tmp= [sine_generator(x, T, rate) for x in idx] + return np.array(tmp) + + +if __name__=='__main__': + # angle_list = [[0 for x in range(12)] for z in range(3)] + idx = [3, 2, 4] + angle_list = sine_generator(idx, 40, 0.3) + print(angle_list) + print(angle_list.shape) \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp index 8d582f19d..5661bbaa0 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/Environment_ylq.hpp @@ -82,7 +82,6 @@ void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd //} void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) { - // todo ang2, rate, ang // std::cout<< "size is "<< angle_list.size() << std::endl; double base1= 0.8, base3=0.0; double base2 = -2 * base1; diff --git a/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp b/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp index a5934edb6..431445229 100755 --- a/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp +++ b/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp @@ -6,7 +6,7 @@ #include #include #include -#include "Environment.hpp" +#include "Environment_tobuildforpython.hpp" #include "VectorizedEnvironment.hpp" namespace py = pybind11; @@ -24,6 +24,7 @@ PYBIND11_MODULE(RAISIMGYM_TORCH_ENV_NAME, m) { .def("reset", &VectorizedEnvironment::reset) .def("observe", &VectorizedEnvironment::observe) .def("step", &VectorizedEnvironment::step) + .def("init_posi", &VectorizedEnvironment::init_position) .def("setSeed", &VectorizedEnvironment::setSeed) .def("getRewardInfo", &VectorizedEnvironment::getRewardInfo) .def("close", &VectorizedEnvironment::close) diff --git a/raisimGymTorch/raisimGymTorch/env/utils/transfer_act.py b/raisimGymTorch/raisimGymTorch/env/utils/transfer_act.py new file mode 100644 index 000000000..e69de29bb From 76ae26de03e499916b18958fc6621ae85b5e7d1b Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Wed, 9 Aug 2023 11:39:25 +0800 Subject: [PATCH 12/62] 1. add submodule A1_raspi_py 2. archive now module --- raisimGymTorch/A1_raspi_py | 1 + .../raisimGymTorch/env/RaisimGymVecEnv.py | 3 + .../raisimGymTorch/env/auto_runner.py | 8 +- .../raisimGymTorch/env/deploy/deploy.py | 1 - .../envs/rsg/Environment_tobuildforpython.hpp | 263 ++++++++++++++++++ .../raisimGymTorch/env/envs/rsg/cfg.yaml | 4 +- .../raisimGymTorch/env/envs/rsg/runner.py | 8 +- .../env/envs/rsg/sim_with_real.py | 164 +++++++++++ .../env/envs/rsg/sine_generator.py | 4 +- .../raisimGymTorch/env/envs/rsg/tester.py | 103 +++---- 10 files changed, 494 insertions(+), 65 deletions(-) create mode 160000 raisimGymTorch/A1_raspi_py create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py diff --git a/raisimGymTorch/A1_raspi_py b/raisimGymTorch/A1_raspi_py new file mode 160000 index 000000000..a565b08d1 --- /dev/null +++ b/raisimGymTorch/A1_raspi_py @@ -0,0 +1 @@ +Subproject commit a565b08d1bde6f797782e88d85b3f7361c4a6f8d diff --git a/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py b/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py index 0aea66510..bec722c02 100755 --- a/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py +++ b/raisimGymTorch/raisimGymTorch/env/RaisimGymVecEnv.py @@ -32,6 +32,9 @@ def __init__(self, impl, normalize_ob=True, seed=0, clip_obs=10.): def seed(self, seed=None): self.wrapper.setSeed(seed) + def init_position(self, position): + self.wrapper.init_position(position) + def turn_on_visualization(self): self.wrapper.turnOnVisualization() diff --git a/raisimGymTorch/raisimGymTorch/env/auto_runner.py b/raisimGymTorch/raisimGymTorch/env/auto_runner.py index aff020b07..be137ccd6 100644 --- a/raisimGymTorch/raisimGymTorch/env/auto_runner.py +++ b/raisimGymTorch/raisimGymTorch/env/auto_runner.py @@ -11,16 +11,16 @@ def change_data(path, flag, data): with open(path, 'w') as f : dump(y, f, Dumper=RoundTripDumper) -test_list = [x/1000 for x in range(0,20,2)] -test_T = [x for x in range(30, 70, 10)] +test_list = [x/1000 for x in range(2,20,2)] +test_T = [x for x in range(40, 70, 10)] # print(test_list) length = 300 for j in test_T: for i in test_list: - change_data('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/cfg.yaml',['action_std','schedule'], [i, j]) + change_data('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml',['action_std','schedule'], [i, j]) if i == 0: continue else: - os.system(f'python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py -u {length} |grep biggest' ) + os.system(f'python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py -u {length} |grep biggest' ) # os.system('python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py -u 3 |grep biggest' ) diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py index 239ead534..d67c5acac 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/deploy.py @@ -11,7 +11,6 @@ import torch.nn as nn from angle_utils import sine_generator -robot = Robot() diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp new file mode 100644 index 000000000..0e6fe0644 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -0,0 +1,263 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#include +#define PI 3.1415926 +/*todo + * 1. test the acceleration + * 2. change the terminator + * 3. change reward + */ +namespace raisim { + +class ENVIRONMENT : public RaisimGymEnv { + + public: + + explicit ENVIRONMENT(const std::string& resourceDir, const Yaml::Node& cfg, bool visualizable) : + RaisimGymEnv(resourceDir, cfg), visualizable_(visualizable), normDist_(0, 1) { + /// create world + world_ = std::make_unique(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + READ_YAML(std::string, urdf_path, cfg_["urdf_path"]); + READ_YAML(double, p_gain, cfg_["p_gain"]); + READ_YAML(double, d_gain, cfg_["d_gain"]); + anymal_ = world_->addArticulatedSystem(urdf_path); + anymal_->setName("model"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); // 18 + nJoints_ = gvDim_ - 6; + + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + acc_.setZero();//1 + +// init_position(); + gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883; // todo implement in python using list +// init_position(gc_init_); + init(); + + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + + actionStd_.setConstant(action_std); + + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + + + void init() final { + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(p_gain); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(d_gain); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(urdf_path); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + std::cout<<"position inited\n"; + } + + void init_position(const Eigen::Ref& posi) final + { + gc_init_ = posi.cast(); + init(); + } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + if (show_ref) + { + Eigen::Vector3d po(3, 3 ,10); + anymal_1->setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + } + + pTarget12_ = action.cast(); + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + +// auto get_orientation() +// { +// // todo return the orientation +// raisim::Vec<4> quat; +// +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// return quat.e(); +// } +// +// auto get_body_linear_velocity(){ +// return bodyLinearVel_; +// } +// auto get_body_angular_velocity() +// { +// return bodyAngularVel_; +// } +// +// auto get_joint_coordinate() +// { +// return gc_; +// } +// +// auto get_joint_velocity() +// { +// return gv_; +// } + void updateObservation() { + anymal_->getState(gc_, gv_); + std::string root_name = "ROOT"; + anymal_->getFrameAcceleration(root_name , acc_); // todo find the acc + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); + Eigen::VectorXd gcc = gc_.tail(12); + Eigen::VectorXd gvv = gv_.tail(12); + Eigen::VectorXd c_v(24); + for(auto i = 0; i <12 ; i++ ) + { + c_v << gcc[i], gvv[i]; + } + obDouble_ << quat, // quaternion + bodyAngularVel_, // ras/s + acc_, // m/s^2 +// gc_.tail(12), // rad/s +// gv_.tail(12); // rad/s^2 + c_v; + + } + + void observe(Eigen::Ref ob) final { + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + + Eigen::Quaternion quat(gc_[3], gc_[4], gc_[5], gc_[6]); + Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(0,1,2); + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over + rewards_.record("Stable", -10, false); + return true;} + if(abs(gc_[2] - gc_init_[2]) < 0.5) return false; + if(fmin(abs(euler[1]), abs(euler[1] - 360.0)) > 0.175) return false; + if(fmin(abs(euler[0]), abs(euler[0] - 360.0)) > 0.175) return false; + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Vec<3> acc_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + double p_gain,d_gain; + std::string urdf_path; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 32d37f3c3..88ff4cea2 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -10,12 +10,12 @@ environment: simulation_dt: 0.0025 control_dt: 0.01 max_time: 8.0 - action_std: 0.03 + action_std: 0.010 show_ref: false angle_rate: 0.3 stable: 1 reference: 0 - schedule: 50 + schedule: 40 for_work: 1 float_base: false learnning_rate: 5e-4 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index c86e686f4..0d0e9d46b 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -151,13 +151,11 @@ with torch.no_grad(): frame_start = time.time() obs = env.observe(False) - - # action = ppo.act(torch.from_numpy(obs).cpu()) action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) action = action.cpu().detach().numpy() sine = sine_generator(envs_idx, schedule, angle_rate) action = transfer(action, sine, act_rate).astype(np.float32) - # print(action.min()) + reward, dones = env.step(action) envs_idx = list(map(check_done, envs_idx, dones)) reward_analyzer.add_reward_info(env.get_reward_info()) @@ -226,7 +224,7 @@ else: env.reset() start = time.time() - onnx_flag = True + onnx_flag = False if onnx_flag: cnt_onnx = 0 from raisimGymTorch.env.deploy import onnx_deploy @@ -234,7 +232,7 @@ # load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) for step in range(n_steps * 10): time.sleep(0.01) - obs = env.observe() + obs = env.observe(False) # print(obs.shape) if onnx_flag: action = onnx_deploy.run_model(obs, cnt_onnx, 50) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py new file mode 100644 index 000000000..d63fe5d38 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -0,0 +1,164 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg import NormalSampler +from raisimGymTorch.env.bin.rsg import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +from raisimGymTorch.env.deploy.angle_utils import transfer + +import os +import math +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse +from sine_generator import sine_generator + +from raisimGymTorch.env.deploy.py.api import robot as rbt + + + + +# task specification +task_name = "sim2real" + + +""" +todo: + 1. make the model go to the same position + 2. pause check + 3. move + 1. imu info + 2. gyroscope + 3. accelerator + 4. position + 5. velocity + 4. log +""" + + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=120) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') + +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) +print(cfg['environment']) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +if mode =='train' or mode == 'retrain': + tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update +num_envs = cfg['environment']['num_envs'] +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=4, + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + learning_rate=cfg['environment']['learnning_rate'] + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +check_done = lambda a, b: a + 1 if not b else 0 + +print = logger.info + +mode == 'train' + +total_update = args.update + +schedule = cfg['environment']['schedule'] +angle_rate = cfg['environment']['angle_rate'] +act_rate = cfg['environment']['action_std'] # how many action generated use for work +act_rate = float(act_rate) + + +env.reset() +start = time.time() +onnx_flag = False +if onnx_flag: + cnt_onnx = 0 + from raisimGymTorch.env.deploy import onnx_deploy +else: + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +envs_idx = [0] * num_envs + +for step in range(n_steps * 10): + time.sleep(0.01) + obs = env.observe(False) + + if onnx_flag: + action = onnx_deploy.run_model(obs, cnt_onnx, 50) + action = np.array(action)[0] + cnt_onnx += 1 + else: + action = ppo.act(obs) + sine = sine_generator(envs_idx, schedule, angle_rate) + action = transfer(action, sine, act_rate).astype(np.float32) + reward, dones = env.step(action) + envs_idx = list(map(check_done, envs_idx, dones)) + +print(f'biggest:{biggest_reward},rate = {biggest_iter}') + + diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py index fb0947df9..fd6d973bf 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py @@ -2,9 +2,9 @@ import numpy as np def sine_generator(idx, T, rate=1): if isinstance(idx, int): - base1= 0.82 + base1= 0.4 base3= 0.0 - base2 = -2 * base1 + base2 = -0.8529411764705883 ang = abs(sin( float(idx) / T * pi)) * rate angle_list = [0] * 12 idx_base = 0 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py index bdea58d30..f54879d50 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/tester.py @@ -1,5 +1,5 @@ from ruamel.yaml import YAML, dump, RoundTripDumper -from raisimGymTorch.env.bin import rsg_anymal +from raisimGymTorch.env.bin import rsg from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv import raisimGymTorch.algo.ppo.module as ppo_module import os @@ -24,53 +24,54 @@ # create environment from the configuration file cfg['environment']['num_envs'] = 1 -env = VecEnv(rsg_anymal.RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper)), cfg['environment']) - -# shortcuts -ob_dim = env.num_obs -act_dim = env.num_acts - -weight_path = args.weight -iteration_number = weight_path.rsplit('/', 1)[1].split('_', 1)[1].rsplit('.', 1)[0] -weight_dir = weight_path.rsplit('/', 1)[0] + '/' - -if weight_path == "": - print("Can't find trained weight, please provide a trained weight with --weight switch\n") -else: - print("Loaded weight from {}\n".format(weight_path)) - start = time.time() - env.reset() - reward_ll_sum = 0 - done_sum = 0 - average_dones = 0. - n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) - total_steps = n_steps * 1 - start_step_id = 0 - - print("Visualizing and evaluating the policy: ", weight_path) - loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], torch.nn.LeakyReLU, ob_dim, act_dim) - loaded_graph.load_state_dict(torch.load(weight_path)['actor_architecture_state_dict']) - - env.load_scaling(weight_dir, int(iteration_number)) - env.turn_on_visualization() - - # max_steps = 1000000 - max_steps = 1000 ## 10 secs - - for step in range(max_steps): - time.sleep(0.01) - obs = env.observe(False) - action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) - reward_ll, dones = env.step(action_ll.cpu().detach().numpy()) - reward_ll_sum = reward_ll_sum + reward_ll[0] - if dones or step == max_steps - 1: - print('----------------------------------------------------') - print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(reward_ll_sum / (step + 1 - start_step_id)))) - print('{:<40} {:>6}'.format("time elapsed [sec]: ", '{:6.4f}'.format((step + 1 - start_step_id) * 0.01))) - print('----------------------------------------------------\n') - start_step_id = step + 1 - reward_ll_sum = 0.0 - - env.turn_off_visualization() - env.reset() - print("Finished at the maximum visualization steps") +env = rsg.RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper)), cfg['environment'] +env.init_position([0] * 12) +print(env) +# # shortcuts +# ob_dim = env.num_obs +# act_dim = env.num_acts +# +# weight_path = args.weight +# iteration_number = weight_path.rsplit('/', 1)[1].split('_', 1)[1].rsplit('.', 1)[0] +# weight_dir = weight_path.rsplit('/', 1)[0] + '/' +# +# if weight_path == "": +# print("Can't find trained weight, please provide a trained weight with --weight switch\n") +# else: +# print("Loaded weight from {}\n".format(weight_path)) +# start = time.time() +# env.reset() +# reward_ll_sum = 0 +# done_sum = 0 +# average_dones = 0. +# n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +# total_steps = n_steps * 1 +# start_step_id = 0 +# +# print("Visualizing and evaluating the policy: ", weight_path) +# loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], torch.nn.LeakyReLU, ob_dim, act_dim) +# loaded_graph.load_state_dict(torch.load(weight_path)['actor_architecture_state_dict']) +# +# env.load_scaling(weight_dir, int(iteration_number)) +# env.turn_on_visualization() +# +# # max_steps = 1000000 +# max_steps = 1000 ## 10 secs +# +# for step in range(max_steps): +# time.sleep(0.01) +# obs = env.observe(False) +# action_ll = loaded_graph.architecture(torch.from_numpy(obs).cpu()) +# reward_ll, dones = env.step(action_ll.cpu().detach().numpy()) +# reward_ll_sum = reward_ll_sum + reward_ll[0] +# if dones or step == max_steps - 1: +# print('----------------------------------------------------') +# print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(reward_ll_sum / (step + 1 - start_step_id)))) +# print('{:<40} {:>6}'.format("time elapsed [sec]: ", '{:6.4f}'.format((step + 1 - start_step_id) * 0.01))) +# print('----------------------------------------------------\n') +# start_step_id = step + 1 +# reward_ll_sum = 0.0 +# +# env.turn_off_visualization() +# env.reset() +# print("Finished at the maximum visualization steps") From 6118d7e2f1c16cb201065721e3262270b031db18 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Wed, 9 Aug 2023 11:40:09 +0800 Subject: [PATCH 13/62] 1. add submodule A1_raspi_py 2. archive now module --- .gitmodules | 3 +++ .../env/envs/rsg/Environment_tobuildforpython.hpp | 12 ++++-------- 2 files changed, 7 insertions(+), 8 deletions(-) create mode 100644 .gitmodules diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 000000000..7575e7b6c --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "raisimGymTorch/A1_raspi_py"] + path = raisimGymTorch/A1_raspi_py + url = https://github.com/Lr-2002/A1_raspi_py.git diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index 0e6fe0644..e6371edf2 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -11,11 +11,7 @@ #include "../../RaisimGymEnv.hpp" #include #define PI 3.1415926 -/*todo - * 1. test the acceleration - * 2. change the terminator - * 3. change reward - */ + namespace raisim { class ENVIRONMENT : public RaisimGymEnv { @@ -57,7 +53,7 @@ class ENVIRONMENT : public RaisimGymEnv { acc_.setZero();//1 // init_position(); - gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883; // todo implement in python using list + gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883; // init_position(gc_init_); init(); @@ -161,7 +157,7 @@ class ENVIRONMENT : public RaisimGymEnv { // auto get_orientation() // { -// // todo return the orientation +// // raisim::Vec<4> quat; // // quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; @@ -188,7 +184,7 @@ class ENVIRONMENT : public RaisimGymEnv { void updateObservation() { anymal_->getState(gc_, gv_); std::string root_name = "ROOT"; - anymal_->getFrameAcceleration(root_name , acc_); // todo find the acc + anymal_->getFrameAcceleration(root_name , acc_); raisim::Vec<4> quat; raisim::Mat<3,3> rot; quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; From 6306fbb1a821b762180e2c3a91585e3265690b6c Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Wed, 9 Aug 2023 12:52:28 +0800 Subject: [PATCH 14/62] 1. add submodule A1_raspi_py 2. archive now module --- raisimGymTorch/A1_raspi_py | 1 - 1 file changed, 1 deletion(-) delete mode 160000 raisimGymTorch/A1_raspi_py diff --git a/raisimGymTorch/A1_raspi_py b/raisimGymTorch/A1_raspi_py deleted file mode 160000 index a565b08d1..000000000 --- a/raisimGymTorch/A1_raspi_py +++ /dev/null @@ -1 +0,0 @@ -Subproject commit a565b08d1bde6f797782e88d85b3f7361c4a6f8d From c0f96f27ef32b326fb500acd279d42a238c2b8f2 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Wed, 9 Aug 2023 12:52:30 +0800 Subject: [PATCH 15/62] 1. add submodule A1_raspi_py 2. archive now module --- .../raisimGymTorch/env/envs/rsg/sim_with_real.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index d63fe5d38..80075ad76 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -18,7 +18,12 @@ import argparse from sine_generator import sine_generator -from raisimGymTorch.env.deploy.py.api import robot as rbt +"""" +todo + 1. add rbt + 2. modify lib rbt + +""" From 6910f144c593f9a25d6b10c7cc3a3be3a71ef3a7 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Wed, 9 Aug 2023 13:24:04 +0800 Subject: [PATCH 16/62] 1. add submodule A1_raspi_py 2. archive now module --- .../raisimGymTorch/env/deploy/onnx_deploy.py | 1 + .../env/envs/rsg/robot_utils.py | 18 ++++++++++ .../env/envs/rsg/sim_with_real.py | 35 ++++++++++++++++--- 3 files changed, 50 insertions(+), 4 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py index c20f0a074..eb1b17997 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py @@ -7,6 +7,7 @@ # 加载模型 + def ang_trans(lower, upper, x): """ trans the rate x to the angle between lower and upper diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py new file mode 100644 index 000000000..0465a885f --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py @@ -0,0 +1,18 @@ +from unitree_api import robot as rbt +from unitree_deploy.sine_generator import sine_generator +a1 = rbt.Robot() + +# todo test this after sleep +def init_position(position, timing = 100): + a1.go_position(position, timing) + +def init_robot(): + a1.observe() + act = a1.position + a1.init_motor(act) + + +if __name__=='__main__': + init_robot() + + init_position(position=sine_generator(0, 40, 0.14)) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index 80075ad76..6dfe07253 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -16,8 +16,8 @@ import torch import datetime import argparse -from sine_generator import sine_generator - +# from sine_generator import sine_generator +from unitree_deploy.sine_generator import sine_generator """" todo 1. add rbt @@ -28,6 +28,7 @@ + # task specification task_name = "sim2real" @@ -128,7 +129,6 @@ print = logger.info -mode == 'train' total_update = args.update @@ -138,6 +138,25 @@ act_rate = float(act_rate) + +# NOTE : a1 init +moving_robot = False +if moving_robot: + from robot_utils import * + + init_robot() + + ori_posi = sine_generator(0, schedule, rate=angle_rate) # initial position + # a1.kp = cfg['environment']['kp'] + + init_position(ori_posi) + + input('Are you sure to go on?') + + + + + env.reset() start = time.time() onnx_flag = False @@ -148,11 +167,14 @@ load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) envs_idx = [0] * num_envs +if moving_robot : + real_idx = 0 for step in range(n_steps * 10): time.sleep(0.01) obs = env.observe(False) - + if moving_robot: + real_obs = a1.observe() if onnx_flag: action = onnx_deploy.run_model(obs, cnt_onnx, 50) action = np.array(action)[0] @@ -161,6 +183,11 @@ action = ppo.act(obs) sine = sine_generator(envs_idx, schedule, angle_rate) action = transfer(action, sine, act_rate).astype(np.float32) + if moving_robot: + real_action = ppo.act(real_obs) + sine = sine_generator(real_idx, schedule, angle_rate) + real_action = transfer(real_action, sine, act_rate).astype(np.float32) + a1.take_action(real_action) reward, dones = env.step(action) envs_idx = list(map(check_done, envs_idx, dones)) From 918228aec4ad80c1dc7d62de8e71099fba71195a Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Wed, 9 Aug 2023 16:29:56 +0800 Subject: [PATCH 17/62] deploy part --- .../raisimGymTorch/env/deploy/angle_utils.py | 5 +- .../envs/rsg/Environment_tobuildforpython.hpp | 2 +- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 4 +- .../env/envs/rsg/robot_utils.py | 29 +++++-- .../raisimGymTorch/env/envs/rsg/runner.py | 78 +++++++++---------- .../env/envs/rsg/sim_with_real.py | 43 +++++++--- .../env/envs/rsg/sine_generator.py | 50 ------------ 7 files changed, 100 insertions(+), 111 deletions(-) delete mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py index 01b6c7fbf..bba1b2e6c 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py @@ -54,13 +54,14 @@ def sine_generator(angle_list, idx, T, rate=1): angle_list[idx_base+9] = base3 return angle_list -def transfer(act_gen, sine, k): +def transfer(act_gen, sine, k) ->np.array: """ clip, lerp, generate the final action params: act_gen: [12 * (-1, 1)] np.array params: sine: [12 * rad_target] np.array """ - + if act_gen.shape[0] == 1: + act_gen = act_gen[0] action = act_gen * k + sine * (1-k) action = np.clip(action, low, upp) return action diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index e6371edf2..fc11d37f9 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -53,7 +53,7 @@ class ENVIRONMENT : public RaisimGymEnv { acc_.setZero();//1 // init_position(); - gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883, 0.0, 0.4, -0.8529411764705883; + gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; // init_position(gc_init_); init(); diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 88ff4cea2..0bf506309 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -10,9 +10,9 @@ environment: simulation_dt: 0.0025 control_dt: 0.01 max_time: 8.0 - action_std: 0.010 + action_std: 0.01 show_ref: false - angle_rate: 0.3 + angle_rate: 0.15 stable: 1 reference: 0 schedule: 40 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py index 0465a885f..a23ac60fd 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py @@ -1,18 +1,37 @@ from unitree_api import robot as rbt from unitree_deploy.sine_generator import sine_generator +import signal +import sys a1 = rbt.Robot() # todo test this after sleep def init_position(position, timing = 100): a1.go_position(position, timing) - -def init_robot(): a1.observe() + +def quit_robot(robot): + robot.back_safe() + print('Task finished') + sys.exit(0) + +def signal_handler(signal, frame): + print('You pressed Ctrl+C!') + quit_robot(a1) + +signal.signal(signal.SIGINT, signal_handler) +def init_robot(dt): + a1.dt = dt + print(a1.observe()) + act = a1.position + # print(act) a1.init_motor(act) if __name__=='__main__': - init_robot() - - init_position(position=sine_generator(0, 40, 0.14)) + init_robot(0.01) + print(a1.observe()) + # init_position(position=sine_generator(0, 40, 0.14)) + # + # while True: + # a1.hold_on() diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 0d0e9d46b..0ef130d65 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -16,7 +16,7 @@ import torch import datetime import argparse -from sine_generator import sine_generator +from unitree_deploy.sine_generator import sine_generator @@ -132,44 +132,44 @@ done_sum = 0 average_dones = 0. - if update % cfg['environment']['eval_every_n'] == 0: - print("Visualizing and evaluating the current policy") - torch.save({ - 'actor_architecture_state_dict': actor.architecture.state_dict(), - 'actor_distribution_state_dict': actor.distribution.state_dict(), - 'critic_architecture_state_dict': critic.architecture.state_dict(), - 'optimizer_state_dict': ppo.optimizer.state_dict(), - }, saver.data_dir+"/full_"+str(update)+'.pt') - # we create another graph just to demonstrate the save/load method - loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) - loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) - - env.turn_on_visualization() - env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') - envs_idx = [0] * num_envs - for step in range(n_steps): - with torch.no_grad(): - frame_start = time.time() - obs = env.observe(False) - action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) - action = action.cpu().detach().numpy() - sine = sine_generator(envs_idx, schedule, angle_rate) - action = transfer(action, sine, act_rate).astype(np.float32) - - reward, dones = env.step(action) - envs_idx = list(map(check_done, envs_idx, dones)) - reward_analyzer.add_reward_info(env.get_reward_info()) - frame_end = time.time() - wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) - if wait_time > 0.: - time.sleep(wait_time) - - env.stop_video_recording() - env.turn_off_visualization() - - reward_analyzer.analyze_and_plot(update) - env.reset() - env.save_scaling(saver.data_dir, str(update)) + # if update % cfg['environment']['eval_every_n'] == 0: + # print("Visualizing and evaluating the current policy") + # torch.save({ + # 'actor_architecture_state_dict': actor.architecture.state_dict(), + # 'actor_distribution_state_dict': actor.distribution.state_dict(), + # 'critic_architecture_state_dict': critic.architecture.state_dict(), + # 'optimizer_state_dict': ppo.optimizer.state_dict(), + # }, saver.data_dir+"/full_"+str(update)+'.pt') + # # we create another graph just to demonstrate the save/load method + # loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + # loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) + # + # env.turn_on_visualization() + # env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') + # envs_idx = [0] * num_envs + # for step in range(n_steps): + # with torch.no_grad(): + # frame_start = time.time() + # obs = env.observe(False) + # action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + # action = action.cpu().detach().numpy() + # sine = sine_generator(envs_idx, schedule, angle_rate) + # action = transfer(action, sine, act_rate).astype(np.float32) + # + # reward, dones = env.step(action) + # envs_idx = list(map(check_done, envs_idx, dones)) + # reward_analyzer.add_reward_info(env.get_reward_info()) + # frame_end = time.time() + # wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) + # if wait_time > 0.: + # time.sleep(wait_time) + # + # env.stop_video_recording() + # env.turn_off_visualization() + # + # reward_analyzer.analyze_and_plot(update) + # env.reset() + # env.save_scaling(saver.data_dir, str(update)) # actual training # sine = [0] * 12 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index 6dfe07253..59eb7278b 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -16,12 +16,13 @@ import torch import datetime import argparse +# import pandas as pd # from sine_generator import sine_generator from unitree_deploy.sine_generator import sine_generator """" todo - 1. add rbt - 2. modify lib rbt + 1. left-hand right-hand check + 2. raisim data check """ @@ -77,6 +78,7 @@ env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) env.seed(cfg['seed']) +dt = cfg['environment']['control_dt'] # shortcuts ob_dim = env.num_obs act_dim = env.num_acts @@ -140,18 +142,22 @@ # NOTE : a1 init -moving_robot = False +moving_robot = True if moving_robot: from robot_utils import * - init_robot() + init_robot(dt) - ori_posi = sine_generator(0, schedule, rate=angle_rate) # initial position + ori_posi = sine_generator(0, schedule, rate=angle_rate).tolist() # initial position # a1.kp = cfg['environment']['kp'] - + # ori_posi = a1.position init_position(ori_posi) - - input('Are you sure to go on?') + print(f""" + now_posi: {a1.position}, + angle_rate : {angle_rate} + schedule: {schedule} + """) + # input('Are you sure to go on?') @@ -167,14 +173,24 @@ load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) envs_idx = [0] * num_envs -if moving_robot : +if moving_robot: real_idx = 0 for step in range(n_steps * 10): - time.sleep(0.01) + # time.sleep(0.01) obs = env.observe(False) + + print(f""" + virtual_observation: + {obs} + """) + if moving_robot: real_obs = a1.observe() + print(f""" + real_observation + {real_obs} + """) if onnx_flag: action = onnx_deploy.run_model(obs, cnt_onnx, 50) action = np.array(action)[0] @@ -186,8 +202,11 @@ if moving_robot: real_action = ppo.act(real_obs) sine = sine_generator(real_idx, schedule, angle_rate) - real_action = transfer(real_action, sine, act_rate).astype(np.float32) - a1.take_action(real_action) + real_action = transfer(real_action, sine, act_rate) + # real_action = real_action + a1.take_action(real_action.tolist()) + real_idx += 1 + reward, dones = env.step(action) envs_idx = list(map(check_done, envs_idx, dones)) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py deleted file mode 100644 index fd6d973bf..000000000 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sine_generator.py +++ /dev/null @@ -1,50 +0,0 @@ -from math import sin,pi -import numpy as np -def sine_generator(idx, T, rate=1): - if isinstance(idx, int): - base1= 0.4 - base3= 0.0 - base2 = -0.8529411764705883 - ang = abs(sin( float(idx) / T * pi)) * rate - angle_list = [0] * 12 - idx_base = 0 - - if (int(idx/T) % 2 ) == 1: - angle_list[idx_base+1] = ang + base1 - angle_list[idx_base+2] = -2 * ang + base2 - - angle_list[idx_base+4] = base1 - angle_list[idx_base+5] = base2 - - angle_list[idx_base+7] = base1 - angle_list[idx_base+8] = base2 - angle_list[idx_base+10] = ang + base1 - angle_list[idx_base+11] = - 2 * ang + base2 - else: - angle_list[idx_base+1] = base1 - angle_list[idx_base+2] = base2 - - angle_list[idx_base+10] = base1 - angle_list[idx_base+11] = base2 - angle_list[idx_base+4] = ang + base1 - angle_list[idx_base+5] = -2 * ang + base2 - - angle_list[idx_base+7] = ang + base1 - angle_list[idx_base+8] = -2 * ang + base2 - angle_list[idx_base+0] = base3 - angle_list[idx_base+3] = base3 - angle_list[idx_base+6] = base3 - angle_list[idx_base+9] = base3 - return angle_list - else: - # tmp = [] - tmp= [sine_generator(x, T, rate) for x in idx] - return np.array(tmp) - - -if __name__=='__main__': - # angle_list = [[0 for x in range(12)] for z in range(3)] - idx = [3, 2, 4] - angle_list = sine_generator(idx, 40, 0.3) - print(angle_list) - print(angle_list.shape) \ No newline at end of file From 7f1e7bfd394be0c7190949c9d8dc7892b06bf550 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Wed, 9 Aug 2023 21:58:53 +0800 Subject: [PATCH 18/62] modified sim_with_real.py could test on A1 --- .../envs/rsg/Environment_tobuildforpython.hpp | 25 ++++-- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 2 +- .../env/envs/rsg/robot_utils.py | 7 +- .../raisimGymTorch/env/envs/rsg/runner.py | 90 ++++++++++--------- .../env/envs/rsg/sim_with_real.py | 20 +++-- 5 files changed, 84 insertions(+), 60 deletions(-) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index fc11d37f9..2a94685dd 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -41,7 +41,7 @@ class ENVIRONMENT : public RaisimGymEnv { world_->addGround(); /// get robot data - gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gcDim_ = anymal_->getGeneralizedCoordinateDim(); // 19 gvDim_ = anymal_->getDOF(); // 18 nJoints_ = gvDim_ - 6; @@ -53,7 +53,7 @@ class ENVIRONMENT : public RaisimGymEnv { acc_.setZero();//1 // init_position(); - gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; + gc_init_<< 0, 0, 0.32, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; // init_position(gc_init_); init(); @@ -188,22 +188,31 @@ class ENVIRONMENT : public RaisimGymEnv { raisim::Vec<4> quat; raisim::Mat<3,3> rot; quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + quat /= quat.norm(); +// std::cout << quat << std::endl; raisim::quatToRotMat(quat, rot); bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); Eigen::VectorXd gcc = gc_.tail(12); Eigen::VectorXd gvv = gv_.tail(12); +// std::cout << "gcc_ : \n " << gcc << std::endl << "gvv : \n" << gvv << std::endl; Eigen::VectorXd c_v(24); + c_v.setZero(24); for(auto i = 0; i <12 ; i++ ) { - c_v << gcc[i], gvv[i]; + c_v[i*2] = gcc[i]; + c_v[i*2 + 1] = gvv[i]; } - obDouble_ << quat, // quaternion - bodyAngularVel_, // ras/s - acc_, // m/s^2 -// gc_.tail(12), // rad/s -// gv_.tail(12); // rad/s^2 +// std::cout << "quat" << quat << "\n body angular vel" << bodyAngularVel_ << "\n acc " << acc_ << "\nc_v "<< c_v << std::endl; + obDouble_ << quat[0], quat[1], quat[2], quat[3], // quaternion + bodyAngularVel_[0], // ras/s + bodyAngularVel_[1], // ras/s + bodyAngularVel_[2], // ras/s + acc_[0], // m/s^2 + acc_[1], // m/s^2 + acc_[2], // m/s^2 c_v; +// std::cout<< "obdouble \n" << obDouble_ << std::endl; } diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 0bf506309..60d69f9e1 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -10,7 +10,7 @@ environment: simulation_dt: 0.0025 control_dt: 0.01 max_time: 8.0 - action_std: 0.01 + action_std: 0.05 show_ref: false angle_rate: 0.15 stable: 1 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py index a23ac60fd..291157427 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py @@ -31,7 +31,8 @@ def init_robot(dt): if __name__=='__main__': init_robot(0.01) print(a1.observe()) - # init_position(position=sine_generator(0, 40, 0.14)) + init_position(position=sine_generator(0, 40, 0.14).tolist()) # - # while True: - # a1.hold_on() + while True: + # print(a1.observe()) + a1.hold_on() diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 0ef130d65..13c2bfec9 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -37,7 +37,7 @@ parser = argparse.ArgumentParser() parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') -parser.add_argument('-u', '--update', help='update times', type=int, default=120) +parser.add_argument('-u', '--update', help='update times', type=int, default=300) parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) # parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) args = parser.parse_args() @@ -47,7 +47,7 @@ # load_best = args.load_best # check if gpu is available device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') - +print(device) # directories task_path = os.path.dirname(os.path.realpath(__file__)) home_path = task_path + "/../../../../.." @@ -132,50 +132,55 @@ done_sum = 0 average_dones = 0. - # if update % cfg['environment']['eval_every_n'] == 0: - # print("Visualizing and evaluating the current policy") - # torch.save({ - # 'actor_architecture_state_dict': actor.architecture.state_dict(), - # 'actor_distribution_state_dict': actor.distribution.state_dict(), - # 'critic_architecture_state_dict': critic.architecture.state_dict(), - # 'optimizer_state_dict': ppo.optimizer.state_dict(), - # }, saver.data_dir+"/full_"+str(update)+'.pt') - # # we create another graph just to demonstrate the save/load method - # loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) - # loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) - # - # env.turn_on_visualization() - # env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') - # envs_idx = [0] * num_envs - # for step in range(n_steps): - # with torch.no_grad(): - # frame_start = time.time() - # obs = env.observe(False) - # action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) - # action = action.cpu().detach().numpy() - # sine = sine_generator(envs_idx, schedule, angle_rate) - # action = transfer(action, sine, act_rate).astype(np.float32) - # - # reward, dones = env.step(action) - # envs_idx = list(map(check_done, envs_idx, dones)) - # reward_analyzer.add_reward_info(env.get_reward_info()) - # frame_end = time.time() - # wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) - # if wait_time > 0.: - # time.sleep(wait_time) - # - # env.stop_video_recording() - # env.turn_off_visualization() - # - # reward_analyzer.analyze_and_plot(update) - # env.reset() - # env.save_scaling(saver.data_dir, str(update)) + if update % cfg['environment']['eval_every_n'] == 0: + print("Visualizing and evaluating the current policy") + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + # we create another graph just to demonstrate the save/load method + loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) + + env.turn_on_visualization() + env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') + envs_idx = [0] * num_envs + for step in range(n_steps): + with torch.no_grad(): + frame_start = time.time() + obs = env.observe(False) + action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) + action = action.cpu().detach().numpy() + sine = sine_generator(envs_idx, schedule, angle_rate) + action = transfer(action, sine, act_rate).astype(np.float32) + + reward, dones = env.step(action) + envs_idx = list(map(check_done, envs_idx, dones)) + reward_analyzer.add_reward_info(env.get_reward_info()) + frame_end = time.time() + wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) + if wait_time > 0.: + time.sleep(wait_time) + + env.stop_video_recording() + env.turn_off_visualization() + + reward_analyzer.analyze_and_plot(update) + env.reset() + env.save_scaling(saver.data_dir, str(update)) # actual training # sine = [0] * 12 envs_idx = [0] * num_envs for step in range(n_steps): - obs = env.observe() + obs = env.observe(False) + """ + 1. z轴方向的加速度的处理方法 + 2. 为什么后边的轴没有速度? + + """ action = ppo.act(obs) @@ -188,7 +193,7 @@ done_sum = done_sum + np.sum(dones) reward_sum = reward_sum + np.sum(reward) # take st step to get value obs - obs = env.observe() + obs = env.observe(False) ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 == 0, update=update) average_ll_performance = reward_sum / total_steps if average_ll_performance > biggest_reward: @@ -242,6 +247,7 @@ else: action = ppo.act(obs) + reward, dones = env.step(action) print(f'biggest:{biggest_reward},rate = {biggest_iter}') diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index 59eb7278b..b8f7f171e 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -142,7 +142,8 @@ # NOTE : a1 init -moving_robot = True +moving_robot = False + if moving_robot: from robot_utils import * @@ -175,15 +176,17 @@ envs_idx = [0] * num_envs if moving_robot: real_idx = 0 + for i in range(schedule): + a1.hold_on() for step in range(n_steps * 10): - # time.sleep(0.01) + time.sleep(0.01) obs = env.observe(False) - print(f""" - virtual_observation: - {obs} - """) + # print(f""" + # virtual_observation: + # {obs} + # """) if moving_robot: real_obs = a1.observe() @@ -191,6 +194,11 @@ real_observation {real_obs} """) + # for i in range(schedule): + # a1.hold_on() + # print(a1.observe()) + # real_obs = a1.observe() + # print(real_obs) if onnx_flag: action = onnx_deploy.run_model(obs, cnt_onnx, 50) action = np.array(action)[0] From 6a8a93a73ed88f4b2204ba559025e7d96771a3eb Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Thu, 10 Aug 2023 16:58:04 +0800 Subject: [PATCH 19/62] modified time-waiter --- raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py | 4 +- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 2 +- .../raisimGymTorch/env/envs/rsg/runner.py | 1 - .../env/envs/rsg/sim_with_real.py | 83 ++++++++++--------- .../helper/raisim_gym_helper.py | 12 +-- 5 files changed, 54 insertions(+), 48 deletions(-) diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py index f50835a61..1a1d872d4 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py @@ -76,8 +76,8 @@ def __init__(self, def act(self, actor_obs): self.actor_obs = actor_obs with torch.no_grad(): - tmp = torch.from_numpy(actor_obs) - self.actions, self.actions_log_prob = self.actor.sample(tmp.to(self.device)) + # tmp = torch.from_numpy(actor_obs) + self.actions, self.actions_log_prob = self.actor.sample(torch.from_numpy(self.actor_obs).to(self.device)) return self.actions diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 60d69f9e1..55d4732ed 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -10,7 +10,7 @@ environment: simulation_dt: 0.0025 control_dt: 0.01 max_time: 8.0 - action_std: 0.05 + action_std: 0.00 show_ref: false angle_rate: 0.15 stable: 1 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 13c2bfec9..1fdf184cc 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -178,7 +178,6 @@ obs = env.observe(False) """ 1. z轴方向的加速度的处理方法 - 2. 为什么后边的轴没有速度? """ action = ppo.act(obs) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index b8f7f171e..1f4b50013 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -61,7 +61,7 @@ cfg_path = args.cfg_path # load_best = args.load_best # check if gpu is available -device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') +device = torch.device('cpu') # directories task_path = os.path.dirname(os.path.realpath(__file__)) @@ -139,10 +139,23 @@ act_rate = cfg['environment']['action_std'] # how many action generated use for work act_rate = float(act_rate) +input(f"Are you sure to execute the action in schedule: {schedule}, angle_rate: {angle_rate}, act_rate(how many action generated from NN used for work): {act_rate}") + +# init virtual part +env.reset() +start = time.time() +onnx_flag = False +if onnx_flag: + cnt_onnx = 0 + from raisimGymTorch.env.deploy import onnx_deploy +else: + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +envs_idx = [0] * num_envs # NOTE : a1 init -moving_robot = False +moving_robot = True if moving_robot: from robot_utils import * @@ -164,59 +177,53 @@ -env.reset() -start = time.time() -onnx_flag = False -if onnx_flag: - cnt_onnx = 0 - from raisimGymTorch.env.deploy import onnx_deploy -else: - load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) -envs_idx = [0] * num_envs + if moving_robot: real_idx = 0 for i in range(schedule): a1.hold_on() + # print(f"before work {a1.position}") for step in range(n_steps * 10): - time.sleep(0.01) + if not moving_robot: + print('moving?') + time.sleep(0.01) obs = env.observe(False) - # print(f""" - # virtual_observation: - # {obs} - # """) + #virtual bot part + # if onnx_flag: + # action = onnx_deploy.run_model(obs, cnt_onnx, 50) + # action = np.array(action)[0] + # cnt_onnx += 1 + # else: + # gen_action = ppo.act(obs) + # sine = sine_generator(envs_idx, schedule, angle_rate) + # action = transfer(gen_action, sine, act_rate).astype(np.float32) + # print(f"virtual_obs:{obs} \n virtual_gen_action:{gen_action} \n virtual_action:{action}") + # if real_idx == 0: + # a1.hold_on() + + # real bot part if moving_robot: + print('b-observe') real_obs = a1.observe() - print(f""" - real_observation - {real_obs} - """) - # for i in range(schedule): - # a1.hold_on() - # print(a1.observe()) - # real_obs = a1.observe() - # print(real_obs) - if onnx_flag: - action = onnx_deploy.run_model(obs, cnt_onnx, 50) - action = np.array(action)[0] - cnt_onnx += 1 - else: - action = ppo.act(obs) - sine = sine_generator(envs_idx, schedule, angle_rate) - action = transfer(action, sine, act_rate).astype(np.float32) - if moving_robot: - real_action = ppo.act(real_obs) + print('b-ppo') + gen_action = ppo.act(real_obs) + print('b-sin') sine = sine_generator(real_idx, schedule, angle_rate) - real_action = transfer(real_action, sine, act_rate) + print('b-trans') + real_action = transfer(gen_action, sine, act_rate) # real_action = real_action + print(f"real_obs:{real_obs} \n gen_action : {gen_action}\n for work_action:{real_action}") + a1.take_action(real_action.tolist()) real_idx += 1 - reward, dones = env.step(action) - envs_idx = list(map(check_done, envs_idx, dones)) + # update virtual bot + # reward, dones = env.step(action) + # envs_idx = list(map(check_done, envs_idx, dones)) print(f'biggest:{biggest_reward},rate = {biggest_iter}') diff --git a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py index 9eca4634f..a747eae1e 100755 --- a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py +++ b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py @@ -63,17 +63,17 @@ class RaisimLogger(): def __init__(self, path): self.logger = logging.getLogger(__file__) self.logger.setLevel(logging.INFO) - self.fh = logging.FileHandler(path) + # self.fh = logging.FileHandler(path) self.ch = logging.StreamHandler() - self.fh.setLevel(logging.INFO) + # self.fh.setLevel(logging.INFO) self.ch.setLevel(logging.INFO) - self.formatter = logging.Formatter("%(asctime)s - %(name)s - %(levelname)s - %(message)s", - datefmt="%Y-%m-%d %H:%M:%S") + self.formatter = logging.Formatter("%(asctime)s.%(msecs)03d - %(levelname)s - %(message)s", + datefmt='%Y-%m-%d,%H:%M:%S') self.ch.setFormatter(self.formatter) - self.fh.setFormatter(self.formatter) + # self.fh.setFormatter(self.formatter) self.logger.addHandler(self.ch) - self.logger.addHandler(self.fh) + # self.logger.addHandler(self.fh) def info(self, msg): self.logger.info(msg) From e19d53243b1e42f72f47b8db5b507941b74a586e Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Fri, 11 Aug 2023 19:42:17 +0800 Subject: [PATCH 20/62] a1 trot step finished --- examples/src/server/go1.cpp | 151 ++++++++++++++---- .../raisimGymTorch/deploy_log/anay.py | 8 + .../raisimGymTorch/env/auto_runner.py | 6 +- .../raisimGymTorch/env/deploy/angle_utils.py | 44 +++-- .../envs/rsg/Environment_tobuildforpython.hpp | 99 ++++++++---- .../raisimGymTorch/env/envs/rsg/runner.py | 20 ++- .../env/envs/rsg/sim_with_real.py | 122 ++++++++------ 7 files changed, 324 insertions(+), 126 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/deploy_log/anay.py diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index 0b3ce6deb..0a143cd4e 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -4,7 +4,27 @@ #include "raisim/RaisimServer.hpp" #include "raisim/World.hpp" #define PI 3.1415926 - +#include +auto ToEulerAngles(Eigen::Quaterniond q) { + Eigen::Vector3d angles; + + // roll (x-axis rotation) + double sinr_cosp = 2 * (q.w() * q.x() + q.y() * q.z()); + double cosr_cosp = 1 - 2 * (q.x ()* q.x() + q.y() * q.y()); + angles[0] = std::atan2(sinr_cosp, cosr_cosp); + + // pitch (y-axis rotation) + double sinp = std::sqrt(1 + 2 * (q.w ()* q.y ()- q.x() * q.z())); + double cosp = std::sqrt(1 - 2 * (q.w ()* q.y() - q.x() * q.z())); + angles[1] = 2 * std::atan2(sinp, cosp) - M_PI / 2; + + // yaw (z-axis rotation) + double siny_cosp = 2 * (q.w() * q.z() + q.x() * q.y()); + double cosy_cosp = 1 - 2 * (q.y() * q.y() + q.z() * q.z()); + angles[2] = std::atan2(siny_cosp, cosy_cosp); + + return angles; +} void swap(Eigen::VectorXd &ob, int a, int b) { @@ -12,15 +32,60 @@ void swap(Eigen::VectorXd &ob, int a, int b) ob[a] = ob[b]; ob[b] = ob[a]; } +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +// // todo ang2, rate, ang +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.523, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// double ang2 = -0.15 * ang * 0; +// double ang3 = ang2 * -2; +// int idx_base = 0; +//// std::cout<getGeneralizedCoordinateDim()), jointVelocityTarget(go1->getDOF()); // jointNominalConfig << 0, 0, 0.41, 1.0, 0.0, 0.0, 0.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; - jointNominalConfig << 0, 0, 0.36, 1.0, 0.0, 0, 0, 0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976 ; // todo implement in python using list + jointNominalConfig << 0, 0, 0.33, 1.0, 0.0, 0, 0, 0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976 ; // todo implement in python using list // jointNominalConfig.tail(12).setZero(); // Eigen::VectorXd tmp(12); // tmp.setZero(); @@ -100,12 +163,22 @@ int main(int argc, char* argv[]) { Eigen::Vector3d pos(0,0, 3); Eigen::VectorXd ob_(24); ob_.setZero(); + Eigen::VectorXd gc, gv; + Eigen::VectorXd position, velo; + position.setZero(12), velo.setZero(12); + gc.setZero(19), gv.setZero(18); size_t dof = go1->getDOF(); + + raisim::Vec<3> vel; + vel.setZero(); + raisim::Vec<3> acc; + Eigen::Vector3d ma; + ma.setZero(); for (int i=0; i<2000000; i++) { - go1->getState(jointNominalConfig,jointVelocityTarget); + go1->getState(gc,gv); Eigen::VectorXd tmp1(12), tmp2(12); - tmp1 = jointNominalConfig.tail(12); - tmp2 = jointVelocityTarget.tail(12); + tmp1 = gc.tail(12); + tmp2 = gv.tail(12); for(auto i=0; i<12; i++){ ob_[2*i] = tmp1[i]; ob_[2 * i+1] = tmp2[i]; @@ -114,13 +187,34 @@ int main(int argc, char* argv[]) { { swap(ob_, i, 12 +i); } - raisim::Vec<3> acc_; - go1->getFrameAcceleration("ROOT", acc_); - std::cout< vel_temp; + go1->getFrameVelocity("ROOT", vel_temp); +// for(auto i =0;i <2; i++) +// { + acc = (vel_temp - vel) / 0.01; + vel = vel_temp; +// acc[i] = vel_temp +// } +// std::cout << "vel \n" << vel << std::endl << "acc\n " << acc << std::endl; + usleep(10000); + angle_generator(position, i, 40, 0.15); + jointNominalConfig.tail(12) = position; + + Eigen::Quaterniond quat(gc[3], gc[4], gc[5], gc[6]); + Eigen::Vector3d angle = ToEulerAngles(quat); + if (abs(angle[0]) >abs(ma[0]) ) ma[0] = abs(angle[0]); + if (abs(angle[1]) >abs(ma[1]) ) ma[1] = abs(angle[1]); + if (abs(angle[2]) >abs(ma[2]) ) ma[2] = abs(angle[2]); + +// std::cout<setBasePos(pos); // angle_generator(tmp, i, 50.f, 0.3); // double rrr = 0; @@ -130,7 +224,8 @@ int main(int argc, char* argv[]) { // } // jointNominalConfig.tail(12) = tmp; // std::cout<< tmp << std::endl; - go1->setPdTarget(jointNominalConfig, jointVelocityTarget); + +go1->setPdTarget(jointNominalConfig, jointVelocityTarget); server.integrateWorldThreadSafe(); diff --git a/raisimGymTorch/raisimGymTorch/deploy_log/anay.py b/raisimGymTorch/raisimGymTorch/deploy_log/anay.py new file mode 100644 index 000000000..6d6bcbf51 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_log/anay.py @@ -0,0 +1,8 @@ +import re +with open("./08-11-15-28", 'r') as f: + lines = f.readlines() + for line in lines: + # x = re.search("work_action", line) + # print(x) + if "work_action" in line: + print(line) \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/auto_runner.py b/raisimGymTorch/raisimGymTorch/env/auto_runner.py index be137ccd6..456a2161c 100644 --- a/raisimGymTorch/raisimGymTorch/env/auto_runner.py +++ b/raisimGymTorch/raisimGymTorch/env/auto_runner.py @@ -11,10 +11,10 @@ def change_data(path, flag, data): with open(path, 'w') as f : dump(y, f, Dumper=RoundTripDumper) -test_list = [x/1000 for x in range(2,20,2)] -test_T = [x for x in range(40, 70, 10)] +test_list = [x/10 for x in range(1,20,4)] +test_T = [40] # print(test_list) -length = 300 +length = 500 for j in test_T: for i in test_list: change_data('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml',['action_std','schedule'], [i, j]) diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py index bba1b2e6c..6d2609009 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py @@ -18,8 +18,9 @@ def rad_deg(x): upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] low = deg_rad(low) upp = deg_rad(upp) +bund = [upp[i] - low[i] for i in range(12)] def sine_generator(angle_list, idx, T, rate=1): - base1= 0.82 + base1= 0.523 base3= 0.0 base2 = -2 * base1 ang = abs(sin( float(idx) / T * pi)) * rate @@ -54,12 +55,20 @@ def sine_generator(angle_list, idx, T, rate=1): angle_list[idx_base+9] = base3 return angle_list -def transfer(act_gen, sine, k) ->np.array: +def transfer(act_gen, sine, k, history_act = None) ->np.array: """ clip, lerp, generate the final action params: act_gen: [12 * (-1, 1)] np.array params: sine: [12 * rad_target] np.array """ + # act_gen = (act_gen + 1) /2 # 0-1 + act_gen = act_gen * bund # - + + act_gen = np.clip(act_gen, low, upp) + if history_act is not None: + kk = 0.9 + # act_gen = (1-kk) * act_gen + act_gen = act_gen * (1-kk) + history_act * kk + act_gen = np.clip(act_gen, low, upp) if act_gen.shape[0] == 1: act_gen = act_gen[0] action = act_gen * k + sine * (1-k) @@ -67,12 +76,25 @@ def transfer(act_gen, sine, k) ->np.array: return action if __name__=='__main__': - angle_list = [0 for x in range(12)] - - sine_generator(angle_list, 2, 40, 0.3) - angle_list = np.array(angle_list) - act = transfer(np.random.random((100,12)), angle_list, 0.3) - print('sine:', angle_list) - print('low:', low) - print('upp:', upp) - print(act.shape, type(act)) + # angle_list = [0 for x in range(12)] + # + # sine_generator(angle_list, 0, 40, 0.3) + # angle_list = np.array(angle_list) + # act = transfer(np.zeros((100,12)), angle_list, 1) + # print('sine:', angle_list) + # print('low:', low) + # print('upp:', upp) + # print('bound', bund) + # print(act[0]) + his_util = [0, 0.523, -1.046] * 4 + check_done = lambda a, b: a + 1 if not b else 0 + check_history = lambda a, b: a if not b else his_util + check_zero = lambda a:1 if a!=0 else 0 + tmp1 = np.zeros((100,12)) + idx = np.random.rand(100) + idx[1:10] = False + idx = list(map(check_zero, idx)) + print(idx) + tmp = np.array([check_history(tmp1[i], idx[i]) for i in range(100) ]) + assert tmp1.shape == tmp.shape + print(tmp) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index 2a94685dd..b8ace7b94 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -14,7 +14,28 @@ namespace raisim { -class ENVIRONMENT : public RaisimGymEnv { + auto ToEulerAngles(Eigen::Quaterniond q) { + Eigen::Vector3d angles; + + // roll (x-axis rotation) + double sinr_cosp = 2 * (q.w() * q.x() + q.y() * q.z()); + double cosr_cosp = 1 - 2 * (q.x ()* q.x() + q.y() * q.y()); + angles[0] = std::atan2(sinr_cosp, cosr_cosp); + + // pitch (y-axis rotation) + double sinp = std::sqrt(1 + 2 * (q.w ()* q.y ()- q.x() * q.z())); + double cosp = std::sqrt(1 - 2 * (q.w ()* q.y() - q.x() * q.z())); + angles[1] = 2 * std::atan2(sinp, cosp) - M_PI / 2; + + // yaw (z-axis rotation) + double siny_cosp = 2 * (q.w() * q.z() + q.x() * q.y()); + double cosy_cosp = 1 - 2 * (q.y() * q.y() + q.z() * q.z()); + angles[2] = std::atan2(siny_cosp, cosy_cosp); + + return angles; + } + + class ENVIRONMENT : public RaisimGymEnv { public: @@ -47,17 +68,18 @@ class ENVIRONMENT : public RaisimGymEnv { gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + euler_angle.setZero(); pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); acc_.setZero();//1 // init_position(); - gc_init_<< 0, 0, 0.32, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; + gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; // init_position(gc_init_); init(); - obDim_ = 34; + obDim_ = 31; actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); obDouble_.setZero(obDim_); @@ -85,9 +107,20 @@ class ENVIRONMENT : public RaisimGymEnv { void init() final { Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); - jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(p_gain); - jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(d_gain); + jointPgain.setZero(); + jointPgain.tail(nJoints_).setConstant(p_gain); + jointPgain.tail(nJoints_)[2] = 300; + jointPgain.tail(nJoints_)[5] = 300; + jointPgain.tail(nJoints_)[8] = 300; + jointPgain.tail(nJoints_)[11] = 300; + jointDgain.setZero(); + jointDgain.tail(nJoints_).setConstant(d_gain); + jointDgain.tail(nJoints_)[2] = 15; + jointDgain.tail(nJoints_)[5] = 15; + jointDgain.tail(nJoints_)[8] = 15; + jointDgain.tail(nJoints_)[11] = 15; anymal_->setPdGains(jointPgain, jointDgain); +// std::cout<setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); if(show_ref) @@ -98,7 +131,7 @@ class ENVIRONMENT : public RaisimGymEnv { anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); anymal_1->setPdGains(jointPgain,jointDgain); } - std::cout<<"position inited\n"; +// std::cout<<"position inited\n"; } void init_position(const Eigen::Ref& posi) final @@ -142,16 +175,20 @@ class ENVIRONMENT : public RaisimGymEnv { } updateObservation(); double rrr =0; - for(int i=4; i<=6 ; i++) - { - rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; - } -// rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; - rewards_.record("Stable", 1 - rrr, false); - rewards_.record("forwardVel", bodyLinearVel_[0], false); - - gc_old = gc_.tail(12); - ref_old = angle_list; +// for(int i=4; i<=6 ; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// for(int i =0;i<=2; i++)rrr += abs(bodyAngularVel_[i]); +//std::cout<getState(gc_, gv_); - std::string root_name = "ROOT"; - anymal_->getFrameAcceleration(root_name , acc_); +// std::string root_name = "ROOT"; +// anymal_->getFrameAcceleration(root_name , acc_); raisim::Vec<4> quat; raisim::Mat<3,3> rot; quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; @@ -208,9 +245,9 @@ class ENVIRONMENT : public RaisimGymEnv { bodyAngularVel_[0], // ras/s bodyAngularVel_[1], // ras/s bodyAngularVel_[2], // ras/s - acc_[0], // m/s^2 - acc_[1], // m/s^2 - acc_[2], // m/s^2 +// acc_[0], // m/s^2 +// acc_[1], // m/s^2 +// acc_[2], // m/s^2 # todo recall acc c_v; // std::cout<< "obdouble \n" << obDouble_ << std::endl; @@ -223,16 +260,23 @@ class ENVIRONMENT : public RaisimGymEnv { bool isTerminalState(float& terminalReward) final { terminalReward = float(terminalRewardCoeff_); - Eigen::Quaternion quat(gc_[3], gc_[4], gc_[5], gc_[6]); - Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(0,1,2); + Eigen::Quaterniond quat(gc_[3], gc_[4], gc_[5], gc_[6]); +// std::cout<<"quat" << quat.w() << " " <getContacts()) if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) {// if there is any contact body was not in the footIndices the over - rewards_.record("Stable", -10, false); + rewards_.record("Stable", -10, true); return true;} - if(abs(gc_[2] - gc_init_[2]) < 0.5) return false; - if(fmin(abs(euler[1]), abs(euler[1] - 360.0)) > 0.175) return false; - if(fmin(abs(euler[0]), abs(euler[0] - 360.0)) > 0.175) return false; + if(abs(gc_[2] - gc_init_[2]) > 0.3){ return true;} + if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.1){ return true;} + if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.1){ return true;} + if(fmin(abs(euler_angle[2]), abs(euler_angle[2] + 2 * PI)) > 0.1){ return true;} + if(abs(gc_.tail(12)[0]) >0.17) return true; + if(abs(gc_.tail(12)[3]) >0.17) return true; + if(abs(gc_.tail(12)[6]) >0.17) return true; + if(abs(gc_.tail(12)[9]) >0.17) return true; terminalReward = 0.f; return false; } @@ -258,6 +302,7 @@ class ENVIRONMENT : public RaisimGymEnv { double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; Eigen::VectorXd angle_list, angle_list_for_work; Eigen::VectorXd gc_old, ref_old; + Eigen::Vector3d euler_angle; /// these variables are not in use. They are placed to show you how to create a random number sampler. bool float_base; std::normal_distribution normDist_; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 1fdf184cc..888cbf5e2 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -111,13 +111,17 @@ if mode == 'retrain': load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) +his_util=[0, 0.523, -1.046] * 4 check_done = lambda a, b: a + 1 if not b else 0 +check_history = lambda a, b: a if not b else his_util +# need_to_review = lambda a,b: a if not b else np.array([[0, 0.523, -1.046] * 4]) # todo make sure the shape # if load_best == True: # weight_path = "" + print = logger.info mode == 'train' - +history_act = np.array([his_util] * 100) total_update = args.update if mode =='train' or mode == 'retrain': # print('start train') @@ -147,6 +151,7 @@ env.turn_on_visualization() env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') envs_idx = [0] * num_envs + for step in range(n_steps): with torch.no_grad(): frame_start = time.time() @@ -154,10 +159,11 @@ action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) action = action.cpu().detach().numpy() sine = sine_generator(envs_idx, schedule, angle_rate) - action = transfer(action, sine, act_rate).astype(np.float32) - + action = transfer(action, sine, act_rate, history_act=history_act).astype(np.float32) reward, dones = env.step(action) envs_idx = list(map(check_done, envs_idx, dones)) + history_act = np.array([ check_history(history_act[i], dones[i]) for i in range(num_envs)] ) + reward_analyzer.add_reward_info(env.get_reward_info()) frame_end = time.time() wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) @@ -184,9 +190,15 @@ sine = sine_generator(envs_idx, schedule, angle_rate) - action = transfer(action, sine, act_rate).astype(np.float32) + action = transfer(action, sine, act_rate, history_act=history_act).astype(np.float32) # todo the transfer has bug reward, dones = env.step(action) + history_act = sine + envs_idx = list(map(check_done, envs_idx, dones)) + history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) + + reward = reward * envs_idx / n_steps * 2 + envs_idx = list(map(check_done, envs_idx, dones)) ppo.step(value_obs=obs, rews=reward, dones=dones) done_sum = done_sum + np.sum(dones) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index 1f4b50013..52620ab9e 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -7,7 +7,7 @@ import raisimGymTorch.algo.ppo.module as ppo_module import raisimGymTorch.algo.ppo.ppo as PPO from raisimGymTorch.env.deploy.angle_utils import transfer - +from unitree_utils.Waiter import Waiter import os import math import time @@ -23,6 +23,8 @@ todo 1. left-hand right-hand check 2. raisim data check + + env cannot get linear-acc """ @@ -34,19 +36,6 @@ task_name = "sim2real" -""" -todo: - 1. make the model go to the same position - 2. pause check - 3. move - 1. imu info - 2. gyroscope - 3. accelerator - 4. position - 5. velocity - 4. log -""" - # configuration parser = argparse.ArgumentParser() @@ -139,23 +128,35 @@ act_rate = cfg['environment']['action_std'] # how many action generated use for work act_rate = float(act_rate) +# act_rate = 0 + input(f"Are you sure to execute the action in schedule: {schedule}, angle_rate: {angle_rate}, act_rate(how many action generated from NN used for work): {act_rate}") + +moving_robot = False +virtual = True + +his_util=[0, 0.523, -1.046] * 4 +# check_done = lambda a, b: a + 1 if not b else 0 +check_history = lambda a, b: a if not b else his_util +history_act = np.array([his_util] * 100) # init virtual part -env.reset() -start = time.time() -onnx_flag = False -if onnx_flag: - cnt_onnx = 0 - from raisimGymTorch.env.deploy import onnx_deploy -else: - load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) +if virtual: + waiter= Waiter(0.01) + env.reset() + start = time.time() + onnx_flag = False + if onnx_flag: + cnt_onnx = 0 + from raisimGymTorch.env.deploy import onnx_deploy + else: + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) -envs_idx = [0] * num_envs + envs_idx = [0] * num_envs # NOTE : a1 init -moving_robot = True + if moving_robot: from robot_utils import * @@ -165,65 +166,80 @@ ori_posi = sine_generator(0, schedule, rate=angle_rate).tolist() # initial position # a1.kp = cfg['environment']['kp'] # ori_posi = a1.position - init_position(ori_posi) + init_position(ori_posi,200) print(f""" now_posi: {a1.position}, angle_rate : {angle_rate} schedule: {schedule} """) - # input('Are you sure to go on?') - - - - - - - -if moving_robot: real_idx = 0 for i in range(schedule): a1.hold_on() - # print(f"before work {a1.position}") for step in range(n_steps * 10): if not moving_robot: + if step == 0: + waiter.update_start() print('moving?') - time.sleep(0.01) - obs = env.observe(False) + time.sleep(0.005) + obs = env.observe(False) #virtual bot part - # if onnx_flag: - # action = onnx_deploy.run_model(obs, cnt_onnx, 50) - # action = np.array(action)[0] - # cnt_onnx += 1 - # else: - # gen_action = ppo.act(obs) - # sine = sine_generator(envs_idx, schedule, angle_rate) - # action = transfer(gen_action, sine, act_rate).astype(np.float32) - # print(f"virtual_obs:{obs} \n virtual_gen_action:{gen_action} \n virtual_action:{action}") - # if real_idx == 0: - # a1.hold_on() + if virtual: + if onnx_flag: + action = onnx_deploy.run_model(obs, cnt_onnx, 50) + action = np.array(action)[0] + cnt_onnx += 1 + else: + gen_action = ppo.act(obs) + sine = sine_generator(envs_idx, schedule, angle_rate) + action = transfer(gen_action, sine, act_rate, history_act=history_act).astype(np.float32) + print(f"virtual_obs:{obs} \n virtual_gen_action:{gen_action} \n virtual_action:{action}") + + # obs = np.zeros((1,31)) + # gen_act = ppo.act(obs) + # sine = sine_generator(real_idx, schedule, angle_rate) + # act = transfer(gen_act, sine, act_rate) + + # real bot part if moving_robot: + if step ==0: + real_history_act = np.array(his_util) print('b-observe') real_obs = a1.observe() + # real_obs = np.array([a1.observe()]) + print(f"real_obs {real_obs}") + # input('now cancel it ') + # print() print('b-ppo') gen_action = ppo.act(real_obs) print('b-sin') - sine = sine_generator(real_idx, schedule, angle_rate) + real_sine = sine_generator(real_idx, schedule, angle_rate) print('b-trans') - real_action = transfer(gen_action, sine, act_rate) + real_action = transfer(gen_action, real_sine, act_rate, history_act=real_history_act) # real_action = real_action print(f"real_obs:{real_obs} \n gen_action : {gen_action}\n for work_action:{real_action}") - + # waiter.wait() + if real_action.shape[0] == 1: + real_action = real_action[0] a1.take_action(real_action.tolist()) + real_history_act = real_sine + # envs_idx = list(map(check_done, real_idx, dones)) + # history_act = np.array([check_history(history_act[i], 0) for i in range(num_envs)]) real_idx += 1 # update virtual bot - # reward, dones = env.step(action) - # envs_idx = list(map(check_done, envs_idx, dones)) + if virtual: + waiter.wait() + reward, dones = env.step(action) + print('exec') + envs_idx = list(map(check_done, envs_idx, dones)) + history_act = sine + envs_idx = list(map(check_done, envs_idx, dones)) + history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) print(f'biggest:{biggest_reward},rate = {biggest_iter}') From 37deb410252045d12a052069a81139157eddaeff Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Sun, 13 Aug 2023 18:30:29 +0800 Subject: [PATCH 21/62] the best perfomance as of 23-08-13-18-30 --- examples/src/server/go1.cpp | 12 +- .../raisimGymTorch/env/deploy/angle_utils.py | 3 +- .../envs/rsg/Environment_tobuildforpython.hpp | 109 ++++++------------ .../raisimGymTorch/env/envs/rsg/cfg.yaml | 23 ++-- .../raisimGymTorch/env/envs/rsg/runner.py | 2 +- 5 files changed, 62 insertions(+), 87 deletions(-) diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index 0a143cd4e..1107ca504 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -176,6 +176,8 @@ int main(int argc, char* argv[]) { ma.setZero(); for (int i=0; i<2000000; i++) { go1->getState(gc,gv); + raisim::Vec<4> qu{1+double(i)/500 , 0, 0, 0 + double(i)/500}; + go1->setBaseOrientation(qu); Eigen::VectorXd tmp1(12), tmp2(12); tmp1 = gc.tail(12); tmp2 = gv.tail(12); @@ -189,17 +191,17 @@ int main(int argc, char* argv[]) { } raisim::Vec<3> vel_temp; - go1->getFrameVelocity("ROOT", vel_temp); +// go1->getFrameVelocity("ROOT", vel_temp); // for(auto i =0;i <2; i++) // { - acc = (vel_temp - vel) / 0.01; +// acc = (vel_temp - vel) / 0.01; vel = vel_temp; // acc[i] = vel_temp // } // std::cout << "vel \n" << vel << std::endl << "acc\n " << acc << std::endl; usleep(10000); - angle_generator(position, i, 40, 0.15); - jointNominalConfig.tail(12) = position; +// angle_generator(position, i, 40, 0.15); +// jointNominalConfig.tail(12) = position; Eigen::Quaterniond quat(gc[3], gc[4], gc[5], gc[6]); Eigen::Vector3d angle = ToEulerAngles(quat); @@ -225,7 +227,7 @@ int main(int argc, char* argv[]) { // jointNominalConfig.tail(12) = tmp; // std::cout<< tmp << std::endl; -go1->setPdTarget(jointNominalConfig, jointVelocityTarget); +//go1->setPdTarget(jointNominalConfig, jointVelocityTarget); server.integrateWorldThreadSafe(); diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py index 6d2609009..3c8e16fea 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py @@ -65,13 +65,14 @@ def transfer(act_gen, sine, k, history_act = None) ->np.array: act_gen = act_gen * bund # - + act_gen = np.clip(act_gen, low, upp) if history_act is not None: - kk = 0.9 + kk = 0.8 # act_gen = (1-kk) * act_gen act_gen = act_gen * (1-kk) + history_act * kk act_gen = np.clip(act_gen, low, upp) if act_gen.shape[0] == 1: act_gen = act_gen[0] action = act_gen * k + sine * (1-k) + # print(np.abs(act_gen).max(), sine.max()) action = np.clip(action, low, upp) return action diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index b8ace7b94..0139a433e 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -48,9 +48,6 @@ namespace raisim { READ_YAML(bool, show_ref, cfg_["show_ref"]); if (show_ref == 0) show_ref = false; READ_YAML(double, angle_rate, cfg_["angle_rate"]); - READ_YAML(double, stable_reward_rate, cfg_["stable"]); - READ_YAML(double, reference_rate, cfg_["reference"]); - READ_YAML(double, for_work_rate, cfg_["for_work"]); READ_YAML(bool, float_base, cfg_["float_base"]); READ_YAML(float,schedule_T, cfg_["schedule"]); READ_YAML(std::string, urdf_path, cfg_["urdf_path"]); @@ -68,7 +65,7 @@ namespace raisim { gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); - euler_angle.setZero(); + euler_angle.setZero();euler_angle_old.setZero(); pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); @@ -79,7 +76,7 @@ namespace raisim { // init_position(gc_init_); init(); - obDim_ = 31; + obDim_ = 30; actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); obDouble_.setZero(obDim_); @@ -144,6 +141,7 @@ namespace raisim { anymal_->setState(gc_init_, gv_init_); rewards_.setZero(); COUNT=0; + euler_angle_old.setZero(); updateObservation(); } @@ -162,7 +160,7 @@ namespace raisim { anymal_->setBasePos(po); } - + COUNT ++; pTarget12_ = action.cast(); pTarget_.tail(nJoints_) = pTarget12_; @@ -175,64 +173,37 @@ namespace raisim { } updateObservation(); double rrr =0; -// for(int i=4; i<=6 ; i++) -// { -// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; -// } -// for(int i =0;i<=2; i++)rrr += abs(bodyAngularVel_[i]); -//std::cout< quat; -// -// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; -// return quat.e(); -// } -// -// auto get_body_linear_velocity(){ -// return bodyLinearVel_; -// } -// auto get_body_angular_velocity() -// { -// return bodyAngularVel_; -// } -// -// auto get_joint_coordinate() -// { -// return gc_; -// } -// -// auto get_joint_velocity() -// { -// return gv_; -// } void updateObservation() { anymal_->getState(gc_, gv_); -// std::string root_name = "ROOT"; -// anymal_->getFrameAcceleration(root_name , acc_); raisim::Vec<4> quat; raisim::Mat<3,3> rot; quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; quat /= quat.norm(); -// std::cout << quat << std::endl; raisim::quatToRotMat(quat, rot); bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); + Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); + euler_angle = ToEulerAngles(qua); + if(euler_angle[1] > PI) euler_angle[1] -= 2*PI; + if(euler_angle[0] > PI) euler_angle[0] -= 2*PI; + if(euler_angle[1] < -PI) euler_angle[1] += 2 * PI; + if(euler_angle[0] < -PI) euler_angle[0] += 2 * PI; Eigen::VectorXd gcc = gc_.tail(12); Eigen::VectorXd gvv = gv_.tail(12); -// std::cout << "gcc_ : \n " << gcc << std::endl << "gvv : \n" << gvv << std::endl; Eigen::VectorXd c_v(24); c_v.setZero(24); for(auto i = 0; i <12 ; i++ ) @@ -240,16 +211,11 @@ namespace raisim { c_v[i*2] = gcc[i]; c_v[i*2 + 1] = gvv[i]; } -// std::cout << "quat" << quat << "\n body angular vel" << bodyAngularVel_ << "\n acc " << acc_ << "\nc_v "<< c_v << std::endl; - obDouble_ << quat[0], quat[1], quat[2], quat[3], // quaternion + obDouble_ << euler_angle, // quaternion bodyAngularVel_[0], // ras/s bodyAngularVel_[1], // ras/s bodyAngularVel_[2], // ras/s -// acc_[0], // m/s^2 -// acc_[1], // m/s^2 -// acc_[2], // m/s^2 # todo recall acc c_v; -// std::cout<< "obdouble \n" << obDouble_ << std::endl; } @@ -260,23 +226,24 @@ namespace raisim { bool isTerminalState(float& terminalReward) final { terminalReward = float(terminalRewardCoeff_); - Eigen::Quaterniond quat(gc_[3], gc_[4], gc_[5], gc_[6]); -// std::cout<<"quat" << quat.w() << " " <getContacts()) if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) {// if there is any contact body was not in the footIndices the over - rewards_.record("Stable", -10, true); + rewards_.record("Live", -10, true); return true;} if(abs(gc_[2] - gc_init_[2]) > 0.3){ return true;} - if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.1){ return true;} - if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.1){ return true;} - if(fmin(abs(euler_angle[2]), abs(euler_angle[2] + 2 * PI)) > 0.1){ return true;} - if(abs(gc_.tail(12)[0]) >0.17) return true; - if(abs(gc_.tail(12)[3]) >0.17) return true; - if(abs(gc_.tail(12)[6]) >0.17) return true; - if(abs(gc_.tail(12)[9]) >0.17) return true; + + + if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.17) + { +// std::cout<<"y angle done" << std::endl; + return true; + } + if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.17) + { +// std::cout<<"x angle done" << std::endl; + return true; + } terminalReward = 0.f; return false; } @@ -288,7 +255,7 @@ namespace raisim { bool visualizable_ = false; raisim::ArticulatedSystem* anymal_, *anymal_1; Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; - double terminalRewardCoeff_ = -10.; + double terminalRewardCoeff_ = -30.; Eigen::VectorXd actionMean_, actionStd_, obDouble_; Vec<3> acc_; Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; @@ -299,10 +266,10 @@ namespace raisim { int COUNT = 0; float schedule_T; bool show_ref= true; - double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + double action_std, angle_rate; Eigen::VectorXd angle_list, angle_list_for_work; Eigen::VectorXd gc_old, ref_old; - Eigen::Vector3d euler_angle; + Eigen::Vector3d euler_angle, euler_angle_old; /// these variables are not in use. They are placed to show you how to create a random number sampler. bool float_base; std::normal_distribution normDist_; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 55d4732ed..974c26c4d 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -1,20 +1,19 @@ seed: 1 -record_video: false +record_video: true environment: render: true # just testing commenting num_envs: 100 - eval_every_n: 100 + eval_every_n: 20 num_threads: 30 simulation_dt: 0.0025 control_dt: 0.01 max_time: 8.0 - action_std: 0.00 + action_std: 0.2 +# action_std: 0 show_ref: false - angle_rate: 0.15 - stable: 1 - reference: 0 + angle_rate: 0.5 schedule: 40 for_work: 1 float_base: false @@ -28,8 +27,14 @@ environment: torque: coeff: -4e-5 Stable: - coeff: 0.9 + coeff: 0.1 + Live: + coeff: 0.4 + Wheel: + coeff: 1 + Mimic: + coeff: 0 architecture: - policy_net: [128, 128] - value_net: [128, 128] + policy_net: [512, 512] + value_net: [512, 512] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 888cbf5e2..35be8ad9f 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -197,7 +197,7 @@ envs_idx = list(map(check_done, envs_idx, dones)) history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) - reward = reward * envs_idx / n_steps * 2 + # reward = reward * envs_idx / n_steps * 2 envs_idx = list(map(check_done, envs_idx, dones)) ppo.step(value_obs=obs, rews=reward, dones=dones) From c57caaad189bcfea1c0ddc406542fb3b474cbd81 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 15 Aug 2023 14:30:04 +0800 Subject: [PATCH 22/62] the performance is too weird why the envs_idx is so important? --- examples/src/server/go1.cpp | 21 +++++----- .../raisimGymTorch/env/deploy/angle_utils.py | 41 +++++++++++++------ .../envs/rsg/Environment_tobuildforpython.hpp | 41 +++++++++++++------ .../raisimGymTorch/env/envs/rsg/cfg.yaml | 16 ++++---- .../env/envs/rsg/robot_utils.py | 2 +- .../raisimGymTorch/env/envs/rsg/runner.py | 28 +++++++++---- .../env/envs/rsg/sim_with_real.py | 11 +++-- 7 files changed, 104 insertions(+), 56 deletions(-) diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index 1107ca504..b6cd51418 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -132,23 +132,24 @@ int main(int argc, char* argv[]) { /// create objects auto ground = world.addGround(); - auto go1 = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\a1_description\\urdf\\a1.urdf"); + auto go1 = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\a1\\urdf\\a1.urdf"); /// go1 joint PD controller Eigen::VectorXd jointNominalConfig(go1->getGeneralizedCoordinateDim()), jointVelocityTarget(go1->getDOF()); // jointNominalConfig << 0, 0, 0.41, 1.0, 0.0, 0.0, 0.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; jointNominalConfig << 0, 0, 0.33, 1.0, 0.0, 0, 0, 0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976 ; // todo implement in python using list +// jointNominalConfig << 0, 0, 0.33, 1.0, 0.0, 0, 0, 0, 1, -2.2, 0.0, 1, -2.2, 0.0, 1, -2.2, 0.0, 1, -2.2; // todo implement in python using list // jointNominalConfig.tail(12).setZero(); // Eigen::VectorXd tmp(12); // tmp.setZero(); // angle_generator(tmp, 0, 80.f); // jointNominalConfig.tail(12) = tmp; jointVelocityTarget.setZero(); - + go1->setControlMode(raisim::ControlMode::FORCE_AND_TORQUE); Eigen::VectorXd jointPgain(go1->getDOF()), jointDgain(go1->getDOF()); - jointPgain.tail(12).setConstant(2000.0); - jointDgain.tail(12).setConstant(100); + jointPgain.tail(12).setConstant(80); + jointDgain.tail(12).setConstant(4); go1->setGeneralizedCoordinate(jointNominalConfig); go1->setGeneralizedForce(Eigen::VectorXd::Zero(go1->getDOF())); @@ -176,8 +177,8 @@ int main(int argc, char* argv[]) { ma.setZero(); for (int i=0; i<2000000; i++) { go1->getState(gc,gv); - raisim::Vec<4> qu{1+double(i)/500 , 0, 0, 0 + double(i)/500}; - go1->setBaseOrientation(qu); +// raisim::Vec<4> qu{1+double(i)/500 , 0, 0, 0 + double(i)/500}; +// go1->setBaseOrientation(qu); Eigen::VectorXd tmp1(12), tmp2(12); tmp1 = gc.tail(12); tmp2 = gv.tail(12); @@ -199,9 +200,9 @@ int main(int argc, char* argv[]) { // acc[i] = vel_temp // } // std::cout << "vel \n" << vel << std::endl << "acc\n " << acc << std::endl; - usleep(10000); -// angle_generator(position, i, 40, 0.15); -// jointNominalConfig.tail(12) = position; + usleep(5000); + angle_generator(position, i, 40, 0.35); + jointNominalConfig.tail(12) = position; Eigen::Quaterniond quat(gc[3], gc[4], gc[5], gc[6]); Eigen::Vector3d angle = ToEulerAngles(quat); @@ -227,7 +228,7 @@ int main(int argc, char* argv[]) { // jointNominalConfig.tail(12) = tmp; // std::cout<< tmp << std::endl; -//go1->setPdTarget(jointNominalConfig, jointVelocityTarget); +go1->setPdTarget(jointNominalConfig, jointVelocityTarget); server.integrateWorldThreadSafe(); diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py index 3c8e16fea..aaca1b211 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py @@ -65,7 +65,7 @@ def transfer(act_gen, sine, k, history_act = None) ->np.array: act_gen = act_gen * bund # - + act_gen = np.clip(act_gen, low, upp) if history_act is not None: - kk = 0.8 + kk = 0.6 # act_gen = (1-kk) * act_gen act_gen = act_gen * (1-kk) + history_act * kk act_gen = np.clip(act_gen, low, upp) @@ -76,6 +76,18 @@ def transfer(act_gen, sine, k, history_act = None) ->np.array: action = np.clip(action, low, upp) return action +def get_last_position(obs): + if isinstance(obs, list): + x = [obs[-2 * i] for i in range(1, 13)] + x.reverse() + return x + elif isinstance(obs, np.ndarray): + x = [] + for i in range(1, 13): + x.append(obs[:, -2*i]) + x.reverse() + return np.stack(x, axis=1) + if __name__=='__main__': # angle_list = [0 for x in range(12)] # @@ -87,15 +99,18 @@ def transfer(act_gen, sine, k, history_act = None) ->np.array: # print('upp:', upp) # print('bound', bund) # print(act[0]) - his_util = [0, 0.523, -1.046] * 4 - check_done = lambda a, b: a + 1 if not b else 0 - check_history = lambda a, b: a if not b else his_util - check_zero = lambda a:1 if a!=0 else 0 - tmp1 = np.zeros((100,12)) - idx = np.random.rand(100) - idx[1:10] = False - idx = list(map(check_zero, idx)) - print(idx) - tmp = np.array([check_history(tmp1[i], idx[i]) for i in range(100) ]) - assert tmp1.shape == tmp.shape - print(tmp) + # his_util = [0, 0.523, -1.046] * 4 + # check_done = lambda a, b: a + 1 if not b else 0 + # check_history = lambda a, b: a if not b else his_util + # check_zero = lambda a:1 if a!=0 else 0 + # tmp1 = np.zeros((100,12)) + # idx = np.random.rand(100) + # idx[1:10] = False + # idx = list(map(check_zero, idx)) + # print(idx) + # tmp = np.array([check_history(tmp1[i], idx[i]) for i in range(100) ]) + # assert tmp1.shape == tmp.shape + # print(tmp) + a = np.random.rand(2,30) + print(a) + print(get_last_position(a).shape) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index 0139a433e..e2e6ea184 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -175,13 +175,15 @@ namespace raisim { double rrr =0; // for(int i=0;i<=2;i++) rrr += abs(euler_angle[i]) ; rrr = abs(euler_angle[0]) + abs(euler_angle[1]); + rrr = abs(gc_[0]) + abs(gc_[1]); // rrr += (gc_.tail(12) - pTarget12_).norm() ; - bool accu = true; + bool accu = false; rewards_.record("Stable", - rrr, accu); rewards_.record("Live", 1, accu); rewards_.record("forwardVel", bodyLinearVel_[0], accu); rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); - rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); +// rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); + rewards_.record("Wheel", euler_angle[2] * 0.1 + (bodyAngularVel_[2] * 1), accu); euler_angle_old = euler_angle; // rewards_.record("torque", ) return rewards_.sum(); @@ -198,10 +200,10 @@ namespace raisim { bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); euler_angle = ToEulerAngles(qua); - if(euler_angle[1] > PI) euler_angle[1] -= 2*PI; - if(euler_angle[0] > PI) euler_angle[0] -= 2*PI; - if(euler_angle[1] < -PI) euler_angle[1] += 2 * PI; - if(euler_angle[0] < -PI) euler_angle[0] += 2 * PI; +// if(euler_angle[1] > PI) euler_angle[1] -= 2*PI; +// if(euler_angle[0] > PI) euler_angle[0] -= 2*PI; +// if(euler_angle[1] < -PI) euler_angle[1] += 2 * PI; +// if(euler_angle[0] < -PI) euler_angle[0] += 2 * PI; Eigen::VectorXd gcc = gc_.tail(12); Eigen::VectorXd gvv = gv_.tail(12); Eigen::VectorXd c_v(24); @@ -211,7 +213,8 @@ namespace raisim { c_v[i*2] = gcc[i]; c_v[i*2 + 1] = gvv[i]; } - obDouble_ << euler_angle, // quaternion + obDouble_ << euler_angle[0], + euler_angle[1],// quaternion bodyAngularVel_[0], // ras/s bodyAngularVel_[1], // ras/s bodyAngularVel_[2], // ras/s @@ -229,21 +232,33 @@ namespace raisim { for(auto& contact: anymal_->getContacts()) if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) {// if there is any contact body was not in the footIndices the over - rewards_.record("Live", -10, true); + rewards_.record("Live", -10, false); return true;} if(abs(gc_[2] - gc_init_[2]) > 0.3){ return true;} - if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.17) + if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.2) { // std::cout<<"y angle done" << std::endl; - return true; + return true; } - if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.17) + if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.2) { // std::cout<<"x angle done" << std::endl; - return true; + return true; } + if (abs(gc_[0] - gc_init_[0]) >= 0.4) + { + return true; + } + if (abs(gc_[1] - gc_init_[1]) >= 0.4) + { + return true; + } + if(euler_angle[2] < -0.3) + { + return true; + } terminalReward = 0.f; return false; } @@ -255,7 +270,7 @@ namespace raisim { bool visualizable_ = false; raisim::ArticulatedSystem* anymal_, *anymal_1; Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; - double terminalRewardCoeff_ = -30.; + double terminalRewardCoeff_ = -10.; Eigen::VectorXd actionMean_, actionStd_, obDouble_; Vec<3> acc_; Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 974c26c4d..167540e16 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -5,19 +5,19 @@ environment: render: true # just testing commenting num_envs: 100 - eval_every_n: 20 + eval_every_n: 50 num_threads: 30 simulation_dt: 0.0025 control_dt: 0.01 - max_time: 8.0 - action_std: 0.2 + max_time: 4 + action_std: 0.03 # action_std: 0 show_ref: false - angle_rate: 0.5 + angle_rate: 0.2 schedule: 40 for_work: 1 float_base: false - learnning_rate: 5e-4 + learnning_rate: 1e-3 p_gain: 180 d_gain: 8 urdf_path: /home/lr-2002/code/raisimLib/rsc/a1_description/urdf/a1.urdf @@ -27,11 +27,11 @@ environment: torque: coeff: -4e-5 Stable: - coeff: 0.1 + coeff: 2 Live: - coeff: 0.4 + coeff: 0.5 Wheel: - coeff: 1 + coeff: 15 Mimic: coeff: 0 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py index 291157427..1f9381f59 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py @@ -1,5 +1,5 @@ from unitree_api import robot as rbt -from unitree_deploy.sine_generator import sine_generator +from unitree_deploy.angle_utils import sine_generator import signal import sys a1 = rbt.Robot() diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 35be8ad9f..a557fd8cf 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -6,7 +6,7 @@ from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer import raisimGymTorch.algo.ppo.module as ppo_module import raisimGymTorch.algo.ppo.ppo as PPO -from raisimGymTorch.env.deploy.angle_utils import transfer +from raisimGymTorch.env.deploy.angle_utils import transfer,get_last_position import os import math @@ -16,8 +16,8 @@ import torch import datetime import argparse -from unitree_deploy.sine_generator import sine_generator - +from unitree_deploy.angle_utils import sine_generator +from unitree_utils.Waiter import Waiter # task specification @@ -137,6 +137,7 @@ average_dones = 0. if update % cfg['environment']['eval_every_n'] == 0: + waiter = Waiter(0.01) print("Visualizing and evaluating the current policy") torch.save({ 'actor_architecture_state_dict': actor.architecture.state_dict(), @@ -151,24 +152,34 @@ env.turn_on_visualization() env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') envs_idx = [0] * num_envs - + waiter.update_start() for step in range(n_steps): with torch.no_grad(): + waiter.wait() frame_start = time.time() obs = env.observe(False) + + # history_act = get_last_position(obs) + # history_act = np.array([ check_history(history_act[i], dones[i]) for i in range(num_envs)] ) + + action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) action = action.cpu().detach().numpy() sine = sine_generator(envs_idx, schedule, angle_rate) action = transfer(action, sine, act_rate, history_act=history_act).astype(np.float32) reward, dones = env.step(action) + + history_act = sine + # envs_idx = list(map(check_done, envs_idx, dones)) + history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) + envs_idx = list(map(check_done, envs_idx, dones)) - history_act = np.array([ check_history(history_act[i], dones[i]) for i in range(num_envs)] ) reward_analyzer.add_reward_info(env.get_reward_info()) frame_end = time.time() wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) - if wait_time > 0.: - time.sleep(wait_time) + # if wait_time > 0.: + # time.sleep(wait_time) env.stop_video_recording() env.turn_off_visualization() @@ -186,6 +197,8 @@ 1. z轴方向的加速度的处理方法 """ + # history_act = get_last_position(obs) + action = ppo.act(obs) @@ -193,6 +206,7 @@ action = transfer(action, sine, act_rate, history_act=history_act).astype(np.float32) # todo the transfer has bug reward, dones = env.step(action) + history_act = sine envs_idx = list(map(check_done, envs_idx, dones)) history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index 52620ab9e..5624adfcf 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -18,7 +18,7 @@ import argparse # import pandas as pd # from sine_generator import sine_generator -from unitree_deploy.sine_generator import sine_generator +from unitree_deploy.angle_utils import sine_generator """" todo 1. left-hand right-hand check @@ -160,7 +160,7 @@ if moving_robot: from robot_utils import * - + a1.torque_limit = 33.15 init_robot(dt) ori_posi = sine_generator(0, schedule, rate=angle_rate).tolist() # initial position @@ -175,6 +175,9 @@ real_idx = 0 for i in range(schedule): a1.hold_on() + a1.kp = [100] * 12 + a1.kd = [7] * 12 + a1.init_k(a1.kp, a1.kd) for step in range(n_steps * 10): if not moving_robot: @@ -221,7 +224,7 @@ print('b-trans') real_action = transfer(gen_action, real_sine, act_rate, history_act=real_history_act) # real_action = real_action - print(f"real_obs:{real_obs} \n gen_action : {gen_action}\n for work_action:{real_action}") + print(f"real_obs:{real_obs} \n gen_action : {gen_action}\n for work_action:{real_action} \n now_tau_est:{a1.tau}") # waiter.wait() if real_action.shape[0] == 1: real_action = real_action[0] @@ -236,7 +239,7 @@ waiter.wait() reward, dones = env.step(action) print('exec') - envs_idx = list(map(check_done, envs_idx, dones)) + # envs_idx = list(map(check_done, envs_idx, dones)) history_act = sine envs_idx = list(map(check_done, envs_idx, dones)) history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) From edb15c70a9fef8ffa643d7cbd0197b8996bdef26 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Thu, 17 Aug 2023 21:04:04 +0800 Subject: [PATCH 23/62] saver drawer --- examples/src/server/go1.cpp | 64 ++- .../raisimGymTorch/deploy_log/anay.py | 22 +- .../raisimGymTorch/deploy_log/csv_saver.py | 26 ++ .../raisimGymTorch/deploy_log/draw_map.py | 77 ++++ .../raisimGymTorch/env/RewardAnalyzer.py | 26 +- .../env/VectorizedEnvironment.hpp | 4 +- .../raisimGymTorch/env/auto_runner.py | 2 +- .../raisimGymTorch/env/deploy/angle_utils.py | 59 +-- .../raisimGymTorch/env/deploy/onnx_deploy.py | 394 ++++++++++++------ .../envs/rsg/Environment_tobuildforpython.hpp | 97 +++-- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 32 +- .../env/envs/rsg/robot_utils.py | 2 + .../raisimGymTorch/env/envs/rsg/runner.py | 52 ++- .../env/envs/rsg/sim_with_real.py | 124 ++++-- 14 files changed, 686 insertions(+), 295 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/deploy_log/csv_saver.py create mode 100644 raisimGymTorch/raisimGymTorch/deploy_log/draw_map.py diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index b6cd51418..09abd91a8 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -79,6 +79,13 @@ void swap(Eigen::VectorXd &ob, int a, int b) // //} +void rot2euler( const raisim::Mat<3,3>& mat, Eigen::Vector3d& euler) +{ + euler[0] = atan2(mat[2], mat[8]); + euler[1] = asin(- mat[5]); + euler[2] = atan2(mat[3], mat[4]); +} + void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) { // std::cout<< "size is "<< angle_list.size() << std::endl; @@ -125,14 +132,14 @@ void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1 } int main(int argc, char* argv[]) { auto binaryPath = raisim::Path::setFromArgv(argv[0]); - + char c; /// create raisim world raisim::World world; world.setTimeStep(0.01); /// create objects auto ground = world.addGround(); - auto go1 = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\a1\\urdf\\a1.urdf"); + auto go1 = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\a1_description\\urdf\\a1.urdf"); /// go1 joint PD controller Eigen::VectorXd jointNominalConfig(go1->getGeneralizedCoordinateDim()), jointVelocityTarget(go1->getDOF()); @@ -175,9 +182,36 @@ int main(int argc, char* argv[]) { raisim::Vec<3> acc; Eigen::Vector3d ma; ma.setZero(); - for (int i=0; i<2000000; i++) { + Eigen::VectorXd bodyLinearVelocity, bodyAngularVelocity; + bodyAngularVelocity.setZero(3); + bodyLinearVelocity.setZero(3); + auto roott = go1->getBodyIdx("base"); +// auto imu = go1->getSensor("imu_joint"); + + for (int i=0; i<2000000; i++) { + + std::cin.ignore(); +// imu->getAngularVelocity() + + go1->getState(gc,gv); -// raisim::Vec<4> qu{1+double(i)/500 , 0, 0, 0 + double(i)/500}; + + +// anymal_->getState(gc, gv); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc[3]; quat[1] = gc[4]; quat[2] = gc[5]; quat[3] = gc[6]; + quat /= quat.norm(); + raisim::quatToRotMat(quat, rot); + + bodyLinearVelocity = rot.e().transpose() * gv.segment(0, 3); + bodyAngularVelocity = rot.e().transpose() * gv.segment(3, 3); + Eigen::Vector3d eule; + rot2euler(rot, eule); + std::cout<<"euler " << bodyAngularVelocity< qu{1+double(i)/500 , 0 , 0, 0+ double(i) / 500 }; // go1->setBaseOrientation(qu); Eigen::VectorXd tmp1(12), tmp2(12); tmp1 = gc.tail(12); @@ -203,16 +237,30 @@ int main(int argc, char* argv[]) { usleep(5000); angle_generator(position, i, 40, 0.35); jointNominalConfig.tail(12) = position; + for(auto n: go1->getBodyNames()) + { + std::cout << n << std::endl; + } + Eigen::Quaterniond quata(gc[3], gc[4], gc[5], gc[6]); + Eigen::Vector3d angle = ToEulerAngles(quata); + Eigen::Matrix3d root(quata); - Eigen::Quaterniond quat(gc[3], gc[4], gc[5], gc[6]); - Eigen::Vector3d angle = ToEulerAngles(quat); + bodyLinearVelocity = root.transpose() * gv.segment(0, 3); + bodyAngularVelocity = root.transpose() * gv.segment(3, 3); if (abs(angle[0]) >abs(ma[0]) ) ma[0] = abs(angle[0]); if (abs(angle[1]) >abs(ma[1]) ) ma[1] = abs(angle[1]); if (abs(angle[2]) >abs(ma[2]) ) ma[2] = abs(angle[2]); - + raisim::Vec<3> angvel; + go1->getAngularVelocity(roott, angvel); // std::cout<printOutFrameNamesInOrder(); + go1->getFrameAcceleration("floating_base", angvel); + std::cout<getAngularVelocity(); RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) // std::cout<< ob_ << std::endl< &reward, Eigen::Ref &done) { reward[agentId] = environments_[agentId]->step(action.row(agentId)); - rewardInformation_[agentId] = environments_[agentId]->getRewards().getStdMap(); float terminalReward = 0; done[agentId] = environments_[agentId]->isTerminalState(terminalReward); + rewardInformation_[agentId] = environments_[agentId]->getRewards().getStdMap(); if (done[agentId]) { environments_[agentId]->reset(); - reward[agentId] += terminalReward; +// reward[agentId] += terminalReward; } } diff --git a/raisimGymTorch/raisimGymTorch/env/auto_runner.py b/raisimGymTorch/raisimGymTorch/env/auto_runner.py index 456a2161c..c655590a6 100644 --- a/raisimGymTorch/raisimGymTorch/env/auto_runner.py +++ b/raisimGymTorch/raisimGymTorch/env/auto_runner.py @@ -11,7 +11,7 @@ def change_data(path, flag, data): with open(path, 'w') as f : dump(y, f, Dumper=RoundTripDumper) -test_list = [x/10 for x in range(1,20,4)] +test_list = [x/100 for x in range(4,20,4)] test_T = [40] # print(test_list) length = 500 diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py index aaca1b211..2b6a31acf 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py @@ -1,6 +1,7 @@ from math import sin,pi import numpy as np # from onnx_deploy import rad_deg, deg_rad +from raisimGymTorch.deploy_log.draw_map import Drawer def deg_rad(x): if isinstance(x, list): return [deg_rad(a) for a in x] @@ -11,7 +12,7 @@ def rad_deg(x): if isinstance(x, list): return [rad_deg(a) for a in x] else: - return x * pi / 180 + return x / pi * 180 low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] @@ -63,19 +64,49 @@ def transfer(act_gen, sine, k, history_act = None) ->np.array: """ # act_gen = (act_gen + 1) /2 # 0-1 act_gen = act_gen * bund # - + + # print(act_gen) act_gen = np.clip(act_gen, low, upp) if history_act is not None: - kk = 0.6 + kk = 0.9 # act_gen = (1-kk) * act_gen act_gen = act_gen * (1-kk) + history_act * kk act_gen = np.clip(act_gen, low, upp) if act_gen.shape[0] == 1: act_gen = act_gen[0] - action = act_gen * k + sine * (1-k) + action = act_gen * k + sine # print(np.abs(act_gen).max(), sine.max()) action = np.clip(action, low, upp) return action +def transfer_f(act_gen, sine, k, history_act = None) ->np.array: + """ + clip, lerp, generate the final action + params: act_gen: [12 * (-1, 1)] np.array + params: sine: [12 * rad_target] np.array + """ + # act_gen = (act_gen + 1) /2 # 0-1 + act_gen = act_gen * bund / 2 # - + + # print(act_gen) + act_gen = np.clip(act_gen, low, upp) + if history_act is not None: + kk = 1-k + # act_gen = (1-kk) * act_gen + # print(f'his1 {history_act}\n act_gen{act_gen}') + history_act = act_gen * (1-kk) + history_act * kk + history_act = np.clip(history_act, low, upp) + # print(f'his2 {history_act}') + + if history_act.shape[0] == 1: + tmp = history_act[0] + else: + tmp = history_act + action = tmp * 0.2 + sine + # print(np.abs(act_gen).max(), sine.max()) + action = np.clip(action, low, upp) + # print(f'bound{bund}\n act_gen{act_gen}\n history_act{history_act}\n sine{sine} \naction{action}\nk{k} ') + # input('1') + return action, history_act + def get_last_position(obs): if isinstance(obs, list): x = [obs[-2 * i] for i in range(1, 13)] @@ -89,28 +120,6 @@ def get_last_position(obs): return np.stack(x, axis=1) if __name__=='__main__': - # angle_list = [0 for x in range(12)] - # - # sine_generator(angle_list, 0, 40, 0.3) - # angle_list = np.array(angle_list) - # act = transfer(np.zeros((100,12)), angle_list, 1) - # print('sine:', angle_list) - # print('low:', low) - # print('upp:', upp) - # print('bound', bund) - # print(act[0]) - # his_util = [0, 0.523, -1.046] * 4 - # check_done = lambda a, b: a + 1 if not b else 0 - # check_history = lambda a, b: a if not b else his_util - # check_zero = lambda a:1 if a!=0 else 0 - # tmp1 = np.zeros((100,12)) - # idx = np.random.rand(100) - # idx[1:10] = False - # idx = list(map(check_zero, idx)) - # print(idx) - # tmp = np.array([check_history(tmp1[i], idx[i]) for i in range(100) ]) - # assert tmp1.shape == tmp.shape - # print(tmp) a = np.random.rand(2,30) print(a) print(get_last_position(a).shape) diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py index eb1b17997..bf27f3387 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py @@ -3,19 +3,22 @@ # from mlprodict.onnxrt import OnnxInference from math import cos,pi import numpy as np -from angle_utils import deg_rad, rad_deg +from raisimGymTorch.env.deploy.angle_utils import deg_rad, rad_deg +from raisimGymTorch.deploy_log.draw_map import Drawer # 加载模型 def ang_trans(lower, upper, x): """ - trans the rate x to the angle between lower and upper + trans the rate x to the angle """ x = (x+1)/2 #todo for test return x * upper + (1-x) * lower def norm(lower, upper, x): + # print(lower, upper, x) + assert abs((x - lower) / (upper - lower) ) <= 1 return (x - lower) / (upper - lower) def rad_normalize(lower, upper,x): @@ -30,6 +33,9 @@ def rad_normalize(lower, upper,x): return 2*ang1 - 1 def deg_normalize(lower, upper, x): + """ + make angle to rate from -1 -- 1 + """ if isinstance(lower, list): ans = [] for a,b,c in zip(lower, upper, x): @@ -43,11 +49,18 @@ def deg_normalize(lower, upper, x): low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] u0 = [0, 30, -60,0, 30, -60,0, 30, -60,0, 30, -60] +# u0_rad = deg_rad(u0) +# u0 = [0] * 12 # todo sure ? u0 = 0 +# low_rad = deg_rad(low) +# upp_rad = deg_rad(upp) u0 = deg_normalize(low, upp, u0) +# u0_rad = rad_normalize(low_rad, upp_rad, u0_rad) # u0 = [-deg_normalize(low, upp, u0)[i] if deg_normalize(low, upp, u0)[i]!=0 else 0 for i in range(12)] # print(u0) -history_u = u0 -model = ort.InferenceSession('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/deploy/new.onnx') +history_u = [0] * 12 +# history_u_rad = [0] * 12/ +# history_u = u0.copy() +model = ort.InferenceSession('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/deploy/walk.onnx') idx_local = 0 @@ -58,66 +71,78 @@ def deg_normalize(lower, upper, x): print(input_name, output_name) # input_data = np.random.rand(1, 34).astype(np.float32) -def sine_gene_test_qua(idx, T): - angle_list = [0 for i in range(12)] - if idx >= 2 * T: - idx = 0 - dh = 1 # todo for test - if idx >= 0 and idx <= T: - tp0 =idx - 0 - y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 - y2 = 0 - elif idx>T and idx<=2*T: - tp0 =idx - T - y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 - y1 = 0 - - - angle_list[0] = 0 - angle_list[1] = y1 - angle_list[2] = -2 * y1 - angle_list[3] = 0 - angle_list[4] = y2 - angle_list[5] = -2 * y2 - angle_list[6] = 0 - angle_list[7] = y1 - angle_list[8] = -2 * y1 - angle_list[9] = 0 - angle_list[10] = y2 - angle_list[11] = -2 * y2 - angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i])) for i in range(12)] - return angle_list +# def sine_gene_test_qua(idx, T): +# angle_list = [0 for i in range(12)] +# if idx >= 2 * T: +# idx = 0 +# dh = 1.2 # todo for test +# if idx >= 0 and idx <= T: +# tp0 =idx - 0 +# y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 +# y2 = 0 +# elif idx>T and idx<=2*T: +# tp0 =idx - T +# y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 +# y1 = 0 +# +# +# angle_list[0] = 0 +# angle_list[1] = y1 +# angle_list[2] = -2 * y1 +# angle_list[3] = 0 +# angle_list[4] = y2 +# angle_list[5] = -2 * y2 +# angle_list[6] = 0 +# angle_list[7] = y1 +# angle_list[8] = -2 * y1 +# angle_list[9] = 0 +# angle_list[10] = y2 +# angle_list[11] = -2 * y2 +# angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i])) for i in range(12)] +# return angle_list def sine_gene(idx, T): - angle_list = [0 for i in range(12)] - if idx >= 2 * T: - idx = 0 - dh = 2 # todo for test - if idx >= 0 and idx <= T: - tp0 =idx - 0 - y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 - y2 = 0 - elif idx>T and idx<=2*T: - tp0 =idx - T - y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 - y1 = 0 - - - angle_list[0] = 0 - angle_list[1] = y1 - angle_list[2] = -2 * y1 - angle_list[3] = 0 - angle_list[4] = y2 - angle_list[5] = -2 * y2 - angle_list[6] = 0 - angle_list[7] = y2 - angle_list[8] = -2 * y2 - angle_list[9] = 0 - angle_list[10] = y1 - angle_list[11] = -2 * y1 - angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i])) for i in range(12)] - return angle_list + # if isinstance(idx, np.ndarray): + # + if not isinstance(idx, list): + angle_list = [0 for i in range(12)] + if idx >= 2 * T: + idx = 0 + dh = 0.8 # todo for test + if idx >= 0 and idx <= T: + tp0 =idx - 0 + y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y2 = 0 + elif idx>T and idx<=2*T: + tp0 =idx - T + y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y1 = 0 + + + angle_list[0] = 0 + angle_list[1] = y1 + angle_list[2] = -2 * y1 + angle_list[3] = 0 + angle_list[4] = y2 + angle_list[5] = -2 * y2 + angle_list[6] = 0 + angle_list[7] = y2 + angle_list[8] = -2 * y2 + angle_list[9] = 0 + angle_list[10] = y1 + angle_list[11] = -2 * y1 + # print("ang_list ", angle_list) + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i]) ) for i in range(12)] + # print("ang_list ", angle_list) + return angle_list + else: + ans = [] + for i in idx: + ans.append(sine_gene(i, T)) + return ans + + def rate_to_act(lower, upper, rate): if isinstance(lower, list): @@ -125,48 +150,151 @@ def rate_to_act(lower, upper, rate): else: norm_for_act = lambda a: (a+1)*0.5 lerp = lambda a, b, c: a*(1-c) + b * c + # print("11111 ", lower, upper, rate, lerp(lower, upper, norm_for_act(rate))) + return lerp(lower, upper, norm_for_act(rate)) -def add_list(act_gen, sine): - global history_u +def clip(a,b,c): + # print('before clip ', a, b, c) + + if isinstance(a, np.ndarray): + return np.clip(a,b,c) + + if a <= b : + a = b + if a >= c: + a = c + # print('clip ', a) + return a + +def add_list(act_gen, sine, history=None): + if isinstance(act_gen, np.ndarray): + # print(act_gen) + assert act_gen.shape[0] == 12 + else: + # print(act_gen) + assert len(act_gen) == 12 kk = 0.9 kf = 1 - kb = 0.5 - history_u = [history_u[i] * kk + (1-kk) * act_gen[i] for i in range(12)] # todo the act_gen[i] is to big - clip = lambda a, b, c: np.clip(a, b, c) + kb = 0.2 + if history is None: + global history_u + + # print(history_u, act_gen) + history_u = [history_u[i] * kk + (1-kk) * act_gen[i] for i in range(12)] # todo the act_gen[i] is to big + + ans = [rate_to_act(low[i], upp[i], clip(kb * history_u[i] + kf * sine[i], -1, 1)) for i in range(12)] + ans = [deg_rad(x) for x in ans] + # todo swap the ans + + return ans + else: + # history_u = history + history = [history[i] * kk + (1-kk) * act_gen[i] for i in range(12)] # todo the act_gen[i] is to big + + ans = [rate_to_act(low[i], upp[i], clip(kb * history[i] + kf * sine[i], -1, 1)) for i in range(12)] + ans = [deg_rad(x) for x in ans] + # todo swap the ans + + return ans, history + + +def run_model_with_pt_input(act_gen, idx, T, history): + if isinstance(idx, list): + idx = [i%(2*T) for i in idx] + else: + idx = idx % (2 * T) + # act_gen = act_gen/3.14 * 180 + # act_gen = np.zeros_like(act_gen) + sine = sine_gene(idx, T) + ans = [] + new_his = [] + for i in range(act_gen.shape[0]): + tmp, tmp_his= add_list(act_gen[i], sine[i], history[i]) + ans.append(tmp) + new_his.append(tmp_his) + + return np.array(ans).astype(np.float32),np.array(new_his).astype(np.float32) + +def run_model_with_pt_input_modify(act_gen, idx, T, history): + if isinstance(idx, list): + idx = np.array(idx) + print(idx.shape) + idx = idx%(2*T) + else: + idx = idx % (2 * T) + + sine = sine_gene(idx, T) + ans = [] + new_his = [] + for i in range(act_gen.shape[0]): + tmp, tmp_his= add_list(act_gen[i], sine[i], history[i]) + ans.append(tmp) + new_his.append(tmp_his) + return np.array(ans).astype(np.float32),np.array(new_his).astype(np.float32) - # f0 = lambda a: a - # f1 = lambda a, b, c: a - ans = [rate_to_act(low[i], upp[i], clip(kb * history_u[i] + kf * sine[i], -1, 1)) for i in range(12)] - ans = [deg_rad(x) for x in ans] - # todo swap the ans - # for i in range(6): - # tmp = ans[i+6] - # ans[i+6] = ans[i] - # ans[i] = tmp - return ans +def list_pt(act_gen, idx, T): + ans = [] + for i in range(act_gen.shape[0]): + ans.append(run_model_with_pt_input(act_gen[i, :], idx[i], T)) + ans = np.vstack(ans).astype(np.float32) + return ans -def run_model(observation, idx, T): +def run_model(observation, idx, T, save_gen=None): # todo idx should return 0 when fall - # idx = idx % T + idx = idx % (2 * T) + # print(observation.shape) + # obs = rad_deg(observation) + observation[:, [0,1]] = observation[:, [1,0]] + observation[:, [1]] = - observation[:, [1]] + + # observation[:,[2,3,4]] = rad_deg(observation[:, [2,3,4]]) + # observation[:,[2,3,4]] = observation[:, [2,3,4]] + observation[:,[2,3,4]] = observation[:, [3,4,2]] + # observation[:,[2,3,4]] = rad_deg(observation[:, [3,4,2]]) + observation[:, [3, 4]] = - observation[:, [3, 4]] + # observation[:, [4] + if observation.shape[1] == 29: + offset = 0 + elif observation.shape[1] == 26: + offset = 3 + else: + offset = 5 + print('offset' ,offset) + be_obe =[5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28] + aft_obs = [23,24,25,26,27,28,17,18,19,20,21,22,11,12,13,14,15,16,5,6,7,8,9,10] + be_obe = [i -offset for i in be_obe] + aft_obs=[i -offset for i in aft_obs] + # print(be_obe, aft_obs) + observation[: ,be_obe]=\ + observation[: ,aft_obs] + + act_gen = model.run([output_name], input_feed={input_name: observation}) act_gen = act_gen[0] - act_gen = np.zeros((1,12)) - # [array([[]])] + + # minu = np.array([0, 0, deg_rad(30), 0, deg_rad(-60), 0] * 4) # 6 + # observation[:, -24:] -= minu + + # act_gen = np.zeros((1,12)) + if save_gen is not None: + save_gen.add_list(act_gen[0]) + sine = sine_gene(idx, T) - sine = sine_gene_test_qua(idx, T) - # sine = [0 for x in range(12)] - # print(sine,act_gen) + ans = [] for act in act_gen: ans.append(add_list(act, sine)) + ans = np.array(ans).astype(np.float32) + # be_ans = + ans[:, [0,1,2,3,4,5,6,7,8,9,10,11]] = \ + ans[:, [9,10,11,6,7,8,3,4,5,0,1,2]] + ans = [ans] - ans = [np.array(ans).astype(np.float32)] - - return ans + return ans, observation def run_model1(observation): @@ -178,63 +306,55 @@ def run_model1(observation): # print(outputs) # x = run_model(input_data) # print(x) -if __name__=="__main__": - # test_exp = np.zeros((1,34)) - # test_exp1 = np.zeros((1,34)) - # for i in range(12): - # test_exp[0][i * 2 + 10] = -u0[i] - # test_exp1[0][i * 2 + 10] = u0[i] - # # print(test_exp) - # - # ans = run_model(test_exp.astype(np.float32),0, 50) - # ans1 = run_model(test_exp1.astype(np.float32),0, 50) - # # ans1 = run_model(np.zeros((1,34)).astype(np.float32)) - # print(ans) - # print(ans1) - # print(u0) - - a = [ang_trans(low[i], upp[i], u0[i]) for i in range(12)] - print(a) - print(u0) - uu = rate_to_act(low, upp, u0) - uu = deg_rad(uu) - print(uu) - # norm_for_act = lambda a: (a + 1) * 0.5 - # lerp = lambda a, b, c: a * (1 - c) + b * c - # print(deg_normalize(-10,10,6)) - # print(norm_for_act(deg_normalize(-10,10,6))) - # print(lerp(-10, 10,norm_for_act(deg_normalize(-10,10,6)) )) - - # import matplotlib.pyplot as plt - # x = [x for x in range(200)] - # y = [sine_gene(a ,50) for a in x] - # y =np.array(y).transpose() + + + # if not isinstance(idx, list): + # angle_list = [0 for i in range(12)] + # if idx >= 2 * T: + # idx = 0 + # dh = 0.8 # todo for test + # if idx >= 0 and idx <= T: + # tp0 =idx - 0 + # y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y2 = 0 + # elif idx>T and idx<=2*T: + # tp0 =idx - T + # y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y1 = 0 # - # for i in range(12): # - # plt.plot(x,y[i]) - # plt.show() - -""" -def test_rad_deg(): - assert rad_deg(1.57)-90 <=1 -def test_rad_deg_list(): - assert isinstance(rad_deg([1, 2,3]), list) + # angle_list[0] = 0 + # angle_list[1] = y1 + # angle_list[2] = -2 * y1 + # angle_list[3] = 0 + # angle_list[4] = y2 + # angle_list[5] = -2 * y2 + # angle_list[6] = 0 + # angle_list[7] = y2 + # angle_list[8] = -2 * y2 + # angle_list[9] = 0 + # angle_list[10] = y1 + # angle_list[11] = -2 * y1 + # # print("ang_list ", angle_list) + # angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i]) ) for i in range(12)] + # # print("ang_list ", angle_list) + # return angle_list + +def sine_gen(idx, T): + """ + idx : 0~ 2*T + iter ? + """ + angle_list = np.zeros((idx.shape[0], 12)) -def test_deg_rad(): - assert deg_rad(90) - 1.57 <= 0.05 -def test_deg_rad_list(): - assert isinstance(deg_rad([1, 2, 3]), list) -""" -# def test_sine_gene(): -# for i in range(0, 200, 10): -# a = sine_gene(i, 50) -# print(a) -# assert max(a) <= pi and min(a) >= 0 -# todo +if __name__=="__main__": + # sine_gen(np.zeros(100), 40) + mat = np.zeros((100,12)) + mat = np.where(np.indices(mat)>20, 1, 0) + print(mat) """ todo 1. on action 的范围 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index e2e6ea184..38caead50 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -70,13 +70,14 @@ namespace raisim { angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); acc_.setZero();//1 + ang_vel_.setZero(); // init_position(); gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; // init_position(gc_init_); init(); - obDim_ = 30; + obDim_ = 29; actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); obDouble_.setZero(obDim_); @@ -175,15 +176,15 @@ namespace raisim { double rrr =0; // for(int i=0;i<=2;i++) rrr += abs(euler_angle[i]) ; rrr = abs(euler_angle[0]) + abs(euler_angle[1]); - rrr = abs(gc_[0]) + abs(gc_[1]); +// rrr = abs(gc_[0]) + abs(gc_[1]); // rrr += (gc_.tail(12) - pTarget12_).norm() ; bool accu = false; - rewards_.record("Stable", - rrr, accu); + rewards_.record("Stable",-rrr, accu); rewards_.record("Live", 1, accu); - rewards_.record("forwardVel", bodyLinearVel_[0], accu); - rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); +// rewards_.record("forwardVel", bodyLinearVel_[0], accu); +// rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); // rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); - rewards_.record("Wheel", euler_angle[2] * 0.1 + (bodyAngularVel_[2] * 1), accu); + rewards_.record("Wheel", 0.3 - abs(ang_vel_[2]- 0.3), accu); euler_angle_old = euler_angle; // rewards_.record("torque", ) return rewards_.sum(); @@ -198,6 +199,7 @@ namespace raisim { raisim::quatToRotMat(quat, rot); bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); + anymal_->getAngularVelocity(anymal_->getBodyIdx("base"), ang_vel_); Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); euler_angle = ToEulerAngles(qua); // if(euler_angle[1] > PI) euler_angle[1] -= 2*PI; @@ -213,12 +215,16 @@ namespace raisim { c_v[i*2] = gcc[i]; c_v[i*2 + 1] = gvv[i]; } - obDouble_ << euler_angle[0], + + obDouble_ << + euler_angle[0], euler_angle[1],// quaternion - bodyAngularVel_[0], // ras/s - bodyAngularVel_[1], // ras/s - bodyAngularVel_[2], // ras/s - c_v; + ang_vel_[0], + ang_vel_[1], + ang_vel_[2], + c_v; +// std::cout<<"ang_vel : " << ang_vel_ << std::endl; + } @@ -229,36 +235,45 @@ namespace raisim { bool isTerminalState(float& terminalReward) final { terminalReward = float(terminalRewardCoeff_); - for(auto& contact: anymal_->getContacts()) - if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) - {// if there is any contact body was not in the footIndices the over - rewards_.record("Live", -10, false); - return true;} - if(abs(gc_[2] - gc_init_[2]) > 0.3){ return true;} - +// for(auto& contact: anymal_->getContacts()) +// if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) +// {// if there is any contact body was not in the footIndices the over +// rewards_.record("Live", -10, false); +// return true;} + if(abs(gc_[2] - gc_init_[2]) > 0.22){ +// std::cout<<"z done" << std::endl; + rewards_.record("Live", terminalReward, false); - if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.2) - { -// std::cout<<"y angle done" << std::endl; - return true; - } - if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.2) - { -// std::cout<<"x angle done" << std::endl; - return true; - } - if (abs(gc_[0] - gc_init_[0]) >= 0.4) - { - return true; - } - if (abs(gc_[1] - gc_init_[1]) >= 0.4) - { - return true; - } - if(euler_angle[2] < -0.3) - { - return true; + return true; } + + +// if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.17) +// { +//// std::cout<<"y angle done" << std::endl; +// rewards_.record("Live", terminalReward, false); +// +// return true; +// } +// if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.17) +// { +//// std::cout<<"x angle done" << std::endl; +// rewards_.record("Live", terminalReward, false); +// +// return true; +// } +// if (abs(gc_[0] - gc_init_[0]) >= 0.4) +// { +// return true; +// } +// if (abs(gc_[1] - gc_init_[1]) >= 0.4) +// { +// return true; +// } +// if(euler_angle[2] < -0.3) +// { +// return true; +// } terminalReward = 0.f; return false; } @@ -270,9 +285,9 @@ namespace raisim { bool visualizable_ = false; raisim::ArticulatedSystem* anymal_, *anymal_1; Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; - double terminalRewardCoeff_ = -10.; + double terminalRewardCoeff_ = -100.; Eigen::VectorXd actionMean_, actionStd_, obDouble_; - Vec<3> acc_; + Vec<3> acc_, ang_vel_; Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; std::set footIndices_; double p_gain,d_gain; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 167540e16..996b3d834 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -5,36 +5,36 @@ environment: render: true # just testing commenting num_envs: 100 - eval_every_n: 50 + eval_every_n: 100 num_threads: 30 simulation_dt: 0.0025 control_dt: 0.01 max_time: 4 - action_std: 0.03 + action_std: 0.5 # action_std: 0 show_ref: false - angle_rate: 0.2 + angle_rate: 0.21 schedule: 40 - for_work: 1 +# for_work: 1 float_base: false - learnning_rate: 1e-3 + learnning_rate: 5e-4 p_gain: 180 d_gain: 8 urdf_path: /home/lr-2002/code/raisimLib/rsc/a1_description/urdf/a1.urdf reward: - forwardVel: - coeff: 0 - torque: - coeff: -4e-5 +# forwardVel: +# coeff: 0 +# torque: +# coeff: -4e-5 Stable: - coeff: 2 + coeff: 0.4 Live: - coeff: 0.5 + coeff: 1 Wheel: - coeff: 15 - Mimic: - coeff: 0 + coeff: 0.3 +# Mimic: +# coeff: 0. architecture: - policy_net: [512, 512] - value_net: [512, 512] + policy_net: [128, 128] + value_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py index 1f9381f59..4ce308a58 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/robot_utils.py @@ -1,5 +1,6 @@ from unitree_api import robot as rbt from unitree_deploy.angle_utils import sine_generator +# from raisimGymTorch.deploy_log.draw_map import draw import signal import sys a1 = rbt.Robot() @@ -12,6 +13,7 @@ def init_position(position, timing = 100): def quit_robot(robot): robot.back_safe() print('Task finished') + # draw() sys.exit(0) def signal_handler(signal, frame): diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index a557fd8cf..685b47833 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -6,8 +6,8 @@ from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer import raisimGymTorch.algo.ppo.module as ppo_module import raisimGymTorch.algo.ppo.ppo as PPO -from raisimGymTorch.env.deploy.angle_utils import transfer,get_last_position - +from raisimGymTorch.env.deploy.angle_utils import transfer_f ,get_last_position +from raisimGymTorch.env.deploy.onnx_deploy import run_model_with_pt_input_modify, list_pt import os import math import time @@ -18,6 +18,7 @@ import argparse from unitree_deploy.angle_utils import sine_generator from unitree_utils.Waiter import Waiter +from raisimGymTorch.deploy_log.draw_map import Drawer # task specification @@ -111,7 +112,8 @@ if mode == 'retrain': load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) -his_util=[0, 0.523, -1.046] * 4 +# his_util=[0, 0.523, -1.046] * 4 +his_util=[0] * 12 check_done = lambda a, b: a + 1 if not b else 0 check_history = lambda a, b: a if not b else his_util # need_to_review = lambda a,b: a if not b else np.array([[0, 0.523, -1.046] * 4]) # todo make sure the shape @@ -121,7 +123,7 @@ print = logger.info mode == 'train' -history_act = np.array([his_util] * 100) +history_act = np.array([his_util] * num_envs) total_update = args.update if mode =='train' or mode == 'retrain': # print('start train') @@ -149,6 +151,9 @@ loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) + # debug_draw_action = Drawer('debug_draw_action') + # debug_draw_history = Drawer('debug_draw_history') + env.turn_on_visualization() env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') envs_idx = [0] * num_envs @@ -158,6 +163,7 @@ waiter.wait() frame_start = time.time() obs = env.observe(False) + # print(obs.shape) # history_act = get_last_position(obs) # history_act = np.array([ check_history(history_act[i], dones[i]) for i in range(num_envs)] ) @@ -165,12 +171,23 @@ action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) action = action.cpu().detach().numpy() - sine = sine_generator(envs_idx, schedule, angle_rate) - action = transfer(action, sine, act_rate, history_act=history_act).astype(np.float32) + + # sine = sine_generator(envs_idx, schedule, angle_rate) + # action, history_act = transfer_f(action, sine, act_rate, history_act=history_act) + # action = action.astype(np.float32) + # + + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + + + # debug_draw_action.add_map_list(action[0]) + # debug_draw_history.add_map_list(history_act[0]) + reward, dones = env.step(action) - history_act = sine + # history_act = sine # envs_idx = list(map(check_done, envs_idx, dones)) + # history_act = action history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) envs_idx = list(map(check_done, envs_idx, dones)) @@ -183,11 +200,14 @@ env.stop_video_recording() env.turn_off_visualization() - + history_act = np.array([his_util] * num_envs) reward_analyzer.analyze_and_plot(update) env.reset() env.save_scaling(saver.data_dir, str(update)) + # debug_draw_action.draw() + # debug_draw_history.draw() + # actual training # sine = [0] * 12 envs_idx = [0] * num_envs @@ -202,13 +222,19 @@ action = ppo.act(obs) - sine = sine_generator(envs_idx, schedule, angle_rate) - action = transfer(action, sine, act_rate, history_act=history_act).astype(np.float32) + # sine = sine_generator(envs_idx, schedule, angle_rate) + # action, history_act = transfer_f(action, sine, act_rate, history_act=history_act) + # action = action.astype(np.float32) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + # todo the transfer has bug reward, dones = env.step(action) + # input('1') + # print(f"history : {history_act}") - history_act = sine - envs_idx = list(map(check_done, envs_idx, dones)) + # history_act = sine + # envs_idx = list(map(check_done, envs_idx, dones)) + # history_act = action history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) # reward = reward * envs_idx / n_steps * 2 @@ -217,6 +243,8 @@ ppo.step(value_obs=obs, rews=reward, dones=dones) done_sum = done_sum + np.sum(dones) reward_sum = reward_sum + np.sum(reward) + reward_analyzer.add_reward_info(env.get_reward_info()) + reward_analyzer.analyze_and_plot(update) # take st step to get value obs obs = env.observe(False) ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 == 0, update=update) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index 5624adfcf..d009849a3 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -8,6 +8,9 @@ import raisimGymTorch.algo.ppo.ppo as PPO from raisimGymTorch.env.deploy.angle_utils import transfer from unitree_utils.Waiter import Waiter +from raisimGymTorch.env.deploy.angle_utils import get_last_position +from raisimGymTorch.deploy_log.draw_map import Drawer +from raisimGymTorch.deploy_log.csv_saver import CSV_saver import os import math import time @@ -19,6 +22,7 @@ # import pandas as pd # from sine_generator import sine_generator from unitree_deploy.angle_utils import sine_generator +from raisimGymTorch.env.deploy.angle_utils import deg_rad, rad_deg """" todo 1. left-hand right-hand check @@ -134,18 +138,20 @@ moving_robot = False +onnx_flag = True virtual = True +# his_util=[0, 0.523, -1.046] * 4 his_util=[0, 0.523, -1.046] * 4 # check_done = lambda a, b: a + 1 if not b else 0 check_history = lambda a, b: a if not b else his_util -history_act = np.array([his_util] * 100) +history_act = np.array([his_util] * num_envs) # init virtual part if virtual: waiter= Waiter(0.01) env.reset() start = time.time() - onnx_flag = False + onnx_flag = True if onnx_flag: cnt_onnx = 0 from raisimGymTorch.env.deploy import onnx_deploy @@ -159,6 +165,10 @@ if moving_robot: + history_obs = None + if onnx_flag: + cnt_onnx = 0 + from raisimGymTorch.env.deploy import onnx_deploy from robot_utils import * a1.torque_limit = 33.15 init_robot(dt) @@ -166,7 +176,7 @@ ori_posi = sine_generator(0, schedule, rate=angle_rate).tolist() # initial position # a1.kp = cfg['environment']['kp'] # ori_posi = a1.position - init_position(ori_posi,200) + init_position(ori_posi,250) print(f""" now_posi: {a1.position}, angle_rate : {angle_rate} @@ -176,73 +186,123 @@ for i in range(schedule): a1.hold_on() a1.kp = [100] * 12 - a1.kd = [7] * 12 + a1.kd = [3] * 12 a1.init_k(a1.kp, a1.kd) + history_obs = a1.observe()[ :5] -for step in range(n_steps * 10): - if not moving_robot: +for step in range(n_steps * 2): + #virtual bot part + if virtual: + # if step%1 ==0 : + # input() if step == 0: + draw_vir_obs = Drawer('vir_obs1') + draw_vir_action = Drawer('vir_sent_act') + draw_vir_recv_action = Drawer('vir_recv_act') waiter.update_start() - print('moving?') - time.sleep(0.005) + # save_gen_act = CSV_saver('virtual_gen_act', './') + save_obs = CSV_saver('virtual_obs', './') + save_for_work = CSV_saver('virtual_for_work', './') obs = env.observe(False) - - - #virtual bot part - if virtual: + print('saving') + last_p = get_last_position(obs) + print(f'last{last_p}') + draw_vir_recv_action.add_map_list(last_p[0]) if onnx_flag: - action = onnx_deploy.run_model(obs, cnt_onnx, 50) + # obs = rad_deg(obs) + # print(obs.shape) + action, obs = onnx_deploy.run_model(obs, cnt_onnx, 40) action = np.array(action)[0] cnt_onnx += 1 else: gen_action = ppo.act(obs) sine = sine_generator(envs_idx, schedule, angle_rate) action = transfer(gen_action, sine, act_rate, history_act=history_act).astype(np.float32) - print(f"virtual_obs:{obs} \n virtual_gen_action:{gen_action} \n virtual_action:{action}") + # history_act = + print(f"virtual_obs:{obs} \n virtual_action:{action}") + save_obs.add_list(obs[0]) + # draw_vir_recv_action.add_map_list(action[0]) + save_for_work.add_list(action[0]) - # obs = np.zeros((1,31)) - # gen_act = ppo.act(obs) - # sine = sine_generator(real_idx, schedule, angle_rate) - # act = transfer(gen_act, sine, act_rate) # real bot part if moving_robot: + if step ==0: + draw_real_obs = Drawer('real_obs') + draw_sent_action = Drawer('real_sent_act') + draw_recv_action = Drawer('real_a_recv_act') real_history_act = np.array(his_util) + save_real_obs = CSV_saver('real_a_obs') + save_real_action = CSV_saver('real_a_action') print('b-observe') - real_obs = a1.observe() + obbs = a1.observe() + obbs[:5] -= history_obs + real_obs = np.array([obbs]) # real_obs = np.array([a1.observe()]) print(f"real_obs {real_obs}") # input('now cancel it ') # print() print('b-ppo') - gen_action = ppo.act(real_obs) - print('b-sin') - real_sine = sine_generator(real_idx, schedule, angle_rate) - print('b-trans') - real_action = transfer(gen_action, real_sine, act_rate, history_act=real_history_act) + + + if onnx_flag: + action, real_obs = onnx_deploy.run_model(real_obs, cnt_onnx, 40) + real_obs = real_obs[0] + real_action = np.array(action)[0] + cnt_onnx += 1 + + else: + gen_action = ppo.act(real_obs) + print('b-sin') + real_sine = sine_generator(real_idx, schedule, angle_rate) + print('b-trans') + real_action = transfer(gen_action, real_sine, act_rate, history_act=real_history_act) + + + # real_action = real_action - print(f"real_obs:{real_obs} \n gen_action : {gen_action}\n for work_action:{real_action} \n now_tau_est:{a1.tau}") + # add_map_list(real_action) + draw_real_obs.add_map_list(real_obs[:5]) + save_real_obs.add_list(real_obs) + save_real_action.add_list(a1.position) + draw_recv_action.add_map_list(a1.position) + draw_sent_action.add_map_list(real_action[0]) + print(f"real_obs:{real_obs} \n for work_action:{real_action} ") # waiter.wait() if real_action.shape[0] == 1: real_action = real_action[0] a1.take_action(real_action.tolist()) - real_history_act = real_sine - # envs_idx = list(map(check_done, real_idx, dones)) - # history_act = np.array([check_history(history_act[i], 0) for i in range(num_envs)]) - real_idx += 1 + # real_history_act = real_sine + real_idx +=1 + # update virtual bot if virtual: waiter.wait() reward, dones = env.step(action) - print('exec') - # envs_idx = list(map(check_done, envs_idx, dones)) - history_act = sine envs_idx = list(map(check_done, envs_idx, dones)) + + draw_vir_obs.add_map_list(obs[0][:5]) + draw_vir_action.add_map_list(action[0]) history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) +# draw() +if virtual: + save_obs.save() + save_for_work.save() + draw_vir_obs.draw() + draw_vir_action.draw() + draw_vir_recv_action.draw() + # save_gen_act.save() +else: + a1.back_safe() + save_real_obs.save() + save_real_action.save() + draw_real_obs.draw() + draw_sent_action.draw() + draw_recv_action.draw() print(f'biggest:{biggest_reward},rate = {biggest_iter}') From 71055cedc8766ef53fa853e078c66f671163b469 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Thu, 17 Aug 2023 23:27:43 +0800 Subject: [PATCH 24/62] todo: 1. sine_line has a little different (recv) 2. train of the rotate --- examples/src/server/sensors.cpp | 1 + .../raisimGymTorch/env/deploy/onnx_deploy.py | 104 +++++++++++++----- .../envs/rsg/Environment_tobuildforpython.hpp | 28 ++--- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 4 +- .../raisimGymTorch/env/envs/rsg/runner.py | 8 +- .../env/envs/rsg/sim_with_real.py | 7 +- 6 files changed, 104 insertions(+), 48 deletions(-) diff --git a/examples/src/server/sensors.cpp b/examples/src/server/sensors.cpp index 41f814831..f4076bdf1 100755 --- a/examples/src/server/sensors.cpp +++ b/examples/src/server/sensors.cpp @@ -52,6 +52,7 @@ int main(int argc, char **argv) { for (int k = 0; k < loopN; k++) { RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) server.integrateWorldThreadSafe(); + std::cout << imu->getAngularVelocity(); } server.killServer(); diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py index bf27f3387..c8f5039cc 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py @@ -1,3 +1,5 @@ +import time + import onnxruntime as ort # import onnx # from mlprodict.onnxrt import OnnxInference @@ -49,6 +51,8 @@ def deg_normalize(lower, upper, x): low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] u0 = [0, 30, -60,0, 30, -60,0, 30, -60,0, 30, -60] +low_np = np.array(low) +upp_np = np.array(upp) # u0_rad = deg_rad(u0) # u0 = [0] * 12 # todo sure ? u0 = 0 # low_rad = deg_rad(low) @@ -60,7 +64,7 @@ def deg_normalize(lower, upper, x): history_u = [0] * 12 # history_u_rad = [0] * 12/ # history_u = u0.copy() -model = ort.InferenceSession('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/deploy/walk.onnx') +model = ort.InferenceSession('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/deploy/2203.onnx') idx_local = 0 @@ -103,21 +107,32 @@ def deg_normalize(lower, upper, x): def sine_gene(idx, T): - # if isinstance(idx, np.ndarray): - # + # print(idx) + if isinstance(idx, np.ndarray) or isinstance(idx, list): + mat = np.zeros((len(idx), 12)) + i_set = set(idx) + idd = {} + for i in i_set: + idd[i] = sine_gene(i, 40) + for i in range(len(idx)): + mat[i] = idd[idx[i]] + return mat if not isinstance(idx, list): angle_list = [0 for i in range(12)] if idx >= 2 * T: idx = 0 - dh = 0.8 # todo for test + dh = 1.6 # todo for test + if idx >= 0 and idx <= T: tp0 =idx - 0 y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 y2 = 0 + y2 = y1 elif idx>T and idx<=2*T: tp0 =idx - T y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 y1 = 0 + y1 = y2 angle_list[0] = 0 @@ -176,28 +191,41 @@ def add_list(act_gen, sine, history=None): assert len(act_gen) == 12 kk = 0.9 kf = 1 - kb = 0.2 + kb = 0.4 if history is None: global history_u # print(history_u, act_gen) history_u = [history_u[i] * kk + (1-kk) * act_gen[i] for i in range(12)] # todo the act_gen[i] is to big + # print("11111", history_u, act_gen) ans = [rate_to_act(low[i], upp[i], clip(kb * history_u[i] + kf * sine[i], -1, 1)) for i in range(12)] ans = [deg_rad(x) for x in ans] # todo swap the ans - + # print(ans) + # input()/ return ans else: # history_u = history history = [history[i] * kk + (1-kk) * act_gen[i] for i in range(12)] # todo the act_gen[i] is to big - ans = [rate_to_act(low[i], upp[i], clip(kb * history[i] + kf * sine[i], -1, 1)) for i in range(12)] ans = [deg_rad(x) for x in ans] # todo swap the ans return ans, history +def lerp_np(a, b, c): + return a* (1-c) + b*c + +def add_list_np(act_gen, sine, history): + kk = 0.9 + kf = 1 + kb = 0.2 + history = history*kk + (1-kk) * act_gen + ans = np.clip(kb*history + kf * sine, -1, 1) + ans = (ans + 1) /2 # 100 * 12 + ans = lerp_np(low_np, upp_np, ans) + return ans, history def run_model_with_pt_input(act_gen, idx, T, history): if isinstance(idx, list): @@ -219,20 +247,18 @@ def run_model_with_pt_input(act_gen, idx, T, history): def run_model_with_pt_input_modify(act_gen, idx, T, history): if isinstance(idx, list): idx = np.array(idx) - print(idx.shape) + # print(idx.shape) idx = idx%(2*T) else: idx = idx % (2 * T) sine = sine_gene(idx, T) - ans = [] - new_his = [] - for i in range(act_gen.shape[0]): - tmp, tmp_his= add_list(act_gen[i], sine[i], history[i]) - ans.append(tmp) - new_his.append(tmp_his) - return np.array(ans).astype(np.float32),np.array(new_his).astype(np.float32) + ans, history = add_list_np(act_gen, sine, history) + ans = ans / 180 * 3.14 + + + return ans.astype(np.float32), history.astype(np.float32) @@ -263,7 +289,7 @@ def run_model(observation, idx, T, save_gen=None): offset = 3 else: offset = 5 - print('offset' ,offset) + # print('offset' ,offset) be_obe =[5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28] aft_obs = [23,24,25,26,27,28,17,18,19,20,21,22,11,12,13,14,15,16,5,6,7,8,9,10] be_obe = [i -offset for i in be_obe] @@ -279,16 +305,18 @@ def run_model(observation, idx, T, save_gen=None): # minu = np.array([0, 0, deg_rad(30), 0, deg_rad(-60), 0] * 4) # 6 # observation[:, -24:] -= minu - # act_gen = np.zeros((1,12)) + act_gen = np.zeros((1,12)) if save_gen is not None: save_gen.add_list(act_gen[0]) sine = sine_gene(idx, T) - + # print(sine) ans = [] for act in act_gen: ans.append(add_list(act, sine)) ans = np.array(ans).astype(np.float32) + # print(ans) + # input() # be_ans = ans[:, [0,1,2,3,4,5,6,7,8,9,10,11]] = \ ans[:, [9,10,11,6,7,8,3,4,5,0,1,2]] @@ -340,21 +368,39 @@ def run_model1(observation): # # print("ang_list ", angle_list) # return angle_list -def sine_gen(idx, T): - """ - idx : 0~ 2*T - iter ? - """ - angle_list = np.zeros((idx.shape[0], 12)) - - if __name__=="__main__": # sine_gen(np.zeros(100), 40) - mat = np.zeros((100,12)) - mat = np.where(np.indices(mat)>20, 1, 0) - print(mat) + # idx = [3,2,1,4,1,3,2,3,2,3,1,2,3,2,3,1] + # a = [0,2,3,0] + # b= [ 5, 3, 5,0] + # a= np.array(a) + # b= np.array(b) + # c = np.array([[0.2, 0.5, 0.3, 0.4], [0,0.3,0.2,0]]) + # print(a * (1-c) + b * c) + z = [] + minn = 100 + minnn =[] + for i in range(100): + # x = run_model(np.zeros((1,26)).astype(np.float32), i, 40)[0][0][0] + x = add_list(np.zeros((12)), sine_gene(i, 40)) + if i == 0: + print(x) + if x[1] <= minn: + print(x[1], minn) + minn = x[1] + minnn =x + z.append(x) + z = np.vstack(z) + print(minnn) + x= [i for i in range(z.shape[0])] + import matplotlib.pyplot as plt + plt.plot(x, z) + plt.show() + # mat = np.zeros((100,12)) + # mat = np.where(np.indices(mat)>20, 1, 0) + # print(mat) """ todo 1. on action 的范围 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index 38caead50..3bf55302c 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -73,11 +73,13 @@ namespace raisim { ang_vel_.setZero(); // init_position(); - gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; +double aa = double(30) /180*PI, bb = double(-60) /180*PI; + gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, aa, bb, 0.0, aa, bb, 0.0,aa,bb, 0.0, aa,bb; +// gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; // init_position(gc_init_); init(); - obDim_ = 29; + obDim_ = 26; actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); obDouble_.setZero(obDim_); @@ -107,16 +109,16 @@ namespace raisim { Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(p_gain); - jointPgain.tail(nJoints_)[2] = 300; - jointPgain.tail(nJoints_)[5] = 300; - jointPgain.tail(nJoints_)[8] = 300; - jointPgain.tail(nJoints_)[11] = 300; +// jointPgain.tail(nJoints_)[2] = 300; +// jointPgain.tail(nJoints_)[5] = 300; +// jointPgain.tail(nJoints_)[8] = 300; +// jointPgain.tail(nJoints_)[11] = 300; jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(d_gain); - jointDgain.tail(nJoints_)[2] = 15; - jointDgain.tail(nJoints_)[5] = 15; - jointDgain.tail(nJoints_)[8] = 15; - jointDgain.tail(nJoints_)[11] = 15; +// jointDgain.tail(nJoints_)[2] = 15; +// jointDgain.tail(nJoints_)[5] = 15; +// jointDgain.tail(nJoints_)[8] = 15; +// jointDgain.tail(nJoints_)[11] = 15; anymal_->setPdGains(jointPgain, jointDgain); // std::cout<setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); @@ -219,9 +221,9 @@ namespace raisim { obDouble_ << euler_angle[0], euler_angle[1],// quaternion - ang_vel_[0], - ang_vel_[1], - ang_vel_[2], +// ang_vel_[0], +// ang_vel_[1], +// ang_vel_[2], c_v; // std::cout<<"ang_vel : " << ang_vel_ << std::endl; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 996b3d834..521829ff6 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -4,9 +4,9 @@ record_video: true environment: render: true # just testing commenting - num_envs: 100 + num_envs: 1 eval_every_n: 100 - num_threads: 30 + num_threads: 1 simulation_dt: 0.0025 control_dt: 0.01 max_time: 4 diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 685b47833..9b38cf536 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -7,7 +7,7 @@ import raisimGymTorch.algo.ppo.module as ppo_module import raisimGymTorch.algo.ppo.ppo as PPO from raisimGymTorch.env.deploy.angle_utils import transfer_f ,get_last_position -from raisimGymTorch.env.deploy.onnx_deploy import run_model_with_pt_input_modify, list_pt +from raisimGymTorch.env.deploy.onnx_deploy import run_model_with_pt_input_modify, list_pt, run_model_with_pt_input import os import math import time @@ -225,8 +225,12 @@ # sine = sine_generator(envs_idx, schedule, angle_rate) # action, history_act = transfer_f(action, sine, act_rate, history_act=history_act) # action = action.astype(np.float32) + # action1, history_act1 = run_model_with_pt_input(action,envs_idx,schedule,history_act) action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) - + # print(f'action1 {action1}\n action{action}') + # print(f'history1 {history_act1} \n history{history_act}') + # input() + # print(f'3{time.time()}') # todo the transfer has bug reward, dones = env.step(action) # input('1') diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index d009849a3..33517884f 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -196,17 +196,19 @@ # if step%1 ==0 : # input() if step == 0: - draw_vir_obs = Drawer('vir_obs1') + draw_vir_obs = Drawer('vir_obs') draw_vir_action = Drawer('vir_sent_act') draw_vir_recv_action = Drawer('vir_recv_act') waiter.update_start() # save_gen_act = CSV_saver('virtual_gen_act', './') save_obs = CSV_saver('virtual_obs', './') - save_for_work = CSV_saver('virtual_for_work', './') + save_for_work = CSV_saver('virtual_sent', './') + save_recv = CSV_saver('virtual_recv', './') obs = env.observe(False) print('saving') last_p = get_last_position(obs) print(f'last{last_p}') + save_recv.add_list(last_p[0]) draw_vir_recv_action.add_map_list(last_p[0]) if onnx_flag: # obs = rad_deg(obs) @@ -295,6 +297,7 @@ draw_vir_obs.draw() draw_vir_action.draw() draw_vir_recv_action.draw() + save_recv.save() # save_gen_act.save() else: a1.back_safe() From 865d460384591e03e2b82a208313c39713ea5824 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Fri, 18 Aug 2023 15:09:14 +0800 Subject: [PATCH 25/62] now ok to train --- .../raisimGymTorch/algo/ppo/module.py | 5 +- raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py | 7 +- .../env/VectorizedEnvironment.hpp | 4 +- .../raisimGymTorch/env/deploy/onnx_deploy.py | 56 ++++++++++++- .../raisimGymTorch/env/deploy/robot.py | 50 ++--------- .../envs/rsg/Environment_tobuildforpython.hpp | 84 +++++++++---------- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 12 +-- .../raisimGymTorch/env/envs/rsg/runner.py | 45 +++++++--- 8 files changed, 147 insertions(+), 116 deletions(-) diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/module.py b/raisimGymTorch/raisimGymTorch/algo/ppo/module.py index 6d931b4b5..9ec7baf87 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/module.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/module.py @@ -18,8 +18,8 @@ def __init__(self, architecture, distribution, device='cpu'): def sample(self, obs): self.action_mean = self.architecture.architecture(obs).cpu().numpy() actions, log_prob = self.distribution.sample(self.action_mean) - # actions = (actions - actions.min()) / (actions.max() - actions.min()) * np.pi - actions = np.clip(actions, -1, 1) + # todo + # actions = (np.clip(actions, self.action_mean -np.pi, self.action_mean+np.pi) - self.action_mean) / np.pi return actions, log_prob def evaluate(self, obs, actions): @@ -112,6 +112,7 @@ def __init__(self, dim, size, init_std, fast_sampler, seed=0): self.std_np = self.std.detach().cpu().numpy() def update(self): + print(self.std) self.std_np = self.std.detach().cpu().numpy() def sample(self, logits): diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py index 1a1d872d4..df54c47be 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py @@ -76,9 +76,7 @@ def __init__(self, def act(self, actor_obs): self.actor_obs = actor_obs with torch.no_grad(): - # tmp = torch.from_numpy(actor_obs) - self.actions, self.actions_log_prob = self.actor.sample(torch.from_numpy(self.actor_obs).to(self.device)) - + self.actions, self.actions_log_prob = self.actor.sample(torch.from_numpy(actor_obs).to(self.device)) return self.actions def forward(self, actor_obs): @@ -111,6 +109,7 @@ def log(self, variables): def _train_step(self, log_this_iteration): mean_value_loss = 0 mean_surrogate_loss = 0 + # cnnt = 0 for epoch in range(self.num_learning_epochs): for actor_obs_batch, critic_obs_batch, actions_batch, old_sigma_batch, old_mu_batch, current_values_batch, advantages_batch, returns_batch, old_actions_log_prob_batch \ in self.batch_sampler(self.num_mini_batches): @@ -170,5 +169,5 @@ def _train_step(self, log_this_iteration): num_updates = self.num_learning_epochs * self.num_mini_batches mean_value_loss /= num_updates mean_surrogate_loss /= num_updates - + # print('cnnt ', cnnt) return mean_value_loss, mean_surrogate_loss, locals() diff --git a/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp b/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp index 411a6312f..627f468c6 100755 --- a/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp +++ b/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp @@ -8,6 +8,7 @@ #include "RaisimGymEnv.hpp" #include "omp.h" +#include #include "Yaml.hpp" namespace raisim { @@ -188,7 +189,8 @@ class VectorizedEnvironment { if (done[agentId]) { environments_[agentId]->reset(); -// reward[agentId] += terminalReward; + reward[agentId] += terminalReward; +// std::cout<<"agentid "<< agentId <<" reward " << reward[agentId] << std::endl; } } diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py index c8f5039cc..ff553a767 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py @@ -157,6 +157,56 @@ def sine_gene(idx, T): ans.append(sine_gene(i, T)) return ans +def sine_gene_pt(idx, T): + # print(idx) + if isinstance(idx, np.ndarray) or isinstance(idx, list): + mat = np.zeros((len(idx), 12)) + i_set = set(idx) + idd = {} + for i in i_set: + idd[i] = sine_gene_pt(i, 40) + for i in range(len(idx)): + mat[i] = idd[idx[i]] + return mat + if not isinstance(idx, list): + angle_list = [0 for i in range(12)] + if idx >= 2 * T: + idx = 0 + dh = 0.8 # todo for test + + if idx >= 0 and idx <= T: + tp0 =idx - 0 + y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y2 = 0 + # y2 = y1 + elif idx>T and idx<=2*T: + tp0 =idx - T + y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y1 = 0 + # y1 = y2 + + + angle_list[0] = 0 + angle_list[1] = y1 + angle_list[2] = -2 * y1 + angle_list[3] = 0 + angle_list[4] = y2 + angle_list[5] = -2 * y2 + angle_list[6] = 0 + angle_list[7] = y2 + angle_list[8] = -2 * y2 + angle_list[9] = 0 + angle_list[10] = y1 + angle_list[11] = -2 * y1 + # print("ang_list ", angle_list) + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i]) ) for i in range(12)] + # print("ang_list ", angle_list) + return angle_list + else: + ans = [] + for i in idx: + ans.append(sine_gene_pt(i, T)) + return ans def rate_to_act(lower, upper, rate): @@ -221,10 +271,12 @@ def add_list_np(act_gen, sine, history): kk = 0.9 kf = 1 kb = 0.2 + # print('be history ', history, 'act_gen ', act_gen) history = history*kk + (1-kk) * act_gen ans = np.clip(kb*history + kf * sine, -1, 1) ans = (ans + 1) /2 # 100 * 12 ans = lerp_np(low_np, upp_np, ans) + # print('af history ', history) return ans, history def run_model_with_pt_input(act_gen, idx, T, history): @@ -252,8 +304,8 @@ def run_model_with_pt_input_modify(act_gen, idx, T, history): else: idx = idx % (2 * T) - sine = sine_gene(idx, T) - + sine = sine_gene_pt(idx, T) + # act_gen = np.zeros_like(act_gen) ans, history = add_list_np(act_gen, sine, history) ans = ans / 180 * 3.14 diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/robot.py b/raisimGymTorch/raisimGymTorch/env/deploy/robot.py index a2d066cee..f164332b1 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/robot.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/robot.py @@ -1,44 +1,8 @@ +from math import cos import numpy as np -class Robot(): - def __init__(self): - self.robot = None - self.ob_dims = self.robot.ob_dims if self.robot is not None else 34 - self.act_dims = self.robot.act_dims if self.robot is not None else 12 - pass - - - def connect(self): - """ - connect to A1 with high level first - """ - - pass - - def ob_dim(self) -> int: - return self.ob_dims - - def act_dim(self) -> int: - return self.act_dims - - def alive(self) -> bool: - return True - - def observe(self) -> np.ndarray: - return np.random.rand(1, 34).astype(np.float32) - pass - - def take_action(self, act): - """ - upd recv and send - """ - pass - - def reset(self): - """ - how to implement - maybe to be implement with stand - """ - self.robot.reset() - - - +T=100 +x = [i for i in range(4 * T)] +y = [1.2 * 10 *(-cos(3.14 * 2 * (i % T) /T) + 1) /2 for i in x] +import matplotlib.pyplot as plt +plt.plot(x,y) +plt.show() \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index 3bf55302c..a5fa0d47f 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -79,7 +79,7 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; // init_position(gc_init_); init(); - obDim_ = 26; + obDim_ = 29; actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); obDouble_.setZero(obDim_); @@ -178,29 +178,31 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; double rrr =0; // for(int i=0;i<=2;i++) rrr += abs(euler_angle[i]) ; rrr = abs(euler_angle[0]) + abs(euler_angle[1]); + rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1]) ); // rrr = abs(gc_[0]) + abs(gc_[1]); // rrr += (gc_.tail(12) - pTarget12_).norm() ; bool accu = false; rewards_.record("Stable",-rrr, accu); +// std::cout<<"eu 0 "<< euler_angle[0] << " eu1 " << euler_angle[1] << std::endl; rewards_.record("Live", 1, accu); // rewards_.record("forwardVel", bodyLinearVel_[0], accu); // rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); // rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); - rewards_.record("Wheel", 0.3 - abs(ang_vel_[2]- 0.3), accu); - euler_angle_old = euler_angle; + rewards_.record("Wheel", 0.5 - abs(ang_vel_[2]- 0.5), accu); +// euler_angle_old = euler_angle; // rewards_.record("torque", ) return rewards_.sum(); } void updateObservation() { anymal_->getState(gc_, gv_); - raisim::Vec<4> quat; - raisim::Mat<3,3> rot; - quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; - quat /= quat.norm(); - raisim::quatToRotMat(quat, rot); - bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); - bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// quat /= quat.norm(); +// raisim::quatToRotMat(quat, rot); +// bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); +// bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); anymal_->getAngularVelocity(anymal_->getBodyIdx("base"), ang_vel_); Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); euler_angle = ToEulerAngles(qua); @@ -221,9 +223,9 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; obDouble_ << euler_angle[0], euler_angle[1],// quaternion -// ang_vel_[0], -// ang_vel_[1], -// ang_vel_[2], + ang_vel_[0], + ang_vel_[1], + ang_vel_[2], c_v; // std::cout<<"ang_vel : " << ang_vel_ << std::endl; @@ -236,46 +238,36 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; bool isTerminalState(float& terminalReward) final { terminalReward = float(terminalRewardCoeff_); - -// for(auto& contact: anymal_->getContacts()) -// if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) -// {// if there is any contact body was not in the footIndices the over -// rewards_.record("Live", -10, false); -// return true;} + bool accu = true; + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// rewards_.record("Live", terminalReward, accu); + std::cout<<"foot done " << std::endl; + return true;} if(abs(gc_[2] - gc_init_[2]) > 0.22){ // std::cout<<"z done" << std::endl; - rewards_.record("Live", terminalReward, false); +// rewards_.record("Live", terminalReward, accu); return true; } -// if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.17) -// { -//// std::cout<<"y angle done" << std::endl; -// rewards_.record("Live", terminalReward, false); -// -// return true; -// } -// if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.17) -// { -//// std::cout<<"x angle done" << std::endl; -// rewards_.record("Live", terminalReward, false); + if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.17) + { +// std::cout<<"y angle done" <<" " << euler_angle[1]<< std::endl; +// rewards_.record("Live", terminalReward, accu); + + return true; + } + if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.17) + { +// std::cout<<"x angle done " << euler_angle[0] << std::endl; +// rewards_.record("Live", terminalReward, accu); // -// return true; -// } -// if (abs(gc_[0] - gc_init_[0]) >= 0.4) -// { -// return true; -// } -// if (abs(gc_[1] - gc_init_[1]) >= 0.4) -// { -// return true; -// } -// if(euler_angle[2] < -0.3) -// { -// return true; -// } + return true; + } + terminalReward = 0.f; return false; } @@ -287,7 +279,7 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; bool visualizable_ = false; raisim::ArticulatedSystem* anymal_, *anymal_1; Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; - double terminalRewardCoeff_ = -100.; + double terminalRewardCoeff_ = -10.; Eigen::VectorXd actionMean_, actionStd_, obDouble_; Vec<3> acc_, ang_vel_; Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 521829ff6..d1c71c6e9 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -4,9 +4,9 @@ record_video: true environment: render: true # just testing commenting - num_envs: 1 - eval_every_n: 100 - num_threads: 1 + num_envs: 100 + eval_every_n: 40 + num_threads: 30 simulation_dt: 0.0025 control_dt: 0.01 max_time: 4 @@ -27,11 +27,11 @@ environment: # torque: # coeff: -4e-5 Stable: - coeff: 0.4 + coeff: 0.3 Live: - coeff: 1 + coeff: 0 Wheel: - coeff: 0.3 + coeff: 0.2 # Mimic: # coeff: 0. diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 9b38cf536..44eee451a 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -99,11 +99,12 @@ num_learning_epochs=4, gamma=0.996, lam=0.95, - num_mini_batches=4, + num_mini_batches=16, + # learning_rate_schedule='', device=device, log_dir=saver.data_dir, shuffle_batch=False, - learning_rate=cfg['environment']['learnning_rate'] + # learning_rate=cfg['environment']['learnning_rate'] ) reward_analyzer = RewardAnalyzer(env, ppo.writer) @@ -124,6 +125,7 @@ mode == 'train' history_act = np.array([his_util] * num_envs) +history_act_0 = np.array([his_util] * num_envs) total_update = args.update if mode =='train' or mode == 'retrain': # print('start train') @@ -135,10 +137,13 @@ start = time.time() env.reset() reward_sum = 0 + envs_idx = [0] * num_envs + history_act=history_act_0 done_sum = 0 average_dones = 0. if update % cfg['environment']['eval_every_n'] == 0: + # draw_his = Drawer('history') waiter = Waiter(0.01) print("Visualizing and evaluating the current policy") torch.save({ @@ -148,15 +153,15 @@ 'optimizer_state_dict': ppo.optimizer.state_dict(), }, saver.data_dir+"/full_"+str(update)+'.pt') # we create another graph just to demonstrate the save/load method - loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) - loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) + # loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) + # loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) # debug_draw_action = Drawer('debug_draw_action') # debug_draw_history = Drawer('debug_draw_history') env.turn_on_visualization() env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') - envs_idx = [0] * num_envs + # envs_idx = [0] * num_envs waiter.update_start() for step in range(n_steps): with torch.no_grad(): @@ -169,17 +174,24 @@ # history_act = np.array([ check_history(history_act[i], dones[i]) for i in range(num_envs)] ) - action = loaded_graph.architecture(torch.from_numpy(obs).cpu()) - action = action.cpu().detach().numpy() + action = ppo.act(obs) + # action = action.cpu().detach().numpy() # sine = sine_generator(envs_idx, schedule, angle_rate) # action, history_act = transfer_f(action, sine, act_rate, history_act=history_act) # action = action.astype(np.float32) # - +#todo action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + + + + # draw_his.add_map_list(history_act[0]) + # + # history_act = history_act_0 + # print(history_act) # debug_draw_action.add_map_list(action[0]) # debug_draw_history.add_map_list(history_act[0]) @@ -188,8 +200,10 @@ # history_act = sine # envs_idx = list(map(check_done, envs_idx, dones)) # history_act = action - history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) + + # todo + history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) envs_idx = list(map(check_done, envs_idx, dones)) reward_analyzer.add_reward_info(env.get_reward_info()) @@ -197,7 +211,7 @@ wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) # if wait_time > 0.: # time.sleep(wait_time) - + # draw_his.draw() env.stop_video_recording() env.turn_off_visualization() history_act = np.array([his_util] * num_envs) @@ -211,6 +225,7 @@ # actual training # sine = [0] * 12 envs_idx = [0] * num_envs + history_act=history_act_0 for step in range(n_steps): obs = env.observe(False) """ @@ -220,13 +235,18 @@ # history_act = get_last_position(obs) action = ppo.act(obs) - + # if step== 100: + # print(action) # sine = sine_generator(envs_idx, schedule, angle_rate) # action, history_act = transfer_f(action, sine, act_rate, history_act=history_act) # action = action.astype(np.float32) # action1, history_act1 = run_model_with_pt_input(action,envs_idx,schedule,history_act) + #todo action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + + # history_act = history_act_0 + # print(f'action1 {action1}\n action{action}') # print(f'history1 {history_act1} \n history{history_act}') # input() @@ -239,6 +259,7 @@ # history_act = sine # envs_idx = list(map(check_done, envs_idx, dones)) # history_act = action + history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) # reward = reward * envs_idx / n_steps * 2 @@ -251,7 +272,7 @@ reward_analyzer.analyze_and_plot(update) # take st step to get value obs obs = env.observe(False) - ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 10 == 0, update=update) + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) average_ll_performance = reward_sum / total_steps if average_ll_performance > biggest_reward: biggest_iter = update From 3b56aa09cdc03731bec30efc534fed731e364736 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Fri, 18 Aug 2023 22:17:25 +0800 Subject: [PATCH 26/62] the skate model has been written wishing to make the model up to the skate --- examples/CMakeLists.txt | 2 + examples/src/server/go1.cpp | 72 +++++++++++-------- examples/src/server/skate.cpp | 63 ++++++++++++++++ .../raisimGymTorch/algo/ppo/module.py | 3 +- .../raisimGymTorch/env/deploy/onnx_deploy.py | 13 ++-- .../envs/rsg/Environment_tobuildforpython.hpp | 32 +++++---- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 10 +-- .../raisimGymTorch/env/envs/rsg/runner.py | 31 ++++---- 8 files changed, 160 insertions(+), 66 deletions(-) create mode 100644 examples/src/server/skate.cpp diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 24d95b4bb..2af672918 100755 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -98,3 +98,5 @@ create_executable(anymals src/maps/anymals.cpp) create_executable(hill1 src/maps/hill1.cpp) create_executable(kinova src/maps/kinova.cpp) +create_executable(skate src/server/skate.cpp) + diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index 09abd91a8..32abb187d 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -140,12 +140,15 @@ int main(int argc, char* argv[]) { /// create objects auto ground = world.addGround(); auto go1 = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\a1_description\\urdf\\a1.urdf"); - + auto board = world.addArticulatedSystem(binaryPath.getDirectory() +"\\rsc\\skate\\skate.urdf"); /// go1 joint PD controller Eigen::VectorXd jointNominalConfig(go1->getGeneralizedCoordinateDim()), jointVelocityTarget(go1->getDOF()); // jointNominalConfig << 0, 0, 0.41, 1.0, 0.0, 0.0, 0.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; - - jointNominalConfig << 0, 0, 0.33, 1.0, 0.0, 0, 0, 0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976 ; // todo implement in python using list + Eigen::VectorXd board_posi(board->getGeneralizedCoordinateDim()); + board_posi << 0,0,0.11, 0.707, 0,0, 0.707,0,0; + board->setGeneralizedCoordinate(board_posi); + board->setName("board"); + jointNominalConfig << -0, 0, 0.49, 1.0, 0.0, 0, 0, 0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976, 0.0, 0.5235987755982988, -1.0471975511965976 ; // todo implement in python using list // jointNominalConfig << 0, 0, 0.33, 1.0, 0.0, 0, 0, 0, 1, -2.2, 0.0, 1, -2.2, 0.0, 1, -2.2, 0.0, 1, -2.2; // todo implement in python using list // jointNominalConfig.tail(12).setZero(); // Eigen::VectorXd tmp(12); @@ -190,7 +193,7 @@ int main(int argc, char* argv[]) { for (int i=0; i<2000000; i++) { - std::cin.ignore(); +// std::cin.ignore(); // imu->getAngularVelocity() @@ -208,22 +211,22 @@ int main(int argc, char* argv[]) { bodyAngularVelocity = rot.e().transpose() * gv.segment(3, 3); Eigen::Vector3d eule; rot2euler(rot, eule); - std::cout<<"euler " << bodyAngularVelocity< qu{1+double(i)/500 , 0 , 0, 0+ double(i) / 500 }; // go1->setBaseOrientation(qu); - Eigen::VectorXd tmp1(12), tmp2(12); - tmp1 = gc.tail(12); - tmp2 = gv.tail(12); - for(auto i=0; i<12; i++){ - ob_[2*i] = tmp1[i]; - ob_[2 * i+1] = tmp2[i]; - } - for(auto i=0;i <12; i++) - { - swap(ob_, i, 12 +i); - } +// Eigen::VectorXd tmp1(12), tmp2(12); +// tmp1 = gc.tail(12); +// tmp2 = gv.tail(12); +// for(auto i=0; i<12; i++){ +// ob_[2*i] = tmp1[i]; +// ob_[2 * i+1] = tmp2[i]; +// } +// for(auto i=0;i <12; i++) +// { +// swap(ob_, i, 12 +i); +// } raisim::Vec<3> vel_temp; // go1->getFrameVelocity("ROOT", vel_temp); @@ -234,13 +237,19 @@ int main(int argc, char* argv[]) { // acc[i] = vel_temp // } // std::cout << "vel \n" << vel << std::endl << "acc\n " << acc << std::endl; - usleep(5000); + usleep(10000); angle_generator(position, i, 40, 0.35); jointNominalConfig.tail(12) = position; - for(auto n: go1->getBodyNames()) - { - std::cout << n << std::endl; - } +// for(auto n: go1->getContacts()) +// { +// std::cout << n.getPairContactIndexInPairObject()<< std::endl; +// } + for(auto obj:world.getObjList()) + { + std::cout<getName()< angvel; go1->getAngularVelocity(roott, angvel); // std::cout<printOutFrameNamesInOrder(); +// std::cout<< "angle" << b/odyAngularVelocity << std::endl; +// std::cout<<"GET " << angvel << std::endl; +// go1->printOutFrameNamesInOrder(); go1->getFrameAcceleration("floating_base", angvel); - std::cout<getAngularVelocity(); RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) @@ -275,10 +284,17 @@ int main(int argc, char* argv[]) { // } // jointNominalConfig.tail(12) = tmp; // std::cout<< tmp << std::endl; - +// jointNominalConfig[8] = - 0.01 * i ; go1->setPdTarget(jointNominalConfig, jointVelocityTarget); - +// for(auto& contact : go1->getContacts()) +// { +//// if(contact.getPairContactIndexInPairObject() != raisim::BodyType::STATIC) +//// { +//// world.getObject(contact.getPairObjectIndex())->getContacts(); +//// } +// } +// server.integrateWorldThreadSafe(); } diff --git a/examples/src/server/skate.cpp b/examples/src/server/skate.cpp new file mode 100644 index 000000000..78dfcc449 --- /dev/null +++ b/examples/src/server/skate.cpp @@ -0,0 +1,63 @@ +// +// Created by lr-2002 on 23-8-18. +// +// This file is part of RaiSim. You must obtain a valid license from RaiSim Tech +// Inc. prior to usage. + +#include "raisim/RaisimServer.hpp" +#include "raisim/World.hpp" +#include + +int main(int argc, char* argv[]) { + auto binaryPath = raisim::Path::setFromArgv(argv[0]); + + /// create raisim world + raisim::World world; + world.setTimeStep(0.01); + + /// create objects + world.addGround(); + raisim::RaisimServer server(&world); + server.launchServer(); + auto skate = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\skate\\skate.urdf"); + /// skate state + Eigen::VectorXd jointNominalConfig(skate->getGeneralizedCoordinateDim()); + skate->setName("skate"); + jointNominalConfig.setZero(); +// jointNominalConfig[1] = 0.01; + jointNominalConfig<< 0, 0, 0.11, 1 , 0, 0, 0 ,0 , 0; + Eigen::VectorXd jointVelocityTarget(skate->getDOF() ); + jointVelocityTarget.setZero(); + skate->setControlMode(raisim::ControlMode::FORCE_AND_TORQUE); + Eigen::VectorXd jointPgain(skate->getDOF()), jointDgain(skate->getDOF()); + jointPgain.tail(2).setConstant(80); + jointDgain.tail(2).setConstant(4); + + skate->setGeneralizedCoordinate(jointNominalConfig); + skate->setGeneralizedForce(Eigen::VectorXd::Zero(skate->getDOF())); + skate->setPdGains(jointPgain, jointDgain); + skate->setPdTarget(jointNominalConfig, jointVelocityTarget); + skate->setGeneralizedCoordinate(jointNominalConfig); + std::cout << " position " << jointNominalConfig; + /// launch raisim server + + std::cout<<"gra " << world.getGravity(); + std::cout << "\n mov "; + auto na = skate->getMovableJointNames(); + + server.focusOn(skate); + for (auto i:na) + { + std::cout << i << std::endl; + } + for (int i=0; i<200000; i++) { + RS_TIMED_LOOP(int(world.getTimeStep()*1e6)) + server.integrateWorldThreadSafe(); + jointNominalConfig.tail(2).setConstant( 0.02 * i); + jointVelocityTarget.tail(2).setConstant(0); + skate->setPdTarget(jointNominalConfig, jointVelocityTarget); + } + + server.killServer(); +} + diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/module.py b/raisimGymTorch/raisimGymTorch/algo/ppo/module.py index 9ec7baf87..b888a9b36 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/module.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/module.py @@ -19,7 +19,8 @@ def sample(self, obs): self.action_mean = self.architecture.architecture(obs).cpu().numpy() actions, log_prob = self.distribution.sample(self.action_mean) # todo - # actions = (np.clip(actions, self.action_mean -np.pi, self.action_mean+np.pi) - self.action_mean) / np.pi + # actions = actions- + # actions =np.clip(actions- 1,-1 ,1) return actions, log_prob def evaluate(self, obs, actions): diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py index ff553a767..c3514b444 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py @@ -15,8 +15,11 @@ def ang_trans(lower, upper, x): """ trans the rate x to the angle """ - x = (x+1)/2 #todo for test - return x * upper + (1-x) * lower + if isinstance(lower, list): + return [ang_trans(lower[i], upper[i], x[i]) for i in range(len(lower))] + else: + x = (x+1)/2 #todo for test + return x * upper + (1-x) * lower def norm(lower, upper, x): # print(lower, upper, x) @@ -58,6 +61,7 @@ def deg_normalize(lower, upper, x): # low_rad = deg_rad(low) # upp_rad = deg_rad(upp) u0 = deg_normalize(low, upp, u0) +u0_ang = ang_trans(low, upp, u0) # u0_rad = rad_normalize(low_rad, upp_rad, u0_rad) # u0 = [-deg_normalize(low, upp, u0)[i] if deg_normalize(low, upp, u0)[i]!=0 else 0 for i in range(12)] # print(u0) @@ -172,7 +176,8 @@ def sine_gene_pt(idx, T): angle_list = [0 for i in range(12)] if idx >= 2 * T: idx = 0 - dh = 0.8 # todo for test + dh =0.8 #:w + if idx >= 0 and idx <= T: tp0 =idx - 0 @@ -199,7 +204,7 @@ def sine_gene_pt(idx, T): angle_list[10] = y1 angle_list[11] = -2 * y1 # print("ang_list ", angle_list) - angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i]) ) for i in range(12)] + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + u0_ang[i]) for i in range(12)] # print("ang_list ", angle_list) return angle_list else: diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index a5fa0d47f..f15214b44 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -144,7 +144,7 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; anymal_->setState(gc_init_, gv_init_); rewards_.setZero(); COUNT=0; - euler_angle_old.setZero(); +// euler_angle_old.setZero(); updateObservation(); } @@ -177,33 +177,35 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; updateObservation(); double rrr =0; // for(int i=0;i<=2;i++) rrr += abs(euler_angle[i]) ; - rrr = abs(euler_angle[0]) + abs(euler_angle[1]); - rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1]) ); + rrr = abs(euler_angle[0]) + abs(euler_angle[1]) + abs(euler_angle[2]); + rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1]) +abs(ang_vel_[2])); // rrr = abs(gc_[0]) + abs(gc_[1]); // rrr += (gc_.tail(12) - pTarget12_).norm() ; bool accu = false; rewards_.record("Stable",-rrr, accu); // std::cout<<"eu 0 "<< euler_angle[0] << " eu1 " << euler_angle[1] << std::endl; rewards_.record("Live", 1, accu); -// rewards_.record("forwardVel", bodyLinearVel_[0], accu); + rewards_.record("forwardVel", bodyLinearVel_[0], accu); // rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); // rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); - rewards_.record("Wheel", 0.5 - abs(ang_vel_[2]- 0.5), accu); +// rewards_.record("Wheel", 0.5 - abs(ang_vel_[2]- 0.5), accu); // euler_angle_old = euler_angle; -// rewards_.record("torque", ) + rewards_.record("torque",anymal_->getGeneralizedForce().squaredNorm() ); return rewards_.sum(); } void updateObservation() { anymal_->getState(gc_, gv_); -// raisim::Vec<4> quat; -// raisim::Mat<3,3> rot; -// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; -// quat /= quat.norm(); -// raisim::quatToRotMat(quat, rot); -// bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); -// bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + quat /= quat.norm(); + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); anymal_->getAngularVelocity(anymal_->getBodyIdx("base"), ang_vel_); +// anymal_->getVelocity(anymal_->getBodyIdx("base"), bodyLinearVel_); +// anymal_->get Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); euler_angle = ToEulerAngles(qua); // if(euler_angle[1] > PI) euler_angle[1] -= 2*PI; @@ -243,9 +245,9 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) {// if there is any contact body was not in the footIndices the over // rewards_.record("Live", terminalReward, accu); - std::cout<<"foot done " << std::endl; +// std::cout<<"foot done " << std::endl; return true;} - if(abs(gc_[2] - gc_init_[2]) > 0.22){ + if(abs(gc_[2] - gc_init_[2]) > 0.2){ // std::cout<<"z done" << std::endl; // rewards_.record("Live", terminalReward, accu); diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index d1c71c6e9..927305ac2 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -22,16 +22,16 @@ environment: d_gain: 8 urdf_path: /home/lr-2002/code/raisimLib/rsc/a1_description/urdf/a1.urdf reward: -# forwardVel: -# coeff: 0 -# torque: -# coeff: -4e-5 + forwardVel: + coeff: 0.2 + torque: + coeff: -4e-5 Stable: coeff: 0.3 Live: coeff: 0 Wheel: - coeff: 0.2 + coeff: 0. # Mimic: # coeff: 0. diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 44eee451a..e986795bf 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -122,7 +122,7 @@ # weight_path = "" print = logger.info - +env_idx = np.zeros(100) mode == 'train' history_act = np.array([his_util] * num_envs) history_act_0 = np.array([his_util] * num_envs) @@ -137,7 +137,7 @@ start = time.time() env.reset() reward_sum = 0 - envs_idx = [0] * num_envs + envs_idx = env_idx history_act=history_act_0 done_sum = 0 average_dones = 0. @@ -161,7 +161,7 @@ env.turn_on_visualization() env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') - # envs_idx = [0] * num_envs + envs_idx = env_idx waiter.update_start() for step in range(n_steps): with torch.no_grad(): @@ -175,6 +175,8 @@ action = ppo.act(obs) + aa = action.copy() + aa = np.clip(aa-1, -1, 1) # todo # action = action.cpu().detach().numpy() # sine = sine_generator(envs_idx, schedule, angle_rate) @@ -182,7 +184,7 @@ # action = action.astype(np.float32) # #todo - action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + aa, history_act = run_model_with_pt_input_modify(aa, envs_idx, schedule, history_act) @@ -195,7 +197,7 @@ # debug_draw_action.add_map_list(action[0]) # debug_draw_history.add_map_list(history_act[0]) - reward, dones = env.step(action) + reward, dones = env.step(aa) # history_act = sine # envs_idx = list(map(check_done, envs_idx, dones)) @@ -204,8 +206,8 @@ # todo history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) - envs_idx = list(map(check_done, envs_idx, dones)) - + # envs_idx = list(map(check_done, envs_idx, dones)) + envs_idx = np.where(dones ==1, 0, envs_idx+1) reward_analyzer.add_reward_info(env.get_reward_info()) frame_end = time.time() wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) @@ -224,7 +226,7 @@ # actual training # sine = [0] * 12 - envs_idx = [0] * num_envs + envs_idx = env_idx history_act=history_act_0 for step in range(n_steps): obs = env.observe(False) @@ -235,6 +237,8 @@ # history_act = get_last_position(obs) action = ppo.act(obs) + aa = action.copy() + aa = np.clip(aa - 1, -1, 1) # todo # if step== 100: # print(action) @@ -242,8 +246,8 @@ # action, history_act = transfer_f(action, sine, act_rate, history_act=history_act) # action = action.astype(np.float32) # action1, history_act1 = run_model_with_pt_input(action,envs_idx,schedule,history_act) - #todo - action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + + aa, history_act = run_model_with_pt_input_modify(aa, envs_idx, schedule, history_act) # history_act = history_act_0 @@ -251,8 +255,8 @@ # print(f'history1 {history_act1} \n history{history_act}') # input() # print(f'3{time.time()}') - # todo the transfer has bug - reward, dones = env.step(action) + + reward, dones = env.step(aa) # input('1') # print(f"history : {history_act}") @@ -263,8 +267,9 @@ history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) # reward = reward * envs_idx / n_steps * 2 + envs_idx = np.where(dones == 1, 0, envs_idx + 1) - envs_idx = list(map(check_done, envs_idx, dones)) + # envs_idx = list(map(check_done, envs_idx, dones)) ppo.step(value_obs=obs, rews=reward, dones=dones) done_sum = done_sum + np.sum(dones) reward_sum = reward_sum + np.sum(reward) From fdd34ac2cf819ff54dc4f2e955fdd131d88ca32c Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Fri, 18 Aug 2023 23:33:20 +0800 Subject: [PATCH 27/62] onnx_deploy.py sine_pt need fix the boundry you can let the angle lower --- .../raisimGymTorch/env/deploy/onnx_deploy.py | 43 ++++++++++--------- .../envs/rsg/Environment_tobuildforpython.hpp | 40 ++++++++++------- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 6 ++- .../raisimGymTorch/env/envs/rsg/runner.py | 2 +- 4 files changed, 53 insertions(+), 38 deletions(-) diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py index c3514b444..8126e8fe1 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py @@ -23,7 +23,7 @@ def ang_trans(lower, upper, x): def norm(lower, upper, x): # print(lower, upper, x) - assert abs((x - lower) / (upper - lower) ) <= 1 + assert abs((x - lower) / (upper - lower) ) <= 1, f"{abs((x - lower) / (upper - lower) )} {x, upper, lower} " return (x - lower) / (upper - lower) def rad_normalize(lower, upper,x): @@ -53,7 +53,9 @@ def deg_normalize(lower, upper, x): low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] -u0 = [0, 30, -60,0, 30, -60,0, 30, -60,0, 30, -60] +tha1,tha2 = 60, 30 +u0 = [0, tha2, -2*tha2, 0 ,tha1, -tha1 * 2, 0 , tha2, -2*tha2, 0, tha1,-2*tha1] + low_np = np.array(low) upp_np = np.array(upp) # u0_rad = deg_rad(u0) @@ -176,21 +178,22 @@ def sine_gene_pt(idx, T): angle_list = [0 for i in range(12)] if idx >= 2 * T: idx = 0 - dh =0.8 #:w - - - if idx >= 0 and idx <= T: - tp0 =idx - 0 - y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 - y2 = 0 - # y2 = y1 - elif idx>T and idx<=2*T: - tp0 =idx - T - y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 - y1 = 0 + dh =-0.5 #:w + + + # if idx >= 0 and idx <= T: + # tp0 =idx - 0 + # y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y2 = 0 + # # y2 = y1 + # elif idx>T and idx<=2*T: + # tp0 =idx - T + # y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + # y1 = 0 # y1 = y2 - - + idx = idx % T + y1 = dh * 10 * (-cos(pi * 2 *idx /T) + 1) + y2 = deg_rad(60) angle_list[0] = 0 angle_list[1] = y1 angle_list[2] = -2 * y1 @@ -198,11 +201,11 @@ def sine_gene_pt(idx, T): angle_list[4] = y2 angle_list[5] = -2 * y2 angle_list[6] = 0 - angle_list[7] = y2 - angle_list[8] = -2 * y2 + angle_list[7] = y1 + angle_list[8] = -2 * y1 angle_list[9] = 0 - angle_list[10] = y1 - angle_list[11] = -2 * y1 + angle_list[10] = y2 + angle_list[11] = -2 * y2 # print("ang_list ", angle_list) angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + u0_ang[i]) for i in range(12)] # print("ang_list ", angle_list) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index f15214b44..6c0643880 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -54,6 +54,7 @@ namespace raisim { READ_YAML(double, p_gain, cfg_["p_gain"]); READ_YAML(double, d_gain, cfg_["d_gain"]); anymal_ = world_->addArticulatedSystem(urdf_path); + skate = world_ ->addArticulatedSystem("/home/lr-2002/code/raisimLib/rsc/skate/skate.urdf"); anymal_->setName("model"); anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); world_->addGround(); @@ -62,7 +63,10 @@ namespace raisim { gcDim_ = anymal_->getGeneralizedCoordinateDim(); // 19 gvDim_ = anymal_->getDOF(); // 18 nJoints_ = gvDim_ - 6; - + skate_posi_init.setZero(9); + skate_vel_init.setZero(8); + skate_posi_init << 0, 0.12, 0.11, 0.707, 0., 0, 0.707, 0 , 0; + skate ->setGeneralizedCoordinate(skate_posi_init); gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); euler_angle.setZero();euler_angle_old.setZero(); @@ -71,10 +75,12 @@ namespace raisim { gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); acc_.setZero();//1 ang_vel_.setZero(); - + skate_vel_.setZero(8); + skate_posi_.setZero(9); // init_position(); -double aa = double(30) /180*PI, bb = double(-60) /180*PI; - gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, aa, bb, 0.0, aa, bb, 0.0,aa,bb, 0.0, aa,bb; +double aa = double(30) /180*PI, bb = double(60) /180*PI; + gc_init_<< 0, 0, 0.35, 1.0, 0.0, 0.0, 0.0, 0.0, aa, -2*aa, 0.0, bb, -2*bb, 0.0,aa,-2*aa, 0.0, bb, -2*bb; + // gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; // init_position(gc_init_); init(); @@ -142,6 +148,7 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; void reset() final { anymal_->setState(gc_init_, gv_init_); + skate->setState(skate_posi_init, skate_vel_init); rewards_.setZero(); COUNT=0; // euler_angle_old.setZero(); @@ -185,7 +192,8 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; rewards_.record("Stable",-rrr, accu); // std::cout<<"eu 0 "<< euler_angle[0] << " eu1 " << euler_angle[1] << std::endl; rewards_.record("Live", 1, accu); - rewards_.record("forwardVel", bodyLinearVel_[0], accu); + rewards_.record("forwardVel", skate_vel_[0], accu); + rewards_.record("height", 0.45- abs(gc_[2] - 0.45) - abs(gc_[0] ) - abs(gc_[1]) , accu); // rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); // rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); // rewards_.record("Wheel", 0.5 - abs(ang_vel_[2]- 0.5), accu); @@ -196,6 +204,7 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; void updateObservation() { anymal_->getState(gc_, gv_); + skate -> getState(skate_posi_, skate_vel_); raisim::Vec<4> quat; raisim::Mat<3,3> rot; quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; @@ -241,13 +250,13 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; bool isTerminalState(float& terminalReward) final { terminalReward = float(terminalRewardCoeff_); bool accu = true; - for(auto& contact: anymal_->getContacts()) - if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) - {// if there is any contact body was not in the footIndices the over -// rewards_.record("Live", terminalReward, accu); -// std::cout<<"foot done " << std::endl; - return true;} - if(abs(gc_[2] - gc_init_[2]) > 0.2){ +// for(auto& contact: anymal_->getContacts()) +// if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) +// {// if there is any contact body was not in the footIndices the over +//// rewards_.record("Live", terminalReward, accu); +//// std::cout<<"foot done " << std::endl; +// return true;} + if(gc_[2] - gc_init_[2] > 0.3){ // std::cout<<"z done" << std::endl; // rewards_.record("Live", terminalReward, accu); @@ -255,14 +264,14 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; } - if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.17) + if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.3) { // std::cout<<"y angle done" <<" " << euler_angle[1]<< std::endl; // rewards_.record("Live", terminalReward, accu); return true; } - if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.17) + if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.3) { // std::cout<<"x angle done " << euler_angle[0] << std::endl; // rewards_.record("Live", terminalReward, accu); @@ -279,7 +288,7 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; private: int gcDim_, gvDim_, nJoints_; bool visualizable_ = false; - raisim::ArticulatedSystem* anymal_, *anymal_1; + raisim::ArticulatedSystem* anymal_, *anymal_1, *skate; Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; double terminalRewardCoeff_ = -10.; Eigen::VectorXd actionMean_, actionStd_, obDouble_; @@ -298,6 +307,7 @@ double aa = double(30) /180*PI, bb = double(-60) /180*PI; Eigen::Vector3d euler_angle, euler_angle_old; /// these variables are not in use. They are placed to show you how to create a random number sampler. bool float_base; + Eigen::VectorXd skate_vel_, skate_posi_,skate_posi_init, skate_vel_init; std::normal_distribution normDist_; thread_local static std::mt19937 gen_; }; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 927305ac2..e0d4d6c53 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -23,11 +23,13 @@ environment: urdf_path: /home/lr-2002/code/raisimLib/rsc/a1_description/urdf/a1.urdf reward: forwardVel: - coeff: 0.2 + coeff: 0.5 torque: coeff: -4e-5 Stable: - coeff: 0.3 + coeff: 0.01 + height: + coeff: 0. Live: coeff: 0 Wheel: diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index e986795bf..e373474c7 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -172,7 +172,7 @@ # history_act = get_last_position(obs) # history_act = np.array([ check_history(history_act[i], dones[i]) for i in range(num_envs)] ) - + # time.sleep(1) action = ppo.act(obs) aa = action.copy() From cf8919c9fa6bd8bd4a7454ef05e49ee06af11c55 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Sun, 20 Aug 2023 20:40:19 +0800 Subject: [PATCH 28/62] update running file --- examples/src/server/go1.cpp | 52 ++++++- raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py | 3 +- .../raisimGymTorch/env/deploy/deploy.py | 141 ----------------- .../raisimGymTorch/env/deploy/onnx_deploy.py | 113 +------------- .../raisimGymTorch/env/deploy/robot.py | 8 - .../raisimGymTorch/env/envs/rsg/runner.py | 144 ++---------------- .../env/envs/rsg/sim_with_real.py | 16 -- .../helper/raisim_gym_helper.py | 8 +- raisimUnity/linux/.gitignore | 0 9 files changed, 75 insertions(+), 410 deletions(-) delete mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/deploy.py delete mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/robot.py mode change 100644 => 100755 raisimUnity/linux/.gitignore diff --git a/examples/src/server/go1.cpp b/examples/src/server/go1.cpp index 32abb187d..b19442107 100644 --- a/examples/src/server/go1.cpp +++ b/examples/src/server/go1.cpp @@ -138,7 +138,7 @@ int main(int argc, char* argv[]) { world.setTimeStep(0.01); /// create objects - auto ground = world.addGround(); + auto ground = world.addGround(0, "land"); auto go1 = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\a1_description\\urdf\\a1.urdf"); auto board = world.addArticulatedSystem(binaryPath.getDirectory() +"\\rsc\\skate\\skate.urdf"); /// go1 joint PD controller @@ -167,6 +167,35 @@ int main(int argc, char* argv[]) { go1->setPdTarget(jointNominalConfig, jointVelocityTarget); go1->setName("go1"); std::cout<< go1->getGeneralizedCoordinate(); + + for(auto n : go1->getCollisionBodies()) + { + auto name = n.colObj->name; + go1->getCollisionBody(name).setMaterial("steel"); +// go1->getCollisionBody() + } + + for(auto n : board->getCollisionBodies()) + { + auto name = n.colObj->name; + std::cout << name << std::endl; +// board->getCollisionBody(name).setMaterial("steel"); +// go1->getCollisionBody() + } +// wrl + board->getCollisionBody("base/0").setMaterial("sandpaper"); + board->getCollisionBody("rotater_r/0").setMaterial("rubber"); + board->getCollisionBody("rotater_f/0").setMaterial("rubber"); + go1->getCollisionBody("FL_foot/0").setMaterial("rubber"); + go1->getCollisionBody("FR_foot/0").setMaterial("rubber"); + go1->getCollisionBody("RR_foot/0").setMaterial("rubber"); + go1->getCollisionBody("RL_foot/0").setMaterial("rubber"); + world.setMaterialPairProp("steel", "rubber", 0.8, 0.15, 0.001); + world.setMaterialPairProp("rubber", "sandpaper", 0.99, 0.15, 0.001); + world.setMaterialPairProp("land", "rubber", 0.8, 0.1,0.001); + world.setMaterialPairProp("sandpaper", "land", 0.4, 0.15,0.001); + world.setMaterialPairProp("steel","land", 0.1, 0.05,0.001); +// world.updateMaterialProp(); /// launch raisim server raisim::RaisimServer server(&world); server.focusOn(go1); @@ -179,6 +208,8 @@ int main(int argc, char* argv[]) { position.setZero(12), velo.setZero(12); gc.setZero(19), gv.setZero(18); size_t dof = go1->getDOF(); +// go1->set + raisim::Vec<3> vel; vel.setZero(); @@ -189,6 +220,7 @@ int main(int argc, char* argv[]) { bodyAngularVelocity.setZero(3); bodyLinearVelocity.setZero(3); auto roott = go1->getBodyIdx("base"); +// go1->getCollisionBodies(); // auto imu = go1->getSensor("imu_joint"); for (int i=0; i<2000000; i++) { @@ -206,7 +238,15 @@ int main(int argc, char* argv[]) { quat[0] = gc[3]; quat[1] = gc[4]; quat[2] = gc[5]; quat[3] = gc[6]; quat /= quat.norm(); raisim::quatToRotMat(quat, rot); - +// auto nn =go1->getCollisionBodies(); +// int cnt = 0; +// for(auto n : nn ) +// { +// +// std::cout<< cnt ++ << " " << n.getMaterial() << std::endl; +// } +// std::cout<getCollisionBody("FL_FOOT/0").getMaterial(); bodyLinearVelocity = rot.e().transpose() * gv.segment(0, 3); bodyAngularVelocity = rot.e().transpose() * gv.segment(3, 3); Eigen::Vector3d eule; @@ -244,10 +284,10 @@ int main(int argc, char* argv[]) { // { // std::cout << n.getPairContactIndexInPairObject()<< std::endl; // } - for(auto obj:world.getObjList()) - { - std::cout<getName()<getName()< np.array: - """ - cal the act to the limit and add it with the sine - - """ - sine = np.array(sine) - act = cal_limit(act) - return act + sine - -def run(): - """ - run the ob-act - """ - cnt = 0 - angle_list = [0 for x in range(12)] - while True: - print('running func') - if not robot.alive(): - break - - ob = robot.observe() - - act = actor.architecture(torch.from_numpy(ob).cpu()).cpu().detach().numpy() - - angle_list = sine_generator(angle_list, cnt, cfg['environment']['schedule'], cfg['environment']['angle_rate']) - - act = act_concate(act, angle_list) - - robot.take_action(act) - - time.sleep(0.1) - - cnt += 1 - -if __name__=='__main__': - init() - - run() - diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py index 8126e8fe1..785f9059f 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py +++ b/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py @@ -23,7 +23,7 @@ def ang_trans(lower, upper, x): def norm(lower, upper, x): # print(lower, upper, x) - assert abs((x - lower) / (upper - lower) ) <= 1, f"{abs((x - lower) / (upper - lower) )} {x, upper, lower} " + # assert abs((x - lower) / (upper - lower) ) <= 1, f"{abs((x - lower) / (upper - lower) )} {x, upper, lower} " return (x - lower) / (upper - lower) def rad_normalize(lower, upper,x): @@ -178,7 +178,7 @@ def sine_gene_pt(idx, T): angle_list = [0 for i in range(12)] if idx >= 2 * T: idx = 0 - dh =-0.5 #:w + dh =-0.5#:w # if idx >= 0 and idx <= T: @@ -206,9 +206,9 @@ def sine_gene_pt(idx, T): angle_list[9] = 0 angle_list[10] = y2 angle_list[11] = -2 * y2 - # print("ang_list ", angle_list) + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + u0_ang[i]) for i in range(12)] - # print("ang_list ", angle_list) + return angle_list else: ans = [] @@ -228,8 +228,6 @@ def rate_to_act(lower, upper, rate): return lerp(lower, upper, norm_for_act(rate)) def clip(a,b,c): - # print('before clip ', a, b, c) - if isinstance(a, np.ndarray): return np.clip(a,b,c) @@ -237,15 +235,12 @@ def clip(a,b,c): a = b if a >= c: a = c - # print('clip ', a) return a def add_list(act_gen, sine, history=None): if isinstance(act_gen, np.ndarray): - # print(act_gen) assert act_gen.shape[0] == 12 else: - # print(act_gen) assert len(act_gen) == 12 kk = 0.9 kf = 1 @@ -259,17 +254,11 @@ def add_list(act_gen, sine, history=None): ans = [rate_to_act(low[i], upp[i], clip(kb * history_u[i] + kf * sine[i], -1, 1)) for i in range(12)] ans = [deg_rad(x) for x in ans] - # todo swap the ans - # print(ans) - # input()/ return ans else: - # history_u = history history = [history[i] * kk + (1-kk) * act_gen[i] for i in range(12)] # todo the act_gen[i] is to big ans = [rate_to_act(low[i], upp[i], clip(kb * history[i] + kf * sine[i], -1, 1)) for i in range(12)] ans = [deg_rad(x) for x in ans] - # todo swap the ans - return ans, history def lerp_np(a, b, c): @@ -279,45 +268,26 @@ def add_list_np(act_gen, sine, history): kk = 0.9 kf = 1 kb = 0.2 - # print('be history ', history, 'act_gen ', act_gen) history = history*kk + (1-kk) * act_gen ans = np.clip(kb*history + kf * sine, -1, 1) ans = (ans + 1) /2 # 100 * 12 ans = lerp_np(low_np, upp_np, ans) - # print('af history ', history) - return ans, history -def run_model_with_pt_input(act_gen, idx, T, history): - if isinstance(idx, list): - idx = [i%(2*T) for i in idx] - else: - idx = idx % (2 * T) - # act_gen = act_gen/3.14 * 180 - # act_gen = np.zeros_like(act_gen) - sine = sine_gene(idx, T) - ans = [] - new_his = [] - for i in range(act_gen.shape[0]): - tmp, tmp_his= add_list(act_gen[i], sine[i], history[i]) - ans.append(tmp) - new_his.append(tmp_his) + return ans, history - return np.array(ans).astype(np.float32),np.array(new_his).astype(np.float32) def run_model_with_pt_input_modify(act_gen, idx, T, history): + act_gen = np.clip(act_gen- 1, -1, 1) if isinstance(idx, list): idx = np.array(idx) - # print(idx.shape) idx = idx%(2*T) else: idx = idx % (2 * T) sine = sine_gene_pt(idx, T) - # act_gen = np.zeros_like(act_gen) ans, history = add_list_np(act_gen, sine, history) ans = ans / 180 * 3.14 - return ans.astype(np.float32), history.astype(np.float32) @@ -370,14 +340,10 @@ def run_model(observation, idx, T, save_gen=None): save_gen.add_list(act_gen[0]) sine = sine_gene(idx, T) - # print(sine) ans = [] for act in act_gen: ans.append(add_list(act, sine)) ans = np.array(ans).astype(np.float32) - # print(ans) - # input() - # be_ans = ans[:, [0,1,2,3,4,5,6,7,8,9,10,11]] = \ ans[:, [9,10,11,6,7,8,3,4,5,0,1,2]] ans = [ans] @@ -388,57 +354,8 @@ def run_model(observation, idx, T, save_gen=None): def run_model1(observation): return model.run([output_name], input_feed={input_name: observation}) -# 运行模型 - -# outputs = model.run([output_name], input_feed={input_name: input_data}) -# print(outputs) -# x = run_model(input_data) -# print(x) - - - # if not isinstance(idx, list): - # angle_list = [0 for i in range(12)] - # if idx >= 2 * T: - # idx = 0 - # dh = 0.8 # todo for test - # if idx >= 0 and idx <= T: - # tp0 =idx - 0 - # y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 - # y2 = 0 - # elif idx>T and idx<=2*T: - # tp0 =idx - T - # y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 - # y1 = 0 - # - # - # angle_list[0] = 0 - # angle_list[1] = y1 - # angle_list[2] = -2 * y1 - # angle_list[3] = 0 - # angle_list[4] = y2 - # angle_list[5] = -2 * y2 - # angle_list[6] = 0 - # angle_list[7] = y2 - # angle_list[8] = -2 * y2 - # angle_list[9] = 0 - # angle_list[10] = y1 - # angle_list[11] = -2 * y1 - # # print("ang_list ", angle_list) - # angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + ang_trans(low[i], upp[i], u0[i]) ) for i in range(12)] - # # print("ang_list ", angle_list) - # return angle_list - - - if __name__=="__main__": - # sine_gen(np.zeros(100), 40) - # idx = [3,2,1,4,1,3,2,3,2,3,1,2,3,2,3,1] - # a = [0,2,3,0] - # b= [ 5, 3, 5,0] - # a= np.array(a) - # b= np.array(b) - # c = np.array([[0.2, 0.5, 0.3, 0.4], [0,0.3,0.2,0]]) - # print(a * (1-c) + b * c) + z = [] minn = 100 minnn =[] @@ -458,23 +375,7 @@ def run_model1(observation): import matplotlib.pyplot as plt plt.plot(x, z) plt.show() - # mat = np.zeros((100,12)) - # mat = np.where(np.indices(mat)>20, 1, 0) - # print(mat) -""" -todo -1. on action 的范围 -2. 似乎是角度问题?应该是范围需要考虑是 角度还是弧度 - - -老师的输入是deg or rad -what's my output - - -using deg to get the rate -and feed the rate to the env -""" def test_run_model(): diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/robot.py b/raisimGymTorch/raisimGymTorch/env/deploy/robot.py deleted file mode 100644 index f164332b1..000000000 --- a/raisimGymTorch/raisimGymTorch/env/deploy/robot.py +++ /dev/null @@ -1,8 +0,0 @@ -from math import cos -import numpy as np -T=100 -x = [i for i in range(4 * T)] -y = [1.2 * 10 *(-cos(3.14 * 2 * (i % T) /T) + 1) /2 for i in x] -import matplotlib.pyplot as plt -plt.plot(x,y) -plt.show() \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index e373474c7..15f06e3bc 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -6,8 +6,8 @@ from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer import raisimGymTorch.algo.ppo.module as ppo_module import raisimGymTorch.algo.ppo.ppo as PPO -from raisimGymTorch.env.deploy.angle_utils import transfer_f ,get_last_position -from raisimGymTorch.env.deploy.onnx_deploy import run_model_with_pt_input_modify, list_pt, run_model_with_pt_input +from raisimGymTorch.env.deploy.angle_utils import get_last_position +from raisimGymTorch.env.deploy.onnx_deploy import run_model_with_pt_input_modify, list_pt import os import math import time @@ -21,19 +21,10 @@ from raisimGymTorch.deploy_log.draw_map import Drawer + # task specification task_name = "rsg_test" - -""" -todo: - 1. init model - 2. change p-d info - 3. debug and add_on sine_gait - -""" - - # configuration parser = argparse.ArgumentParser() parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') @@ -117,22 +108,16 @@ his_util=[0] * 12 check_done = lambda a, b: a + 1 if not b else 0 check_history = lambda a, b: a if not b else his_util -# need_to_review = lambda a,b: a if not b else np.array([[0, 0.523, -1.046] * 4]) # todo make sure the shape -# if load_best == True: -# weight_path = "" + print = logger.info -env_idx = np.zeros(100) +env_idx = np.zeros(num_envs) mode == 'train' history_act = np.array([his_util] * num_envs) history_act_0 = np.array([his_util] * num_envs) total_update = args.update if mode =='train' or mode == 'retrain': - # print('start train') schedule = cfg['environment']['schedule'] - angle_rate = cfg['environment']['angle_rate'] - act_rate = cfg['environment']['action_std'] # how many action generated use for work - act_rate = float(act_rate) for update in range(total_update): start = time.time() env.reset() @@ -152,12 +137,6 @@ 'critic_architecture_state_dict': critic.architecture.state_dict(), 'optimizer_state_dict': ppo.optimizer.state_dict(), }, saver.data_dir+"/full_"+str(update)+'.pt') - # we create another graph just to demonstrate the save/load method - # loaded_graph = ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim) - # loaded_graph.load_state_dict(torch.load(saver.data_dir+"/full_"+str(update)+'.pt')['actor_architecture_state_dict']) - - # debug_draw_action = Drawer('debug_draw_action') - # debug_draw_history = Drawer('debug_draw_history') env.turn_on_visualization() env.start_video_recording(datetime.datetime.now().strftime("%Y-%m-%d-%H-%M-%S") + "policy_"+str(update)+'.mp4') @@ -167,110 +146,39 @@ with torch.no_grad(): waiter.wait() frame_start = time.time() - obs = env.observe(False) - # print(obs.shape) - # history_act = get_last_position(obs) - # history_act = np.array([ check_history(history_act[i], dones[i]) for i in range(num_envs)] ) - # time.sleep(1) + obs = env.observe(False) action = ppo.act(obs) - aa = action.copy() - aa = np.clip(aa-1, -1, 1) # todo - # action = action.cpu().detach().numpy() - - # sine = sine_generator(envs_idx, schedule, angle_rate) - # action, history_act = transfer_f(action, sine, act_rate, history_act=history_act) - # action = action.astype(np.float32) - # -#todo - aa, history_act = run_model_with_pt_input_modify(aa, envs_idx, schedule, history_act) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + reward, dones = env.step(action) - - - - # draw_his.add_map_list(history_act[0]) - # - # history_act = history_act_0 - # print(history_act) - # debug_draw_action.add_map_list(action[0]) - # debug_draw_history.add_map_list(history_act[0]) - - reward, dones = env.step(aa) - - # history_act = sine - # envs_idx = list(map(check_done, envs_idx, dones)) - # history_act = action - - - # todo history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) - # envs_idx = list(map(check_done, envs_idx, dones)) envs_idx = np.where(dones ==1, 0, envs_idx+1) reward_analyzer.add_reward_info(env.get_reward_info()) frame_end = time.time() wait_time = cfg['environment']['control_dt'] - (frame_end-frame_start) - # if wait_time > 0.: - # time.sleep(wait_time) - # draw_his.draw() + env.stop_video_recording() env.turn_off_visualization() history_act = np.array([his_util] * num_envs) reward_analyzer.analyze_and_plot(update) env.reset() env.save_scaling(saver.data_dir, str(update)) - - # debug_draw_action.draw() - # debug_draw_history.draw() - - # actual training - # sine = [0] * 12 envs_idx = env_idx history_act=history_act_0 for step in range(n_steps): obs = env.observe(False) - """ - 1. z轴方向的加速度的处理方法 - - """ - # history_act = get_last_position(obs) - action = ppo.act(obs) - aa = action.copy() - aa = np.clip(aa - 1, -1, 1) # todo - # if step== 100: - # print(action) - - # sine = sine_generator(envs_idx, schedule, angle_rate) - # action, history_act = transfer_f(action, sine, act_rate, history_act=history_act) - # action = action.astype(np.float32) - # action1, history_act1 = run_model_with_pt_input(action,envs_idx,schedule,history_act) - - aa, history_act = run_model_with_pt_input_modify(aa, envs_idx, schedule, history_act) - - # history_act = history_act_0 - - # print(f'action1 {action1}\n action{action}') - # print(f'history1 {history_act1} \n history{history_act}') - # input() - # print(f'3{time.time()}') - - reward, dones = env.step(aa) - # input('1') - # print(f"history : {history_act}") - - # history_act = sine - # envs_idx = list(map(check_done, envs_idx, dones)) - # history_act = action - + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + reward, dones = env.step(action) history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) - - # reward = reward * envs_idx / n_steps * 2 envs_idx = np.where(dones == 1, 0, envs_idx + 1) - - # envs_idx = list(map(check_done, envs_idx, dones)) ppo.step(value_obs=obs, rews=reward, dones=dones) + + + done_sum = done_sum + np.sum(dones) reward_sum = reward_sum + np.sum(reward) reward_analyzer.add_reward_info(env.get_reward_info()) @@ -279,6 +187,8 @@ obs = env.observe(False) ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) average_ll_performance = reward_sum / total_steps + + if average_ll_performance > biggest_reward: biggest_iter = update biggest_reward = average_ll_performance @@ -309,29 +219,7 @@ print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) * cfg['environment']['control_dt']))) print('----------------------------------------------------\n') -else: - env.reset() - start = time.time() - onnx_flag = False - if onnx_flag: - cnt_onnx = 0 - from raisimGymTorch.env.deploy import onnx_deploy - - # load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) - for step in range(n_steps * 10): - time.sleep(0.01) - obs = env.observe(False) - # print(obs.shape) - if onnx_flag: - action = onnx_deploy.run_model(obs, cnt_onnx, 50) - action = np.array(action)[0] - cnt_onnx += 1 - # action = np.array([act for x in range(100)]) - else: - action = ppo.act(obs) - - reward, dones = env.step(action) print(f'biggest:{biggest_reward},rate = {biggest_iter}') diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index 33517884f..38d619c40 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -23,18 +23,6 @@ # from sine_generator import sine_generator from unitree_deploy.angle_utils import sine_generator from raisimGymTorch.env.deploy.angle_utils import deg_rad, rad_deg -"""" -todo - 1. left-hand right-hand check - 2. raisim data check - - env cannot get linear-acc - -""" - - - - # task specification task_name = "sim2real" @@ -52,8 +40,6 @@ mode = args.mode weight_path = args.weight cfg_path = args.cfg_path -# load_best = args.load_best -# check if gpu is available device = torch.device('cpu') # directories @@ -97,8 +83,6 @@ save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) logger = RaisimLogger(saver.data_dir+"/train.log") -if mode =='train' or mode == 'retrain': - tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update num_envs = cfg['environment']['num_envs'] ppo = PPO.PPO(actor=actor, critic=critic, diff --git a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py index a747eae1e..d6d1e8fad 100755 --- a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py +++ b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py @@ -63,17 +63,17 @@ class RaisimLogger(): def __init__(self, path): self.logger = logging.getLogger(__file__) self.logger.setLevel(logging.INFO) - # self.fh = logging.FileHandler(path) + self.fh = logging.FileHandler(path) self.ch = logging.StreamHandler() - # self.fh.setLevel(logging.INFO) + self.fh.setLevel(logging.INFO) self.ch.setLevel(logging.INFO) self.formatter = logging.Formatter("%(asctime)s.%(msecs)03d - %(levelname)s - %(message)s", datefmt='%Y-%m-%d,%H:%M:%S') self.ch.setFormatter(self.formatter) - # self.fh.setFormatter(self.formatter) + self.fh.setFormatter(self.formatter) self.logger.addHandler(self.ch) - # self.logger.addHandler(self.fh) + self.logger.addHandler(self.fh) def info(self, msg): self.logger.info(msg) diff --git a/raisimUnity/linux/.gitignore b/raisimUnity/linux/.gitignore old mode 100644 new mode 100755 From 23b563d3cbbb21d9ce25f25a60a1903e8aeb8bdd Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Mon, 21 Aug 2023 12:19:47 +0800 Subject: [PATCH 29/62] change the file-structure next to make the wheel model --- .../deploy_utils/angle_utils.py | 58 ++++++++ .../data/Environment.hpp | 0 .../deploy => deploy_utils}/onnx_deploy.py | 6 +- .../deploy_utils/thread_protect.py | 27 ++++ .../raisimGymTorch/env/auto_runner.py | 2 +- .../raisimGymTorch/env/deploy/angle_utils.py | 125 ------------------ .../envs/rsg/Environment_tobuildforpython.hpp | 68 +++++----- .../raisimGymTorch/env/envs/rsg/runner.py | 4 +- .../env/envs/rsg/sim_with_real.py | 10 +- .../helper/raisim_gym_helper.py | 10 +- 10 files changed, 137 insertions(+), 173 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/deploy_utils/angle_utils.py rename raisimGymTorch/raisimGymTorch/{env/deploy => deploy_utils}/data/Environment.hpp (100%) rename raisimGymTorch/raisimGymTorch/{env/deploy => deploy_utils}/onnx_deploy.py (98%) create mode 100644 raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py delete mode 100644 raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/angle_utils.py b/raisimGymTorch/raisimGymTorch/deploy_utils/angle_utils.py new file mode 100644 index 000000000..e5021ef50 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/angle_utils.py @@ -0,0 +1,58 @@ +from math import sin,pi +import numpy as np +# from onnx_deploy import rad_deg, deg_rad +from raisimGymTorch.deploy_log.draw_map import Drawer +def deg_rad(x): + if isinstance(x, list): + return [deg_rad(a) for a in x] + else: + return x / 180 * pi + +def rad_deg(x): + if isinstance(x, list): + return [rad_deg(a) for a in x] + else: + return x / pi * 180 + + +low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] +upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] +low = deg_rad(low) +upp = deg_rad(upp) +bund = [upp[i] - low[i] for i in range(12)] +def transfer(act_gen, sine, k, history_act = None) ->np.array: + """ + clip, lerp, generate the final action + params: act_gen: [12 * (-1, 1)] np.array + params: sine: [12 * rad_target] np.array + """ + act_gen = act_gen * bund # - + + act_gen = np.clip(act_gen, low, upp) + if history_act is not None: + kk = 0.9 + act_gen = act_gen * (1-kk) + history_act * kk + act_gen = np.clip(act_gen, low, upp) + if act_gen.shape[0] == 1: + act_gen = act_gen[0] + action = act_gen * k + sine + # print(np.abs(act_gen).max(), sine.max()) + action = np.clip(action, low, upp) + return action + + +def get_last_position(obs): + if isinstance(obs, list): + x = [obs[-2 * i] for i in range(1, 13)] + x.reverse() + return x + elif isinstance(obs, np.ndarray): + x = [] + for i in range(1, 13): + x.append(obs[:, -2*i]) + x.reverse() + return np.stack(x, axis=1) + +if __name__=='__main__': + a = np.random.rand(2,30) + print(a) + print(get_last_position(a).shape) diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/data/Environment.hpp b/raisimGymTorch/raisimGymTorch/deploy_utils/data/Environment.hpp similarity index 100% rename from raisimGymTorch/raisimGymTorch/env/deploy/data/Environment.hpp rename to raisimGymTorch/raisimGymTorch/deploy_utils/data/Environment.hpp diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py b/raisimGymTorch/raisimGymTorch/deploy_utils/onnx_deploy.py similarity index 98% rename from raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py rename to raisimGymTorch/raisimGymTorch/deploy_utils/onnx_deploy.py index 785f9059f..62849eff3 100644 --- a/raisimGymTorch/raisimGymTorch/env/deploy/onnx_deploy.py +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/onnx_deploy.py @@ -1,11 +1,11 @@ import time import onnxruntime as ort -# import onnx +# import onnx_file # from mlprodict.onnxrt import OnnxInference from math import cos,pi import numpy as np -from raisimGymTorch.env.deploy.angle_utils import deg_rad, rad_deg +from raisimGymTorch.deploy_utils.angle_utils import deg_rad, rad_deg from raisimGymTorch.deploy_log.draw_map import Drawer # 加载模型 @@ -70,7 +70,7 @@ def deg_normalize(lower, upper, x): history_u = [0] * 12 # history_u_rad = [0] * 12/ # history_u = u0.copy() -model = ort.InferenceSession('/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/deploy/2203.onnx') +model = ort.InferenceSession('/env/deploy_utils/onnx_file/2203.onnx') idx_local = 0 diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py b/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py new file mode 100644 index 000000000..1bdee005f --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py @@ -0,0 +1,27 @@ +import concurrent.futures +import threading +import time +import numpy as np +from raisimGymTorch.deploy_log.csv_saver import CSV_saver +def cal(): + print('calculating model') + time.sleep(0.3) + + +def save(saver:CSV_saver, data): + print('add data') + saver.add_list(data) + + +if __name__=='__main__': + print('start') + + csv = CSV_saver('./test.csv') + + for i in range(100): + data = np.random.rand(10) + cal() + print(data) + with concurrent.futures.ThreadPoolExecutor(max_workers=1) as exec: + exec.submit(save, data) + print('running robot') \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/auto_runner.py b/raisimGymTorch/raisimGymTorch/env/auto_runner.py index c655590a6..5cf11d923 100644 --- a/raisimGymTorch/raisimGymTorch/env/auto_runner.py +++ b/raisimGymTorch/raisimGymTorch/env/auto_runner.py @@ -23,4 +23,4 @@ def change_data(path, flag, data): else: os.system(f'python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py -u {length} |grep biggest' ) -# os.system('python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py -u 3 |grep biggest' ) +# os.system('python /home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner_util.py -u 3 |grep biggest' ) diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py b/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py deleted file mode 100644 index 2b6a31acf..000000000 --- a/raisimGymTorch/raisimGymTorch/env/deploy/angle_utils.py +++ /dev/null @@ -1,125 +0,0 @@ -from math import sin,pi -import numpy as np -# from onnx_deploy import rad_deg, deg_rad -from raisimGymTorch.deploy_log.draw_map import Drawer -def deg_rad(x): - if isinstance(x, list): - return [deg_rad(a) for a in x] - else: - return x / 180 * pi - -def rad_deg(x): - if isinstance(x, list): - return [rad_deg(a) for a in x] - else: - return x / pi * 180 - - -low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] -upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] -low = deg_rad(low) -upp = deg_rad(upp) -bund = [upp[i] - low[i] for i in range(12)] -def sine_generator(angle_list, idx, T, rate=1): - base1= 0.523 - base3= 0.0 - base2 = -2 * base1 - ang = abs(sin( float(idx) / T * pi)) * rate - - idx_base = 0 - - if (int(idx/T) % 2 ) == 1: - angle_list[idx_base+1] = ang + base1 - angle_list[idx_base+2] = -2 * ang + base2 - - angle_list[idx_base+4] = base1 - angle_list[idx_base+5] = base2 - - angle_list[idx_base+7] = base1 - angle_list[idx_base+8] = base2 - angle_list[idx_base+10] = ang + base1 - angle_list[idx_base+11] = - 2 * ang + base2 - else: - angle_list[idx_base+1] = base1 - angle_list[idx_base+2] = base2 - - angle_list[idx_base+10] = base1 - angle_list[idx_base+11] = base2 - angle_list[idx_base+4] = ang + base1 - angle_list[idx_base+5] = -2 * ang + base2 - - angle_list[idx_base+7] = ang + base1 - angle_list[idx_base+8] = -2 * ang + base2 - angle_list[idx_base+0] = base3 - angle_list[idx_base+3] = base3 - angle_list[idx_base+6] = base3 - angle_list[idx_base+9] = base3 - return angle_list - -def transfer(act_gen, sine, k, history_act = None) ->np.array: - """ - clip, lerp, generate the final action - params: act_gen: [12 * (-1, 1)] np.array - params: sine: [12 * rad_target] np.array - """ - # act_gen = (act_gen + 1) /2 # 0-1 - act_gen = act_gen * bund # - + - # print(act_gen) - act_gen = np.clip(act_gen, low, upp) - if history_act is not None: - kk = 0.9 - # act_gen = (1-kk) * act_gen - act_gen = act_gen * (1-kk) + history_act * kk - act_gen = np.clip(act_gen, low, upp) - if act_gen.shape[0] == 1: - act_gen = act_gen[0] - action = act_gen * k + sine - # print(np.abs(act_gen).max(), sine.max()) - action = np.clip(action, low, upp) - return action - -def transfer_f(act_gen, sine, k, history_act = None) ->np.array: - """ - clip, lerp, generate the final action - params: act_gen: [12 * (-1, 1)] np.array - params: sine: [12 * rad_target] np.array - """ - # act_gen = (act_gen + 1) /2 # 0-1 - act_gen = act_gen * bund / 2 # - + - # print(act_gen) - act_gen = np.clip(act_gen, low, upp) - if history_act is not None: - kk = 1-k - # act_gen = (1-kk) * act_gen - # print(f'his1 {history_act}\n act_gen{act_gen}') - history_act = act_gen * (1-kk) + history_act * kk - history_act = np.clip(history_act, low, upp) - # print(f'his2 {history_act}') - - if history_act.shape[0] == 1: - tmp = history_act[0] - else: - tmp = history_act - action = tmp * 0.2 + sine - # print(np.abs(act_gen).max(), sine.max()) - action = np.clip(action, low, upp) - # print(f'bound{bund}\n act_gen{act_gen}\n history_act{history_act}\n sine{sine} \naction{action}\nk{k} ') - # input('1') - return action, history_act - -def get_last_position(obs): - if isinstance(obs, list): - x = [obs[-2 * i] for i in range(1, 13)] - x.reverse() - return x - elif isinstance(obs, np.ndarray): - x = [] - for i in range(1, 13): - x.append(obs[:, -2*i]) - x.reverse() - return np.stack(x, axis=1) - -if __name__=='__main__': - a = np.random.rand(2,30) - print(a) - print(get_last_position(a).shape) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp index 6c0643880..6fa5d0d06 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp @@ -57,7 +57,7 @@ namespace raisim { skate = world_ ->addArticulatedSystem("/home/lr-2002/code/raisimLib/rsc/skate/skate.urdf"); anymal_->setName("model"); anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); - world_->addGround(); + world_->addGround(0,"land"); /// get robot data gcDim_ = anymal_->getGeneralizedCoordinateDim(); // 19 @@ -65,7 +65,7 @@ namespace raisim { nJoints_ = gvDim_ - 6; skate_posi_init.setZero(9); skate_vel_init.setZero(8); - skate_posi_init << 0, 0.12, 0.11, 0.707, 0., 0, 0.707, 0 , 0; + skate_posi_init << 0, 0.15, 0.11, 0.707, 0., 0, 0.707, 0 , 0; skate ->setGeneralizedCoordinate(skate_posi_init); gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); @@ -78,11 +78,9 @@ namespace raisim { skate_vel_.setZero(8); skate_posi_.setZero(9); // init_position(); -double aa = double(30) /180*PI, bb = double(60) /180*PI; +double aa = 0.5233 , bb = double(60) /180*PI; gc_init_<< 0, 0, 0.35, 1.0, 0.0, 0.0, 0.0, 0.0, aa, -2*aa, 0.0, bb, -2*bb, 0.0,aa,-2*aa, 0.0, bb, -2*bb; - // gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; -// init_position(gc_init_); init(); obDim_ = 29; @@ -101,7 +99,25 @@ double aa = double(30) /180*PI, bb = double(60) /180*PI; footIndices_.insert(anymal_->getBodyIdx("RL_calf")); footIndices_.insert(anymal_->getBodyIdx("RR_calf")); - /// visualize if it is the first environment + for(auto n : anymal_->getCollisionBodies()) + { + auto name = n.colObj->name; + anymal_->getCollisionBody(name).setMaterial("steel"); + } + + skate->getCollisionBody("base/0").setMaterial("sandpaper"); + skate->getCollisionBody("rotater_r/0").setMaterial("rubber"); + skate->getCollisionBody("rotater_f/0").setMaterial("rubber"); + anymal_->getCollisionBody("FL_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("FR_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("RR_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("RL_foot/0").setMaterial("rubber"); + world_->setMaterialPairProp("steel", "rubber", 0.8, 0.15, 0.001); + world_->setMaterialPairProp("rubber", "sandpaper", 0.99, 0.15, 0.001); + world_->setMaterialPairProp("land", "rubber", 0.8, 0.1,0.001); + world_->setMaterialPairProp("sandpaper", "land", 0.4, 0.15,0.001); + world_->setMaterialPairProp("steel","land", 0.1, 0.05,0.001); + if (visualizable_) { server_ = std::make_unique(world_.get()); server_->launchServer(); @@ -115,19 +131,9 @@ double aa = double(30) /180*PI, bb = double(60) /180*PI; Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(p_gain); -// jointPgain.tail(nJoints_)[2] = 300; -// jointPgain.tail(nJoints_)[5] = 300; -// jointPgain.tail(nJoints_)[8] = 300; -// jointPgain.tail(nJoints_)[11] = 300; jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(d_gain); -// jointDgain.tail(nJoints_)[2] = 15; -// jointDgain.tail(nJoints_)[5] = 15; -// jointDgain.tail(nJoints_)[8] = 15; -// jointDgain.tail(nJoints_)[11] = 15; anymal_->setPdGains(jointPgain, jointDgain); -// std::cout<setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); if(show_ref) { @@ -137,7 +143,6 @@ double aa = double(30) /180*PI, bb = double(60) /180*PI; anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); anymal_1->setPdGains(jointPgain,jointDgain); } -// std::cout<<"position inited\n"; } void init_position(const Eigen::Ref& posi) final @@ -183,21 +188,17 @@ double aa = double(30) /180*PI, bb = double(60) /180*PI; } updateObservation(); double rrr =0; -// for(int i=0;i<=2;i++) rrr += abs(euler_angle[i]) ; rrr = abs(euler_angle[0]) + abs(euler_angle[1]) + abs(euler_angle[2]); rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1]) +abs(ang_vel_[2])); -// rrr = abs(gc_[0]) + abs(gc_[1]); -// rrr += (gc_.tail(12) - pTarget12_).norm() ; + rrr += abs(gc_[0] - skate_posi_[0]) + abs(gc_[1] - (skate_posi_[1] - 0.15)); bool accu = false; rewards_.record("Stable",-rrr, accu); -// std::cout<<"eu 0 "<< euler_angle[0] << " eu1 " << euler_angle[1] << std::endl; rewards_.record("Live", 1, accu); rewards_.record("forwardVel", skate_vel_[0], accu); rewards_.record("height", 0.45- abs(gc_[2] - 0.45) - abs(gc_[0] ) - abs(gc_[1]) , accu); // rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); // rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); // rewards_.record("Wheel", 0.5 - abs(ang_vel_[2]- 0.5), accu); -// euler_angle_old = euler_angle; rewards_.record("torque",anymal_->getGeneralizedForce().squaredNorm() ); return rewards_.sum(); } @@ -205,6 +206,7 @@ double aa = double(30) /180*PI, bb = double(60) /180*PI; void updateObservation() { anymal_->getState(gc_, gv_); skate -> getState(skate_posi_, skate_vel_); + raisim::Vec<4> quat; raisim::Mat<3,3> rot; quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; @@ -213,14 +215,8 @@ double aa = double(30) /180*PI, bb = double(60) /180*PI; bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); anymal_->getAngularVelocity(anymal_->getBodyIdx("base"), ang_vel_); -// anymal_->getVelocity(anymal_->getBodyIdx("base"), bodyLinearVel_); -// anymal_->get Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); euler_angle = ToEulerAngles(qua); -// if(euler_angle[1] > PI) euler_angle[1] -= 2*PI; -// if(euler_angle[0] > PI) euler_angle[0] -= 2*PI; -// if(euler_angle[1] < -PI) euler_angle[1] += 2 * PI; -// if(euler_angle[0] < -PI) euler_angle[0] += 2 * PI; Eigen::VectorXd gcc = gc_.tail(12); Eigen::VectorXd gvv = gv_.tail(12); Eigen::VectorXd c_v(24); @@ -238,8 +234,6 @@ double aa = double(30) /180*PI, bb = double(60) /180*PI; ang_vel_[1], ang_vel_[2], c_v; -// std::cout<<"ang_vel : " << ang_vel_ << std::endl; - } @@ -253,17 +247,15 @@ double aa = double(30) /180*PI, bb = double(60) /180*PI; // for(auto& contact: anymal_->getContacts()) // if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) // {// if there is any contact body was not in the footIndices the over -//// rewards_.record("Live", terminalReward, accu); -//// std::cout<<"foot done " << std::endl; +// rewards_.record("Live", terminalReward, accu); +// std::cout<<"foot done " << std::endl; // return true;} if(gc_[2] - gc_init_[2] > 0.3){ // std::cout<<"z done" << std::endl; // rewards_.record("Live", terminalReward, accu); - return true; } - if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.3) { // std::cout<<"y angle done" <<" " << euler_angle[1]<< std::endl; @@ -278,6 +270,14 @@ double aa = double(30) /180*PI, bb = double(60) /180*PI; // return true; } + if(abs(gc_[0] - skate_posi_[0]) >0.2) + { + return true; + } + if(abs(gc_[1] - (skate_posi_[1] - 0.15)) >0.1) + { + return true; + } terminalReward = 0.f; return false; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 15f06e3bc..3eac3c551 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -6,8 +6,8 @@ from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer import raisimGymTorch.algo.ppo.module as ppo_module import raisimGymTorch.algo.ppo.ppo as PPO -from raisimGymTorch.env.deploy.angle_utils import get_last_position -from raisimGymTorch.env.deploy.onnx_deploy import run_model_with_pt_input_modify, list_pt +from raisimGymTorch.deploy_utils.angle_utils import get_last_position +from raisimGymTorch.deploy_utils.runner_util import run_model_with_pt_input_modify, list_pt import os import math import time diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py index 38d619c40..11bfb70df 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/sim_with_real.py @@ -6,9 +6,9 @@ from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer import raisimGymTorch.algo.ppo.module as ppo_module import raisimGymTorch.algo.ppo.ppo as PPO -from raisimGymTorch.env.deploy.angle_utils import transfer +from raisimGymTorch.env.deploy_util.angle_utils import transfer from unitree_utils.Waiter import Waiter -from raisimGymTorch.env.deploy.angle_utils import get_last_position +from raisimGymTorch.deploy_utils.angle_utils import get_last_position from raisimGymTorch.deploy_log.draw_map import Drawer from raisimGymTorch.deploy_log.csv_saver import CSV_saver import os @@ -22,7 +22,7 @@ # import pandas as pd # from sine_generator import sine_generator from unitree_deploy.angle_utils import sine_generator -from raisimGymTorch.env.deploy.angle_utils import deg_rad, rad_deg +from raisimGymTorch.deploy_utils.angle_utils import deg_rad, rad_deg # task specification task_name = "sim2real" @@ -138,7 +138,7 @@ onnx_flag = True if onnx_flag: cnt_onnx = 0 - from raisimGymTorch.env.deploy import onnx_deploy + from raisimGymTorch.env.deploy_util import onnx_deploy else: load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) @@ -152,7 +152,7 @@ history_obs = None if onnx_flag: cnt_onnx = 0 - from raisimGymTorch.env.deploy import onnx_deploy + from raisimGymTorch.env.deploy_util import onnx_deploy from robot_utils import * a1.torque_limit = 33.15 init_robot(dt) diff --git a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py index d6d1e8fad..16aea52d6 100755 --- a/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py +++ b/raisimGymTorch/raisimGymTorch/helper/raisim_gym_helper.py @@ -65,8 +65,8 @@ def __init__(self, path): self.logger.setLevel(logging.INFO) self.fh = logging.FileHandler(path) self.ch = logging.StreamHandler() - self.fh.setLevel(logging.INFO) - self.ch.setLevel(logging.INFO) + self.fh.setLevel(logging.DEBUG) + self.ch.setLevel(logging.DEBUG) self.formatter = logging.Formatter("%(asctime)s.%(msecs)03d - %(levelname)s - %(message)s", datefmt='%Y-%m-%d,%H:%M:%S') @@ -82,4 +82,8 @@ def warning(self, msg): def debug(self, msg): self.logger.debug(msg) def error(self, msg): - self.logger.error(msg) \ No newline at end of file + self.logger.error(msg) + + def setLevel(self, Level): + self.fh.setLevel(Level) + self.ch.setLevel(Level) \ No newline at end of file From 1587f1891ee5a72163cb5badff451679cc523c34 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Mon, 21 Aug 2023 14:57:32 +0800 Subject: [PATCH 30/62] real-time training without threading --- raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py | 4 +- .../deploy_utils/thread_protect.py | 12 +- ...ildforpython.hpp => Environment_skate.hpp} | 0 .../env/envs/rsg/Environment_wheel.hpp | 316 ++++++++++++++++++ .../raisimGymTorch/env/envs/rsg/cfg.yaml | 16 +- .../raisimGymTorch/env/envs/rsg/on_p_train.py | 189 +++++++++++ .../raisimGymTorch/env/envs/rsg/runner.py | 8 +- .../raisimGymTorch/env/envs/rsg_go1/runner.py | 2 +- .../raisimGymTorch/env/raisim_gym.cpp | 2 +- 9 files changed, 531 insertions(+), 18 deletions(-) rename raisimGymTorch/raisimGymTorch/env/envs/rsg/{Environment_tobuildforpython.hpp => Environment_skate.hpp} (100%) create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp create mode 100755 raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py diff --git a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py index 20c802822..292f3e164 100755 --- a/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py +++ b/raisimGymTorch/raisimGymTorch/algo/ppo/ppo.py @@ -77,8 +77,8 @@ def act(self, actor_obs): self.actor_obs = actor_obs with torch.no_grad(): self.actions, self.actions_log_prob = self.actor.sample(torch.from_numpy(actor_obs).to(self.device)) - # self.actions = np.clip(self.actions - 1, -1, 1) - return self.actions + actions = np.clip(self.actions - 1, -1, 1) + return actions def forward(self, actor_obs): return self.act(actor_obs) diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py b/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py index 1bdee005f..8c5760b51 100644 --- a/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/thread_protect.py @@ -5,23 +5,25 @@ from raisimGymTorch.deploy_log.csv_saver import CSV_saver def cal(): print('calculating model') - time.sleep(0.3) + time.sleep(0.1) def save(saver:CSV_saver, data): - print('add data') + # print('add data') saver.add_list(data) + print(len(saver.csv_list)) + saver.save() if __name__=='__main__': print('start') - csv = CSV_saver('./test.csv') + csv = CSV_saver('./test') for i in range(100): - data = np.random.rand(10) + data = np.zeros((1000,10)) cal() - print(data) + # print(data) with concurrent.futures.ThreadPoolExecutor(max_workers=1) as exec: exec.submit(save, data) print('running robot') \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_skate.hpp similarity index 100% rename from raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_tobuildforpython.hpp rename to raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_skate.hpp diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp new file mode 100644 index 000000000..5f5c749f8 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp @@ -0,0 +1,316 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#include +#define PI 3.1415926 + +namespace raisim { + + auto ToEulerAngles(Eigen::Quaterniond q) { + Eigen::Vector3d angles; + + // roll (x-axis rotation) + double sinr_cosp = 2 * (q.w() * q.x() + q.y() * q.z()); + double cosr_cosp = 1 - 2 * (q.x ()* q.x() + q.y() * q.y()); + angles[0] = std::atan2(sinr_cosp, cosr_cosp); + + // pitch (y-axis rotation) + double sinp = std::sqrt(1 + 2 * (q.w ()* q.y ()- q.x() * q.z())); + double cosp = std::sqrt(1 - 2 * (q.w ()* q.y() - q.x() * q.z())); + angles[1] = 2 * std::atan2(sinp, cosp) - M_PI / 2; + + // yaw (z-axis rotation) + double siny_cosp = 2 * (q.w() * q.z() + q.x() * q.y()); + double cosy_cosp = 1 - 2 * (q.y() * q.y() + q.z() * q.z()); + angles[2] = std::atan2(siny_cosp, cosy_cosp); + + return angles; + } + + class ENVIRONMENT : public RaisimGymEnv { + + public: + + explicit ENVIRONMENT(const std::string& resourceDir, const Yaml::Node& cfg, bool visualizable) : + RaisimGymEnv(resourceDir, cfg), visualizable_(visualizable), normDist_(0, 1) { + /// create world + world_ = std::make_unique(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + READ_YAML(std::string, urdf_path, cfg_["urdf_path"]); + READ_YAML(double, p_gain, cfg_["p_gain"]); + READ_YAML(double, d_gain, cfg_["d_gain"]); + anymal_ = world_->addArticulatedSystem(urdf_path); +// skate = world_ ->addArticulatedSystem("/home/lr-2002/code/raisimLib/rsc/skate/skate.urdf"); + anymal_->setName("model"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(0,"land"); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); // 19 + gvDim_ = anymal_->getDOF(); // 18 + nJoints_ = gvDim_ - 6; +// skate_posi_init.setZero(9); +// skate_vel_init.setZero(8); +// skate_posi_init << 0, 0.15, 0.11, 0.707, 0., 0, 0.707, 0 , 0; +// skate ->setGeneralizedCoordinate(skate_posi_init); + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + euler_angle.setZero();euler_angle_old.setZero(); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + acc_.setZero();//1 + ang_vel_.setZero(); +// skate_vel_.setZero(8); +// skate_posi_.setZero(9); +// init_position(); +double aa = 0.5233 , bb = double(30) /180*PI; + gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, aa, -2*aa, 0.0, bb, -2*bb, 0.0,aa,-2*aa, 0.0, bb, -2*bb; +// gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; + init(); + + obDim_ = 29; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + + actionStd_.setConstant(action_std); + + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + for(auto n : anymal_->getCollisionBodies()) + { + auto name = n.colObj->name; + anymal_->getCollisionBody(name).setMaterial("steel"); + } + +// skate->getCollisionBody("base/0").setMaterial("sandpaper"); +// skate->getCollisionBody("rotater_r/0").setMaterial("rubber"); +// skate->getCollisionBody("rotater_f/0").setMaterial("rubber"); + anymal_->getCollisionBody("FL_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("FR_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("RR_foot/0").setMaterial("rubber"); + anymal_->getCollisionBody("RL_foot/0").setMaterial("rubber"); + world_->setMaterialPairProp("steel", "rubber", 0.8, 0.15, 0.001); + world_->setMaterialPairProp("rubber", "sandpaper", 0.99, 0.15, 0.001); + world_->setMaterialPairProp("land", "rubber", 0.8, 0.1,0.001); + world_->setMaterialPairProp("sandpaper", "land", 0.4, 0.15,0.001); + world_->setMaterialPairProp("steel","land", 0.1, 0.05,0.001); + + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + + + void init() final { + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); + jointPgain.tail(nJoints_).setConstant(p_gain); + jointDgain.setZero(); + jointDgain.tail(nJoints_).setConstant(d_gain); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(urdf_path); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + } + + void init_position(const Eigen::Ref& posi) final + { + gc_init_ = posi.cast(); + init(); + } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); +// skate->setState(skate_posi_init, skate_vel_init); + rewards_.setZero(); + COUNT=0; +// euler_angle_old.setZero(); + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + if (show_ref) + { + Eigen::Vector3d po(3, 3 ,10); + anymal_1->setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + } + COUNT ++; + pTarget12_ = action.cast(); + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + updateObservation(); + double rrr =0; + rrr = abs(euler_angle[0]) + abs(euler_angle[1]) ; + rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1])); +// rrr += abs(gc_[0] - skate_posi_[0]) + abs(gc_[1] - (skate_posi_[1] - 0.15)); + bool accu = false; + rewards_.record("Stable",-rrr, accu); + rewards_.record("Live", 1, accu); +// rewards_.record("forwardVel", skate_vel_[0], accu); +// rewards_.record("height", 0.45- abs(gc_[2] - 0.45) - abs(gc_[0] ) - abs(gc_[1]) , accu); +// rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); +// rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); + rewards_.record("Wheel", 0.5 - abs(ang_vel_[2]- 0.5), accu); + rewards_.record("torque",anymal_->getGeneralizedForce().squaredNorm() ); + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); +// skate -> getState(skate_posi_, skate_vel_); + + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + quat /= quat.norm(); + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); + anymal_->getAngularVelocity(anymal_->getBodyIdx("base"), ang_vel_); + Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); + euler_angle = ToEulerAngles(qua); + Eigen::VectorXd gcc = gc_.tail(12); + Eigen::VectorXd gvv = gv_.tail(12); + Eigen::VectorXd c_v(24); + c_v.setZero(24); + for(auto i = 0; i <12 ; i++ ) + { + c_v[i*2] = gcc[i]; + c_v[i*2 + 1] = gvv[i]; + } + + obDouble_ << + euler_angle[0], + euler_angle[1],// quaternion + ang_vel_[0], + ang_vel_[1], + ang_vel_[2], + c_v; + + } + + void observe(Eigen::Ref ob) final { + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + bool accu = true; +// for(auto& contact: anymal_->getContacts()) +// if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) +// {// if there is any contact body was not in the footIndices the over +// rewards_.record("Live", terminalReward, accu); +// std::cout<<"foot done " << std::endl; +// return true;} +// if(gc_[2] - gc_init_[2] > 0.3){ +// std::cout<<"z done" << std::endl; +// rewards_.record("Live", terminalReward, accu); +// return true; +// } + +// if(fmin(abs(euler_angle[1]), abs(euler_angle[1] + 2 * PI)) > 0.3) +// { +// std::cout<<"y angle done" <<" " << euler_angle[1]<< std::endl; +// rewards_.record("Live", terminalReward, accu); + +// return true; +// } +// if(fmin(abs(euler_angle[0]), abs(euler_angle[0] + 2 * PI)) > 0.3) +// { +// std::cout<<"x angle done " << euler_angle[0] << std::endl; +// rewards_.record("Live", terminalReward, accu); +// +// return true; +// } +// if(abs(gc_[0] - skate_posi_[0]) >0.2) +// { +// return true; +// } +// if(abs(gc_[1] - (skate_posi_[1] - 0.15)) >0.1) +// { +// return true; +// } + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Vec<3> acc_, ang_vel_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + double p_gain,d_gain; + std::string urdf_path; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + Eigen::Vector3d euler_angle, euler_angle_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; +// Eigen::VectorXd skate_vel_, skate_posi_,skate_posi_init, skate_vel_init; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index e0d4d6c53..0740969c9 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -4,9 +4,9 @@ record_video: true environment: render: true # just testing commenting - num_envs: 100 + num_envs: 1 eval_every_n: 40 - num_threads: 30 + num_threads: 1 simulation_dt: 0.0025 control_dt: 0.01 max_time: 4 @@ -23,20 +23,24 @@ environment: urdf_path: /home/lr-2002/code/raisimLib/rsc/a1_description/urdf/a1.urdf reward: forwardVel: - coeff: 0.5 + coeff: 0. torque: coeff: -4e-5 Stable: - coeff: 0.01 + coeff: 0.4 height: coeff: 0. Live: - coeff: 0 + coeff: 1 Wheel: - coeff: 0. + coeff: 0.3 # Mimic: # coeff: 0. architecture: policy_net: [128, 128] value_net: [128, 128] + +on_policy: + rate: 0.6 # for sine A + kb: 0.05 # act_gen * kb diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py new file mode 100755 index 000000000..9b531cbd7 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py @@ -0,0 +1,189 @@ +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +from raisimGymTorch.env.bin.rsg import NormalSampler +from raisimGymTorch.env.bin.rsg import RaisimGymEnv +from raisimGymTorch.env.RewardAnalyzer import RewardAnalyzer +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +from raisimGymTorch.deploy_utils.angle_utils import get_last_position +from raisimGymTorch.deploy_utils.runner_util import run_model_with_pt_input_modify, list_pt +import os +import math +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse + +from unitree_utils.Waiter import Waiter +from raisimGymTorch.deploy_log.draw_map import Drawer +from raisimGymTorch.deploy_log.csv_saver import CSV_saver + +# task specification +task_name = "rsg_test" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=300) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') +print(device) +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) +print(cfg['environment']) + +# create environment from the configuration file +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +# shortcuts +ob_dim = env.num_obs +act_dim = env.num_acts +num_threads = cfg['environment']['num_threads'] + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * env.num_envs + +avg_rewards = [] + +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + env.num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +if mode =='train' or mode == 'retrain': + tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update +num_envs = cfg['environment']['num_envs'] +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=16, + # learning_rate_schedule='', + device=device, + log_dir=saver.data_dir, + shuffle_batch=False, + # learning_rate=cfg['environment']['learnning_rate'] + ) + +reward_analyzer = RewardAnalyzer(env, ppo.writer) +biggest_reward = 0 +biggest_iter = 0 +if mode == 'retrain': + load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) + +# his_util=[0, 0.523, -1.046] * 4 +his_util=[0] * 12 +check_done = lambda a, b: a + 1 if not b else 0 +check_history = lambda a, b: a if not b else his_util + +save_observe = CSV_saver('./observation_saver') +save_act = CSV_saver('./act_saver') + +print = logger.info +on_p_rate =cfg['on_policy']['rate'] +on_p_kb = cfg['on_policy']['kb'] +env_idx = np.zeros(num_envs) +mode == 'train' +history_act = np.array([his_util] * num_envs) +history_act_0 = np.array([his_util] * num_envs) +total_update = args.update +if mode =='train' or mode == 'retrain': + env.turn_on_visualization() + schedule = cfg['environment']['schedule'] + envs_idx = 0 + waiter = Waiter(0.01) + waiter.update_start() + for update in range(total_update): + # print('after update') + reward_sum = 0 + + for step in range(n_steps): + waiter.wait() + obs = env.observe(False) + action = ppo.act(obs) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) + reward, _ = env.step(action) + + envs_idx +=1 + ppo.step(value_obs=obs, rews=reward, dones=_) + + save_observe.add_list(obs[0]) + save_act.add_list(action[0]) + + reward_sum = reward_sum + np.sum(reward) + reward_analyzer.add_reward_info(env.get_reward_info()) + reward_analyzer.analyze_and_plot(update) + # take st step to get value obs + print('before update') + obs = env.observe(False) + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) + average_ll_performance = reward_sum / total_steps + + print('before saving') + + if update % cfg['environment']['eval_every_n'] == 0: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir+"/full_"+str(update)+'.pt') + env.save_scaling(saver.data_dir, str(update)) + save_act.save() + save_observe.save() + print('after save') + + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + print('after update') + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + # print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) + # print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) + # print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) + # print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) + # * cfg['environment']['control_dt']))) + print('----------------------------------------------------\n') + print('after print') + env.turn_off_visualization() +print(f'biggest:{biggest_reward},rate = {biggest_iter}') + + diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py index 3eac3c551..4d66c3a34 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/runner.py @@ -16,7 +16,7 @@ import torch import datetime import argparse -from unitree_deploy.angle_utils import sine_generator + from unitree_utils.Waiter import Waiter from raisimGymTorch.deploy_log.draw_map import Drawer @@ -111,6 +111,8 @@ print = logger.info +on_p_rate =cfg['on_policy']['rate'] +on_p_kb = cfg['on_policy']['kb'] env_idx = np.zeros(num_envs) mode == 'train' history_act = np.array([his_util] * num_envs) @@ -150,7 +152,7 @@ obs = env.observe(False) action = ppo.act(obs) - action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) reward, dones = env.step(action) @@ -171,7 +173,7 @@ for step in range(n_steps): obs = env.observe(False) action = ppo.act(obs) - action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) reward, dones = env.step(action) history_act = np.array([check_history(history_act[i], dones[i]) for i in range(num_envs)]) envs_idx = np.where(dones == 1, 0, envs_idx + 1) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py index 880a89c12..bb92a989a 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg_go1/runner.py @@ -200,7 +200,7 @@ debug = True if onnx_flag: cnt_onnx = 0 - from raisimGymTorch.env.deploy import onnx_deploy + from raisimGymTorch.env.deploy_util import onnx_deploy T = 50 np.set_printoptions(threshold=np.inf) draw_line =[] diff --git a/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp b/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp index 431445229..2ce437582 100755 --- a/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp +++ b/raisimGymTorch/raisimGymTorch/env/raisim_gym.cpp @@ -6,7 +6,7 @@ #include #include #include -#include "Environment_tobuildforpython.hpp" +#include "Environment_wheel.hpp" #include "VectorizedEnvironment.hpp" namespace py = pybind11; From ef6931ad7e23c4b0369e72e224fb9d70e243c931 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Mon, 21 Aug 2023 15:21:36 +0800 Subject: [PATCH 31/62] this version is able to wheel with real time in raisim --- raisimGymTorch/raisimGymTorch/.gitignore | 2 + .../deploy => deploy_utils}/data/full_152.pt | Bin .../deploy => deploy_utils}/data/mean152.csv | 0 .../raisimGymTorch/env/envs/rsg/on_p_train.py | 98 +++++++++--------- 4 files changed, 51 insertions(+), 49 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/.gitignore rename raisimGymTorch/raisimGymTorch/{env/deploy => deploy_utils}/data/full_152.pt (100%) rename raisimGymTorch/raisimGymTorch/{env/deploy => deploy_utils}/data/mean152.csv (100%) diff --git a/raisimGymTorch/raisimGymTorch/.gitignore b/raisimGymTorch/raisimGymTorch/.gitignore new file mode 100644 index 000000000..6321e422d --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/.gitignore @@ -0,0 +1,2 @@ +*.onnx +*.pt diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/data/full_152.pt b/raisimGymTorch/raisimGymTorch/deploy_utils/data/full_152.pt similarity index 100% rename from raisimGymTorch/raisimGymTorch/env/deploy/data/full_152.pt rename to raisimGymTorch/raisimGymTorch/deploy_utils/data/full_152.pt diff --git a/raisimGymTorch/raisimGymTorch/env/deploy/data/mean152.csv b/raisimGymTorch/raisimGymTorch/deploy_utils/data/mean152.csv similarity index 100% rename from raisimGymTorch/raisimGymTorch/env/deploy/data/mean152.csv rename to raisimGymTorch/raisimGymTorch/deploy_utils/data/mean152.csv diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py index 9b531cbd7..c24201e36 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py @@ -1,3 +1,6 @@ +import concurrent.futures +import threading + from ruamel.yaml import YAML, dump, RoundTripDumper from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger @@ -79,6 +82,41 @@ save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) logger = RaisimLogger(saver.data_dir+"/train.log") + + +def updating(): + obs = env.observe(False) + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) + average_ll_performance = reward_sum / total_steps + + + if update % cfg['environment']['eval_every_n'] == 0: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir + "/full_" + str(update) + '.pt') + env.save_scaling(saver.data_dir, str(update)) + save_act.save() + save_observe.save() + + + avg_rewards.append(average_ll_performance) + + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('----------------------------------------------------\n') + + + if mode =='train' or mode == 'retrain': tensorboard_launcher(saver.data_dir+"/..") # press refresh (F5) after the first ppo update num_envs = cfg['environment']['num_envs'] @@ -90,11 +128,9 @@ gamma=0.996, lam=0.95, num_mini_batches=16, - # learning_rate_schedule='', device=device, log_dir=saver.data_dir, shuffle_batch=False, - # learning_rate=cfg['environment']['learnning_rate'] ) reward_analyzer = RewardAnalyzer(env, ppo.writer) @@ -103,21 +139,16 @@ if mode == 'retrain': load_param(weight_path, env, actor, critic, ppo.optimizer, saver.data_dir) -# his_util=[0, 0.523, -1.046] * 4 -his_util=[0] * 12 -check_done = lambda a, b: a + 1 if not b else 0 -check_history = lambda a, b: a if not b else his_util - save_observe = CSV_saver('./observation_saver') save_act = CSV_saver('./act_saver') - print = logger.info + + on_p_rate =cfg['on_policy']['rate'] on_p_kb = cfg['on_policy']['kb'] -env_idx = np.zeros(num_envs) + mode == 'train' -history_act = np.array([his_util] * num_envs) -history_act_0 = np.array([his_util] * num_envs) + total_update = args.update if mode =='train' or mode == 'retrain': env.turn_on_visualization() @@ -126,7 +157,6 @@ waiter = Waiter(0.01) waiter.update_start() for update in range(total_update): - # print('after update') reward_sum = 0 for step in range(n_steps): @@ -146,43 +176,13 @@ reward_analyzer.add_reward_info(env.get_reward_info()) reward_analyzer.analyze_and_plot(update) # take st step to get value obs - print('before update') - obs = env.observe(False) - ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) - average_ll_performance = reward_sum / total_steps - - print('before saving') - - if update % cfg['environment']['eval_every_n'] == 0: - biggest_iter = update - biggest_reward = average_ll_performance - torch.save({ - 'actor_architecture_state_dict': actor.architecture.state_dict(), - 'actor_distribution_state_dict': actor.distribution.state_dict(), - 'critic_architecture_state_dict': critic.architecture.state_dict(), - 'optimizer_state_dict': ppo.optimizer.state_dict(), - }, saver.data_dir+"/full_"+str(update)+'.pt') - env.save_scaling(saver.data_dir, str(update)) - save_act.save() - save_observe.save() - print('after save') - - avg_rewards.append(average_ll_performance) - - actor.update() - actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) - print('after update') - - print('----------------------------------------------------') - print('{:>6}th iteration'.format(update)) - print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) - # print('{:<40} {:>6}'.format("dones: ", '{:0.6f}'.format(average_dones))) - # print('{:<40} {:>6}'.format("time elapsed in this iteration: ", '{:6.4f}'.format(end - start))) - # print('{:<40} {:>6}'.format("fps: ", '{:6.0f}'.format(total_steps / (end - start)))) - # print('{:<40} {:>6}'.format("real time factor: ", '{:6.0f}'.format(total_steps / (end - start) - # * cfg['environment']['control_dt']))) - print('----------------------------------------------------\n') - print('after print') + update_thread = threading.Thread(target=updating) + update_thread.start() + while update_thread.is_alive(): + waiter.wait() + # print('threading running') + env.step(action) + print('updating finished') env.turn_off_visualization() print(f'biggest:{biggest_reward},rate = {biggest_iter}') From 976ff33458e99a3a5f5bd7be043a3d58383bdd3d Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Mon, 21 Aug 2023 15:22:59 +0800 Subject: [PATCH 32/62] this version is able to wheel with real time in raisim --- .../deploy_utils/runner_util.py | 134 ++++++++++++++++++ 1 file changed, 134 insertions(+) create mode 100644 raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py new file mode 100644 index 000000000..0d420bbca --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py @@ -0,0 +1,134 @@ +import numpy as np +from math import cos,pi +def lerp_np(a, b, c): + return a* (1-c) + b*c +def add_list_np(act_gen, sine, history,kb): + kk = 0.9 + kf = 1 + kb = kb + history = history*kk + (1-kk) * act_gen + ans = np.clip(kb*history + kf * sine, -1, 1) + ans = (ans + 1) /2 # 100 * 12 + ans = lerp_np(low_np, upp_np, ans) + + return ans, history +def ang_trans(lower, upper, x): + """ + trans the rate x to the angle + """ + if isinstance(lower, list): + return [ang_trans(lower[i], upper[i], x[i]) for i in range(len(lower))] + else: + x = (x+1)/2 #todo for test + return x * upper + (1-x) * lower +def norm(lower, upper, x): + # print(lower, upper, x) + # assert abs((x - lower) / (upper - lower) ) <= 1, f"{abs((x - lower) / (upper - lower) )} {x, upper, lower} " + return (x - lower) / (upper - lower) +def deg_rad(x): + if isinstance(x, list): + return [deg_rad(a) for a in x] + else: + return x / 180 * pi + +def rad_deg(x): + if isinstance(x, list): + return [rad_deg(a) for a in x] + else: + return x / pi * 180 +def deg_normalize(lower, upper, x): + """ + make angle to rate from -1 -- 1 + """ + if isinstance(lower, list): + ans = [] + for a,b,c in zip(lower, upper, x): + ans.append(deg_normalize(a,b,c)) + return ans + else: + return 2 * norm(lower, upper, x) - 1 #todo for test + # return 1 - 2* norm(lower, upper,x) +low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] +upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] +tha1,tha2 = 30, 30 +u0 = [0, tha2, -2*tha2, 0 ,tha1, -tha1 * 2, 0 , tha2, -2*tha2, 0, tha1,-2*tha1] + +low_np = np.array(low) +upp_np = np.array(upp) +u0 = deg_normalize(low, upp, u0) +u0_ang = ang_trans(low, upp, u0) + +def sine_gene_pt(idx, T, rate): + # print(idx) + if isinstance(idx, np.ndarray) or isinstance(idx, list): + mat = np.zeros((len(idx), 12)) + i_set = set(idx) + idd = {} + for i in i_set: + idd[i] = sine_gene_pt(i, T, rate) + for i in range(len(idx)): + mat[i] = idd[idx[i]] + return mat + if not isinstance(idx, list): + angle_list = [0 for i in range(12)] + if idx >= 2 * T: + idx = 0 + dh = rate #:w + + + if idx >= 0 and idx <= T: + tp0 =idx - 0 + y1 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y2 = 0 + # y2 = y1 + elif idx>T and idx<=2*T: + tp0 =idx - T + y2 = dh * 10 * (-cos(pi * 2 * tp0 / T) + 1 ) / 2 + y1 = 0 + # y1 = y2 + # idx = idx % T + # y1 = dh * 10 * (-cos(pi * 2 *idx /T) + 1) + # y2 = deg_rad(60) + angle_list[0] = 0 + angle_list[1] = y1 + angle_list[2] = -2 * y1 + angle_list[3] = 0 + angle_list[4] = y2 + angle_list[5] = -2 * y2 + angle_list[6] = 0 + angle_list[7] = y2 + angle_list[8] = -2 * y2 + angle_list[9] = 0 + angle_list[10] = y1 + angle_list[11] = -2 * y1 + + angle_list = [deg_normalize(low[i], upp[i], angle_list[i] + u0_ang[i]) for i in range(12)] + + return angle_list + else: + ans = [] + for i in idx: + ans.append(sine_gene_pt(i, T, rate)) + return ans +def list_pt(act_gen, idx, T): + ans = [] + for i in range(act_gen.shape[0]): + ans.append(run_model_with_pt_input(act_gen[i, :], idx[i], T)) + ans = np.vstack(ans).astype(np.float32) + return ans +def run_model_with_pt_input_modify(act_gen, idx, T, history, kb, rate): + # act_gen = np.clip(act_gen- 1, -1, 1) + if isinstance(idx, list): + idx = np.array(idx) + idx = idx%(2*T) + else: + idx = idx % (2 * T) + # act_gen = np.zeros_like(act_gen) + sine = sine_gene_pt(idx, T, rate) + ans, history = add_list_np(act_gen, sine, history, kb) + ans = ans / 180 * 3.14 + + return ans.astype(np.float32), history.astype(np.float32) + +if __name__=='__main__': + print(run_model_with_pt_input_modify(np.zeros((1,12)), 1, 50, np.zeros((1,12)))) \ No newline at end of file From 20a73bd2f8dd0977682c88d631a577cd138d1876 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Mon, 21 Aug 2023 15:23:25 +0800 Subject: [PATCH 33/62] this version is able to wheel with real time in raisim --- raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py index 0d420bbca..324ba3f1d 100644 --- a/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py @@ -19,7 +19,7 @@ def ang_trans(lower, upper, x): if isinstance(lower, list): return [ang_trans(lower[i], upper[i], x[i]) for i in range(len(lower))] else: - x = (x+1)/2 #todo for test + x = (x+1)/2 return x * upper + (1-x) * lower def norm(lower, upper, x): # print(lower, upper, x) @@ -46,7 +46,7 @@ def deg_normalize(lower, upper, x): ans.append(deg_normalize(a,b,c)) return ans else: - return 2 * norm(lower, upper, x) - 1 #todo for test + return 2 * norm(lower, upper, x) - 1 # return 1 - 2* norm(lower, upper,x) low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] From 96ede5e41877f11deb2a9791c21453147e0b051a Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Mon, 21 Aug 2023 22:22:03 +0800 Subject: [PATCH 34/62] able to turn not able to walk --- .../deploy_utils/runner_util.py | 13 +++---- .../env/VectorizedEnvironment.hpp | 2 +- .../env/envs/rsg/Environment_wheel.hpp | 22 +++++++----- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 12 +++---- .../raisimGymTorch/env/envs/rsg/fake_a1.py | 34 +++++++++++++++++++ .../raisimGymTorch/env/envs/rsg/on_p_train.py | 13 +++---- 6 files changed, 67 insertions(+), 29 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/env/envs/rsg/fake_a1.py diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py index 324ba3f1d..519cf15e0 100644 --- a/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py @@ -3,9 +3,9 @@ def lerp_np(a, b, c): return a* (1-c) + b*c def add_list_np(act_gen, sine, history,kb): - kk = 0.9 + kk = 0.95 kf = 1 - kb = kb + kb = np.array([0.2, 0.1, 0.1] * 4) history = history*kk + (1-kk) * act_gen ans = np.clip(kb*history + kf * sine, -1, 1) ans = (ans + 1) /2 # 100 * 12 @@ -50,14 +50,15 @@ def deg_normalize(lower, upper, x): # return 1 - 2* norm(lower, upper,x) low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] -tha1,tha2 = 30, 30 -u0 = [0, tha2, -2*tha2, 0 ,tha1, -tha1 * 2, 0 , tha2, -2*tha2, 0, tha1,-2*tha1] +tha1,tha2 = 35,35 +u0 = [0, tha2, -2*tha2 + 10, 0 ,tha1, -tha1 * 2 +10 , 0 , tha2, -2*tha2 + 10, 0, tha1,-2*tha1 + 10] low_np = np.array(low) upp_np = np.array(upp) +u0_rad = deg_rad(u0) + u0 = deg_normalize(low, upp, u0) u0_ang = ang_trans(low, upp, u0) - def sine_gene_pt(idx, T, rate): # print(idx) if isinstance(idx, np.ndarray) or isinstance(idx, list): @@ -131,4 +132,4 @@ def run_model_with_pt_input_modify(act_gen, idx, T, history, kb, rate): return ans.astype(np.float32), history.astype(np.float32) if __name__=='__main__': - print(run_model_with_pt_input_modify(np.zeros((1,12)), 1, 50, np.zeros((1,12)))) \ No newline at end of file + print(run_model_with_pt_input_modify(np.zeros((1,12)), 1, 50, np.zeros((1,12)), 0.15, 0.6)) \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp b/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp index 627f468c6..8e4583230 100755 --- a/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp +++ b/raisimGymTorch/raisimGymTorch/env/VectorizedEnvironment.hpp @@ -237,7 +237,7 @@ class NormalSampler { } void seed(int seed) { - // this ensures that every thread gets a different seed + // this ensures that every thread gets a different see #pragma omp parallel for schedule(static, 1) for (int i = 0; i < THREAD_COUNT; i++) normal_[0].seed(i + seed); diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp index 5f5c749f8..2ffe1f3bc 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp @@ -78,12 +78,12 @@ namespace raisim { // skate_vel_.setZero(8); // skate_posi_.setZero(9); // init_position(); -double aa = 0.5233 , bb = double(30) /180*PI; - gc_init_<< 0, 0, 0.33, 1.0, 0.0, 0.0, 0.0, 0.0, aa, -2*aa, 0.0, bb, -2*bb, 0.0,aa,-2*aa, 0.0, bb, -2*bb; +double aa = double(35)/ 180 * PI , bb = double(35) /180*PI; + gc_init_<< 0, 0, cos(aa) * 2 * 0.2, 1.0, 0.0, 0.0, 0.0, 0.0, aa, -2*aa, 0.0, bb, -2*bb, 0.0,aa,-2*aa, 0.0, bb, -2*bb; // gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; init(); - obDim_ = 29; + obDim_ = 31; actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); obDouble_.setZero(obDim_); @@ -188,13 +188,13 @@ double aa = 0.5233 , bb = double(30) /180*PI; } updateObservation(); double rrr =0; - rrr = abs(euler_angle[0]) + abs(euler_angle[1]) ; - rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1])); + rrr = abs(euler_angle[0]) + abs(euler_angle[1]) + abs(euler_angle[2]) ; + rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1]) + abs(ang_vel_[2])); // rrr += abs(gc_[0] - skate_posi_[0]) + abs(gc_[1] - (skate_posi_[1] - 0.15)); bool accu = false; rewards_.record("Stable",-rrr, accu); rewards_.record("Live", 1, accu); -// rewards_.record("forwardVel", skate_vel_[0], accu); + rewards_.record("forwardVel", -abs(3- line_vel_[0]), accu); // rewards_.record("height", 0.45- abs(gc_[2] - 0.45) - abs(gc_[0] ) - abs(gc_[1]) , accu); // rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); // rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); @@ -204,6 +204,9 @@ double aa = 0.5233 , bb = double(30) /180*PI; } void updateObservation() { +// raisim::Vec<3> acc_w; + +// std::cout<< "acc? " <getFrameAcceleration("base",acc_w); anymal_->getState(gc_, gv_); // skate -> getState(skate_posi_, skate_vel_); @@ -212,9 +215,10 @@ double aa = 0.5233 , bb = double(30) /180*PI; quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; quat /= quat.norm(); raisim::quatToRotMat(quat, rot); - bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); +// bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); anymal_->getAngularVelocity(anymal_->getBodyIdx("base"), ang_vel_); + anymal_->getFrameVelocity(anymal_->getBodyIdx("base"), line_vel_); Eigen::Quaterniond qua(gc_[3], gc_[4], gc_[5], gc_[6]); euler_angle = ToEulerAngles(qua); Eigen::VectorXd gcc = gc_.tail(12); @@ -233,6 +237,8 @@ double aa = 0.5233 , bb = double(30) /180*PI; ang_vel_[0], ang_vel_[1], ang_vel_[2], + line_vel_[0], + line_vel_[1], c_v; } @@ -292,7 +298,7 @@ double aa = 0.5233 , bb = double(30) /180*PI; Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; double terminalRewardCoeff_ = -10.; Eigen::VectorXd actionMean_, actionStd_, obDouble_; - Vec<3> acc_, ang_vel_; + Vec<3> acc_, ang_vel_, line_vel_; Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; std::set footIndices_; double p_gain,d_gain; diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 0740969c9..72996ee48 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -4,9 +4,9 @@ record_video: true environment: render: true # just testing commenting - num_envs: 1 + num_envs: 100 eval_every_n: 40 - num_threads: 1 + num_threads: 30 simulation_dt: 0.0025 control_dt: 0.01 max_time: 4 @@ -23,7 +23,7 @@ environment: urdf_path: /home/lr-2002/code/raisimLib/rsc/a1_description/urdf/a1.urdf reward: forwardVel: - coeff: 0. + coeff: 0.3 torque: coeff: -4e-5 Stable: @@ -33,7 +33,7 @@ environment: Live: coeff: 1 Wheel: - coeff: 0.3 + coeff: 0 # Mimic: # coeff: 0. @@ -42,5 +42,5 @@ architecture: value_net: [128, 128] on_policy: - rate: 0.6 # for sine A - kb: 0.05 # act_gen * kb + rate: 0.8 # for sine A + kb: 0.15 # act_gen * kb diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/fake_a1.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/fake_a1.py new file mode 100644 index 000000000..cc35b8a8f --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/fake_a1.py @@ -0,0 +1,34 @@ +import numpy as np +class Robot: + def __init__(self): + self.ob_dims = 29 + self.act_dims = 12 + self.position = [0, 0.5233, -1.0466] * 4 + + + + def observe(self): + return np.array( + [[0. , 0. , 0. , 0. , 0. , 0., + 0. , 0.5233 , 0., - 1.0466 , 0. , 0., + 0. , 0.5235988, 0., - 1.0471976 , 0. , 0., + 0. , 0.5233 , 0., - 1.0466 , 0. , 0., + 0. , 0.5235988, 0., - 1.0471976 , 0.]] + ).astype(np.float32) + + def ob_dim(self): + return self.ob_dims + + def act_dim(self): + return self.act_dims + + def take_action(self,action): + pass + + def init_motor(self,act): + pass + +def init_position(a,b): + pass + +a1 = Robot() \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py index c24201e36..09e6dfb69 100755 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/on_p_train.py @@ -67,7 +67,7 @@ total_steps = n_steps * env.num_envs avg_rewards = [] - +print(env.num_envs) actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, env.num_envs, @@ -82,8 +82,6 @@ save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) logger = RaisimLogger(saver.data_dir+"/train.log") - - def updating(): obs = env.observe(False) ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) @@ -102,14 +100,11 @@ def updating(): env.save_scaling(saver.data_dir, str(update)) save_act.save() save_observe.save() - - avg_rewards.append(average_ll_performance) actor.update() actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) - print('----------------------------------------------------') print('{:>6}th iteration'.format(update)) print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) @@ -146,9 +141,9 @@ def updating(): on_p_rate =cfg['on_policy']['rate'] on_p_kb = cfg['on_policy']['kb'] - mode == 'train' - +his_util = [0] * 12 +history_act = np.array([his_util] * num_envs) total_update = args.update if mode =='train' or mode == 'retrain': env.turn_on_visualization() @@ -162,7 +157,9 @@ def updating(): for step in range(n_steps): waiter.wait() obs = env.observe(False) + # print(obs) action = ppo.act(obs) + # action = np.zeros_like(action) action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) reward, _ = env.step(action) From 336d561df78f3a13f2db7c2785391b5448edf8a8 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 22 Aug 2023 18:16:06 +0800 Subject: [PATCH 35/62] inverse turning with this version --- .../deploy_utils/runner_util.py | 8 +- .../env/envs/rsg/Environment_wheel.hpp | 47 +-- .../raisimGymTorch/env/envs/rsg/cfg.yaml | 14 +- .../env/envs/rsg/real_on_policy_train.py | 268 ++++++++++++++++++ 4 files changed, 304 insertions(+), 33 deletions(-) create mode 100755 raisimGymTorch/raisimGymTorch/env/envs/rsg/real_on_policy_train.py diff --git a/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py index 519cf15e0..80737271f 100644 --- a/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py +++ b/raisimGymTorch/raisimGymTorch/deploy_utils/runner_util.py @@ -5,7 +5,8 @@ def lerp_np(a, b, c): def add_list_np(act_gen, sine, history,kb): kk = 0.95 kf = 1 - kb = np.array([0.2, 0.1, 0.1] * 4) + # kb = np.array([0.2 ,0.1, 0.1] * 4) + kb = np.array([0.3, 0., 0.] * 4) history = history*kk + (1-kk) * act_gen ans = np.clip(kb*history + kf * sine, -1, 1) ans = (ans + 1) /2 # 100 * 12 @@ -50,8 +51,9 @@ def deg_normalize(lower, upper, x): # return 1 - 2* norm(lower, upper,x) low = [-46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5, -46, -60, -154.5] upp = [46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5, 46, 240, -52.5] -tha1,tha2 = 35,35 -u0 = [0, tha2, -2*tha2 + 10, 0 ,tha1, -tha1 * 2 +10 , 0 , tha2, -2*tha2 + 10, 0, tha1,-2*tha1 + 10] +tha1,tha2 = 40, 40 +for_r = -2.5 +u0 = [0, tha2, -2*tha2 , 0 ,tha1, -tha1 * 2 , 0 , tha2 + for_r , -2*tha2 - 2 * for_r , 0, tha1 + for_r ,-2*tha1 -2 * for_r] low_np = np.array(low) upp_np = np.array(upp) diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp index 2ffe1f3bc..c7a1eee69 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/Environment_wheel.hpp @@ -57,8 +57,8 @@ namespace raisim { // skate = world_ ->addArticulatedSystem("/home/lr-2002/code/raisimLib/rsc/skate/skate.urdf"); anymal_->setName("model"); anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); - world_->addGround(0,"land"); - +// world_->addGround(0,"land"); +world_->addGround(); /// get robot data gcDim_ = anymal_->getGeneralizedCoordinateDim(); // 19 gvDim_ = anymal_->getDOF(); // 18 @@ -78,8 +78,9 @@ namespace raisim { // skate_vel_.setZero(8); // skate_posi_.setZero(9); // init_position(); -double aa = double(35)/ 180 * PI , bb = double(35) /180*PI; - gc_init_<< 0, 0, cos(aa) * 2 * 0.2, 1.0, 0.0, 0.0, 0.0, 0.0, aa, -2*aa, 0.0, bb, -2*bb, 0.0,aa,-2*aa, 0.0, bb, -2*bb; +double aa = double(40)/ 180 * PI , bb = double(40) /180*PI; + double for_r = double(-2.5) / 180 * PI ; + gc_init_<< 0, 0, cos(aa) * 2 * 0.2, 1.0, 0.0, 0.0, 0.0, 0.0, aa, -2*aa, 0.0, bb, -2*bb, 0.0,aa +for_r ,-2*aa -2 * for_r , 0.0, bb + for_r, -2*bb -2 * for_r; // gc_init_<< 0, 0, 0.37, 1.0, 0.0, 0.0, 0.0, 0.0, 0.5233, -1.046, 0.0, 0.5233, -1.046, 0.0, 0.523, -1.046, 0.0, 0.523, -1.046; init(); @@ -99,24 +100,24 @@ double aa = double(35)/ 180 * PI , bb = double(35) /180*PI; footIndices_.insert(anymal_->getBodyIdx("RL_calf")); footIndices_.insert(anymal_->getBodyIdx("RR_calf")); - for(auto n : anymal_->getCollisionBodies()) - { - auto name = n.colObj->name; - anymal_->getCollisionBody(name).setMaterial("steel"); - } +// for(auto n : anymal_->getCollisionBodies()) +// { +// auto name = n.colObj->name; +// anymal_->getCollisionBody(name).setMaterial("steel"); +// } // skate->getCollisionBody("base/0").setMaterial("sandpaper"); // skate->getCollisionBody("rotater_r/0").setMaterial("rubber"); // skate->getCollisionBody("rotater_f/0").setMaterial("rubber"); - anymal_->getCollisionBody("FL_foot/0").setMaterial("rubber"); - anymal_->getCollisionBody("FR_foot/0").setMaterial("rubber"); - anymal_->getCollisionBody("RR_foot/0").setMaterial("rubber"); - anymal_->getCollisionBody("RL_foot/0").setMaterial("rubber"); - world_->setMaterialPairProp("steel", "rubber", 0.8, 0.15, 0.001); - world_->setMaterialPairProp("rubber", "sandpaper", 0.99, 0.15, 0.001); - world_->setMaterialPairProp("land", "rubber", 0.8, 0.1,0.001); - world_->setMaterialPairProp("sandpaper", "land", 0.4, 0.15,0.001); - world_->setMaterialPairProp("steel","land", 0.1, 0.05,0.001); +// anymal_->getCollisionBody("FL_foot/0").setMaterial("rubber"); +// anymal_->getCollisionBody("FR_foot/0").setMaterial("rubber"); +// anymal_->getCollisionBody("RR_foot/0").setMaterial("rubber"); +// anymal_->getCollisionBody("RL_foot/0").setMaterial("rubber"); +// world_->setMaterialPairProp("steel", "rubber", 0.8, 0.15, 0.001); +// world_->setMaterialPairProp("rubber", "sandpaper", 0.99, 0.15, 0.001); +// world_->setMaterialPairProp("land", "rubber", 0.8, 0.1,0.001); +// world_->setMaterialPairProp("sandpaper", "land", 0.4, 0.15,0.001); +// world_->setMaterialPairProp("steel","land", 0.1, 0.05,0.001); if (visualizable_) { server_ = std::make_unique(world_.get()); @@ -188,15 +189,15 @@ double aa = double(35)/ 180 * PI , bb = double(35) /180*PI; } updateObservation(); double rrr =0; - rrr = abs(euler_angle[0]) + abs(euler_angle[1]) + abs(euler_angle[2]) ; - rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1]) + abs(ang_vel_[2])); + rrr = abs(euler_angle[0]) + abs(euler_angle[1]) ; + rrr += 0.1 * ( abs(ang_vel_[0]) + abs(ang_vel_[1])); // rrr += abs(gc_[0] - skate_posi_[0]) + abs(gc_[1] - (skate_posi_[1] - 0.15)); bool accu = false; rewards_.record("Stable",-rrr, accu); rewards_.record("Live", 1, accu); rewards_.record("forwardVel", -abs(3- line_vel_[0]), accu); // rewards_.record("height", 0.45- abs(gc_[2] - 0.45) - abs(gc_[0] ) - abs(gc_[1]) , accu); -// rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); + rewards_.record("Mimic", (gc_.tail(12) - pTarget12_).norm(), accu); // rewards_.record("Wheel", euler_angle[2] * double(COUNT) / 400, accu); rewards_.record("Wheel", 0.5 - abs(ang_vel_[2]- 0.5), accu); rewards_.record("torque",anymal_->getGeneralizedForce().squaredNorm() ); @@ -237,8 +238,8 @@ double aa = double(35)/ 180 * PI , bb = double(35) /180*PI; ang_vel_[0], ang_vel_[1], ang_vel_[2], - line_vel_[0], - line_vel_[1], +// line_vel_[0], +// line_vel_[1], c_v; } diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml index 72996ee48..d2cfab356 100644 --- a/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/cfg.yaml @@ -4,9 +4,9 @@ record_video: true environment: render: true # just testing commenting - num_envs: 100 + num_envs: 1 eval_every_n: 40 - num_threads: 30 + num_threads: 1 simulation_dt: 0.0025 control_dt: 0.01 max_time: 4 @@ -23,19 +23,19 @@ environment: urdf_path: /home/lr-2002/code/raisimLib/rsc/a1_description/urdf/a1.urdf reward: forwardVel: - coeff: 0.3 + coeff: 0. torque: coeff: -4e-5 Stable: - coeff: 0.4 + coeff: 0. height: coeff: 0. Live: coeff: 1 Wheel: - coeff: 0 -# Mimic: -# coeff: 0. + coeff: 2 + Mimic: + coeff: 0. architecture: policy_net: [128, 128] diff --git a/raisimGymTorch/raisimGymTorch/env/envs/rsg/real_on_policy_train.py b/raisimGymTorch/raisimGymTorch/env/envs/rsg/real_on_policy_train.py new file mode 100755 index 000000000..9b15f748d --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/env/envs/rsg/real_on_policy_train.py @@ -0,0 +1,268 @@ +import concurrent.futures +import threading + +import asn1crypto.cms +import asn1crypto.core +from raisimGymTorch.env.bin.rsg import NormalSampler +from ruamel.yaml import YAML, dump, RoundTripDumper +from raisimGymTorch.helper.raisim_gym_helper import ConfigurationSaver, load_param, tensorboard_launcher, RaisimLogger +import raisimGymTorch.algo.ppo.module as ppo_module +import raisimGymTorch.algo.ppo.ppo as PPO +from raisimGymTorch.env.RaisimGymVecEnv import RaisimGymVecEnv as VecEnv +from raisimGymTorch.env.bin.rsg import RaisimGymEnv +from raisimGymTorch.deploy_utils.angle_utils import get_last_position +from raisimGymTorch.deploy_utils.runner_util import run_model_with_pt_input_modify, list_pt, u0_rad +import os +import math +import time +import torch.nn as nn +import numpy as np +import torch +import datetime +import argparse +import signal +from raisimGymTorch.deploy_log.draw_map import Drawer +from raisimGymTorch.deploy_log.csv_saver import CSV_saver +# task specification +# from fake_a1 import * +from robot_utils import * + +task_name = "real_time_train_test" + +# configuration +parser = argparse.ArgumentParser() +parser.add_argument('-m', '--mode', help='set mode either train or test', type=str, default='train') +parser.add_argument('-w', '--weight', help='pre-trained weight path', type=str, default='') +parser.add_argument('-u', '--update', help='update times', type=int, default=300) +parser.add_argument('-p', '--cfg_path', help='where to find the path', type=str, default=None) +# parser.add_argument('-b', '--load_best', help='load best file in last train', type=bool, default=False) +args = parser.parse_args() +mode = args.mode +weight_path = args.weight +cfg_path = args.cfg_path +# load_best = args.load_best +# check if gpu is available +device = torch.device('cuda' if torch.cuda.is_available() else 'cpu') +print(device) +# directories +task_path = os.path.dirname(os.path.realpath(__file__)) +home_path = task_path + "/../../../../.." + +# config +if cfg_path is not None: + cfg = YAML().load(open(cfg_path, 'r')) +else: + cfg = YAML().load(open(task_path + "/cfg.yaml", 'r')) + +# shortcuts + + +env = VecEnv(RaisimGymEnv(home_path + "/rsc", dump(cfg['environment'], Dumper=RoundTripDumper))) +env.seed(cfg['seed']) + +ob_dim = a1.ob_dim() +act_dim = a1.act_dim() + +# Training +n_steps = math.floor(cfg['environment']['max_time'] / cfg['environment']['control_dt']) +total_steps = n_steps * 1 + +avg_rewards = [] +num_envs=1 +actor = ppo_module.Actor(ppo_module.MLP(cfg['architecture']['policy_net'], nn.LeakyReLU, ob_dim, act_dim), + ppo_module.MultivariateGaussianDiagonalCovariance(act_dim, + num_envs, + 1.0, + NormalSampler(act_dim), + cfg['seed']), + device) +critic = ppo_module.Critic(ppo_module.MLP(cfg['architecture']['value_net'], nn.LeakyReLU, ob_dim, 1), + device) + +saver = ConfigurationSaver(log_dir=home_path + "/raisimGymTorch/data/"+task_name, + save_items=[task_path + "/cfg.yaml", task_path + "/Environment.hpp"]) +logger = RaisimLogger(saver.data_dir+"/train.log") + +def real_handler(signal, frame): + print('You pressed Ctrl+C!') + a1.quit_robot() + # debug_draw_gry.draw() + draw_reward.draw() + save_reward.save() + sys.exit(0) + +signal.signal(signal.SIGINT, real_handler) + +init_e_x = 0 +init_e_y = 0 +# init_v_x = 0 +# init_v_y = 0 +def cal_reward(robot): + """ + + :param robot: a1 + :return: reward number + """ + global init_e_x + global init_e_y + # global init_v_x + # global init_v_y + obs = robot.observe()[0] + reward = 0 + # reward -= (abs(obs[0] - init_e_x )+ abs(obs[1] - init_e_y)) + # reward -= (abs(obs[2]) + abs(obs[3])) * 0.1 + # reward = reward * 0.4#stable + # reward += 1 + # reward = reward + (0.5 - abs(obs[4] + 0.5)) * 2 # wheel + reward = reward + obs[4]# wheel + + return np.array([reward]) + +def updating(): + obs = a1.observe() + ppo.update(actor_obs=obs, value_obs=obs, log_this_iteration=update % 2 == 0, update=update) + average_ll_performance = reward_sum / total_steps + + + if update % cfg['environment']['eval_every_n'] == 0: + biggest_iter = update + biggest_reward = average_ll_performance + torch.save({ + 'actor_architecture_state_dict': actor.architecture.state_dict(), + 'actor_distribution_state_dict': actor.distribution.state_dict(), + 'critic_architecture_state_dict': critic.architecture.state_dict(), + 'optimizer_state_dict': ppo.optimizer.state_dict(), + }, saver.data_dir + "/full_" + str(update) + '.pt') + save_act.save() + save_observe.save() + + # draw_reward.draw() + + avg_rewards.append(average_ll_performance) + draw_reward.add_map_list([average_ll_performance]) + save_reward.add_list([average_ll_performance]) + actor.update() + actor.distribution.enforce_minimum_std((torch.ones(12)).to(device)) + + print('----------------------------------------------------') + print('{:>6}th iteration'.format(update)) + print('{:<40} {:>6}'.format("average ll reward: ", '{:0.10f}'.format(average_ll_performance))) + print('----------------------------------------------------\n') + + + +num_envs = cfg['environment']['num_envs'] +ppo = PPO.PPO(actor=actor, + critic=critic, + num_envs=cfg['environment']['num_envs'], + num_transitions_per_env=n_steps, + num_learning_epochs=4, + gamma=0.996, + lam=0.95, + num_mini_batches=16, + device=device, + log_dir=saver.data_dir, + ) + + +biggest_reward = 0 +biggest_iter = 0 + +save_observe = CSV_saver('./observation_saver') +save_act = CSV_saver('./act_saver') +save_reward = CSV_saver('./reward_saver') +draw_reward = Drawer('./draw_reward') +print = logger.info + + + +on_p_rate =cfg['on_policy']['rate'] +on_p_kb = cfg['on_policy']['kb'] +mode == 'train' +his_util = [0] * 12 +history_act = np.array([his_util] * num_envs) +total_update = args.update + +obs = a1.observe() +a1.torque_limit =31 +ppo.act(obs) +act = a1.position +a1.kp=[150] * 12 +a1.kd = [7] * 12 +envs_idx = 0 +schedule = cfg['environment']['schedule'] + +action, _ = run_model_with_pt_input_modify(np.zeros((1,12)), 0, schedule, history_act, kb=on_p_kb, + rate=on_p_rate) + +a1.init_motor(act) +init_position(action[0].tolist(), 250) +a1.observe() +print(f'actural position {a1.position}') +for i in range(500): + if i >30 and i <=40: + obs = a1.observe() + init_e_x += obs[0][0] + init_e_y += obs[0][1] + if i==40: + init_e_y /= 10 + init_e_x /= 10 + a1.hold_on() + # print(a1.position) +# obs = a1.observe() + +print(f'actual zero angle : {init_e_x, init_e_y}') + +# obb = obs.copy() +# ppo_act = threading.Thread(target=ppo.act(obs)) +# ppo_act.start() +# while ppo_act.is_alive(): +# a1.hold_on() +# print('holding') +# print('finished hold /on ') +envs_idx = 0 +for update in range(total_update): + reward_sum = 0 + if update==0: + a1.hold_on() + # print('1') + for step in range(n_steps): + # waiter.wait() + obs = a1.observe() + # print(3) + action = ppo.act(obs) + if update == 0 and step == 0 : + a1.hold_on() + # print('2') + + # action = np.zeros_like(action) + + # action=np.clip(action-1, -1, 1) + # print(4) + action, history_act = run_model_with_pt_input_modify(action, envs_idx, schedule, history_act, kb=on_p_kb, rate=on_p_rate) + action=action[0] + if step==0 and update ==0: + print(f"pre take action the first time ") + # print('take action ') + a1.take_action(action.tolist()) + reward = cal_reward(a1) + envs_idx +=1 + + ppo.step(value_obs=obs, rews=reward, dones=np.array([False])) + + save_observe.add_list(obs[0]) + save_act.add_list(action[0]) + + reward_sum = reward_sum + np.sum(reward) + + # take st step to get value obs + update_thread = threading.Thread(target=updating) + update_thread.start() + while update_thread.is_alive(): + # waiter.wait() + print('threading running') + a1.take_action(action.tolist()) + print('updating finished') +print(f'biggest:{biggest_reward},rate = {biggest_iter}') + + From 34e041a6cddc010676740a00e9a0737b3e52da06 Mon Sep 17 00:00:00 2001 From: Lr-2002 <2629651228@qq.com> Date: Tue, 22 Aug 2023 18:53:02 +0800 Subject: [PATCH 36/62] inverse turning data here --- .../raisimGymTorch/deploy_log/anay.py | 28 +- .../trained_data/inverse_turn/Environment.hpp | 466 + .../trained_data/inverse_turn/full_0.pt | Bin 0 -> 531091 bytes .../trained_data/inverse_turn/full_120.pt | Bin 0 -> 533119 bytes .../trained_data/inverse_turn/full_40.pt | Bin 0 -> 532809 bytes .../trained_data/inverse_turn/full_80.pt | Bin 0 -> 532809 bytes .../trained_data/inverse_turn/reward.csv | 134 + .../trained_data/inverse_turn/train.log | 8400 +++++++++++++++++ 8 files changed, 9017 insertions(+), 11 deletions(-) create mode 100644 raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/Environment.hpp create mode 100644 raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_0.pt create mode 100644 raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_120.pt create mode 100644 raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_40.pt create mode 100644 raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_80.pt create mode 100644 raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/reward.csv create mode 100644 raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/train.log diff --git a/raisimGymTorch/raisimGymTorch/deploy_log/anay.py b/raisimGymTorch/raisimGymTorch/deploy_log/anay.py index 5f5d574eb..5410e8140 100644 --- a/raisimGymTorch/raisimGymTorch/deploy_log/anay.py +++ b/raisimGymTorch/raisimGymTorch/deploy_log/anay.py @@ -1,14 +1,20 @@ -# import re -# with open("./08-11-15-28", 'r') as f: -# lines = f.readlines() -# for line in lines: -# # x = re.search("work_action", line) -# # print(x) -# if "work_action" in line: -# print(line) - - +import re import pandas as pd +ans_list = [] import numpy as np -import matplotlib.pyplot as plt +with open("./train.log", 'r') as f: + lines = f.readlines() + for line in lines: + # x = re.search("work_action", line) + # print(x) + if "average" in line: + line = line.strip() + # print(line[-20:]) + x = float(line[-20:]) + ans_list.append(x) + + +df = np.array(ans_list) +dd = pd.DataFrame(df).to_csv('./tss.csv') + diff --git a/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/Environment.hpp b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/Environment.hpp new file mode 100644 index 000000000..82a196374 --- /dev/null +++ b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/Environment.hpp @@ -0,0 +1,466 @@ +//----------------------------// +// This file is part of RaiSim// +// Copyright 2020, RaiSim Tech// +//----------------------------// + +#pragma once + +#include +#include +//#include "yaml.h" +#include "../../RaisimGymEnv.hpp" +#define PI 3.1415926 + +double cal(double low, double upp, double now){ + return (now + 1)/2 * (upp- low) + low; +} +void swap(Eigen::VectorXd &ob, int a, int b) +{ + double tmp = ob[a]; + ob[a] = ob[b]; + ob[b] = ob[a]; +} + +double rad_deg(double rad) +{ + return rad / PI * 180; +} + +void map_from_origin_to_limit(std::vector> join, Eigen::VectorXd& limit_list, Eigen::VectorXd& gen_list) +{ +// Eigen::VectorXd limit_list; +// join = join.tail(12); + limit_list.setZero(join.size() - 6); +// std::cout<< "!------------" << gen_list.size()<< std::endl; + int cnt = 0; + int jp = 6; + int kk = 0; + for( auto i : join) + { + if(kk < jp){ + kk++; + continue; + } +// std::cout << i[1] << " " << i[0]<< std::endl; + limit_list[cnt] = (cal(i[0] , i[1], gen_list[cnt])); + cnt++; + } +} + +//void angle_generator(Eigen::VectorXd& angle_list, int idx, float T, float rate=1.f) +//{ +//// std::cout<< "size is "<< angle_list.size() << std::endl; +// double base1= 0.82, base3=0.0; +// double base2 = -2 * base1; +// double ang = abs(sin( float(idx) / T * PI)) * rate; +// +// int idx_base = 0; +//// std::cout<(); + + READ_YAML(double, action_std, cfg_["action_std"]) /// example of reading params from the config + READ_YAML(bool, show_ref, cfg_["show_ref"]); + if (show_ref == 0) show_ref = false; + READ_YAML(double, angle_rate, cfg_["angle_rate"]); + READ_YAML(double, stable_reward_rate, cfg_["stable"]); + READ_YAML(double, reference_rate, cfg_["reference"]); + READ_YAML(double, for_work_rate, cfg_["for_work"]); + READ_YAML(bool, float_base, cfg_["float_base"]); + READ_YAML(float,schedule_T, cfg_["schedule"]); + /// add objects + anymal_ = world_->addArticulatedSystem(resourceDir_+"/a1_description/urdf/a1.urdf"); + anymal_->setName("dog"); + anymal_->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + world_->addGround(); + + /// get robot data + gcDim_ = anymal_->getGeneralizedCoordinateDim(); + gvDim_ = anymal_->getDOF(); + nJoints_ = gvDim_ - 6; + + /// initialize containers + gc_.setZero(gcDim_); gc_init_.setZero(gcDim_); + gv_.setZero(gvDim_); gv_init_.setZero(gvDim_); + pTarget_.setZero(gcDim_); vTarget_.setZero(gvDim_); pTarget12_.setZero(nJoints_); + angle_list.setZero(nJoints_);angle_list_for_work.setZero(nJoints_); + gc_old.setZero(nJoints_) ; ref_old.setZero(nJoints_); + /// this is nominal configuration of anymal +// gc_init_ << 0, 0, 0.50, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// gc_init_ << 3, 3, 0.54, 1.0, 0.0, 0.0, 0.0, 0.03, 0.4, -0.8, -0.03, 0.4, -0.8, 0.03, -0.4, 0.8, -0.03, -0.4, 0.8; +// anymal_1->setGeneralizedCoordinate(gc_init_); + gc_init_<< 0, 0, 0.41, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + +// jointNominalConfig.tail(12).setZero(); +// Eigen::VectorXd tmp(12); +// tmp.setZero(); +// angle_generator(tmp, 0, 80.f); +// gc_init_.tail(12) = tmp; + + /// set pd gains + Eigen::VectorXd jointPgain(gvDim_), jointDgain(gvDim_); + jointPgain.setZero(); jointPgain.tail(nJoints_).setConstant(2000.0); + jointDgain.setZero(); jointDgain.tail(nJoints_).setConstant(100); + anymal_->setPdGains(jointPgain, jointDgain); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + anymal_->setGeneralizedForce(Eigen::VectorXd::Zero(gvDim_)); + + + if(show_ref) + { + std::cout<<"using ref"; + anymal_1 = world_->addArticulatedSystem(resourceDir_+"/anymal_c/urdf/anymal.urdf"); + anymal_1 ->setName("anymal_ref"); + anymal_1->setControlMode(raisim::ControlMode::PD_PLUS_FEEDFORWARD_TORQUE); + anymal_1->setPdGains(jointPgain,jointDgain); + } + + /// MUST BE DONE FOR ALL ENVIRONMENTS + obDim_ = 34; + actionDim_ = nJoints_; actionMean_.setZero(actionDim_); actionStd_.setZero(actionDim_); + obDouble_.setZero(obDim_); + + /// action scaling + actionMean_ = gc_init_.tail(nJoints_); + +// READ_YAML(); + actionStd_.setConstant(action_std); + + join_limit = anymal_->getJointLimits(); + /// Reward coefficients + rewards_.initializeFromConfigurationFile (cfg["reward"]); + + /// indices of links that should not make contact with ground + footIndices_.insert(anymal_->getBodyIdx("FL_calf")); + footIndices_.insert(anymal_->getBodyIdx("FR_calf")); + footIndices_.insert(anymal_->getBodyIdx("RL_calf")); + footIndices_.insert(anymal_->getBodyIdx("RR_calf")); + + /// visualize if it is the first environment + if (visualizable_) { + server_ = std::make_unique(world_.get()); + server_->launchServer(); + server_->focusOn(anymal_); + } + } + + void init() final { } + + void reset() final { + anymal_->setState(gc_init_, gv_init_); + rewards_.setZero(); + COUNT=0; + updateObservation(); + } + + float step(const Eigen::Ref& action) final { + /// action scaling +// COUNT ++; +// std::cout<setBasePos(po); + pTarget_.tail(nJoints_) = angle_list; + anymal_1->setPdTarget(pTarget_, vTarget_); + } + if (float_base) + { + + Eigen::Vector3d po(3, 3 ,10); + anymal_->setBasePos(po); + + +// raisim::Vec<4> quat; +// raisim::Mat<3,3> rot; +// quat[0] = 0; quat[1] = 0; quat[2] = 0; quat[3] = 0; +// raisim::quatToRotMat(quat, rot); +// anymal_->setBaseOrientation(rot); +// raisim::Vec<4> quat(4); +// quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; +// anymal_->setBaseOrientation(quat); +// pTarget_.tail(nJoints_) = angle_list; +// anymal_->setPdTarget(pTarget_, vTarget_); + } + // angle_list *= 0.3; +// angle_list.setZero(); +// Eigen::VectorXd idx1(8), idx2(4); +// idx1.setZero();idx2.setZero(); +// idx1<<1, 2, 4, 5, 7,8,10,11; +// idx2<<0, 3, 6, 9; + + pTarget12_ = action.cast(); +// Eigen::VectorXd ttmp =action.cast(); +// map_from_origin_to_limit(join_limit, pTarget12_,ttmp); + // pTarget12_ = pTarget12_.cwiseProduct(actionStd_); +// pTarget12_ += actionMean_; +// pTarget12_ = angle_list; + + +// angle_mulit(pTarget12_, idx1, action_std); +// angle_mulit(pTarget12_, idx2, action_std); +// +// +// angle_list_for_work = angle_list * for_work_rate; + + + + +// pTarget12_ = angle_list_for_work + pTarget12_; + + + +// pTarget12_[11] = pTarget12_[10] *-2; +// pTarget12_[8] = pTarget12_[7] * -2; +// pTarget12_[1] = -pTarget12_[10]; +// pTarget12_[2] = -pTarget12_[11]; +// pTarget12_[4] = -pTarget12_[7]; +// pTarget12_[5] = -pTarget12_[8]; +// pTarget12_[9] = -0.03; +// pTarget12_[0] = -pTarget12_[9]; +// pTarget12_[6] = 0.03; +// pTarget12_[3] = -pTarget12_[6]; + pTarget_.tail(nJoints_) = pTarget12_; + + anymal_->setPdTarget(pTarget_, vTarget_); + + for(int i=0; i< int(control_dt_ / simulation_dt_ + 1e-10); i++){ + if(server_) server_->lockVisualizationServerMutex(); + world_->integrate(); + if(server_) server_->unlockVisualizationServerMutex(); + } + + + + updateObservation(); + double rrr =0; + for(int i=4; i<=6 ; i++) + { + rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; + } +// rrr *= float(COUNT )/ schedule_T); +// for(int i=0; i<=1; i++) +// { +// rrr += abs(gc_[i] - gc_init_[i]) * stable_reward_rate ; +// } +// rrr += abs(gc_[5] - gc_init_[5]) * 2 * stable_reward_rate; +// if(COUNT != 0) +// { +// rrr += (gc_ - gc_init_).norm() * reference_rate *0.1; +// } + + +// rrr +=(gc_init_.head(7) - gc_.head(7)).norm() * stable_reward_rate; + rrr += (gc_.tail(12) - angle_list).norm() * reference_rate; +// rrr += abs(bodyLinearVel_[1]); +// rrr += abs(bodyLinearVel_[2]); +// rrr += abs(bodyLinearVel_[0]); + +// rrr += abs(gc_[2] - gc_init_[2]) ; + +// rewards_.record("torque", anymal_->getGeneralizedForce().squaredNorm()); +// rewards_.record("forwardVel", std::mi); + rewards_.record("Stable", 1 - rrr, false); + rewards_.record("forwardVel", bodyLinearVel_[0], false); + + gc_old = gc_.tail(12); + ref_old = angle_list; + return rewards_.sum(); + } + + void updateObservation() { + anymal_->getState(gc_, gv_); + raisim::Vec<4> quat; + raisim::Mat<3,3> rot; + quat[0] = gc_[3]; quat[1] = gc_[4]; quat[2] = gc_[5]; quat[3] = gc_[6]; + raisim::quatToRotMat(quat, rot); + bodyLinearVel_ = rot.e().transpose() * gv_.segment(0, 3); + bodyAngularVel_ = rot.e().transpose() * gv_.segment(3, 3); +// std::cout<< rot.e().row(2).transpose().size() << " " < ob) final { + /// convert it to float + ob = obDouble_.cast(); + } + + bool isTerminalState(float& terminalReward) final { + terminalReward = float(terminalRewardCoeff_); + +// / if the contact body is not feet + for(auto& contact: anymal_->getContacts()) + if(footIndices_.find(contact.getlocalBodyIndex()) == footIndices_.end()) + {// if there is any contact body was not in the footIndices the over +// std::cout<<"terminate "<0.3 ) +// { +// return true; +// } +// if(abs(gc_[4]-gc_init_[4]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[6]-gc_init_[6]) >0.2 ) +// { +// return true; +// } +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8) +// return true; + +// if(abs(gc_[9]) > 1.8 || abs(gc_[12]) > 1.8 || abs(gc_[15]) > 1.8 || abs(gc_[18]) > 1.8 || ) +// return true; + + terminalReward = 0.f; + return false; + } + + void curriculumUpdate() { }; + + private: + int gcDim_, gvDim_, nJoints_; + bool visualizable_ = false; + raisim::ArticulatedSystem* anymal_, *anymal_1; + Eigen::VectorXd gc_init_, gv_init_, gc_, gv_, pTarget_, pTarget12_, vTarget_; + double terminalRewardCoeff_ = -10.; + Eigen::VectorXd actionMean_, actionStd_, obDouble_; + Eigen::Vector3d bodyLinearVel_, bodyAngularVel_; + std::set footIndices_; + std::vector> join_limit; + int COUNT = 0; + float schedule_T; + bool show_ref= true; + double action_std, angle_rate, reference_rate, stable_reward_rate,for_work_rate; + Eigen::VectorXd angle_list, angle_list_for_work; + Eigen::VectorXd gc_old, ref_old; + /// these variables are not in use. They are placed to show you how to create a random number sampler. + bool float_base; + std::normal_distribution normDist_; + thread_local static std::mt19937 gen_; +}; +thread_local std::mt19937 raisim::ENVIRONMENT::gen_; + +} + +//int main() +//{ +// raisim::ENVIRONMENT a("../rsc/","/home/lr-2002/code/raisimLib/raisimGymTorch/raisimGymTorch/env/envs/rsg_anymal_modified/cfg.yaml", +// true); +//} \ No newline at end of file diff --git a/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_0.pt b/raisimGymTorch/raisimGymTorch/trained_data/inverse_turn/full_0.pt new file mode 100644 index 0000000000000000000000000000000000000000..fd452a3371d6bb8f331fdf207de9631e4fd9ad51 GIT binary patch literal 531091 zcmaHR2{={V7q^)tL#8O1iw2Xv=f`Y_fe<~8{648k> zXHKyi8W}DMx12p=rpE{siQs?#rAQ?UB+P>JxYNTUM6-lb!i5nrv7)F5QKB$vN`fd{ z6g4F>HbNwjjEI;ub0+7HofV&;=p&4b5=KS3aXpFxDRaI++AK)31Ebs7mR6Q?qhhDU zhy*en$PqD?QxZk7GZPf22&1MZ#?FkKB8rMn;4V4GMo}PZW)>vR0VHrohEIzU$aS5f z=rMCvxX8cDsVI;SlH`uD5-0@8acx9mWVo}Hpoh1Fsz{*d=Oy8l;$@H_=;>wPC7B^m zS`pJhtd~fj%onHxssGJxYHWCdKsAQDbc|d~7qqoNtvhsYuN09$y%RZIpy4H%F3{{k z)e;G``GP)w$87U|W7hc>u8lyqJ8oZZ30IMzUl-++41pfUoTJ>o3tV3$FyIRe|E6qX z*-6>xU(mJ!?FC}9FOKLsPaBol&^{EEw0> znV2xOTM9ACx{{ie*YTOVFG^lLG|w#)baleYCy-J z26heV1d$+!FPNB+EC`P28pcU6+yGAQB$B`p>CeGO2xCRD5&!ux2&{(JuaFJ%S)!gUe|yW=KwrmU!oGB^JdyXOC#F7UY`!92cT{@;}U zN!bPegO=h(*V;;u)E#?a2j}E}I4|npytoUNbEonJOaA8kznoqAZ(wUdT6f^|4&aOq zV9Ac0UDm~Uc^CK!kzgfXu2(ty(C3~)t%7kf;AnSbGl%2MS`__ zK^~X1>;9Qv>&-eQSbkR;{FRj(k_8+8BSWkNo00{a|D)4duq9cr^*=go1ly7Y+yA4} zRiEox?zIan9it9b&Kk>NN|QPsEhd{ z5(mNA?w38+F;CBTUNv1%-!YjkbY1bHNN|ZSxE%8bYe&JA?x$bvIQ`l`r(f?ly`k&$ zMv>qKU(l53#jSE~{zceH(A-7%RyV>eBEfCGp!E;JHdcZ=-LH7J^J#Fe^O7Bzb-ydK z+PW_LKqPp`7d-ldwT-plad(U-ofuF5hw-cn<9Qdx3z6U@U+^l?OFCKb`cLXMHi9=@ z)Zcca{!S!#&li07le(?oWB1FpcMR62&a0*iK6eb(m#!;*6$!ra1>gT3*s$a%X_687Zmj@5}!iBme5bu3VXy*Q(DM1{(n)$L@(K7p)RNV z6}+RcFX!$Gz8|M`3to>iMZ*4^yop%K@1@=F&QceuD4 zW5Tsv+)O!5Bpkp=zHlHX|A^bxN@&J;yTh7ub_eVruKfqrqQk|(4(8e}*dd%I5?XSS zFC5CrL@&8yp%th68M3Xl(3*31g>1uV-9onIOp(xzlYF6l$3g!N+15rljPrKq=D^t< z+#I>~A8t+^E{>Zs*LHE^ahgcTaFQM{!!WkVkW-NH~U*e4$szL4Sm7FC5Ex zyL0pA?2bpXa2%&}kn7m#2z@xC^8qdN<+Lt>ew-!}@;S*D`g8KnxQ7YHbKdUQ0i4~5 z9mpyF!=AtyUDzFat}g6}oF)FM zFi!G?;T;G45xk>tD(CG^FoLtWr;ad^YdiU+3!^$*+>MFm+AeO>I87vs;Ur%e%gI0E zb`nnKyxn1EaCQgmOs@S0Hm<|P!NzlK7wjxf6A5Q?k}ni+GSRC?vQWq=e}-&lB~0Ml zT_KA&ty{>6oGB8{;Ur%;x8tCHhiqppoX2^)bDPiE9X}7k1)S1JuH%uG#2H&b@{hRfY=kMCw>x$!XLn*R;gtVjFXfCb>@-g6!cONjkuZakeBm-q zCVD9*3zu`sU%}f7S8(pG;8${5x8PTCrbw8{Nxm?vmTKjXF+uIIenVe>h=19k(~{sX(Q!^OdF;@U3Q z&739@Zs8*80!X(C}MC;7rMPW~CTqp+Owc89Lu><;Kk zuKgc$Rj0E9x|-9vp!af`NVt!aeBpjhCVD9)3lDJ0U!gk*4|49V&<}B1x6luBrbu{% zlYHUPj)VRky1kXKhVypkC+2K!Ei7cYwv%7F5IbGzLdvyW+>UXYNO+u+eBlXB{t>pl zweTe8?G9VZ*&VQ_xb`2|)19t#;Tf*&g015;k?<@h`NDIYOib*o8q5wChR02rCY+Tx zJ3)A!^M?rQIhicHz)7>9jxF3wq3|MSc#?--4laKX^R9CzFqJD$BnU5c_+4IJ==i(n z>GJ0DrDm;V78%0JoWFDVAH|_w={(tees-HxrgP^-yJ}@qBBLV0=L@fL-Ch!%dx7w{ zglWR?NZ~ckwIZma&=(gzuWLVYz0=iEHjADmj0%s45jJq1ah*&4i16852`_x=%qU@F z=V2W+kI2~QXs&J-FN*E#xY60sv4@FHOo)mUHg%reQCjO9fdt`A&JiMP<|MbZ;U=Y& zm$a9Rm#mkZm%NvPR}U{muby5?QHkM+iI%=z@(PD4cRGybc1#`rzW-U6>?Of;FH8=# z@)+UxXIb*!Maut=HD{>;4T??$&yuIuDmwzA^6s;@?YD?Ok6pp+O39>g9~^4Fq}V`x zdpm{=Dk3vdRLRt{A7Dj^5~@$AhQkIy@Y600x9{jl^49ObsLb@5t!GDq@WDQKBljG} zP8xzgYxcu}JWp6#+?zfgAWQW^isAgruW-|hh+ln{A`TnW>EdtuQ2kClqp~7`gzZ0u z+1B}F-+l$!9=#RX)T*GNUXC{GOQ5u0B8XDBG|#axitGA8UH)Gb{gWJcL|~6sHXC!D{xgrHzI>kXaW_3%t^?1Pav4C3%G7u~Pt!_Wz0_+_~bp13c-o9!C-Bt??3IChmaeHcQD3tNHtu-p02 zyck++D^K#$d9Yx0E|pHwBA0X{QP#}>em}J(b^9{NWy2m+>X|M*^Y)2&ulWUL`O;}* z)u|rLj#CmeqO32trdGhVuX=Q3sR7uF)}#5|2zWST4^!7riE%T0=up~&J*x77X(9K3 zms!bc<;MEKv=Q{~ zvmw-q7Y(m}{BWA~<_I+G83L<@x8u_nk870J{0pd7D-aewu9#>0i5>lMRdm>!z;_`a2ghbNrM^j{hmBObVb!uWDja!XeffSF!QzUF@;uEZE$zz?}EXu*Y;= zI%wK`Tu^YIk+?aM8qPh41FCzHaqrA9wn>#L^E9ach*W%2YEIwe{$ez4u7~z_68LQQ zY!W52iY$H3r@V26aM*eiggV>aniYn#iM-KcRi~x zzVbVc9<>MGwOFxm`2$M6S8BiXPOukHsPg;aoDTIjh%F>2gyFD z$(lcwMYYyTpuMmk;Vu8h?7KY?K29wr=%NIz`ZLhHZ6$o74UF!*P1rLsj6FKq32Z{z zn0+d9n7LaYz?>{aMsQ0NPX%9rlTx3d&$c1tl8Zhm^d3R%9OCidf_7fK^>e&pT1ijd z(4ajXzCrH6T&I^<=j1l?1J1ao1~P|uI4wMiwps*`M?*Y`Oy*YVa{R={a8*FWCay#3Cg?G&9sQw$7dkx^GI5T9Vv(EoiUcTek>f)}1dkg){EY)}I!l`xzw!9t)T zi#OBHvn@kPu(?*BO0G8|Iu{x-?D;ONu2Lp(ebwP=?k0HX_Z>v9Q}J%4Ivi2SXFdkx z;iyOb@%ma%^!3Wa%OOU1{6QG{CcD8ytxK%o{)sq0_8hyguL`!P*pjTH14!DjAdDV} z_%1X6t`sX`@P|Osw$+5}Rvtn0S{=|Jb|ra`cLMKzaG`2ukz{l9Q5=6WjqIyw6ED|) zz*@+BVsg%nBD*(gVD#+K_`2T>bl$mxNF|@BQ56?J`9~jT^SztVZ`&P^G_Ap=16tH@ zl_J`|9s=(!je6h+lkIv@@55K%jPE=w z$ezx-Z|i{Sei=~RTZnh6L@;Sb4y6ZFsh?ah>(To&?l`J|FA69g-ctt0cc#;KE6jl3xct5q*hl+&6JbGX^phxGYGL_Sb)ofh*GCx&3PVWwajLjwgcCTdA7Ief8-oh2^Z?7$cHz4&kTl~Z!Bq+wIk7o&a$Jc{8`sKyKq;P z4qj%17*&IJjCA@~Y`(8X)=gOem$z!*$3d0i#EPZt`1(weHnR_IGdK=MciS-wQim|b zP7|qX%Q(~yYDMF4UGlx(cINE0Yi!l$1dw(Ykn#^jw8ZBqbJd`jIixcMH!3E=BKZ`$ zCUriKMrtu5rr*TRg9Fjh*Ax26-)8Tx)uVCOwCTgf%ZOqAIBrD=6+70m{Wd?u)jk*S zZl)$(9P=7ZR<*-fjl*y*bPG1`xaB;m;RfmyuEUptM{x7i8yIru2y@J3E4;Yf24!DiA@(7gik#prxmdF_mj2VR(=nkr_1~hpgA&eI&B* z*<&>G#lIECm8`BY)HI}V^5e;Pqc&U>_y7(|8iTb)GrSpf3I>b$NXSH@Q$uCaBDH}V|DDTFO9+S(i+*S+O2_g%aUi{@iINS zeAr165z38I^%gYp^krAqm0?5wQ(_}kZQAD1>^$vW2#onLfr)hXhj?puY&f(Thc__n z+UDUT@OKv7a3Tb=#_U4+T@O~=y2j4kok0qwk0aaKj*xRVp25z|k8tatt2lCM0)&S~ z!|3Zln@n@hK+n3tE7)zg;m81D<7c#efEGb*C5d_cX(a?*{3^S4Y zojT@@8rq2{R{Dsc`*WD{TVl!W@+(MHTVT`#9*Mp&i#@KDLL?Py**jsM9dnwXuYn(im+m2_s=R5b#AXKeJw=aiXHfOE81C-g4m!VYh<6>< zp-~1?p|4~X^^G10M0yW9B~+5Wty%_~0&e1<@86h@J*27YS#FK;U5Pl3vBusrmXoqO zUO0WwVR8CuJN8%KL3FLH99`qBOslWtLZunE*2uJn%#g|S`Bg`D#~uSveLR&W6<%jz z&7^VPd<8uA`wQf`=h3~x0|9e)p(tVuD3B@O=BY`ylrN@4_XqyoFGrRL9SA16J2Ue~ zFy1$%K(5XRveynH!6Uce_TY*&Yd-xB2Hp$TNr*GV{6`7PLd)q<9S3u1+jzBtnI zGiLVCBBN{!$hyAQVc@a`*7vq8C=H;HcdxLF21j=)zIGr@6k2If3oKokn!LR0Sm25&X7MRRI#wmiW(Y%7zh z6wX}U;RjRus8emVI?(x%KwM1_TNX&tug`zOGw(unQS&`GH)brxuDtIw^tLn}`Xocv zzepzEXZw?Ww~oVncPaY$?RT7@JBBR0cmXu^zM;{~sj!(_v(C%A2hBs$m=T*xc-yO{ zK*h~;w6+>fZ;X;8o{8$P{IxMpbwnJ7#f&ENUDK#BISy-o4I&A9D=}Wm0!K(ZVkH#i zvGDmVT>Q8V7c@{b9VkWiN9>0J&jL6J6zbZP@uKNUh(59dnJ>yXtG*U&+wQO#XC>&+ z!1GL>?>dm&rpk=^n1v)ihg=z+M?ZYhB$0tKB-TfgBv`1D>Z~DTB2R+!cxwf(OQykx zJ$#<#vAw7~{v60SE+a`JPs8xv^}xS&0-Nfc;O4ubIQl|8-Y>Yp&KxihoOku3&%IZ` zobPw=ajg|xH*8@oFDc=W^FDasYXQi&n3EfE1Moy#0%$)_Bwy;*FheG1V^I1|*00o% zmg*~`lS~+ieU?jOTm5il;|Dx7dl>s=>nI2a^dq4<5=0^R9KG}S0<|=qh4*~y*p{Dt zXs_qDLAkdY{qZ)KUKi|UPTI79sWHR$n*JMxqCI)JzY2GSSwXI|0qLg{O@D|-Qv1&e zcf76;i|)ox={ugiKf%(Kl;LBpP9H&;w(&Fkw*Q@ccA`9AvCIf!#ir* z=<_=x=-~$^uy-Yc+To8eb8i98S$Yu~J?`Vhao<>VgI&CS>VD*0YZe?i#DnJZg*f*Z z!WFuoJ$?Y$aWbpVx?7g`H=d}TQsZf>n+_;*#vytFdk3gb0e;oPP?+jZx z(2@$>M&eq7B}DG6BQL?UlbmKVlje5xze*jiR2C7BLRrFyuYUS~2|jj3vW9UMEMLyo(p z;kt7-TU$bGh8wSUo03+8!j1u`9V_xPw(KN=L6|hz9ED>OXm5X2&2|NCZSEx z5VC5w3>x*ZfS5BMu+T+}O59^`X%%;W9xcW3^F`#rEOYXubsESfH{dEq2f9yo0`oL+ z6Z-Zxq<-GlVBwH9@ufKd0JCN2gn@&x@MJX>YHbG7gIRcMRxifb_B>`en9wP=(y3s< zI+%N-8Lue)#)&aDU|L&d3h`r*QWDBM>fmOT3QSs(N?)a%!x>*Kv3X=W{u0~c zmBG{CcElK3cW5&WwVgm>Kh36O(mU`OAjSZyKwrnC(SXlwP<2iNb$u1M>j+_>{675J z=mi-%3yDD53ftA9XwT9mc(bk!41d00Tfa!t{W9UO<@8o|ut^C||K?UmIAKhz%g*8I zmv?Y%zB!q<`!39^w}3T|a@dl?DXhqYz`V;^kZ_t?ORGqc`22xvyQ48_YCVicK9}R< z`u%t=dkKwMU5`KaghAaTYpTC$IxXI|31k~A;nerdB+2^@u3yBXOkyLGZsATE8zg8C z`*Gw56yP+18=4 zyhX~&xO2xhT)g!Hrk<_`pYaVCvykEvlpXHjp0 z>>GcYcHfHRW*>xoQU_sfODoPA^Qs3Y#H7Ap5D~8dhTsiWBSKhOUxjk??ow}L6loMj-W0CgY4UZQMVO z_+_fm^31U`x%X1sGv@?0OiZAOzIm{H?qxP|`9s$0k`EZUwlTE>d}!0+G0;Kmw(n1sw_3xXe#vA~RS0a(Jj6DA z=EL@%BdBRw#gG*e&Kw z1)nT^^#h)6=tE9c7}D$e*5lT?Qiz)+%l0o+B?E`q&`qh5FuwjcPA*Dg-i;VV9=^K9 zthXM6pF9oFuJSx+9q0wF!EYJmNI7y-eHqp5ok14{Y0`l3SIn5*}{}{&otqk$mq%XF%%g1VmN9Yk~L-w`)1`~}-VpG>tI&Z}ivc6RZv`g|Z z#-{*Z*0(SN>&H_~t6;K5XFE^9)SDj8N+SL1GkN)}Hq3Y-OVt$TP?rU=Fykt>pNq;v ze*<~M6S{QpjAov`hc3nn7U1<^8&N?hjcF!7S<{{4@#f4ySm^Id)?aC5^0z2q#aKsi z^TiDG8&!p=(^vV- z(Y9n)erUtbm!6|_QyhEomIf&ot;XALn_7x=Gn#b#w!+LCOEOT~k5@x7kZ#%?K;_sN6Or zl&E;Rkhc9;01Nz_NI-}_xi)Yp$vDuDh6gx0U-cPEe_r}2t`VApw#bnzI%-BwnSH=* zC+eZsJ84`jE6HqH6AX^J+K{^F2+_IfN5>Vf0(CUUlaf80B`ucVhlO8ZYzE7y9WbUQ zEeq-U>|SKzB3*K=tdQ&qyaYPeeCX!>A;i~Cg1qpu#DN#$V1}(8NeFT$7f0=8H3d01 zs6`DjOiwV?xqwj$BHPB1@Jk=VS{Ct3w^RN{jixtJ=Twb{F|EISCVX}?CAcz}s1`wSX> z_t~dL{mGkQfy{0ZAL@=w$Kug*AUFuQ^?M0Q=Z_=zZ5N_?!DF@;xBj?T`wc=P%!zvN zP}=Bi%q$G>h1fJLA{o7(@DDG;`=TDSYV1n(hgLZSzfd|mGYwq^rjm6_2fdifTWx9!!X6T}`({$2rK_Rqk8G+h@ z;WS@84lK2LvEGk|(LBTRyb6Idk-9yEzQ|@MBRGwx_{*4@&6lCwxDr-;uY+ptU6#6k z8uKJ&6YjfvhB=;GhrxsU5SQ^1)PKrpkl$;9n#u)YmEp?Je&sd$UF#}V7foXlXekUOm$&1aJ*k;=fMWc;q`=;&8YikKwHPnvo zw5tINKOWT$u^~wn@(`dS#mu+q3l}8(iOGkj%v-Au_~lI>!hhvT6wai!{{n^FXrxWYnu1wG5hw~JEr$reR9e+h$ik5!?KB`ShvlO z-kiG%fv-qKB^yY_%GY3XE)jjKnpoC`Lu?xD&YYo`H2b3lJ< zFKS^-(d618Y}`1WT~N9OY#lV%1W+(~AE95ZPa0p7xw}!n}Ot2+M zk7i1qz&X*M@zKaJOxc=z#$|XoT^PCoj+EKb3zKr;qr-KSky?PGT=H%iv?X zjW{EG3-Vtm!|`DfxM`UYZvU_nN7}xI=T{PFRxM@Tmk$8m!lk5OjXIPRgwj>J55t5( z()7}Pcj8^K7h~DOZ2iD?sPrFAJZH`zgARTL|I6HZmfM@onmrPiWJyt;x*_QsK9Y)a z^hqwa)_&UIJ$) zis-!fLNtG)!1~>Hq#kx2`1*J&FE3q4sz=@immSxjO%B8gpVDxX-XTabzQSs+UWqw! zn^^Y8Lnx@2NK*TMN1tjn(voLLUWPl+*I9QN!{^~>8C1mR)E@)$J9*6ebG>MD$}g@cB?UA(fSAVgQ_b9S_#ab%0 zzX(VF{)wtgF#X&h3$D^@LH}4I^wC*J7wY`P9kIROXIc&WTeb-8wkuI>b`Lwsz znUSS_6(IO9i7FkG2cITq*k?2soNoGo=dNR*+B}-s;_8Ve4e^ZfoO*0}`4WywtHYY9 zt8tueE+eX+O$@Isfn8Ap=v}pCaO}ozcrE2cNmv;y%9Nu$?N{KscaPBPtp}vron>;B zEiiJ_TzuHC0vqjjfbJYQyk7bV#tg}$n(hzT=%795+bW-Dsi2Qjo~Z7Y2CnG2e? zhT|2dkI;T_Gl-{EpoP{6Zog(k29MY-zCPE8E`5Cqng&fpQhJDIs;!NiWCqXz+{0UV z{j#`pYBn4x8Av|Tn5*EjxVHlE$Z_+Lq8vPVf1 z8PCCZZPaV{v|I@r-3rV1tKC7x-i0n~D`6y__-Uf;_BVZh-p@g2_v3S9+g6gvh;dfq+eqVd8W}(xNrN*>Bi3v~iOb_b<51 zS_j*Z*e6OLO!B54i^mbFHwubVm%*p0$KYIUF|Xb79J4HG5G>m3Ni6g7(atCha!jic zTPKQVEg4Kc+!#Y{>G@*OfTL_%{4y$HD&dDs^PeK0dk=l(b2965(1rGvZes2fD^R~lmdrEf(ZprTK{Uwd%e@=A2L0?FL)G3~ zy7t06>^In(t%*&dYFuq?^P%G&cAsq=}f^}vzAjlj#! z#UsrLvW$0?~Uw_A*v+7svJi? zFrmTg+@XqF*Vc$sU>X#mMM4vPV9I#!l94?fdK@QI$AH7L{h~EZouRNH2@B zaeCEx*!kiIYnPQr)pShA)k{Kp=3^gntF{g!q7O1!ZTG-vVw>~v?0iy`pFun&gUH^8 z>+#OLY#i)*7JoPX!mZTk=fdfhK6H z--7!Wc~R@QdghX4C5s=Q!?3BN=%wIouKehKY8p$A&TMHAN<$FcOzFcAOpBI84+p-6f*B*&bssn9UPaWfg_Q`sTr z(w9^WyE=@PO_UIueLjU3REDz!ezvrtyhv>1_mUmfG!(owbKtR}B)m^#VC$DcFu6Dn zrjN{GRdt7wu_N?o*c`w+en(jo^9HCL)_|>Eh^KNaNWeLJ*4uA3v(0S<4JhwN{SV9_ z_Zn=-kqHf0lFZc#7v&R|bC1#KVklcKGmuK3S%*$)wI~RQq1oDF!DI72{IzxhF=F4q z)SouQq`wAfavhJuQsVKe;Yk#msL|#@26*YIIyNqgB_-}h7@pifI@EeP^;66e(`z&E zs74WU#qKEh^2gC0H&kfhqY3Ole^0WyZxgrw6GO;TSGcU=01+3xs76CD+~k!V&Go*^ zTQ;%}DE%-+@1hj?X;T&~yWtL#C&aPGBun7zJq_r^y*t~WU5Sb(N8mx}0N58GLk1_l z1GAs<#P5j=J?^PQE#|+#6Js_~8s;b7*ye#PCyp`aDg-$BX)C^(q(;1TWr(2QA{J%O zXJ=KVqSn?3a!9X=u3V`|wH+>?@`PVFOvwQ!$=&8{@N^@u_XUw78r*j$jmpI4GLQY> z=!WEtI_|tFM^0Zpj1fmA$fA4|+S`bGu2f5r8-2=QQr;FYkVwaOYi6KaSUw5jje~Fc z+o4F_gvh7QWNQO*=(_t)(X7;w+ATZ{BbIxD+BH7)TKgE!-^?bhOOMvLB}idaeIgyR z)RYAJeS|OtJDNVh0&Y4a;PkJ@a*ewX3-EPLw zzdXQtqX*f3)d7u?dQs!+-(lfvYuIf#h%A0}6q=6~L+L2C2D$H-6x~FuLE-^$eOm>u zi&SZ^Q7;(dUsJ>zM*FbGM)#zaDL&LSqz>C6Hqyqi55d>8fw^Y40iDh`;9=wO#P7gv ztazA9D^Dm9E5%#DTJA?>NdxK>96+yJKZ5)LE19;(LEO93o+NDgR}@$c#KouYu-<2G zA8|X~eDr6DG!Y&MBaX>+>>E8RlGHniY?|DI?d2zCrHp#f_JDkRX7*j|VZ+tyb@K7Y zptsQcNt#(`cp8jW8_eynAy3-Q`-(h&9jG;DC=46Aq7ps&tmzL)l(EM$(G?Niys^&>v546pbq>issMX(38@pl>g-z;qAmshdVJcWM*a_opG=a}Ybd z!h`;hyn3E>F>dd={Q4%-q`RJ zSKZ$TOJ!^ zM7`sYQQI|0bGZ^#aO_Q;-wY&yCh}A_b2pw#o(LhdDzup2diE_uu{>-o&ikG|}l!MS4F`G=vetvv}2 zOrY-gCpN_9uK<=%Vpe9opm_5xL0`~?|;%y){+S!b! zOC@o-lr*kCU{7_k`-1Vg+M19Nw)90sD1E-xfv|QnS@q@=R_|p5z4bAjbsRmI9{RGE z=JdGD49G}lvbC4P+MlbS#WE8P{T@%6t(6G!o`tfXj$(<_E%kHm%D4yl4^>d7MCzR zUB(h!UVmc4+eWYM-$7>Gz6cNegW=SsvlzLrKQXCQA%$Ba;6hOVv}EpMrUb-*joVt> z8yQcItC-RcZT)dVfgvLil?0FPN|3}}+ep}@G?JPFNAJKkrr`Drs#@_Hdpk?gmy20g zKiZ0f`7Vb?j`i@=ToW}@E@R>vKeF?zF4FUtv1I0E7GA9*cc0(mE&ucgC6y{*UGxIX zU-kfhd=N4ld+o(En-UPO83O0ocwBYLh&n$@#fBLkaK!v7xS=Y^zGQ#~!^@pzvX8Ug zX6a<5)?l)BtPZKM*v)$A#G%vFBzU#go7Fkz2q}vd=zgmKOr5g~jC&!?)zP#_%{^PX z-y@BbY<&b9r`eGj-#r+zEsxaK{lvkm_mEh*e(+3oFB5m|i_?w3b=22K8()GN{2rG; z&$KTjSIZWni@hhzR~2BB+;FNR$cI^8F>H2_8_ibNK;ze{P-Edv{h~(Tg+1Ii2g5S3 z*@&x$+;kz;hdr2$p}QgH;VSU6-OkL)s%7?TFU154d3cl|togVv4Q}+7B$vN0AuR{e z$nxc5SR2Pd^tbyd*re@_r6Y{t)I~*V8FZ4JH?15tdfJget_Scy#A=$k`8t+tkRoSL znQY6r1mSME?BMu3csfsk6eVB8No`B;)h89)enN+S405DHzO;hcV;gu@973`ZHRz&R z1?n(<6L}aErtaw z2l4mCXwrP0iC-v5#Vt?Rr1z5GV>OY!ykbpOAB-az5-ZVhQZWQh7*8iLTz%=A7UAt% z%Id4PLumFGTB&PF-Br@a)1CYZ^CV!#_bf$Un)iMcs7;3EJ>Sdylds{sx|mO`-0Ohf*H}3Z{nd!L}iT%BwmtlkV*V&7=!p@jR3GoZl&4 zL)7W}EmP=8z9(bDCgC;1ozPwyL!{Z+^!xl+NH}>H--M>JV^%IL6|6jOnl$YqqR$3GM}1|+ z^y6c+GK=>u!&!cs6iwRJpG*v?#?XoGg!VS&EtrtZU4IP8tnz@wpWOQ|Zht*&#~Sur zlNlu*9JtA!)W*0bIf|>I(@$-E|(*L zy~~*&H`E|Wd=GYi(qk5L-y}}Hdjw^*dJ?sdh9u1~Pb}?u9#6#^(;QrR0L}zHN_(GpxW`WyK(4Ume)#XhwK{|sO&-=ihb#QKo+)4#5YZ_d2LTz^I&1g6sZqZaV&kp}hsbdw2DP^HuA%&3%73(raRI%~LL0#k9Qg^6vy346}>pzpqq z!;H4k)OkTK(%xH%C@-`_yPmT2+Jsd!V2Cp&84ag{?`?*bA!h71seHPY`v&2A#Wol# z8;G$pmQ#MXHd(i29=c?`g7S!UpmrvT=twWDk>P47e)SflXYU@=QKcA;ymhB9V*_a2 zojK50Rlrsyu7Ibxm8|Y7WZljiQawrTo6WEBQ1;OoS{>CIdVm*FWl8D=RDETWCJ&xpxBMo-2iu!xG z{aY$c*Egjf-KF59S~R^Gz7AiQaNj0KPlr8%jqn7=i#ObrWwPg4q0UKXsO8@6%`xvy zjHC8LxrZ+XPQAvf%F?E5H!-CCYynJ|69!ehYFwl3+@LFV2gnl_KtZ4w{-fEkC`*r z#LN3}QD0zkU2b4ve@#m5ZJl>~NdoU*)2M?*8s$yg&KvPvi(c2Ng-0|G3*)WvM2s$O z4|gY4d~IqshL2Mxb9)P}Mtozo86CCn8pg~SPOcS(K@^`tVKtxlNq@xmE57j7%^OH1 zzn8L;E1yFBMo)Tk$ryU3)dyzBN|Tw_<>_JWx;Am}3E`b0r(wa+z6dt@cx-1+dhEh4X5q^{kbLzhD0B5^z4*Pb zvs#W=$Zum_&AkmHza9tNxE-&wB;o;!Mz|ckiP0W89eMF5@m3D^O-|ASls$fx*)pUK z!$z(EMc4jx{-K@-J*UydD((O;&SCXcGdSPqj_#ft@M`-7{4(*aIDX4T*1x|qsr_&O zi*}E|)9Eo-yw8TNnJh=;k__<>IozsWIr4Uhx3=v8qBxDNzzW=-5#q(VJo{M$2Uwd7w&+GGE>+>E8B*eE; zp0L`A+3ZJCJMQ!?UEK2gG;z_T2~_ot2VA#ftJoEUB>$aK6|0kZk*EKBGe3+{7Hc*d zu=Q(Lp7+LJ@vl{>EUQ_^CXNM&ZB3{0L%W`^%jKU^!CDtZiLZI${IVog`J5yF<*i2c zv&~wzs?$^CxnbvckJ>Fhun1Fbmz;#kb%3v2m&3n4Dxgd+%@wZ+b`>wYVL-W#>#l7A zefU=26!@!m8B(dkm)VT%)A{UWDQa&6Lut0SQ{U2V^7e!G z{v8PwUx}>eZ!*=P{HAtMfet@eC*Pku1HUrLv~7?l^-M#|@7qAt#*TB$A-4R1Bonb_ z#%U3e{fkYwnanQX?q(Cm?T&Z853y;wv&8FL_OpvNUt))Io47->UsIcn<;Ch57b#oE z_pCv&8$ZSxQJzOy*d*s&Y)y78TRk|ILr^Y|}@g4t{YaV;l=R5n| zy@_|DYqK~kE`{2*q)lYFmcyoA*dYG9c!}ua!$#4`mto=orkrY-vJYjgQL z`#NQqYVh`>t{#>W!^BkHl$=+hwQ1vL`?Z$s{vyxjq&V^`e`HYSD?`|ApYKr5KCPv; zZ7ijn_pairF;7LI{|Fxc;X(d47s$?9J5gM?P(7V2IUTKxoL=?~0EU%}w`|PU?yJPoW`5JG8^tG z*v(H&(iCUzD&ZSviK(LJS9wdnP<%Yio&U-Vv&|1n*lRCu2z$4#5brr778#FvidW24 z69*c*i<#m3<8QSiRLQ67{9SLg_;lM1c7ikzOZQw5$&873E?d;uCEsuH)_Ojriuct~ zNx5R-rx6oYVvnNOA<9)ei=)Ahc74ab$jM{n{f@Fx=U-8OH1+svHqPeVS{){GY0DBl zv8f<=ul2KwZ*f$`Y7LFZJviBLzSGD5#!&q zxTsK*Z=3&(dT`jC?VPU9pKYYhFBgvEYS})%&W&-ulz6iEg}uGl?1K((La07fORl3z zd&MmKIF5ZRI7gj+X-|1r%TPfFGbqV9BkY+zipt*jmwh;8i1+j*&AtfN5E~ddvmA#g z_MS_&&>{OB3quc6vyXYOe{7S)>YruB4k39gA!E)`ex7`fW#8B-u~qEhrL*~G=q>yg z)4EvWyCb|k4f6auCVRyPA~%WFC>n@mtiMu6x7mntzdxkj>WuSz<~i)pLM?uu>kNLp z=@&#eAlPtENG%wTXz$_V9iAFqN}s`Tx}D|T;ezdsm1Kky&OvF z+ITIcoZ)Xjb)kg(%?60~UJxWw+GEQ4+sB zsl8lPcIAS0kxz*%WmWo?>X@Cys)VhjW_b}}Cd`TVq%x5&R#f9POxY>!n*56L{=1d6 z;LK)!RqKkAcJ)#l)+JG8n$!6)ZWmZmc`Eg@bgRf;6waSMxYou#&oANS4HQsA`z_h1O&{6&(^bV* zlakqe-e$O}vdOz7@Oza9ytmd{cq5;7v&t%J;-LHnYV1`#o7Fs1ynK@f`@Xk;7wzZFR@#4N zcX{}*@B&BdncYuiebg6)mMijin;zuXCvRZ4p9p6Eiyg>5v745dH=bHBzW#5q1JeH^ zcEH-%ae{=Ie_XT&vf_wR8~(eRx%_7BS(N%48$OacOMQ^uN-f!-%O4uEYQh{I9*}$4yy2%NfYd;`P%FQjdzsY&PG;Z&XCBQNfuFgi>S-mvSPE3J?yHB zB(?XBF*~rZXxuZ;W8F*LD8KAK?6vPYJVyOFJM_Mt?HTu!g(p2@FYf-zt8CHa4`|Ne zFTIdOiIoh*$HR@q#wta;Rb2zDCg&>kB=iBhulG4Sa@LZ6Ln(@Na~`CQKCx%>UYhft z%3Y^sy)xpjUXvg?eXVO;`)f)W9M$H(dTqzACZxoT^=a%zYfG`=*avD^D5O@rjisc& z6;lUi8I6ZdN{N?x&EN-dRmFxj?(9%I!)kw<$QR~M7gH+`73DL=)BC%CeLcaRf8>pk zxOHR^&(}GP-K;i69K=SlT~k%4n_w1SC+i`5=v}nX4H)xnFGW)C8Xi#@*2_e(pD+a* zzEU>JwfPG2jiP8b4&UkWZt8xXF5kwWnm0pTS$uh|9ecGwpZ{O|R6IN7Eb(8c$N2g` z*N=*X)c>rX@!Sdt2|@iS3XGPsaRrP>dxi|f$rtl{a3ZBJu17vp9v~8X-Qc+|*vZxG z@}V{ad=aX@XDElivOLjDb>8N-X!b3mNf~#ZWG6d^P?9V6v367m)u*_Cn-!YG)2rA{ zImx-OJ-g)!Zz0=JrnE6Wy!4zT9%QG<)3BQ*Oy^j=0E6@s6ZO zhlQfgk83IA?I(FY2~oT)8&?Ubpp7D{`is2Z(MiQ(p3R2#z2QwL zd%)WyT}`zKf~XfC<3-MHXV^JAGTE5mw|2uxwrYC-Yph*F6}>saE(wfbgCdeek(Yu*`c?DU z%ZiEA&!vgn;f<%+w7vw^zVI{G!ciaB`d)^FW(FHQt_gZ+WlP09iDBD&joHkW)$G}> zU@EY2KKnuKvxpmbPxO$T;ODOwwoP(-!F{CU@3)mKm2x@cQ#s9zm7%uD{{9n}1 zcmtA*4DLC=-68}eP0`O>Z67D`NT5nP`@0%V1=1@&{a!(;A@OfK~OC= znA5^0iY3G$$ybHF1%Ig0aSh0!1y9)ImGzWE>|N2j%^%pO1;?qChhinhmzne9*685!AZ z-SQ}rNzXYp^WSNzT1iK2E70XjeY(psdp=PwpMX31d<{;q;UJnMGIvpcIq-Px(j zPc;0)vkzo=s*?=F%A#xRno%k7tC4!v+Hx;7!F~tT?>m=Yqj_1B_O*z&?RSBQ?Bt34 z6po3R0bl-PIcp)V`5~%+XL!SQ$*laQK&t$G7Nwkp*p*(=;x(};yc;*xvo}7Ma@Xw4 zrCw=0qHexb=5O2`%bxccp|be2$W}>#S|>QpwsV@<{&@$eF5XU7@n}D<^1?GpjlRUg zTi&yu;3(BePSzhkEI8_kU48HviR6j_(`M zfB$Icz8vvi?C5{%|JK9i{m&j|>+Hz;UuW<97t13daoq90{ong*M*c7MxBGwH|Hd(z zNb1Sr%s=^;oG08(Ua5G`WXmf8CFvA6$Y$XgWG3-o=q9tRB^qST?f{$4DPhI&+w0?; zqjc$!zcg_u5Ogi9q;1M%@SSQOQ1wuXnAnkobkoCt`Hy@iLG?FUq#+Lu)~3{hsZmJ0 zBMRIM4hN*nM9fcHisiof0cn{vjP8jDEIE5OX}sq)m>+o>ad0Eor*tE?n+_&shMy3kF=_=Znlmmq#G~jR`t7kom@l9eXKfBdA0Y9{nl zcyiguLZsthi?sF(z=Ya+X!Ez7!e1xvfFxQ8t4DLuZpk*N&J&PZtTqUB7i+`M!@)>l zUq8Bzq*ej$;*nQMP~0;f4M(EeMmAH87fT*B<@OU}hfGsy;yBD= ziGslw#|0a`{6y!Hw*-e>Zt1GuPCOZq^79oJ;!6 z@ruYIw%RswR({iA)EBza2X3vS3!FIn+s#5|-`a;McojxJO<2pEVG#y-4T7XmhB=P&}FPQBI&CvSE0^t07Eig^B!za66p!Uhz z8T#}J;DXPAV_VhXk;yjr#cl>iSk*NAGu$EgZC1-jmh5G&zV%^BLo)Hm?-IP+WGgP# zYh)&v6objzt567COw4@_;4H!u*ZmODw*M>$f1gmar@MyfFEoa&J@>(2XALv|@JSF* zl7Z$%)u3S0X>dWZ8~A4Tg|^Fi#UwWh(B;5ru&BuxE((#y#Ni)IvVk^ps3nxFn%Yn9 zq$L5Nzn9#qDJ2XdRfH14NOGfKHkjaW5~rV-0El%u+|@S4=--eoX!JZuR>6 z7(ShQ?0qTDxgiNm|G0zqhUr*S>L2);sm?uq<0QWRq>T)l^OZDhOU4UBj)S(-s@$2k zpP={48=2xYF?34LVP>Cn9&=x#i#V@87nWq)!fuaqVW1034s2OP9{af%A1+>oN1on+ z?VGMZlT9P!#~Hr~`Poi*=GGp;x@R}xC`X5E8=VT4UJ3(uZ$n%jZb05k6+(UYVR9db zCQS|Hm>(q+UV3OLjuc&m&%4^8DvU7bgBpWbMYn>>wJ5joB7 z;D|eC*`*WAOpQWDdU%8|+#f?MBfro;4Nfp=r`iPbZ>j*H>IOplfe+E6a)j=%kSs_Q(tSb7P*`=%F^{7&ThomGId-e#iHhZtmDIfYw5nLx#j z`N9()v+-!kS(Flf2~^LU#65WUGE>-|CH!ftN}M?L1s(Udz}L!TxgIOZ(5{t9LgdN; zbEr^spy(Q?l~&`5JA>dU&kW(9^eA3A;R^BQ_Ync_&Qm5mE}x7W*-aaT-UL%17tb2G ziFfY~Vql;j>2Sy%d^4A(OSjdbF~c)V!-84N;XN6|%{B)RE?rJS$LnaW+fF36K89K9 zs=^34W}q)<2B7B&kav$e3R^DC%+PQlXKtJee*gJLt|`BOrta-!{xtUxXHG;A1N9OJ z|JuytH*3LtF~`CEo+9k?awR@FIfhZNat7za2(V(k7Veg%(ZlW~@N>dG=HK276xY8K zM4gt!7nJ%@Gye!&J(|JjZc>1YtldG!hE$|^=mCnnOG58o>5SD-I*2?l7kv7Qk-FDK zbVn;1HkW6T*IKp^4_^&{MOh<+_XM!VVtsZXZ|4TmD zHiK~(Fhh}HM&y(!GC51^2(KIBhW6YkgvO0gL2h`FAj$nGA-!0hu>K*{a4&W;X9@Hc zxPRB8pFGzh95pluO^d>YhJES8howgaIYIdXRat3bX3!T--|^h~*gGH*H}WW`xLr+ znFHj`p9i7k^D%MJjtq}{Mi%?8K);fQP}4XXC@z-7w!7xj9#a^&eAXe97xjs8`ZxqQ zwNuc_R4qpD-AcH^QyU$;&V^G)ib3qYc>Jiii&RvrA}{Zd0&GwSnHdy=D9vl|!eSL5 z)0{3m;?&AmOE1DZ4oh+UyBEVVljDU~{+`0822Y>^B_pKSQ5i1(-A3SkIaPRMt~7Ff zxfD@DZaCOSnj80^6#NxN3$e+1ba|RR+MTF}=Dqz5x4Y^<&ELm_QYFz?ujU_VB|J%f zSJ?wpHCZOUX$TkG`$2x=o!}~|%76#AUlWmrfmlBLH{3at2!FghE+iiQ!FbOi^i$Xm zE9JefHRkaJ= z^yekm^sgEIU;?qau^woVA<55nUYM>t4K_&JgSmT*@g>7laKO@xc;dsw96fnxYH$r2 zuMWj2>Oe1O1Mo7Wqt(j ze8P|)cAz=jEbQ?p51*kB6g(e-9k-^T?^b;%yRi=bdpiauyygf`k9hv3t{W*EAWHs78E6l#d+z)kUF~(pD>;&l-IoulSp}F(R&uPH=TnE$MNT# zteJ3Ly#>DWTNh;IoFrm9TS14399p~M5cc~t1N3Aq;r^Oxi?10bFw1vop!(i4xN&D3 z6nkn2pM97p#7_p87@!Bwo!SP&dQv&Bj*ViX+?xI}e4$Q@#`x0Vt%>18%IgwI=dA=FU*VlT)fY&lIzHux0etQo3 z=9qz0)6F@_>_*1p$PVU8-h0Nq>LWRz>I7y^G~#$YQWWgDvV?Kk<44LGHj~-JMdtTG z3j(UHC(l}2F|CD#WR4F*PWSjrb4+VE9*GrnHQda|)=ML!yS=1_nF5e6?I*r)4sjGu zd($OhH|Q^Mxy0FtzsR*EUNCRJG>mzXL>sjYGgDHggLk|*)SFX)*2-(Z(?3?z(#C%D z<?D1*$I=q4FekEdJ^O z4-e-8?LGPAT8F!+*lig3w8fxVBimp>nm;@%eU*82+J?xDc?4#piUgzGX-H8)2mSo( zf?Yr6;GAcl$&m6gX2A$R13u4yne92CS002TFO-sM=LeWr^*N|I;W<4=ClOH3KZB@Q zdVt^w(7g6O=7o3;>Ksc3sr!9FoYX>cl8hb7E}n+;Y9-;R2W22V*bwgsUIt1CYcl2` zpLpP@h8`Gc;gO>OIL>e#w_vXX*Rn)oydNr|h=C&Lw8<7!@C}5q&mmfKcM)3dG#^Oc z&43{z7+iDE7Oo9zVZ0Y7BU8>S{I@#}Ug7^HO^TI;L;F*Zg1j=i+Qy<4*RtX4ICFH+ zbc#^YGmy0SL)wR!^xEy*V@Yr(i3K)#>*-xN=jkY~we<5_nvAP!ioN`-9rSsh2x5-C zAIHs6hOxKlZ+LC))v(m-vtZRo0x@k-hJ9{8C7qmdi0GN4N#A_& zi4JVcAvn8*_4}s%ZD`>iCtj1v^%}3f(<>b()AtwX5>m;G;A4*(_=iiFP00z!;*J^S ze(}JhPB`rD5s+mb8rZ5_3_?DOL3j2NymrDUX}ipntY|xhv^O3DEsbLG#_X9m+Mp7Q z^8}>aJ9`|qH4|Ley&fIBuY#Ajk?_ZW66vq10OCV$17E`s#?_6)9hvfY*~vxdw?Yo% zQ=kYl=j9@O$@6$5LteP%UXrjz$sMXaSObV5h~AoZ;Ea~paA(VE?w48_p+_+EVU^Lwm{01+L)gFCE&wzZqY; z8xP+VFXQeCo*@iOxl5!!ttM2>y};Dym2_28tiU(Y1Y@VCpheCaucBC{Z|`Y)w+mB1 z*Zw%5e=QDq>|%gn=yiI%@D0=ORT@Mp?IqhAe=-HHr9nn1L_Z&?fCDa1iGz0}(08!} zvR)wv7Jl!bU8l66Emoh%8v&EhIrR+m&d?fOX&xi~{FElA%WOo;R~dp+!3n6juMxB- z>OiXRBGjsIWy-dwf|7`PK+$0jc{S1S5QJVH8d^YlioS z1DU$Y7P3=D0@ls6#n0D-;NG3(P_8zbY5f{OPU%8G+d=?>`xfI3h2Igut^={|OUSX5 zcETk0IP(3u9D69l;;)7~xhHLRaXV!0PuJwe-aiSSNp+A%6(fl0sb|R(wev_EIfofOGYS8) zz6NJYN(hf$xWFVOq@t)_N-*=>EJndF30GR)B4bB8nR+Q2<=m8kHx53e`*+6S6(-@} zQtn)I;N?Rk>GTckQ0O6)R3dPbaRvBMlEyr|Q-S_nm4HnWt|&(`3Ol32=;+!f0=*V( zLjQ#o9r72T<)u4t;o3sXD{aUG4D8%ASZqiS^gyfCXboHfp2D{xYmli5uDxNJS7?Z z1J;bm7ZoVId<*J(;zJ7Y4`O*oF8Up}4k#vQL7X6ueV?Bs`&$W8y*&Z#{gMIR)yc!` zXf?biY%V#iZw*LMk3vcPevA~5gA1I?nfB&R<^Yq(bm}}quTzvrW8n^%YPB7|d~YXo ze>R4@lq<+h3qH~pccvb>DY17X5^fv!!6v|jYdyF zaOtEe-0yS(W2Gn%j#at(&kmCcA1{y&mkL1C&RCqBdILpBDsmSNxxnQM_M_MPIvJl$ zBsoJd6g6seBjbE&Vchd3;nJi*bV#!Vw8~GyaY-+6@1;M0w(#YC&0C9av*$sc_cQcl z?J%}gj)bpD_Hf^Zgc^Aj2W zK8MuJNI;pp2u5h43_B$-m}0;Xn+NVO30Fgrk#+zwT_y*8w-=&FKg1lU@8w)r%7Vc| zb)=ErD-`%~D~k52o0jJmmPyBiSeK|44lyMbdIL{QQINv6BmNlYj-;Sc7C=>84O#uq@ z=HXWshshHPCx}<4c7t&1&&)HBjmxg)YyFa^o9Hhj890UQp>#BpEGplfQ2&<=Yygqk5NtT5*2N1n&>K^x(mbGax>^nvEh zoCTjAtwyR3&R`}-2OjD-M*Lq75dWJ5G=JqrmbfJ2x)bM6?|=t7Ya7F)FBxH;_F5r( zi&C()Q$|=LmKB;;f5Pvt7K3BroupS+JuW;~1(q(c=f);{W`6ahfN8F^%(hmH2Pf$P z*$k4qc|{*+{O}e$+pB|Q-&Nwf%WjjM>nymL51ir7aoLA={wF%^c^S^n(PLh%Hs|{O z5F`1&4a~8IF#1-!F}n3|Cuzr@hK3r2VCZ@==FU+^Po1OfL*6|m7r)9z2^rUcZkrkm zp;lp!3NE>RRxTOv*%+mN@p7!a29}n7pIe%OVr8!?>tm`S_(*eut3WrA6akbkoNCK>4C#m zC_8h2#ILJ?>gg0zKXa5g#Wx3Miq+BGQ#H(Nx6|Mn{|~wP`wa5yDtEfIJ`0sQ6re!W zaAdV60^M+R#+!aj^ht^E`0$lsmK6`VxA1Qu=yM^EJJ%?HY48eV zs^c2L-pAiin57fW6s&~q=ku8-T06;xs($b)GYy^T-ijXwE(PCLJ!e|B7lE)z&%xfR zSjO+sI;?)w1VptD&`V6eGQ96q;9aFMR=EN3;~86FW=cQ3$%n^G?5jsNH#GnaEoV6K zxFs%7dju>N^)kEz->=9#R=5_Asn)_NE| zm~Mu*lsl5Iqh;Y|t96)4JO>)WpTLnI9sFnf+tW^8nImBv@#^_P;Oq1ps)dqh^Zb6g zy=+Y2Q22u*jLf0wH7l7JJvMkstv*)RNRvAvClS*#Oz2#X3 z7Ae!=!q{K(MB2B{lb<7pf%iC>%6VT*a2B2>{Qr8Q>jtOkS>hLf+-HLD+Cjqo?Kjf= z%VzZO&IvM1rx$$MoQA%|F9!e0BuV0LKFD5QfqLF?@#Y~%IHSOgyK!na^!^!wKJ`q7 z?px--3u`S=&bdO|ryCE}9F1fAH_16IFY z&lKo|VV#0+Xv&xr+G$XN_B_*onoAkY+&{1NVf;8Z z=6$%4)*Q@1iTWSOZ7;%6$2(>CH02!n5xSFWUz0@yndN}L))x5riveZ@TMPHJ%He`z z^<-|%ZSdB9Hr`jB2;K$P!JM}%@qM|K9>;hXyv^k5G~&d!ctnvp+%JN+ii93B3n7&0`=e% zLV%0hXTw+vlKaN^43_cm0xBIsQuWrEaZXMZ58X58{?YLQmo|k1zem3CbMh(t;e8uo zz8Y{F2I@do#xJtVW(@S7tj0}!%i+OtGw$_~LY!zhjh2%**}#!MMU-xk7Tle5fxhzi z0dryM0JE|>pX_O}C!8e0II`<`jCOAZ*`_ZfT@Fk@uEw*8`ZTWwtF3m-s|qghetfQa z(CMl`LnW37IGad^KA*v;Nj`31{4bEPRkn0dkR%~hWlu-nHXrYO5oF%m%VdbU75Xf2ya;tDuW6~SHi#f99gJ5ki_k^?_mAI9EhiFjqsKCafMV_3uMo6!Dv8hrVv2Q8C1 zgIr7Ya%(&$LCehVLbL8l(zrE7@HM(dKn|W_ma5((GVfcHTeeAq{SRi-4<}`SVarRL zeI@q@)4(c5+fbdcxorxXC;TPLo^Xh+`Wa-TbPdz|!~aD?5byxr_Yrz0&D&_4$TB}Y}b(j*?r*d?_x44@e!bt@1W-8 zHlCRzS4euW%HHcWtk-O@4gnk!kfrNUN%U5G+Mao*#`K&WG`|f^O=Ji6u1h)VY0(CL1^o- zoZ&u}Lp7%c=nG3KPdB^!akx6_5I`t!%?9`YdPb zZIK|PC6b=d(nRaezadz}>edG=Fc&N_AqC|z21N9fyPRUPLRzD>)pq0e2X>v+(KFLJ+!si~M{1tT<;&w(7GnqlS|ZV~av4@Trv@|8 z{&9@oi{jJ`VY6s4Fw-i>&Z?;>eX6qHsPl$~c9$iB#cKx|9*zftd#@`Z@{?yUg_GL^ zPh4)=%TD`MS2919-e=JwuwAG|ZXZh}j3Vc8@{A8O+*p}LpJ{64JT%fI*Kr)^+gCj} zS9xbSq3;rD$B+k{RwpIWO{_{QA|=l9DaSd_enr!TGG=tibvd$UQx;)rQ%xQ=?xPnI~1HXlhCT2y3#2%DxhW-Gv?| z)jSTVTzv!rs=tH0qjum_!T|B+tUG>nHxk`UDV5Zuw}&Qy_h0UD?4$?n)#f$RS|tgDXw;F`%rz!?ac-o2ZYAlOq(oaxaj{<UP9gV7 zH8Be_lbF7jF9m{G5rXe0?8!XZk%mbk=GlNEE#-Goph{ALn@U~GNj(>4DL^~)h8_PR7YHY)<$nF+}Ljtl4umV)c5LUGiPD)_bk z47sAJnDpx~1%t~0)>M6qS}diw`Rx|mUd6Y}&vp68WO@fYo@fb`Ej)!&Q%Z2Iqz^JW zZ9!A>+TemlDRl3jr!aY(YufcE9EB>7_jUdOE&uCW!hg`C+Q{Z19 zgZ*mXG83!&~1G-G5}T?>IMm!Z8&dv68{yKoaTnR}swZn}~NEI1f&H zMMKXF0{1;!N*bi}k<%ARU|-MK^gv7`{HvkMT)#O!UJOdP|!46{E3p%g~p~*(kSH ziOCE8LmuSlBe`FHz$#;9=<`rYIBfU?-A?^P=HGe)>}t>8%PF~7p}>$E7cbAfpw9s> zj6`U`#!M_~ibq#7wYd)GCE$q{{y?m)3WbhIcw(*uT@k9x?eZ)nGxVjw&JP!vOM+8a zUaA5gH`V1@ERp90orETf&e!yd@b%d zIyZC)M%u#JYV z2WR8ti~q=j;yg6GtqRdUzTq7^w?WOnT<&3qV#X-5m3W$~3ongsWy;I#vEOw`SY%2F zH+dupZ+>~gnPq#4jJc)^QlSmhan43#3Rc4P$efAMk|!&}BEh!Kb13|n65jgC3_b`; zCu9H0p^6=Ozk7f(ClFyQ_8p6nZ z-Iu`jbLz;&I07Hmm>?|8%Y#MWJ8Y4xW7b3^A!q+;=sHOkdakk(hGieeMorUE`SuRR z>DEQ~-g*War=W!EirV3ZoN4Grof!A7I1gL<_Tb`IM#AHXi7?jmHZ#9(5(=MG3X9se z!PD`ELX*17*yp=Ckzm|J-_p2=o;FSds|RDinM3R0gGt6P%|L*rS=Mm)+RMR~$M&e| z@j2#YvJlLu8ppVz8iM;!1Bf=dBL8cW;6vL@P(AP$Rm4e=4{RS15gmN=_-+>Xep~<+ zPwzt!lT^vSzY@VC8Dq5K%`~)m)@ATQc`?{5?|_yav0?W1ccAukXYkfw67(>U=3cxJ zEi{U^fvz#r$-#$1;AD9tF5NAG>-=1}p0J-Btx*6UT2#n81y%T?oC5X+*4*}M$KaF` zn?bz%e%Qk)!rzU~qFgOQuI-#?*v;!D+crG|zsDoL+Kr3Q0WstTHNOLjd96(FPi;E5 z;3644FO^AhF-MzM?*pk9>+r_aZg8bb6?vn1fk1tW7#Z!vK*9GbQH-7j&Fs9h#f^ zkW5@<4;^$pkoWa|vO=Uw#xE3+i;i0{v2%M-=?71&b8sp*n6pl(?#yQji>KiJ-dt!n zcod+my25XD?x=pM8H#&&mzh_P0V`VGk{Z{h3-#s&0q3gkOxF7_{ID|}Hh6myes1c* z;~MFJJebWin5g4|H|fxUX<~{ustYsX?$PTXn1HNBrNqC~NzB#f=NY**&djFTGvu$X zKk%DkGx|~BfQofLA@SRN@Nla+wrTl-Prnkw(^pMU@b+aWVWS^Ro;jUtdh-?!mOwCH zHwE24;*5T;TnTm4rlIG;r&#NQHdr-%m?_skjIw-u;dQM!Smjwij%})ew>byN)(ex# zIhrxx*+Dn3uP=ps9kmYp8{G&mbWP!2nU}>Z_z}poD4W2uR$9*L9cX*2K&dQ){YG zT;O{$Z;A!<_?(GcJj={wnmr%NBHBFGgo()uZ7Fr@<*5 z05xUh@lXFma`f^`rkR_Aif40B{&Zvbz(_;{)f|$osLD#02%*1G8s69Uf9u^|ZKh=cq9hpmWM0W^|rV3ndcOEHo&f^(xHKD_t zU!><>Ewsl_57zf4qaPOwF!A0D%68__!!d{{C#_)NO&j=Q#(BKsRw@4c?k=M}MUA;~ zNladEeS>x_6cBHBq`+Mvi|`TMa;$yS9qe7wj0E#6@w#`3SS6qaeiYB(p1f}W;*ZK8 z_-q;8elr@Rjxz9f=2@mTEjbeXS4H9k&5iYwyE(lV5;^ zSJk;|<@ST*co($9RDivfnS&pHIoy_(NFbvV2Yv%jl&F0JXBW%`$3~sG{RiUFylEG~ z3nc?4AP!;PHc9Yt{K|7S{}QTJCqaw618_fCfknbE%&#Tmvjvz195>oBlDay~wN4-0 zsq>TEeES_)@0SMXJGRX8#dTbp^|P7s_UZ7e#sO@r=7u*d{|mS3ABBk;wWN;EWQg+o z@xhul=47}8*L&qbq<(#<;m-m~c#XdsTdcN3moL7DdwQFhs-%r%g?J^{RU3$>Px*na zMh?L#oAyGLpR4JQj$XuI#Wpm5%PvMb%n=xUT8nPpKsdMPCfpd>NPDwQWUS#Ja|amX zd!=z;X~$_87mVnM?G_}E&19^oAoL<#1(=K^g7aS>t!r9IN6ADmJ$H7Z_m8B3Pu49E zdo7qFHO|v`$x9)b_~&S6#8J?)HW4~%571?wz7a=US{WO=E9CB=Bp8$X5!PEv3l}~p z5xT9GLyfs}!JHlrSf;0qg9bW~Nqa6#e&5M7nbsr0qJH3YD-kPntih*TYGM7(5$0V{ zEIfat18@_h@V-yWaBBJo$jaSjWNQw9pj|rP#>FqFBjzr;GBF3r|9C-^{)}N>POt%y zlhTn?+#0YVNeRBU9DwhcllY0rJ@UZ%GbrJ*3f`|}i)U$M!jEZX@XJ9tFmv51)MD#` zfulF9-QNOh<_+RQNBhW*;VG!|vlE_@9|R|_6TL2jJ$4tzx_hs0OPRnB_mw=U4y&XOM`2s zs}C5`1&2DG?o&%O0D9oKc9C$>aQAg$*HG1kU^nec@xnM1EHqN%S7z_;Vd z+=%#CqJQCIX4b_T;8`GrEv{POvx`o{%Kc8vZTmQ8Z1Y(#TgC}}nCF7OY_fnY&QA!n zM|DWQK?G{dDYV+3zzu=wFs67~!}h`_j8<7W2+lFb#ul^j!e{5;_0qY_Ok*RuQ&O4? zZjmLMEq$1Zi_6LUpirE+qYF7@s}MCma>YK#s%*;0m!^47tte+;-e*6kSi zD}o8S4PYrZ7JDq4fhBgUa@QQV2UhoACLSvGb1b*q0t;nYnBG4lXrgT|sF_d+D_1TP zu3kEY+;?(4(>(busP{e%+|I4Sox7s2#_C#Hs&pDy(q0d)nihg(bsqR~`y!-{b;#W7 zwiu)|f~#S!p!@bbytwZn($mWn?A+qU{F;0lRD?VLV&I6MJTSs3a%N=61d`k%m&;hc zbp&fZr~=!6=gDJ=b^iTv9gNQ?B^{-dq;GZPA7idI|3`Rm} zq-Wp#euB_fZXF2F*@)iPA0wqZ4nphYJIUW`zhJ>xO;Ec*8F@G?BOmn5huez@I4kx( z9#W~nJ6b=IJN`J6Flio4TCf8>54?l=PX9yP1)Wf#LnvIiSC1LA%|h3f)WKENiqPT< zM|jcf6yCRGE^^gAKv!L^g39vGIiBep;flBK!I32&nA_$N*yq_LdU_B`G z-vAw7-NN~U>jBGI#tms3e}`6@fuC9dpikiup1A4+_I~BX-E?mV&f%_Lj7p>h3Q==V zz?v06bFU=avUdoyKhMC*`D(&{7kufP>qNkH+A9?F-2gpb69A>YxPomskH{QWV$RrH zME@UO-x*Kk|Nn19l$|n?nHA1C*L$6F9VtnYG*Ci`ijtIeX(%g%>`~biQL@hv4ZDp< z5|I=wqoq&d=X>{mZ zWH)kb-Vtu!#y&dzzbn;n7v>PR0YQ#VEl2t8CN5m;#JN%{N;_Noa%zr+3q}UNaV!sW zIEJEYg`1uKaTSvKxX1J+`BQ3=wCd7r+&B>jjsb5-=rMDl-`xegX>aqxK+Nqr_MN_2HrG6WNSWJ;2h#WY`0TA z!ptAfJY=5IolRS54e}pvlC7DoJ*_=Fi8Wul!%diEQbD&Tzoadrq-tc#xm=RlAR#)kJvI6vkxnoaQZS0`Box4c6MPb zJ#q3Oy})~r=Q9z_AF|p=%Y5>oTG1fAk9mggk-Tut73mknhqz}XCj`$u-f}c{i3uFfzY)lKUZU4u@#1o5T)ECOq4@tCO`S?7p#r?%xJTFH$p4lL5;27|yR5JxH z_jJ+mVcGm;N27&WQUZbOV`=&)^Ao>I`X7C&xtJb$Kb?D|c2(f1qRUU)kjgjL(B=x1 zow?_)Bnb1iw+Q9?wg_~GR`R<8N2g~+S$ac+lKIxWV%qGGXN`Anx!fltCXG>h}dJBZ8Y-q zu5YNx3a3R{V)?Fbr(56TZ_=|0R|(jG453+cJ#F;qG~fMP5$8~F9-W$dg|?|T6wbY( zB~-ChpgToc*)p>u`8#CPc|fn86OdiS-4T^xZqaVal~hULKaG1!FLh;bQ}v1j{K^tx z#^G*`o|cFpjjh71IjzF=3bv&krP77I-A9Gr^J&2hwZ*jSc1dpR3}r4!PZX*@t`+|C z&EfkP>d@*_3%SNic!JsUu1 zQ-t#St2yFcExgJ0PJXB*;6gP(kL7(7ei0dEmyW&S|4UI6$c9_-H=fx~e{e@acjY&n zCbcPgnP(qgO1zg|e)j}z>o!mLy!>i)JNZgW#Ygi0+B$GKg$(+t_g&#-%it>6?=*fH zr(0dte4FSr1+zmt6WGUF?RZDFy|4EC8iM-szmkb7ZupwX1Ww9ZP`&IXtGeM!P}Qo# zQ&`LK3>l9GyjiwVyj?HKNbcKb(Am$Qy=)+Yxapf!#kGm?b~tO0li|#&uW7~DA!!25 z5iKX&)eEW*ShLB%rlp)L_hY#2^CHe$JwrkB;etC zchINqM+>x7o(m5A)S%~6`}rPTXXtjZ9kkiRI9)mUL~ugcL-=*)PyWDI2z~4{lm6K! z$z`kD7UZ?=5~`Uaeqr!!PM+*)I_S_K|F><20LDhqCIUO&i>zASt|boKa{UIu9p7?+ z$a7ucLJ1A?t#9^n?+r)LeMhwfgA&s_i5kIz$}v^$2QeeAgW_L~+Vz|Cv2YEc@^KZe zabqagY2{;~{rzZ~d#zodba$qZr)I?U&=2N%C%qKrt?K9G-FPJk-{CCC@OUQJ=&H^= zV||wUTRM_f?DF7fEoRMjObFag#c1=$vauYF;?47Dk?WU-2h48y_3r%I^8^F&chn#mh2m<(a?v z#!h`Zhx0*jinMBVRUdPUVyAfv*w6cw_|(S+y-|SuN+;&7%j{-hMOrIH-$9-&Nx5 zT_eqQbsS?WXUdbicr)L5asjOtGKcF&_wt>W%J2^5HgLu^i_@&S5w?9qsGvsiZM940 zbzZf>H}OlS3Wz%ok>?;*Jid)toe~6BgY%%YVEsh8I*X zBN!5P^L&!t(3`%b(z=}WLJ3V9;ZJW}PXC?R^nvBGgkPt1Z?PrO+@aG)xyOzra^7yN z;#VL0Ehx%u=DSXYa+P-Wv2~&^a(ef+(__283B(vNoJBv5aC`GSdE0DPa#o-D!f&I* zg*(le!k;4{+@Jpia=GcV1*6!Jr&(MgP`TaCAK#r#7A-nQPpW1M+miyhjMz|)TxJP9 z8%7G}xMc`!7Rs96`YLDM6!@DX>3*KxrEy$1zB)tDw@B1ntM@xCSgt~MI_c6qj(dbU zXA%YH8DF?fYaHm}oL`*m^Ydwk>0Jn?x2eKY`(~J@FIO^;35%i~FFj^&9F66ez*~aT zM*j&j)mPVSP6{*UYDaTj@(u|Go>>cjO+MweeHYSNch}Zz9oQ|@x)>~wR-VREE>+wp z<855#3A(0JK}qntr&jP!ZBqDcypZb^Z7%p{YF5+uQB>eyI9Je7fQ9nI_qaE566v0c zRyCX*QNsFl5p0XX24d;Fo98nhu$i59{9>aUoF7ehI97r%LC%>0-WQpCPMzaix}ZLS zv;9V@;HKSr0n_{wul)F9&V{{NwDT@8Udf6q!LvRgTXFMzewfVlDybuLXnmtRUhCOJ zLCcX>)vZl8d4J^QvmGzbqJ#2 zW^aUIjnw<;Uhju@==cqef&}#<;rd@T+{t`n^KGv>gv^FSx`wMRH2hsI{4y0NsM=;~ ze#y{{TfJG5TNBVJnEZ25SYz}>(3-DnzSVUO_sJS7THFB9RTYR{we;Xr{0I=-mIDHHu|M?9c|zLm$9zuUlH6+14+jMf75`OB%KxSv@)Gz# zPqa8kff_v(xl53=+>!Ic{ykkF*3F)*>Sg0QlkE1Negf~{zx-#M&vdb&54}L`GSOL~ z%TpB}9y9J)S(pQn9^*L1g&@4!i>Jyx;#%LCzwCuO4}r+_f$S} zoO}+`fy`Wb=jb1Sv!0kRaN`JnU->%T^{?IZ;kWZSuQlrFy9*?RBXvsC7_Cw`yegP( z1{X<$vW(FF4xf|qG=lp+AVM$}!lqv=`6n<9)E7GK>lTEjr*XqCj?q`9vS=o=h%;kq zw(#8}H9^6jc8V*>TPi|9m;Fm86T-gN}eh<*Skyw`)mfOAkcY7KH(Sp_~N zt;acrK2Y^qHWj>k3OtK(K=OwB;h>WXt}1m#rQ>Xv<3T7a8-j{I8$p@kaAasbf$uIf zWn11@#16?fhI`ddp)wm~67$^>rzWYfpX^>q>?SwCkEcXY!gEO?rri(qAI)Vm5;U=0 zZVz1gz7d5Ee8(*l)=2E9D0`3=!y~(f!RKE?@Sw3IIUeVZSH;d`|DLgoEZ&#M;I4=< zja_w-^#`i5_Pm{bK+O=SA7tF5m$Oc7N@AYuSVi%k=&+V7d}h{{5@9y4Y(49Ik_t<<%$XWD1yo&y z0gTAYqMqKnhbq+4A+uy5ek6I49KLs$jh`%MCzqMP;;e3Tdb>XP#|Xn)G)>rnAet1Q zV=&>@BBYt2LEb)0K(91R*uDj~@dA}`DDvMn>{B35Dn7kJlRk6VHWh6+sP8j~@bN=3 zXXlW^M(6MY8x?l3doYoou40fmc#V~x`wvP^w17qujD5fQ;}x0t*gH9nsL!$jL+*yy zAj}`9?$E@)?2i%#HG?#3W`S+0`{ByBj(FQ|Wpv=b-9+k@BYGqp0aKEun69$Hyv4U* z_aWP9D+?RxQyPG$a2!f_Y{FHWq;LgxBS%%|5R;mDz@R9erB2U+Q!CPd!0-?hScT$` z&ov3%EJNmULcuSaWAK5d7A}u(f+_9>r0CHnxEYdg+jeA` zIvZxCM8SKCGWd$QG-?=8Ako?%k>{V8prF!$jjscAM;T~zK8^d=c9YuFOXRhV1Naj<0uRl%!o8~ zBNWLrS%C|6^ucfKdrSu{ZFpel4<%tK1#fCfVyoNxNztFPICZLmvWR&Er0ox)A_H^W%ya?64&cvTGjqq@3CP?=LtZ!es;MAcUa6k1G)NQ+s9_&0z-0kIv z#kUa9t#lr~^f1L>>pA4NhDj{GCgZdGtKi$n3$XBuI-dOD097rt$<6mGQQBg2h*dh_ zytQIDJvkb7R?86B50KIFm7vFRE8O-#6|b-kM$Xgc*8AB3To`D_Z#(KUt z^<`W#3;i`l*_AB>*|`C%DwRU!Ed4T8*y04rAm}h-IU^0w0sEPeHZ;@ta2pfcE2qBY ze5OAAtN@X&&%nI-txR=c4)dFH7WME^1!b6>4I2M_1-lM)F%AuWH1*^jrT%*FWxVT- z1hds#n46C`1E=az)=Im7aLx6H;85*Pbm&9@woe%(MZkk3MP`D5tN!RpQwnCSXh6Ib z>16%aI=uF63y8iM4PPgQ;7f~Tk-?gHlJ0ODy;0l(mkNuK<1>G(VJ?XtYn>+QOS{pr zeqWGUQUL3fBC+p_DwOs!l6)(@g@0K2Q6gU=84EsL1Haz6QOlXJpleYRJg%sVHJ5G0 zD~_$D#(zmumknOS;5!oV?!MP(+ojcLncr#3fY-<>K&`MOPZ@mr)`ql?Yr`5PIRJCR zsO5XELgDcq@Wo$_unf*=0uBh`TWJg z<*_*OS2v}Qt_wYD>(Qyn%kbFl0X%Elc{upS3M?AxMS%mgNVa|k3=z49hpNs)Z%%s#2XYA<2fV)sFJ62eC(WxQpHyxUhrRK@ z{@?`iKU|KV7};W*e|++Lj6wEf4FOfn5cntJ3O?y4icIhFiCFtNbaxdOO8WZYYacVP zE33yz(k@Ga z9$%*{le?Ir>=F>cnGNobEeCrG-yb_l56*+LExQY*b|(Db})ay<#}ni2AN^$ zjboJct;bY^e-tv`FArm#l5y8a5SkHl0a#o+4xJp1qO}$!Fqa#IA2}XGgY|nTFB>k% zunR>pPoz*;P&hV^9z$RMIRKUjp|n-{P@d0O@bmLkY%t#u`;}zkBkK0-x}cX7cXb}l z%!>4XR4m#%TM{_z=fi)RkMTR%wRpqu1Jbd~i4=cb0TO34vFtT(!Q024fs(5Ac;og9 z`1$rxylkB$xz(Zs_FalXH^O|e>6xpp zMa;fc4^FTour6AOw>D6S?XsG@=vBmP=Z;a2%yvQT1}B`89ES$qPHO=%H8`$|4^$=x zSQF=^(3HkEP}F}0D_nerM@}aYjjQgYDX9Q>pVY&C{Hr*zU^({tP)ynxdIW6k0lhJg zp!{GAj#bu28L}CqIzsR2C=fSwmG7Ppo4JWJe#-NIqFNpCv11+Xf@Xws3 z_|x(CjKd;=Ti7RN*ROb1%;5?U-ToWc;2Jnqu>sC{T*>+rXvt8#0$9tKl}y|1ADIDO@j&Gl z3%jq|h_?H$W0e%2pz2Jgz%1qkU_A5(jxLFX=6qL{O>Gdf+M^2$T{Zv{xv!uVtqYqb z)G2Yl=d872rQp?jE|~M839hPM57S28GkIpxto_ctK&tI9cu+Jj{Xa!PllJStX=^EK zDeQ+YX+LNeGKj<*AK_)M%1D62A>!@B18pjrNaemCR{r%7ZA&^xCj5r6cYPbU@MSaH zo$iUZZ~PBRsrrzceYNOr{}I?%mw+0zt#HEk+31GAp5$%lMBPpS;Qe4JblRuYDZHM<`OQa>mTfX=|YP(o(8Q!38|*ID}Nf1JQrXTKr7Inv&i#1VVg2L!U@< zC>Q<}9g(m{Is4owc`F`(tR8qjB?rVF{fq)G@nNNDKP3W~u<>>i6b8HmIJHG62Zj5YN*g0ao#ugN=C$_$3sF*7m_ zFqZVJW*ME2V73(00Cwas>vd!uj2QU>Hu>?F@VEa0^n))PtY48Q?P$eYkO>ID7q( zha_zDJ1E=KgkH~W!WQ}*>@?#sX}5-?dGidYaODDw{#l0Kim9PLSrXET@fbZISJXQaPK7o2P3eYyfVSw^zS770~E^x7QHmKNr8~CLDLj4OTF>c8wlCCmf_qDz7zm!yTe-0PLq+P-h zJ!^4nw-iV)PXQxV@yNTe97>B^#7Vxb=)HI$SpGvDws)OGzZSiP8;!&9tFaN3*>H*a zW6%Od$3qd`=76dXMq-n+4LH1LHgNee$_yMR1zvOz820N!X-ZDmz0!c>UfWA<+h$VF zGS5Mw<`ZPqsfg&+9eDNc??@(doa*AP0eAAQqO^o#utA-N%ib=6Nm+qlt{(*ZzLe#Rx0F9Rju~)zp`aX6XdfhFftVIiu&dwmX@|h9l zt0)jv<3e_RWHh_thBK_Nk;9zEjYQ7#ESAl8XUB*5k?gC9@Jx3jbh*kU2~~;c-g^i3 zrfH1u?&4e|Cx0Cu^k9jy}qb_I;t(20BOHPPus*_54$3j7!Q z8qG8zDA1%ITTx8x_4pHTmbYi^><@<`Z$AM2P1z_==K;R|M}wUgyNaaeoC6A8w_!!J zAMQ1OjHG|PTUIc&a%urJDbfpP>`nu1Cf(@TsS#K> z-bd*eougK7t%67AFN8%8s!_6~C`!uIq_jLwfxTCYU_@F3CANr%M2+~=t)Lb#AUnb; z;CI5OuNC3RkPZYp+VH%jU&PbXh8#bg1RgsFBiHbF{H{nF`#GhMdA$;3(eMLsbCW(~ z+XUf^HyJP^AewmO*CIK4Z@73O2X)Najkj04hV>7Qkn)U7l;!9P_TN|tXFLwZD;~&T zgGZsn&R>~0<*kP!6CRYrb62!T#S(6=GQz%=<9O=!3AWA7>tv>`Ivj?-(54u9V#&6~ z_0N>pg)7#QGW%VyVACW-f5pf{VHR4tRff%fwicVUe1L;rx%lGa_qcFf6xvz+o%k%? zh3A=n1_c`VFlzH(d@{!Xe{~XLD?CO-O8z8RC^^KcDT#Jw-!GT%8hBpXbrk=wV+wQ{YzB=;tUoledUkKIo zRdCOlV4Pc>2sbVZBXo5ndN*YTQXmf+U5~;t|INm5dlZSU6D4+!Sb%j@lI7$w2zIAk z0v^xWK>DfEc&&>&nd_xStl!N5X-8xsi_wlAmW83d$u4}WJpzwO7y&W%FeU2HfHpoE z0ERj(SUigduXA33a=Clp!iy_N+e;D-mX+Z-&fTyB3{zFdiom4{e3UqP5|!_`jlUi} zi~YCPQBR7_vIKVhuv<4CgnaQu)yu=MK|~|2I_X35mr8@h*%9cxk1YOpW;42wrbOlm zPvG&=#nbrr0Cc%Oy?EJ+Va`59@^9ubzte5IW8J6Esze^WpvO_lvuPb$4wWSf!M@CYTpxm^yvN?xMG$Awkw%S4jXrpg(G~D*6{{x zTQmo|l;6j*XRpH+86BjDR|Azor7Y%`xy2;9+vj9q(kwm+!^K5b1f5ymK%3(T+iiOhx^MJ1U8K}438t28xBF*=% zgv{b%3vqi`sL%tejq35uXi_|&Lye1h2-QJDg zUYS7p$^N8gB@chPiox>{DV9%5J@~6S-F!KD15mDKP+iJ7@?#Ui>JRFvBhRwI^~D9~ z^*}M48$`Q}O7l*|<4-fcaAFD?@(9R?7T4gX$hGq9&ecp{&Cu z=*gv*a97D87Pa9vHI*j;{aVj~j)OB%h1gkWJ2RSPy=4})LrV@0{G115E#;8lZVil# zQ>LUY{bo7(eFPo}BJhIoS6Cg|1TW<3u(W^oQk;3iz(h9-{ImQ9zXmOZmldNyI;m!@ zUL%FB#Y(`Y;Wv=XeSqHtWso(ggdqL_AUn_wy}S3#r#n~S_{K62uD$^p z#qGdOY8PPG`{QIETZj_%jbX-iE?N@54!Z`oK~-s2B9(j_>FOAR<~SqhaKaVqp0`BF z=eLqSr%iF;nNDi|oF1mDWCAozPyl^_KcSaIHInZ%CLGb3WPQnF%5l~s=xR}o&QF|1 zb*FFP#O>a=68@nsC>{kaUD>Gd`f8|s=Q>_9Uj@B-au#%i1fulNcqD2?LG#@yST@lB zDR@lds-AaXG$0=>5AsF(%?oh7!ZAG969yLQq_HA+DX`Nb8;COj{4AuFT`dHvPO$L8|NKxQAChnPg0X!>AxKF61>)k2@I~uz*t~{8^bVAuwK_KNoOl`B zvr`_YT&jjky46TSCm%iDZwcsr8jAf=$Mapok&3Z4NwJN=ALsakAMziR# zJtB6KV;0%yRJsyewa^VMxoCygYd66^m+iH?|xw3s5%>-tRRvn{s4`g z9cT&jHog+5iq9WxBnl%+B3p;ZUx<7a~p(T3_!(s1$u6;)@7W<4xLvO&7&?p!{e{ptq#va^}m zXLbzUXwN`%3*F%NtO`6~u>kFVq6&g^R-+85RP;gM0(Xq3;r@TB$e&(AsZ7rR&fd9b zsHFr-kz6c@twBdXCRn*3o8>a|0+ccs2Azo(sM&QJRyuf})Slf=9`Me92gVXe=H(__ zLh+FHI(KqhyB-%?3c>1Ci{Tzk8$5Td3|i;CfxLoBYSrCG+Lu8DQqGDhKtytfB+^97}x|B-R9kcjFXUuMBvsm3VYZxMii>bFg z_Zast?PMs0{9+7*DYH^pFkA^ zy1=XF?@(p(dC0W#5)2o{W4V%*#6#bd{oQOmn`3qYHtI6*gHbzT|2hOGA79T7SmI4m zmghsgPE90sVhQo}NJimbSF!JPWMQe_3(-*29&9*aO#J`N#N}=*w&m}OxaGAWbltQF z9bX2?jMv+6Y&y;UK5S3YCz=>?v&zjn-Z!w8N^fB8wn}F0IX@q&*5`pQV$slAHkJ8w z!jyVDE(*fsZZO|QibL}tGpeKY3NzN>Gqbcq4m>`e!D>4<8%~CeQvC(8EbGOmm}2Wj zsqJr_Db+0SwV5XHnOJ;36$o{mD>O^Abo&0PV zpss-bw(xOz;4p5!UrLs^<^$2!&yay@8Gf{90&Py?kx^bVCd1!A>F_xywj>Wr+bl-? zG>`05(ZK89t%5DLKBK+fm$3CRFQi3f5_sPg&#>_Y)3Lg+CM_gF0H={wkt^E%{4D@bEy&D5HLsrjw=wU zf3snoOac5cw-LAV*P%U5z2w1DD}2`Z7=)4w@!1gp&ODNUWIolA)%P8-;%GP^SvR4~ zqDFkJLlcK;w-7~3RdTkB36$azS=!ubE}`xps2{I@9{)Zg=}k;BaN{Ko5BCH&_vk|& zXFj$ZuR_l6wTS2QSR7at36c(IgYw7)Sak9hd^@f|+A`Bo`y)+wa)AP5luKZc-vsae zm_@4ko}u~30(56IgWM)b{H?4Wxn;={=EpqTe65CIQO`7UlK#$6t`KFJgEh>+Rv|d& zBLVfSV}Z`*Q07CyGM4(2dz3IgoMAbu5sa~-S$5)?%x}xDF}Jj}Q(g&}MU}RL-qHZd zA?h_VUG4=#KBtrlb~d1%uPp~VRqLtdxnj)h@ENRveOIZ|3&faqF%{tKNEnm5>=NsX zaVE3zssl86IYg0m@;w$*@m^2O za?yh)Pt8JycEkhOhiZ8LQE4>yP$hMsFA&P*ilW=<)2v>Z820+{6W;#vjfHQdgOCMc zXnB-6C}|F#bPK%+^{d@6(+^1;f>cb@W(L*e}^b|ymFM>nYIvV*w*g>~P)Y3@{Y#KrUQw0L~U?VR%{z z^)QE=Y0!b3n3Et(=^XU9z6mcM4nz8{+=xYU3f`dg5yZcdpz^-9ufafiR{}c4u7uHhwG*?@oc1o z=3Ol!@#r_&vH3iV)&Gp@*Id9MemY3`P%=@?oQbh@A}D|-;ry5^9DQRBzV|1W%*ak_wXGa=3c4-zlmKB3lp1OcdA9}zeQ7ODLcRgZnkRv@&1Sgx{1Nui}(c0{< zC`r}_McVzux8o1s=KMh_pldEv5dDB04tSxFr9biL?^vvW z7tvR*Mb_VKAhqxYaz1Z~p~WA#;>k)P&6wt8g95>qQ=u^X>1O=ak2$R^ZzmD=D553z z2>4{u)X|HoXmv#)%yS(_J}ZRSoG;1VH@Ss1Qzqrwc6RxAtMa6{(Ox0?n@-*#Zv4}u`VDmqfq>X z2>fQ@eYDCViVUrNgRL~agN=cQVUbZN-udJwG|7!5b5u;R^MP~l(p^;~9p;U_wU!}` z9s7yZ9R{8u5e@2}-GUYa`>>v?GVbp`PGXAw;P;=Zz?v{Us(?YGUE-g>AH72;6O>@J zmPS(hq=oD^ECb_-XOaK1Qalo=gX?crkrqh>;+HQ8cZBhv^=Ki!oBkV?s#KG!#_srH z(-~O5d=eFXOT(k!FcK`xBInQ804sd||7g2b`#2SB9$VZ3wHejFg->8(9a_}HB7=3=32}J8cv3tHGa%@ll!t8&* zFeMg+IOsvV@51zqeFtrBO8`d`q=7}6Kk^xtLtbwWV|?%l3Uv}twmS#FwJHxJttAcR zlK11peH}2zIUo4t4YHEg8z2xj8}imppIfs+tT9(e>be%NFY82sEh#V1y35mN_1!os z4^JXdcYosA*4segxF`xrI*s?VtwYq_7^1us{f`w$1%m|$e1ba&sRasG$7By<*;qlJdif?E!5PYad=oRdj8Iw6y@H< z@+s@VMvgkmPWcRU7Muk!Dnih&x)@h-)QQc&27K7k8mzoO3!dhWpnH7JX?!_~J6Ag5 z6~7MyMsNan^7=Jec4#3K=^Mt^3Rj|zZ!_U;gEJtwrWWz%`oQ?mNBC3HL3H%PZ)#%R zO;Bmkf=*BRpz7Esxc>4|>{wI);s?L7a{R>5SJxqM`1y8ZViSiS+zBFybT~QV&;hpl zn4!fdQn9q|O>|;&IuUUw$4(o?q3xM1aKVEFJjbXVN(5gf%a_i=DxX7OMEx=J#VQ!T z&RmQl2EvKp%mTdnRwQV$@qz8O=kVgZboA3Tiab{=#Db+ARO6N`R=vJ1l#7i4n>Pd? z58{Hg+Ujw(atV1LqXpht%s?L=Orh+u1IS%Ql%&62gKd9uf!oaWz}EFEx>$J=p7IeR ziZ-8-U)^o+3G1P0&osJs%M5h{zriZLlW0q=kovT{2gphGqGE41l=t#2zIgy+6`L$T z%iU*{P4>go<_1uCgNvpr((uFeDTL$ZOH5u&>$q+9=%HvHuD;QZw5}DCo2&9Lh^+zD zi$b7T*SzpkwGxdXaL-fXdKV}2Nx_)BEnDoC_N__F53JD20S{B9aqjkURuHA ztj8?u_bwiA#&n>WP6%da>f(PJBgo+8c|@6ZWW5Y{&U8u)f;%n`P`BnxfQp=(Xy@=T zB>HRtdEWk#Rl76-I>|9nk>xGWj5*ka)PtHRGs^$%wEktShYGtQL5%W}fh*~SYU;mf{+^!&Twoib*h76jk8I9AAd841r7s$a!(OBiq40y`&4O9*c z$3L25q1mw*ay~B+jW=9?`BQp`R@sB;|L#DIYsbloZRtoq=p2A*<#|QP6(Olq9dVLJ55ZV1Iou8WK^!BLB9*q^#q*HT{hb)ee67wEdZF)GdN!I}k@*mI#ObfejnMW_z)l(mCL zwA}F6Sv?Z(%3`1OTgDc38UPswzoCJ7zcCtHi?3veviByN6PBe3%+QX8!{=V$hrDx0 z;=uoTRgq!-M{MTI!2>7zDQH;; zTz>bU4Tr+eZs~XUgOBTU@!}t_pg@9hFd2bu-eT~Ae=q7*ZNohAnQYoMf^?;{0&}aK zDE?YGmh=3AWT&dhNvaZyc1lB&{|>^<7MXaQXNGz_i%DFU9M0br3o}B0BC_QIwp=_1 z4Q)#yqSJT8`xn#R9;0m7s*#07oP@|FKZjVU-oPssD*>~V38tZj8=UtxmrB{D3wiTu z(9_Zr%bw&ILiO|x1r)X3zd_>Ousl&b3v*Gc*y(ppUI^MIl52akG zAZJ^II4UF`l$zATz2oIr9NXe$=L96h-;VTxQG*hd~%;CG>eW;|52eMb4##Qof;IA2W zV02Ukg%oZ?_Mc7Qdq-D%&U_XsIU7jr5Sas?#CV}OrJXR)%NM_Ot3%vtMqtcqKdZGT z8M-Om0LkuLRA8cv-`MORZdn{M_D>eLoo|E&r;29>Yg{<#5m>7bM*kfwz-8 z5tC;LB}0broia64SNs69iJyeO`3gkM}h0ad%_@?;- z_^-VM7TYAC;vV)vYiB-MwsSG?;Jw7(-t2`|^E#=$OS(|iiW;PUUlM%Ms=-Civw+Hi zMO00V*0jH{1^J!ofSaouu;Mcv{0KP!wH>!utzQz+uA+G`Fsc#`N{8b}@e5?Ok3G93 zWDUr8b_uE6K96||J|NzP1Y)1?0JCy}!2S&wc^o{1^K;~&@Lm-0Je7fjOcAJ9rHGM| zAMT2AfhnQ>#KY(evfpnFl3&Q9zGXqU9DPGx@6M1s=VrV&_&JsBrouWJq6>{!X~6UL zR&=7m59?UWB8-`;Y))w}wJ%g2m3?bPjz>+9!Id^FJiZcJuXs<1_OArbyssm#SPQu7 zUp;n-o5n#mkAY_$LFlqc4m#>S3_pJ_#757Lp@hkOl!Q$vW|0hKCdr(+K`G4=qDV9mNug=4t5Bgt1Cgnp%pnnyqNo4+?R`Hy$ML++ zK92oif7xI5y3T#Bwa#@e;jkFBOIM7I`(r0>k!n-Dko`K?42;hBI>xV=taC4YnnA$ys;^s zEs`E*@pxN+_-4y$QI$xEDI2LG9y!OG`T1_NMb2V#cHZI!k@3eFteLZv*yqj`X4^)2 zi@n7R8_NC>UaQk&^nWUe4T~b#W?2=B3qSUVA7v$(Pg9?4`uo{=f$1J!LGQY2=JOV1 ziwqmLGs~r|*&B6@<~}oJg;K?HMGw|p7p6G5F|lXQiMj^YDZd+B(o;Wbmgs#&xUkCB zjX74eMwCGU1eemE3-%v05*fTcBmCHG!5F*k6{+OUHBV`j5#~H&M3pb@3t4w-CUWR= zQQ?U^vs%YDX5RJwg4yTp3GP)s6#QHoAzF51hR7~*F55Ju$2@Xcyr5yrVbS5BdFG|3 zk224m*b5T&40aiJ4i#)PyDmzQ2^XpL7c+mW#xs%a#|5K`=MZxpya2@v&HgqfQ(L^8{`pXSqtqhR_~V!kx|pGfAtv+zgg-N6yP)Vt9P9W}k8w&-7TTWpvd=?qr=$-6KM{qiWV81lT@)3*D-$0*aG9}rnk{-T`!JKOkjma0-y&iS&x+43KFLhkl`5?E zEfAF!US{7ke`QS1T^3*T>tX4y1Hyl2Z<+rI=oB6G9WVO%;0T*<^@NpPkdxQ(0 ztz@6f_hR$@`#G4S`-lyq4>D8bq=Wtr_A=el4Zv~Z~t z?DJ1x9!vKKhyFdnDh}fFQ`Iz~^KEU>zU|wXP2(d)fu133sW!)4otGsLUMUvp&x~fK zUsYr@p2V?pd}^75hC*T0p`ilP7uw8S#Vf-4*$s?n%MCVTKCoYpfX&b}b3t=1O zoR~d7BE%ENjbrB@*eCosB0yxeC4ybIq=QMfixz*Dd&=f3SqMiC_OhQxZWL`E8!vqN zMVV=DoyV%Ye#$-=GE*#w^%n+=nlActU_2Z7dK$B{$xy7gVks*rI3}#MC=rHpW7wGQ zF`|&NiQ+%aZOn)$HBp*(f@pAC4BPcdi%}XjOdRLZ$&6c|Bb;p&EBZ85m3=TcO#i7# zLp*Jr8M}6MhVk!TIY#&O)lHYje>4s&k2jt8-Nmfv=LhriTT;!ry^+QWuar!CDi@nQ z`+D27^3rni&=YND(7x`Ub5lRB~w{%2XpPjd^3ZItZ;$f9`loRVWNkkCgDHZ zJB&wf7;EtH3F}@yQ>>G{OgQ(MH`BSyh&6kY%}f=WiIp_3vJJY4!Z}XPqA9EO**6C- zi&lM|EZ$$5$2eJQh{kL`#^j`_vQ0_yOztcV@u)i$jCF;jFmaqnRQBIU_F&(2M)Yv3 z`0|CzY|D<%!fHPSfrlI~x<0>67=FD^lzY#Nb=DmapAWt*ewrpNy4hyHD68hO`%_XF zz4}Yyh@S~;{!MAo`;a}Nn-5R0XL?_m()JZfuH3>f|wYVs9!Fu69z~FfM_ud9NyJeYQXlk-vzkZ<#1s;1juX{wED^N?^s*1hzQG=}@}S3R z0(MrYoqV;z+-X;> z+0)uCM9?95=I!ZZo+#`ILDDs+k?= zJz)IOAkE}hYOdMkj9aGJe6IQY$TG8Du~?u!`JU<8DMf-^#ewD*4fF-^va+Iqnv-n& zxu2q*M<>i*ooW{h7#tPtPd_4b{C134{7RNl|J`eDyC+Vtta-U;^ZjV^`OE#8gb8oW zb%d#c{fp0<`#!N270)#g?ACN=c4+@FPy2q*+|8g(aK17^^g+-qRNZ@!(RXeW&0A?J z%xNAlcfIWtm)p!o)|k!{7vHzJ9p_;VO3icQ|b`GTH4=bl;UH>y_e3g zE>TB?OWiF+mzQi|ADGTyPH%}3_xS3uZOXEu+8v3^*?k+>WeZK2J(D(xSDrFuRh*^@ zhkVx)z3AA+E_Qpw?9~Vo8=K~^Z0i-ls~$94vrqo*CrWh(1L zX3llOO#y+-&U5Olt*KNpI0ej17^l{!TskNSk1;c6z2D6=Yc<|4gbHSvZAcLq%*#|srAz6$$X^;k2- zKBl+QK>YXccUG&uRrvFdrhw^P%A7876P>Nw#rka;EB5<5-onIK)}m)#w$SeUCFW&X z3tKbZn{Cf*6OTQ(T&&#RBiu2T745oqo&ERFlR3PuS$sR>Ba_wTBB~smKhb$#z(y|o zD$?w^E>^fx!!$X}7n)zEBFXP6c83M9r`m3b_url?UM;?0*4uNy#QMhp!EPA~fj5yA z)CWHh21IF#wh!tmLSzih+aw~vr$y1iyg*gKaFtk*yOEo)YN@-qPj|E+G3tmgSl&*! zDLO@DaLrV-;Lv$a_G=878Tb1OYhCRHKJWL5 z49+zQUVEeqeGEUFPjp(r6o(89_8zmDci!LGw1^wx%<$;kSs(P20qOqy$0Tnsc z^w1gcLd`#HWz}2Z!6Fo;N++^U6~{39rl*TNYDTe_mu(fLx{qd$`9`pMvnMhlakO~F zWL-AUJ5Z=q^Ho&E$FRHS4q@My#))@r{l)t0y9oC)N6c-8ofnnAJ}z8*QgBAGH0F2nDCi7%t}i~bN?TcM5EH8M5Z?BA~Wq+=3U7W zCi&qBb2Db8xptDDD74yI7&bVIvvurj!G$J6fy+e~QB%5uXr@Dvpt;M1Su!Wie750y z^Y3Gf1&>2_h+O;ki~6E>GHpgN%sGv%f^}vdW~LkG3O@}yFIax+yhtZfz-)bEAH(PT|U z;hMdvq8z&ck<|Ju;XM@vw*KW=(c8fVGaCl;?|=73GFmb>L?w>e>||jfW4L;7zV}{& z`8TdxtouxH!rEk3RE})rp;ouXqbyWnw(*DWXG^S{F6iupA5t&Z#Xg!tBi!wUv`VO zsZ3>8A34f=eq|ya-5SmQkAFb*mbc9R5B~u1|M&+;Nrl+{&pSS?(F&6reEOgJf9F9k zLu&Q*4I7r3o2~TQ=4U3bu(Rc)7X4pbn)Rhte?P{QHpO1C2#uT|@e)#D;O6^BCmhr8J%4&ulDyx25Q!<`7NmTy}x0-$Hu+_(QiFJT*hn11puwp~2xKf25 z5=rzTQ%QnJY+2q(hw|1>U#&e?UA0#1h%Ir+l2}RGPc3^r*{k$Q%6;o&zNHrKr)8}- z-&QFX^NLn<>R4;-k6*1%|7$I~5ChgdS!q^lpWG=et-4V*`rpWMf%;9WsNW@}ed+b3 zc}ps+Rn9N9{;=&!*`!w~rIm6!N{1vU4en%svYu=u>rI{MWp%3ON-usBShqVWl#hA5 zz3iv-w=%;un@g@F=S!4EeJxqSI!KQ6JSdw8A!S#jldk7J-D3T4UnF*ynucIt| zy(&t-sH;l;dq>LJ=LxL-G(9Ry`p>Q`*DcfPbatn8g8hL~RY7lA`j9WBa<5vf^K~+; zr*&_%jxGLGS~zFD^@#LMWm%P*t!IbGl#l+CUsj{4P&!ySwu&zGE6W}8wv2n&X_Yu( zap}+B56d3NXj(tMbj})uf2?bUjx2Zc99CA1Db`_9*5#pf$F0sT&@O8j`m;2`WuCRp z7>#lT$zQ8^zVofC8x>2V{AY_bTw|@w2mQxI@kWx%v(Q5I^aQIi{RNWeyhT}AS6SKl zcsa?pJ`bx&!(W$0#S~hf)4N#Ov7*N6QImDq|HPj2w#QqfWCjCo@c!S$-v7t{!t#IO zch~L@OvAKjab5E#!K|(k;{T4mFrOiNLY(LMoYmiUj9s_oBAfYCjfEA*S=kF3LjN=c z@p@lJ=If2&?5KKAHu3ueae-c*S=Y-6V(;jM;+@w6#fLsAv9Xg~#bp-F?ECWJ;#Ibc zNHoh?l(nas-CDeikuud}?*`SGy|h&mA5&n(E=z`rSKm`&y&R0$Z@HCXI;bffxWKbz zKkS&VUQ*(Szx&1Hl$uyuXu%GZj$-XvCE}F|$lky3i48rf%0^~{h(Z-`j!h?-jsUog&Sjj%K)fR^xkr&&1zsNK=53pxeon_lAoY*DQN1Qu# z4QnH-E57_t%vvncWyX!S5Qpsl!jPTLY-FD^J8P<}_@)-idLDSlOjM2$-?+_-G{9cA&B#-r>suWByWWbb)Dsx#*V+FM{FsGe;;#E*Z5w>ot}Mt3(2thvm6bGTXVq_7389Q>g3_YTZgG=a)T zN+kbSDzP4=N13VzusZVyu?#tmA6_x=``3LG8NJ22wHCxbIteSzzQTDCx6r+`kC(1U zm)IDupy7w=%g?ti;Lb18gA+>?XnbNbcyHFGi^LIpUrY@ut?fm54^=p`z?`^uTGF=p z5fHU*1PLhozQ4ibd&?3eQ)eHg5j6}}?=a%4H*~?@XdoIJ&T`qCro)lF zAGlkWo8eB}7w*Bw4=_WdfgTz{NwmENHD75gxpc1(@4QVyccl1Vur6Pd_KuHI3L<%f zvX|BWt;b3G)#)zH?L^hp3`p)MGBxTkcf|HNnZNHE)(|_gzbTBj_$b9$*i6RIdI$6m z+d)s)&Y`JO*Ogb#JMg;s{OL#tmk=4@$&aZPDtQH2UhQsl{VbU|T98hj3I z1skCme5+vLLyjUXxU&z6iX8Dnhk$;W)PhkCBQdg37IhZ@+}d^s17tVh(VP$%SU7?P z7@UEnBZhPL9_}JN#kx>^#g%RzzLYy#s{mI}o+_HT&~Kv`qSLmo7`w-oZ@DfYd2czQ zaVCpS+z^B*17E>aI1X3I@LW%o9&DR%5M;-wlWoaj4!alO6QwH9yJCPu}>gHDahTo7|96ps};tVgI<9#JS%TwHN+FyLt^8S~8B>n#j?UP5l^i z<`^tD8%Hhs610LVfLV{?b=Z+Wxi%GmRo4)9EjN_ToBf7WoH$th&K{ z7ph@m*+uTbOAqcr`!T$_P=?PB*-U%Z9z=%++lkLrcOrZd38T*Lgt&BbFe2H!+=l0v zwJ8H*iVDFmzY~YWF<7T}6k8|f;kdxt^wG0$vT0-sG;CBP)9MwiFCVDE&*PusilL*( z^&#@4_wi~xTBA-Tdsia%9;MUUWQkV)OfuJYDLLYMm%CM<299PJXDwd&LjZe{P!A7oRrY-($`ik`vHj(8sKXdu}hhqM= zSJ0JbiF3SN$_?DML;O1lF?ugW?lqXxiD85a`sS6_$erf`YBpHAJ7=T9p2OU)hE{m0 zzl@ruT!fG2hIGleztFvKEP2xR1wUzTS5ec@{2@+N2bM{w*Zo4h^_% z;dGK`R|qEuuA`@%TzRoeFj1K8Lf)2`;ewO*VSL{tw12HjmX3|3h2G(i-Y5k#n|v|( zeLN<~-YDBL5L@2cEKi4>nv3^hE`zjL39h&x!+rKYfexn}$$z?|sQ86Baq?}&8E+`Y zUsR>D|4fwp&59iSUfB{2%{_E^QW>0;+05gfuY9glE?93kOpdJ@PG_cg!!3^-L=`ib zd8Heg6Cd$QOkcsWXID5cdrLfzW5HLTKpW?uCM}8!phI4nMBg3CkNxROHW$B!qMe$w z@Z(xqiRWQR`6%kO2l(K)W8fWMi#yMV3Ao6?Em0#ky26XHQL`Xs$0?*XJy5bU7JF9? zLGk_#Xw|V2Yh`cZq_x@TBx`~Ppc-rJ9&xFOL&%rSd$=QcV`;^PzxZyF0-Cvm!IjYC z(DT%X+i>$YE*{Xwit1lzykiBumv@4Pl6BCs>CMm4*K;g zkY-~K?EkfZPCL7uygL*PAC3gqMB8@!-{y@aw8JZMT-D;=JRKB^^g5J^9c22ejjc(2HbE5Rg%u z70A*1!>HfygE&$si&yO=)Yf$!uAat{;~x}Ai`)qMI<<)Vp;?A~`6qcTpCi2*G;A$y`4^=>{)8@29%+#7G$H@cO--Z2Yy=oRtab*_@{BP%3N z`?r!izb2BR{_&i8L@w5qhd_${NUUCTjQ4!wPjxOUk_#ylV3`w=gi&pLYu6~y<0Gif z+xbv8zZ0|_)QEz=3N3!=3}NHVFkrbdIw{6ti{Vky6R1Y#^hM*9>jSvjQ^dLMsg?Zq z#vep41~_+*N&M$j3p`NlMT&!Nz?tp@EWL0ar(fKKMcZ#dhV>mdHhCZaW9U#KTa$=| z6K-OxyD2|5Bb%#!w3x8w9T+n8013~L<#f_x!6y0@_N&CAnzTOt^Z5>2PHDitWrtwv zwNW&vPJ`FjWzL`dGX?%$UJ4pD_B1NZjpnNT1)JI!o)?^l-Ir!!f#qltZnzO;-#F5s zV-z)i&gXYtvxc2%W+2`lS7GINm!vijvv{n)XPE z{tN%cht!ym6@f3&=D`V^wb%!=-yh+F9T|GR`5>iwrQj$Ri|N1OiGs%ntlA+ad$<~Y z>gT(-vS~A2xb-z!uHA@vSMT#BQT;IR>?xo9eOYdZF#|hd$xfB(>+;Fv>4}KZj z37xkJQKFFosefW|ukS}#Iq{VBM;}*cBR3&6?<4O<6nLv9%U{sHyO*Q2599q1z&Ia*Rt&L^DmgJ?|*W_mAJe_-UEAW?&Va zbSN2O-YHU@ss?<)hC#MLF5u5@IJcd*ro)qwH%IXk|$$UR`BzTIx%2( zHR^l^swhc^5zCV?_~8Yp`<+D+Pc`$5Do1WlX~VOF-l=}u4CyGti+t054_eYy1`BU0 zA(_ok%Z-G4{-hbQ`xEGE`7q1~eJx4aEk!d{g!2urbjhruhhV3phnn#d$Xbaxz8S4Z z0>{fsJk;gMo7~5IukIJr`(OwjwntFm?JaKZv%SPb`7>^i>cDMj$9b+W7PZ&baSy%b zV2-5}eZ4`CPVmn||A0H#Vp;^kSN@nXDFX|494gz`6HOL5Qhe#6#;sPqkLgv$pr1bn zJzaK5p7l3N1i7`aSbhnod|?CExFr^zub+ueA92X2XmUgB*6^Ld6uY0l;vDbpg{LW_ z$j2ED-0|40sDAYcm+)JIK63fa^}R}?ehH)a>syOx^4md9JZURrJ_~^Hn|#Y32p3^d zs1A`mWDF~AM!}FHrQEhjzIbr^PdrF>Lrl8@ZL=RJU$%P*s9D*PG4AH@Z?rrwJ<^68 z_)KwLF!EM12M53DQ+jKo7i#BBAt!FA(b&u9_-WzxP#c;7=Pn#7UwTNF>P>T|zn!G9 zxkd{zFa3g!zpdC}wU?SdPsZmPJK=q$Jsp2BYEoxtC>p_PRnw3>eujMbUJv?RwUEy-=fHG0=c^A1O^44=SGCA#@C0xO7i{Q zz`-0%`phFAJ%6{NlkaM-JoN^a6m6D>gG%_hsl{;q>T6g!sTqD8(ZD_n3sNv}5*oNn zw9y&ha_+~|q77I0*Si1sriKHUWU-h=e-6cZs=&`Uu7nCQzMx(~q2E@CIs~sGdmlFA z^J;y%cIlBa-Jt1I-!ukllVZq{kVbsfbqc0DImXAj^Z3H(89!ci2MDsQD6?tGAaB@2 zO8QE`c1sf3`)UtWP2N!cWM(w+=+PoE>!irCOlOjFWj(oLkjFihRm`L#Wvn3DI0(xz>%}a3aeKgX-U-zO+3`T$JdT`&Q(`)q9fmspjP! zi-+Nvd9PvAmAy3e;S{$cyM+5%ir}|&7-==qp+h=j(W!AFl?mDby-&mW>jh5b z9zV>N#dHBSpk_wz&;xu6w% zUtYtQZ-H158H92Vlj*P&1%9D?5^hY>A_wX$$%Yr2WJhcm`gQArROSg@w|511=94q- zEY9Q2+iwufVabD>Qx%KPG33prb_{SiN(}am<&W#$0MDozc#&=j8jhCKWkwL*3%`R; zcdAm`mNHZ^h^L9CBH-6kJJNKzh<{Rc1@9MJ;|2nLp?pmxT-~b#(a+|ix}X43&PCAZ z{Z3dT^R7H?{Bqc`U>a@qmM5KFmhe!+2~J5_lA_2>+~!O-)DG~YWjR5xJ6R82y8tsr7yr%!mlUo+%^g)cq6DY>Eudoil=5Hr@dS zeRnaUWhVx^#^X56B${b>4R^nsNT)vR0?T!`QGVE1(qb@+h8kGX=Q-*aV(TP{8c4zq z`hPifncb8%DMh%Sz#qHumy6gr$hjUW({AbI&{v~_D@6<%t&inXHk6_G-3c;$Z3OK5 z*9Nv9|Kbc$Hq9R7BkdEW5YsQyU=T|s)7H$yC<7zvY&iITZ@EQMv^7v`?`4$fzW_>= z2k7{h<4_j zTL)j3u${=9@hx_4uPQehx{Ld;u?gPVD3jBlF5_trHEw=UEjMA?2#DJ7AKd(=i+9iE z^7}`r(@tG^(m(D91h{XZeQMD#ZOKE7d@_w3TlWdQdJ}NwKs7&!>XR&MC6KW(CM%re zK}Oz{>@*)gn8WR)w(VKm0{La+a6tfGz4?JtDbuD0?aq{69kGB;>FDMj%8%q8Ou7cE z_$u5tX+A!hcMR&ieYjf}=i@KEb_kF3N5lR3)T}NS?XA=y@xwvfE?)tXrt`R{axx8k zIh^Rn$>PM9hj8KB5a@M7ZcSD$&KMSqh4Y@1RA+T!a-NZVlO0bdF3pERuO$2@z6>U| zkt9fN8Y%YA!slE%a5-@z~MB$=0PeyLD2}W*!4j`b|h$zPQlOv zZCu}t?ZBHyK#RE&x$NmoCk(&98^ylFeAOcEYx6ZU)_lQd&d%T`efrI1wkwb!OSZzN z3~%xXw@OY=9Y@wz&c_s6CGz!E0si?H%PkEq#ue$YR5RWbh6c~XjKC6DP;1JI7fV_H z`=<;}ewXq1*mZRE%SANl?g0GXB2#PbJF zV#L^a#9{nViQgOzNI78yf}r7~1Zqf6oDKb3)(vv*vx(k1Wt?Zb3fej}sf0;}36G6w zCff=_Eu^WHS{RMLm5%@HTtU!IpmE;`*!Hd$PW`tD?2e45w-(KYM-AF!jf)z+qNYi7 z`4B9;r$txE-YwtW5dprtN2AtGA98KAIkmQbfBY^NI4oCf=mo0ZKi4G4W<9 zuDh&5mUwkRZM!^0w|r39Rt&el2vBzGBv?><9OE3@_}eIg=G~Vhk4-&s(~i6RaL)!j zA20*ujXY7~(jquH$UNL+2D=)K%i-mD4_f#BndDudCOB9a(Z%26(C&|joS~6;eVrBQ zRBV6?M-1T5+XC=Bs!d}|BDpW&j^zC*TO4!a2|l>q2hrCINx_v_-4yy}YeqJ}&!|AUP#_5+2Hbft)YKe3sS_ z`f^Vuw0({PQkjk_mVyOC?BM<6IK`th!@KOjekY2@5T- z*E+t&{KmpqjA@AoK|K0Tbfzt{_|x-K9$ zPo5#ntH<2d;BTPPoMhdaYRre2=+SQxm-wAR54u_|g!mgKgWm=_>h8FZ?z~fnGWVZh ztU??%j2sDnd0Fzzrx7CpM-wLz<&K?k0D09o3{c5~S-)NJ`~`a$pLP#t+nkc#d;Z{tT5vx-2KFwxMKb1G$3G80!zNoNI;S|^iY#`b=eNFqeqBE*U!DtbALm*3 zCCbxvR+`jcw>sB-+=jHTE#mYPG^vVwI+-#*3y0s=rWuc2$#M-<`r=bPKj*SN^*OYU zEdQ=WCYc4oSD6@K&s>7uR!?$!{XMW&eGbQqRA|lZt+f8;X-v@@53YtHjHxIFHy1D7 zctt9I$vY2*Ur>|83}{j3$&XRDqXqn4jwLTXdtx{j$bCFCh~M9iqT7PQ+%xGi{_d$ZXVI$noduIdw;6Y>_RYvdEVm8ZO729elH;>+=3fpsYfoHXG#2$&)79w0Bf(U zE;me;#d^*Xr~Vp7`T_=XN;DyN^W8|8YcaRrwhR7NIgYw5UGOa|58q$VB=PIqh-=F* zk}7%z9Se`+^fFK2q7EZxpvez>yABzD<6+|PG}ICiC?9^GXKR8$@O=~Hk5D3e*$NnR zhoB9@gIKgEh$QyJOE7&jb!h}}%~ilHLGtv%!{em7$C=tZ4ui7y2K0K^@p4CA0H0?X zl26Qk;BrNs4)s0Hmq(n&(?3(`+YJR0f%j8%$mPg}lUkI~RwT+iqP{3dx4J;|Hq1SUbm+`TmBM>yE%H{lwO zMfAT+9n$v1jZ=)#CYv3k=RG3R=5hpU)QdT2&R z_SJB|b6-l1&HY%$)kVXKC)2@GC9mx6Ol7)emyj;~oCxY=Km@9a5N)AA1Eqe!sgchi zF-eCez0{yyTP-m^{2X{ysnG0RDUz{tIsG)){mGqM1k1walD2*JT#;!etUW%0bf@W% z^8<2d=$?Wv!Xk;oN;A?t?pFCl%d^%^`BX2kQ#sSJERp#W-_@ z4!VPVh_I=p8U4K@gYY3e*@nUn}q`U@q&dnb}RYYVX9_+DykqK%W{ zW|KSd75vwVCFsA&ku-IAai`WR5hr&m||#%55?m*Pec2} z)nMWwN0PY*c*QXuC!17J_g{OV&}TduYkE~ObKeof>iaO=ESZ}*IT>c{D#Y41BgyOQ za?mwbihJjMh`Sc^1fDn-VdkG(uy}$7{quMvagAh2PFDshdQ{@|KTqMa;$m*yr;}h? zYXB8*_7Jtf{3c5A8NV(2Huu8fEwl%&;wlH%3~3!-h|Bl9fcJXxbn#X>YGoWm?=01% zzpiC*p=Y&7e@`{MSY5+ew-!R8#a~q47Kb{Yx8fw9GO+8b!+B{^^y;4=aBnsM`we+u z(y2+6e*ECmem+GDso~T`ONZ{|9mzbSdgv&XCs`JT3`Hjg9lJcEWRAEH}-rrEn zr)<%IMUSM2-5MQ|5W1TBj2OZ36D&by?QM8I`5H{Vs6*8Mrh{Ck3ZuyaZI{enA=KQ8e`^50&G;; zv@{FRcmI9dqd6NkY!|@W%%nlrbv@u$-{I{8mV;HI0uFppK`HACqzdu6LttIEp_9E^zayL~j(?-)PQRFPY6AWILHMi9{m zmPneE$vNjRr=})1#`y+m8Oyk=xWOM#mmFQ@{gM5rr zfm`~TLf^K-#k1brac?tXd%y#~_4v}7u5K`B(;@Sw&c-g$ z6;S`>4Dz-+sh_bOExzQYk-{~9E-3x%@D5{5ok^8Yo>&aO3l2&v z`AdHc=(olp*{g_7TZ4CMF{pm!@ zIE^#pHgZolcfw350rmCB=Oljv_%PyvQQOXi= z*#)TUp-dy(>tLDeCc3=vHcQ9CfI1R0qBGaDwQ*p!@vi-g)&D(tnrr$4wVdvhUmdgnGEHs3ha#I!eEL}mJ zQ`Wb>`q=gU%=K^S2>NF<=o+W4KSwI8zf30Fe^o#%C4M)3B@j? zAy*#`3}Vx5eJzs4kE4gYWAIVlC(dBsa6U6QmEW5*k9HNN!c)6MeAyohJ7yC&W?F<_ zQ$j)h^BhQ@aS!-|ufh0W2PO)?^8ITo0N4G8I(fG-=3;93m+qU~4XHOUa#b8Xnruf7 z{QL*S8%EQf-!7P0unjU&in)7!&4ZS81AEuX~(T$2-{k!jkG=xy1S3nZW%Rdm2__6t{KMYl%wdT)rzT3~bdr z>9;evTte??I;S>**2&xl89xgW67ri*HcThij>yu9m3R5CC%v%$wkIsL9|9wS?a4pA z9q`k54lj59JLGv;z_?X2$jCpxv2SAtgg0-*uQg(BexMPT<-Q7%h1c+7V?Gv?sS*|K z@9^HP6%!K#B%)507?dRO`vSJWsJn-W&%`JEL~C7Yt;u2Q9Ri1Q^x$o)8Fx9Miyzae zQ8sy<4K)~}Oh{ZTxp~-{UQLdmmqr|h<@L^JIy#J3GknK4rQOAZ;qUQs+TZfkau>@> zk8h(dP1NX@Yn6CFJs$E;j^fMdP%bd|8GrP%HvAn~3A<)aA)z|&K>zhwB#k++*J)F^ z)9+|}DyK)D^y@*von9Q!^2V_Xk3+2mQioUhusu5l=C*KL);b4rbCo-vRCtDRGN;Oy z{JREI|4k#-#X6|5*MnY-J_3tJB$FLpPUV{N-uT`zM>6BI7Y)iyLk-p4Wd7Sj=zruZ z7k6|$7uUHEJEfM;nPIJXsVN(ES4^TaFD2paF?*5m>BY>0on;Rzc7y%PCH%r)VX!Q6 zJpVTR12<{*asJm>2d*P#54R_0B0f#sgc}}z#N?%KxK9}OP=d-ECI_1k{h?rYA^I~q@3iVW%6ZAW0*=4DGZi6NkcHMSC)`e-+7=A3+YZoWaN1F_KX- z%enE9p7hb=as0|(OQ3!(LmOmNiR=&^-rwLLR=QeJpS&JkCh81cuX_kyLs)KNmK0XZ zHYEOQ^3k~E2^d>O(X~3G@cg(aTK#k<^$k=cr3Vk;n-yPh)5EOt?=5Py|D-%Gs}_d^ z#ZqLF&RK53kNG4FT#4w{3I5icJKT@_ADr&$p;XoB2sNws$LR~NW6#uRdi}=~+BEJd zC@5q@c-3uCFplPeU&WDdnFn0XR}DDVF$H5T*^#hMBk9}z``m|Pr(mACDcyM40J3Uo zaPBWJ)StM7tZRG-hQYDua%nDE6!#GIH~GNZk$=H$Z8`rhSBAW~^cnL41!P^-V*LA| zfnQ_fL3Rep!LMQ`iZ51B@q#FB$dN%V;CaQ zcE7mZfAeYgykfjPUy=UUCqB@Z67gJfeYtQp?TDQOHP|EVcZ`2b}IXmq1FF{jC{ zwcXsLgBKyZwh3d?8*!ieJziEKO%H5WB8PGY&zory?o61%aq}+ni|_h?XP6zG?qfpZ z@?}vTBB@qh2)D>Kn`hrO;GUzNw7||0j|QxUf9vny^m$^kde=}$yHX3I6c^zvD+L-} zb%45?^l*z}%xT{9QqWV)fS2D7Y z$$)o`Q=<>Zj78&16yW_C%}@sY4DHPNA4}OqJ^o(od3=!cvClzd!J@WMDm?rV&_B3rWYVCy#i%> z{*-U-Xu$63dz`44GLcPGdc{2MbFlF3vA=wNs_O znp#}wt|Tx_^un>^0a%+@;k_fiq(L);w_a|;rQCGp$MtH^*ZVH=Tc0*_o4UV&cX=GF zSMsJ)qBrx?iWJE0ZWVHVQWu7X$8ra@#|`QPC!kZ)2E0yGNUiFt@=4dnP(7JO?#tcQqxkP z{%9ES>2{};19S1v)U$Z@zbzOwY6%|$x-`&u4*XKzg1LLE;o{qM(D&M&?vLo;yuSOu zjQC=_Xr2hWI|eP~TH+z?Veket{St_m#wZd&4dG<9H!KnO)AIM#7^B~e zk004WIAn9$SzbVNf@qCOBIz?33mm(SOj+5(O|@sJUxgbVJVp^N9IwM2E9~j7cSp(G z+lsV4WgXo}K5>z=9cWL74?WVe0QblZSPz87q5nrhP944r=)4iXJIy4|WWPe~V4rE1 z?;#{pLpg^*9{R3z41H{H9!%d`@k;ysQA;5Ub^oXlUC}Y#CeWH}wP^&yvO$rAu{GVE zp9}x~?Se=4H{jX%wPgF7KKyroG=!cOmDx0v^R%!EUz%^nxuSF6*IxnkZx55b%}e3t z25G{)pNDg1weoWX*SRKN3$QLL;S?&J$pTpgzIE>wGF?kdKetDajIp`p*IHF@+h!R! ztUCqX&9H~eLG8y8%Uj@@#?WoFhFT+AR&cVt2!c zm@?Em(Trm(EXh>alN2pG`0)qBuzg(^Db8~MDK~vyy(yCPH>=RM#E+YOUx9m~Dx^DZ zPRAP~6sYywMbxFo2(I)xk`2ojQ;S&<=-5^b75-;%wd4x=CDucCoGmx!`60BdawSiX z`IGO-?l}9)5pJ5^A^wo99G&pl3EroA(T?wt{K&|#K~1UxP0kqtrceB6cT6(<(`!JF z<&L5i(o<=;jU3G#asdiXxufAVcapRthF_zQ%iAoOM;}ktqD7zQ!|*Og$PSprzwg?M zZ+G!f;4p=k@o}fGLSsO7y9>T_AJp*mkHwt%@wfy#Fy+D>PSxfdT=(dK(|e|p>eCja z>wpT`UVRO;{&YYG*-DF7hH$gz2=I^a47ytz5HdZ3fAzl@I`4oS+bE1TB<-TTcSt27 zdY^NXw1|*V+C*hmb|39h(v%_%6_J?=)%%>gB+^hStB?wXL^e^r=im3QcRcU8&wZ}z zcbx~CDD9Do(BeqN?m3dfzowFPR0I*PpuT1zD$Ms}HF^!$@EO}dsk0Dy3g}Jeos^@tDn3OoJ?Qx z{mcI`i|$x~r2KD?m~@%ZwESt6{6ilrGvb)4u64NA|1iIxGnRQ|7=doj_25>o6p_ll z4g$NbLBIJz^6$n99FO$ImRHSirc#~+D6OVqQ+{K{h%}LHOJ(+b^C4nvKI}g@f^pX# z!@b=GD7j6M9=P|F-Fo8!Z0YpFk{4H*w$0P&m0T5C+9QS20_W3OIb#qNO2vwt8(4ST zhgtJQpI&?$N?XQLm|eS6$xyXDeYAH3Tch5i<&9%(p}h+kV@=7;m8v9MOPHD*S0Y7p zCj`9JAy+$eNM_wz-YIcOdT)6L9=pNKqmj#p%wtS>^M`l_8cTK$H>Hu!4SI1p6Y3RhQAG=uyDp1EN{ICmrEpI z!}Ygp^0EnZQ=uj9Rd~hBI-m#^B4v1^Rf~l?hGbv0C2V*>!K%%bF6ynph|h(MLFdNhxi8^?mp z)*N!Q=sZ95@E=gP+y~8xip2U$DJDN~=GV;4#J^*ajN1M}YG|?$+Mmf%ubL`&?I21> zsTi3$uo&W+rjmOfYl)^~2&q-(bm;JG$O<@#3C~2(ufUit;O5jI)dUZ=#j?MBf3TAh zQi<-P!(i(ahYDc@P_|o#JX7_>-l8lFeiTZj$e3rF@1k)KSsWN%t#$B=AYlDMP-&v!=F}9VCnQ8(05#b(T`M6f9o~qk=sI< zWpgN|xx>UkZWflYfX}T?r6(P(TP;b`#i#dzh`?NJlHMr*D&yB!dCy)ZO>i95gr-ti z1!wy7S}k5)Hye}xeqcfb_JgPQQ`i`H7C&8?fC@sYME9rw8S@;$vuTs)iPy!TsTB{e z-1v;ZYli$jvWnrSuP3HremvEtzgR6kpO{CyM&;T*Ja9aT?$}fX&2`%`sId%wH??8R zvbn!RGmXVl}KGZwH~eFj8F zoIvY;1MpI$j8*P0!>!V-Xwq|^StqALOSF{WLi7<*Aovg0=Z#=MmJ<0X>40L(F7cPO zXTZD5Q_+^ckd&FG;Y!zH5+8RMf4p~u-PgqE3}bQPmuL=?^7oU-S98!|#{oQKRl?hP zrI3*_4`&@q8Gf;TJuaK^IYdijzhiAMI&w;*(wvk^jP zZ6beft|v3Ugwwb7_uzu%JLKPUq2cvKc*FLoTng+7PbW*Z$ceCHgKzqyrl*O)<0J1U(>ap9asQ8PSfEH^ekkC_pi}Ijsxh|u zx)_z=bMxrYlq&XP8n0u*IOg9GCHi)^alKb4^qB2|La(22yu_0Jx;GEhUPkghg{9+W zGfTX0JD=D%NzvV$XZv;eZxpmVOtrr7V6M?W-oL9C*t;!L$V9=r4Db9Xd#EOzrqx`8 zQQha&X8$gdnjI8mrb`k7U+&Dbh-Z$8E`j$wH<^&2Npz*$a?}cmV7e|@!%X9~L@`a0 ze4ks#*dHNuo#B1PHO2*m;Obbq$WuiO=Gt&(PxNi8_JkuVbroAeC96#!U^0W6%!Ko-H(9U$nps&p2OMJ(h~I!RR~tmAVdQ0a`%IU|ua+aG zvkpLV<`&jUOqP+;n@pbv+=1}_>evhO)ai=Ev*5cmjqEXrLItO8xa%NEU&hZQZH*3K zVxmoyuT+77UMcVXtaL12l1o+?WMY!ScaDV`X9p9fL*uW<91HOqPo;=s=j6+5*E%is zPP`|M2@J7G89MZ#Vh()V!y^+4bqG)JJF~BAH<3xSA<52{@v(<4^WhvH0{n(R{I?2` zGWEpAJ2g4>tp&R(Ss$~yGX)~ z2+Za5jJDc1-m3gZxbck+t-rmEU*>og#(9!fH9sam)!+nrX1O4Qc?UE3{X%5M-b{S2 zupKuQMZvqoL@e5{iC%Lb!-K**vCH5c815i6>il8&Z%Bqdo@_}+=L*8%CxZ0CurvPG zeheP0Tn5!|PO-b*-o=?uB$%Lf3HnLtKloEEM^h6NiPfR0RP#&;)LYCVuis84p|dMc z{`h=yh4bmwt#+mtyWX+;;-pbi&j3CaEQ5rOFW4bffaAr;Zj)R>_Iij?`>2)l)=h0< zrkh9?Y~6_ZPL-_1;)V44wK`^PTNj*C>PL3n7nt4@3sDw_i7uy~4zTN~T#O$qD;@tD@PaN}&1#KEYvWn$#T_GVacBbLvMH_JKTyJ9WRFLrEr?akK53sI7f2@+!wsYDo zg+LX~NE9>^?QJ}n{bmX1c1Doi-?xW|`)Cnu4J8~4J_h~2dRfQ5@@i+r=~VE!E}rR3 zV#I0-a46e@dE@j4rkHfVYwvTYDlwVv-F_bbSyDEAIEHTMkfl?#XHzFtM`D#+0=%(Y z82IgvN~iClr?U`NT~Q@xIOKleR(|#Fr%O05K|CH=Y(;+04JNlI7eb=)AMn=Fh2!Q#uju+6f{9HLRogLUz)hHO!v0V9;~qk=hSC zsNLp1uz%o%ksG9$f?1g;a&Iy3$Mpi7*?An!w(Nl)IZ348PYe4b;u5^R(+`jP^oYlS z!)%^uE;^i;PIe5rQrjD4jKNWT+Wa&HJ&q2rD|VdcD;PzC$01ve;n6?|HxsIG_X0@X z-NL`~&K3$x*iD zi!j*OZy>hk8Cozo9$R(BV1?&Y`lv1r$xlzJHnfCRRIi7aTzm4i4>6%N9>)q|;G^?| zYVo92bSN=GHLDsF8Bu_E)tl^yiwoqg5+k#|Xp!*^l2GfbO~bn9V1HLJy12Hp3ZKrC z5a9sE4~AJoq1o)hAxkoNb2^ldD^u0$di09!3CNjNg{yhhjM4^VRVBh$ z;Lwi!pUo+62O&+zZ$nD7DpmX<#RLWALwB7FwXw6Ohdvd8@kw{4&%+0!{q4x2^k7)| zF$3;7I^ohFS^Ck%6O}@vKw{wyMy6o_(Ms3|sh?hhTE$rqY(j|kDFdT^V=@?+On3cs zpsv%+z<$t^*k4b_j5J%CqAf~C9v0K_C3?8;?gMNJTSXI+v`Fg*Q#ioRBz>VaG-@z| z4a?5}m2ZC`=v)l0)riFLy8U?nl|Qrk!dce7Vw6?p{GG-VB$;2@uR!183?uYLnSNfe zlN=oWjz#19InOYU-hb~x9VEQ4G-W!(xEayP(K^_1y_m`~rKGw25a!!P(H#Y++0+Ja zNETyJ`Dz#TaBSE3vjjAZT#Nph7ohD25dKqjQn1~PXz0XZ-F{1WAATRQg1#~3BpOwN z55e!A9HiSai9!7!#_!05_+x*V0JnTRqnZJeVxKWFyacl5M=_c{-P^n@8O;Z!0szR~s9?5o=TOdZKbA1@Q_b7($ZUH}kS6cG;Cb~y> zu`ye>f%TJDs2=5y2eKdY{IXhLjrUQIQgUH`^;hvOs(xZkuWiG>k5uUSqSN3OR1TG9 zlQ_Ra9RJ+Pi_F(^6Ue*7d2my+6;t-8QK#bX?4S50nnT6)t1Mg zzCf4=VL9Z?$%4V96UgN}Yt&4=1QR}m^Agt{!3L*E^xW}R*t_Ep6O-yfwxz7V<@WF3 z?(t28DN91ZCNVPSgdy3j6vwP;(yP{$xd@l!BOyfR0cJRbq5oBm6TcEgx@Q=YY)4~y z_mDfgt>GYa6sW_Mu}x%uiwJePVnJi}9)YKQ8_0LRm+bQ2m%-w{M$TjJOj`O+!ZGV? zcC_^`5a}D3B_7SMx|C11YRc2s<{sd>Er9GkX^w$1(`ff46Dl{Y2G5&KL(d0s*uxiu zRI9u2MtL_pFKvN`_v6_YwJ9|I@gVzVd^fE)cLs;|OTZeteQ;{#Zm7{N01&?mcgz&Y zj#f`FfAWC6x>y*tO4P7sJt8F5A&tM=Fb&FnaXjJ-Cop+Pb9J_27w~0W=wdHt+ULBMD&mw?zoqkaV9HR5la1 z=op&!_Z_oc_W-g>%;Cq^=a_!b1wy{;Ao<7hc`0YgFwXl9&S+0yj5UPNHd3C94jNv|Ay99oIO(~XJ8)Y)X{_e;>e zQIA0-USw{EJA3n}9G%{!PhvBt5#?iTa8L^{>GpXP-%<>=lVnJ(*kanI zz4>wu9TS_%e%yK$uS@&j(nejf>`*nkpz0np(wTqdx7k6TaDTBe^m$H89 zMYx}`kmWH72U^PE>2_(dH$9s1zo|vrKiq|iY08wCokHo0cJ!-`6^@lCQ|}v6WWMow z{Ik@HS9ak5Hi!?yo97-NyM7fp?kY-q);ZI|kw)~ipaAGviPLE3N_b>*9aHy6lK7Kq zIBoPY+q2^)E8~z09WVbfCJ(u_iH!?srRfy56*uzI|C>VU7fmKo?{dLy)j_HlUj@Q_ zi=k0+Co!)@_Vy(^C|VVQ{MtIm4fze9cO_z74j-d89L3FFUqJHG7tq`;f*-CW!@eo` z==$I~dr4iE&8oDruyx|12ml=TL zN;%_7lw;#fa zd#*I5XMisiI?60o)S=7r{$p$0#isx7p{6cnu=Sq5qP2qctf5dwQ-b~Pd9bG+LjowbZ z%Sz93#K>7ryrd(q(0=NAqI|O(1Pu1j>RJ!VB+p|~IsfqvVPl$o#}Ev}OJRYW4K=g| zI%d@Y|7H+wtAZVIlo5x=_KG0+@&LzX2$5gwt8m7nROp#?o|ixS9^+?Ogx{D&RLe7k zpX=pE2aRmObi;XUeKwn9hl!HH-TCab-d^}v^apr**cXCZPc>k^u8T|_5p9fghiOlft) zC06TS1)p!ShU(qlPaUPCX`GrNou4d7J~-Wkr7eYcOwEE0A0I(3Y?9cd4x!lJb3Fg3 z4Y>ZIJZ&$Th+j@9(t=Z^Q06R7>U8oLzZ+?gBXS&da=vI&Y<&OKO7CWB7dAxa3Js)Q~kq^^0kG*bXzbD(f5V_#AL{4BSWfq z)tLTW>H+l?Z*VPNoOnhGkxTi(IQH=`^O}^x#_7*+x%6$Y_{{0ZgA?%iY!R~fM zMTZDF5c)GGlU=E6`*D+y2Md<0IMZe@%ic%xXD}!(iZ^SIP{X)w_ph3Z|l)p_X?_~ zjpak6^i;aF?E|B^lhb`>DUf>akIa-UU07Rs73uFSu$!zSEdwVZy=e^%d>%)7=09Q6 zk2Hbxlq?7A=U zn&J-c&QZ3p{x|H9-G$ShAXZ=y)NIy85l=l@8fHohqz>Wezj|&opKnEnw46cBxDpivqu9Ra!?Y>O zmn2>Z!wDPGK-*A(Rx_VKC#3=I%DYj)eg#s(WhJy0i_yfnn(T~jU$WqC8UM!ijktp; z;aer&rl&)SxN^tcQ1!6J8IP1-kzsKK#S4^qoZ$b@|XeALyS=o8WTbKQPdZ z1|QXMNNiDN9hM`VCNhN ze{G1b%;MpYmky15vW>5`D+9J0bTg;&`}lWu6@p-45xpfPLY5bD^Qv7zbja~BgnqHd zlO=BSST!GGb}^)Wq?@;FV-pbT8ql@yWOh_j?6GWMJh>jy=C&$rD4GbPH>|<%~+Q5`Q<_}xUxUnN0G_~NuOu?43d zzKgFSB5}QCAO0#_i3$p6WzsH8gHj|wckLf6Iy8+e)w;-EyeR<>CGCP6nHr$tyt z8qD}_QNY?epWu(~a!8B1jV&umdA>(#;oVnja-MHQV6z+Xa6g6uo0ITm<5FU?+LnyB zOeCs}GvP>{E_=B55r!Bh!d$Z|_U+q34BYq?7HueGc1K0>56K2V2j}-cp>It#+frt@ z(}Yym3_;u8g;Xx02(|86QX_d=vU=xprbOC}E|@D%A8MM-w;Ihtp+ZHJ1r>DOuTKQK z>KSK;D|qa1AK2KmcjotEt;IGT$k$O3%xLgtmctl zDf>{*gTO}D1oEsvAG({AX{bvz(aL5)TJI9}Fz?~`jR#Qe`w~|$4(J85;fmpRz9=^v z6rM%di+ir%>GjY~rqA{&J4b z+9qVrBvdNX3hztoky{ybd_g8ra!$h!@se~V_t~?bo6w=^0lxX6hN>s?gy}p(4~W$A zMr*G=CUH?dG*3K1r#zlQ%y%nL!IY^)sOvL2Uit>&Z4B!;@fXaN@Z*hl+M?cn34D?D zfARFb1dfwR!bMlCnT*E*Mt6VPjY&#bPBT+&fYo8ht$s)1e`F0~>^K5auVl%&PhB8h z9sw=Y2jF>b6TYY_1@pZo#Orq+EobSpPgO@3wo~bnH%V=k&OWBfNrGIeC3PCz2K#LxHU&|Wab0QJyB6#6LA}Fso zOh4=r#G|W|nR~ro;oq1qmjSp55{=i9^`R0llxa?LTn)*5he<@}_-Ces5yJ6W3F@bN zi#;$yia3m!(dl2LfW6X#W5ZeOE7e<8OMLBN_lP`J4ogGbl2*P#K?bYGag1XRk3oia z3G-rLA@A-_0d&&{XY39wAQ2J*^s((!ntC@K4dXjO^HeYVb2q06!eV%^?9mV4L2$96%YSMd)N zbkqnxs19Fm>BHVbyFh$TDcqM(=D37dridp=1h{8Vzx_BQ&sLxp*Ue?Bo(fafrhM8y zU?OY33r-80yxCQhYi%acI) zVi@epqT*Yka4xePI*wW6T=B#7SBgCe`k+Pw-wl?pf$cY0q&bz5&#UR|Z<->yQ*Fj@z4l?pF^q>O=pvmUNTp&9EPHmv9Q1X8kB9=&NN?b#p;^%ROjp|tXnHd!}tG$ zv#%0?NB=TsDp#TMBoUGsAx$dh{bB-|4uCe-Ypmq@xwE?)aQ$g3@?32md0KszMo9MK zF-;z{p1TYlLK#GTNh=&5i)Zu}MPdHlXq*@J0zUj5gv;%pq0O~{6%5vair$G>eNLI$ z&pk>b&F+D~x+hFYq9niE!+BMwbcXE{beou`s)Zxt(Xv$5XwhuD!6gT58Sh@)s z2OfawYiDuE0Xi-uIS#Rh>ldzxj<~rlvKYfsb zzKl<^78ACQhr_7>WLx?}Mq%a$_GQrtoXGnCkNpkl{&8c_ah?q~=5iS&#RBC0sohL? zlozi#RGjP_{K_^zOJ>~GJi;_G#!sCnObVAf5^0|Rx+v)%(4D4a-#2mki_6ljnmh~T z$5W}rJTdYs)r`6e%aU;^bN218GI;*=J|q?B5dXv_a3dxT|GB+Kj|vk|YuL%ySs8(d zMk_om@__zbE)Xtti0yFPOdY-@!|4yZs`<&XG+ccKIq%McUyCw9PFRYZ)$L{aUd4m< z`Dk?6qr`mkUpgehkn^$QsQ+aGtaTA<>C?^^yCU{7Isg4QLk`^pZ$^&Ynsc4@w>sePs%dcarZrt8C=I_AfG+r_LkGn^ zGya!2Ka@Y0dE+AmlO~JOvOhYoZ{uDNu9!svyt&LS)0^x9FEbL>V+V6xjp#LxnehFW zDp{~joHD0JV6;~ex2^Ceh5t11?0qk~pn?!?C_&}j~fq^sc9@_|Y&jam5$ZdUOQGCH7F4B`4{jRU66ukvx3u5W=^7oR9LdukmAu zFD;IlN5q`Q5%15Y9b<#=Vc8pI3Evjx6fOjtZe^U<^$ZlazDTS6Bq)_i($4DEz(kXoAsddTCM)2+ z--Aq_rvx3mw~(y4oQ?DHE>OO%BVI8yVYG(qNYHUvdYETQc$qT9<}7zdKTr=Nx88xA zbSOOQZ>UaQl82YsLH6)zEh5`uMLxLRVJBS_!C^^3x_C+j20OLl3jv_ziOc8;(ILzc zOyvitSD~@7HJw|Qjg22lNpXQBR9IbxCU1FaXTjCS-eSn!xCtgcPK3fw%2nGpNTY(| zI-+62ow<&Utold}r!gycVv%7x9<+@`Wp4p`LB$9b0;l!O*i0 zaQ(71_~Fh<2=s9x8)r6JEf;WR*PD7$zcCH+=V}?UwdruXaRx1StVJ0Np+Yh&1aDEK z{8!~Taz7M*-8l`~37Rxnh5<#9!(f%X2~~EK15bCDS#tX`+x0+cp)76gs#NuWlE*BSsom|G0Lis{+Y-%Wj0qsn#XDvvHe*oGz1pg!@X^^cR)hLr9ziLO} zVCMsLToX>CAALc`txGXt8ON>`?PR)?523HK5%z5ghEZ{8x@AcXvr~5!IluiqK*4ub zU1c%41zli%-qs_ndjs*kq6|jnc(Ob8&LL-iUS?i~sN%Qg7wE1z$js3=#bpj1qnQGz;K9hqaagb<9>nguFxkPuY+jTin)o!p<}c+q>4Fp< zJTJs3PLU-qwjJh=ZCp=MpA=S)bc+#zjzHoSl8Lt;o(Jmwf>CgeA_@_4%!;$^VDW7P zpWNl+wS_=}zNXPT8Es(bm54^Z3N-&+4_{=~DzuNbq|%Wp%)I`3V)%0$RMnpHZs6XZUy!*tm5S_q0rxr1)4A7+o-rLp11#D!#++Rd5sd=H>{%p2rzZKS8 zl7ok#!nES$El_f6z@0}3vu55oMt1u!O!hT|AGK0su-%e4W{yJ;=acy^-^BKGzk$K$ zQ|Z19&Ac^#Kf-&(PwaG~weXb4lDsb;@f=T;9*>tpyO08q8t%a`31JeQrv&b-23ot# z<$Gu}&s|E(jD?Rj`@WHBZV?qDn$ zXOY0?0qjv59!i|Fpq7t?sdF-y-Eh*MwN}by9&Pc*lxAOA^iK?ba&u){o9)br&)i&5 z{2ab~sYHd}=`fK2*3`E66B9FfA49(xfmYEmB2{0++)UD;+J=ENsH2x1`xgoEmmXlT zku=4j4@{!6B91=!!=3Bi7_4^{x3_;}1wPtS|A}isTGWzs<`~fvWkaZ?X~EnY@WJ!T zCUd!7s&tBVDcrd!PNts|A^k({FnCY~d!1fa4Vv3P(rqWI<{?6_DVE~5InA*Cn?BM1 z=1QeEl)}aRb|4^`hl}J7;JTv?->*X1 z#zWZVwvEbeTt^oNtR?y{r-J#|F3ft-z$^%~BJ*2+@@(`HP**`4pS*Elf(lj>1^=h8 zZg&*vne`C7?zqCfgDY@B<8(?ZoXOSj4t#$10_s%9V?mx9yPh$ldF`w4`@k~VDv^TG z$Yo!gv_>5VZ(Q*%5F`#dgJO*X9iFTY-=x&>SIta91h%5h!+!jxREKMuFXOhwPoXBm z1+MgW0Mj^(!Wrk-p}*10C8HW%biM-(6kS1Qh9Nv~<9s&9ra-+=E_t{;fG02{K{6A5 zfSIWu^?#y`B}c!4PxgL}G4a8%J{#KKxP@MbddnY3422g(kz_PLl}O1>xZpEc=o{ zzTf$T`+g)t=dG! zRQh;2B=xT*R`&6jwK9$z@-QJIPo|Mrei7&f6vEq6w^^0R0FmkYtg6pz5#jU*)GzuB zjy>ks;h2a^bu~z?krQ)i+=j^={)7c1{7Dr_RP^denr*F1 zE*$bl^O>NKlS}33Y=zJ5(eP;A-|BOMPuUwu>ioXHoNqmd z1%-(TygO#~{C|&gaLttr-tcKza1PQVzppBz|Fm|a@H+HraY zudZASJQdt%)%#2gG(HJ&>q6*y6$5%^w+xM4?}lEUO7wu~0(@O`7_J3oqR{1QXdY~V zAJ^pJ+6B5y^1*GymoG`go*c!@lps1~eLGs#9YDb?8boM{Dw*~76Kg)>BV4}L#|q9C zqBHvP=&^0qJk7mbXnH7ECGotbI9?D zHgxmKbhdM^c$JK$4)Hi7Oy&>9FyeZARQjYvyk&-PLx?_=$@`SI;6~n8!sd(7tAFDr2l#Ui$X5W2Zi^;yttjOLB+}n1N z-Ec#Yygw5}oudqxY;AAYN_P^Y#%H`wmtR3|Y!@>iYf9&j@1RR&3DKof4Cpq=a?qKr zj($?8k|6Owh-DzV*SI9|H*AQf`raLlT8p|2s9&Ix5)`N=dq{?I=v;*)nqG&Nv#T zN@7Qra4T{4!Zw5RI52pI&R-COHESZs2jdCMEFV$VBGWNSS-ap}%ZY*fw% z)u*GlYx@jRr}YqXRF)IVP(%7NLxV&qx8u`o-K=-;aa<@~Oa@|y7{~lP;Fj|;-xo!( zozef1fZ$^oo>&e8+f+&Gl|hgznFx{@hQys|z&4JtQ9Gav5=qMR=q+X3HSR!+t@P-5 zjzf%Csm8ia>%x0Vzu3-BaXQ|xkG76n!<-u%aZG6^@L~EG=S5mTw-(JR=^VK^>sBeZ$yY& zm=vuHc?Yeh)VX@ZWteUsMw3-@X<%$TtsLh#>5L6<^|Ju~z|$IB*c(I?zWl-8QS)Fz z{BjU_=8m_QmEoYEIVoAz!*pi}f%D1;`1|k<4!%<%l4t7R??n&%^sa|VUi*o^|D`>I z@y-&ykr}O@mxxz|lxWfWIb=oOGkovdi!)<5U&1;s%y};h#`=~tBqAM#)y`q9$u5xK zJ%q21MPQ9&G?9_*<9`2ksP?$dAMN!c*4tN*V;61tM!G%hPwPy^a#JD^5cQ>17dJuR zM_JzF$toy&qMyC8C=1d=^O;YfKqsF*LMo?oo=BgssGJ#zKPANJ#Ou{i@Uj6?%xht4 zXBHVO+=d&z`q76zp}?9}jk(a->IB z3p`dlVPB4pW5SsnRwHFL8J>L!MI+~dmYY5)6AR#*kF2C?N~EgtE0k%1eG=@RRRG&& z?xkbK>YSHFhnCcFtZkbzYIn4Q`fY8JQyj{g+wFzhd;OR%?KSw1EFgA)A|%)GF9-xb(rps{1 zzK^l3P$BMK^>{qx8G2r6!)l%dmOV*iK2IjAoZkccpBR^|p-yj~ zQUtZSJ+$tWEscJc41$}sG4~dKhWwZ*aP4s~D-_ob^8Y=~O`3UBPdbizz%IzEMY z{B|NQl;b$vPL059uU=sPG=r#BH2K11A`zQ-TK97bx#paV_TNsxZ^c@C_v{1_UsQyO zx8LxeOB{rIsqWA)R*9=5{)0o|3RLmKDrSo9Z#HSed+e^g2*=hHF|Iz+RQ|_ryw#kI zy>oO?bn`C0eDNLlaUzS2kb1)$JY@$OFFs*HOCTKFQqCF)O(Dl*E3jf@A${M=)%Hv| zE{jN(h~D$Yl%tLa0O{A`b}mfr=7;Rc!NwbTuVL`kUA0j0B?oNWa(V0;6%>dqVxvjwMFS2;Hhi4!xK%mfx8vSYH{aM_A!W-YgL&FWY@n9((A|8t~W$hF&b zthc}_Oi{=tpA>yzrpPm(!_~)X)!=m?fjH+4>c7^!DN; z_R~~l;+#8?#tF=V9>Hr^s5yx4sZXm7(#@&Ex|Ou{^8x7AQmYD^6-ZMGyogngElE8X zhbOIH!NKY;I8n!vOyJux<|R*Hf|dXgdXUR6wiTwCrt0&b)SF_OWEg%8eSp_KSz=!Q#aiag@tiy1+BWu_bG;@5c&`jd_o%B6+A&tiT+4lLBYllxSqI0x=dV zMm=v^daqU*rodXN^1c`h zcK(qA#xNc`Kdob<)~nOg1`NEJ=!~6hx7Y{Y(oy)G80I*08PNxR0xRQ#@0V_-?ML#k z>qIuTj>phKm+kbuCPBTSJrsYL(n&#;#HS@5B_2f4#mb{NEpiI=SY!)t3dO)yb`tsf z=pR4kn>q@YOoi9iYM@J2oP^A}LOS1WV6V^_uLOfk&x05EiFZRij!?r0|y zs8EW(o&LhuDouJoy%89rA!nGlbINsw8_;4u{H%6Ib*Vi04er!KZO1MA*cRWRf z#Aw!8@g(TVE~bG)7Ub34$y7b!3=^(5gKDpyK|SR|3A1`W8*Vj?<}j{kDWgyS+>EAY z%P*j*lQUt&t69hMDe&}z1F?8k1~-#-lDUdKaB*J*{4$Y52e%IFGAhQ`PEq7voEwO| zs^-q0Mx;*!amDXkc4^`k=1X4#o9btasabu@Xp1a))A<1(iB-GDUkL}p zwaGcRi;xu@ik^S1D15JjzV9w-%cF=G%$O{E7)yU{8-DqHIS*h ziK^J{Wh@p2lE)qKY)8jwwrhAU?BX0%sRQ;HSffgh&1ryVwqLNvw}^QXr_4O9PGReM z?6_2X3M1{21?%;eQGTWxY&KSA9YTvS{rMGasgQ;pt2Mx|<_rIfsuYA4F5^{FE2ecJ!k3x^9s6SIW)VpC=xJ?MFp=4@1cbsYA?L`7wz6`fZl>YnxBew)Y0?WtCId8E^nq&hN#oR?qQ!bPCb=sX`5U$-dLQ4OTUdlfUXWc=FR{c?}*XdLr%m*ErYe0;*axV+^HhBH(4MBpdLQ~3R)}K zQ*SS#zD5M>Sscq~jCX-AH76cX++K&{&O86QhWAbx5IOfoTqre#8f|j`t4|L>%wPk| zK59oTxXdL#a}K=j(4*ItvrsQLg05KpiXCW4Wz*)mAiqlj12-Fy8HtDSiotGd;bwj& z)3upQrG9k2JcpOOdn)FXRf1!;0eyB(n!NuZO$IjqMxXO_{L!p8%oX#mFx)D`@eqyZ zAIWoM%4Q8*RBgq?+wY4CkQ2yxKNYh1 zhku&V8nvacC}uACR~(DO?UQKQoIRvxb42Z=Pp?_2mpdWF;T-2)QX-GnCd0G61MH9M zEAX>^2kWRhfsTB-i;fG6LCa8`2wv49_gCgIHQY08@ISoUWnd{V#%

oH;hp?ae0xTjDyZgylb;p+(&I`@a?M~t#4z?ee#5}7z37$sjJbE>9wwML z&^^6z%y894I<=2;*G3Kk|6e;)XxzbdS$14^=nJkc6DF2qFIh1QIOcW)3g52+yNA}; zt@;6uTh*eRe>~o1z2W)^C6eIXfjEvlt$24Zw{U}f4d!$tWeF;pi_+{`NBmc}f$Vy_ z43bT1iMzsY-tF(g@an%6By`(l97519YXi2UXK;6I315C2vC#G-dYxbem& zYS}4DPiS3%1{=pF)l=Vfhop|6|v!vL#DItg&nj z=Lze)1hQvugQun~Z*=PB&_eTHd9lACVhqupXK)P z{YBW6Y(=)WnNk78d^8j5L9tC!h{hHZ)?#QW=F|sLoucXBD<=yNeJxR(+l8Es>tmj| zo~4oU;RJ-=Gk!sqBs63lE#TSFmyH^X`gR#)#@A4*HM_|2wO83)GgNWi?hpt{NC2$~ zQnX6w3f`wl(9*P$j*Qe+mma!+3OQzQWElpMgv4pww%*CN>Adyw11#L;3OF%bH5g>CSWByop+ zu>neJ@TS2UHdj@iip{x5X^*_jGUJ;8{Up{rMEOSbt>vtF(yo=gl+~ z0ncQ|V&oS$kTnQ`<_%Y|(()sy92TZtro;Ga(qj7Iq&b%EJ%hWR%HSyvLcSU2f>f*! z3i_KdljQlw1o>YEYAlWU;NwVhd-TmVwyvLx-<5t73(G%`N!fS-<@cr{C%rhfa% z*XLNBEjAXcp}QhIuqAOC19A>u%yFz}`WRhn; z1-nA+sZPXU(p|8V#LxPMncw#?-iHQQToQnF{@l0vvb_Y&PSGM_597w;s9+mPizh9E zpHH7Nan~e?utG4do?Xd`y%!*>ezxG|&l$Kdp20t5Ev)IQ4d^H|jzRbKLP~=z+59z{ zEIX=3uT+WR#I8QJlHJ7YNx6>elJ;Y^MLNv%;c`H~?!noef)=%I^)9CxNMV*w74Bdf|r> zc~DRf!{$*~eEcGFHo%#zc)gk#tyP5nGxzW)=Uwz*D%csD_K~7>PvPSCNVfQWE@P}N zN)D@tQqR2q@Q3~=bKa&HW8O?=!#uRf!>cUBw@^GVe>a7*p!iq^KH2>r(^n-{HK+Fz>^wV>Rz3Ac8BqZ|cT)z(vvpC7<>j-hod zMG^z`MM%$7W4zGcgh!A0(Y3So5Z8)rs3X8Jm!5iXx#9u58_>`8rKRBh@OSX_P9@gP zD#t578ky>iLg3!e&de^j3uz8lK*hb8bJhKZ0qvRSJ6MXBZWKa2=TZ?(Pr?WNfh@Z{ z2QA%>(^XNOC~X--70VXk`>sTw)qC072I;6-&hdV`rVzXNUF_i6ndDXL8a$q_Ll1PE zpie}nlZ8cGm&RcRx^|Sn{yZUIKbJGFz0;t7kr=g*cEbcrCT2grax_;;S1P9@5a?7RctZdPP<*NQ{1 z>^)3zFo$hzh4Am$2^30OUAuhx6MXU~iTZPy$Uh05G?~kyjePpWOt~|RFUTNcm;D&n zeN%DHgHHSwcL8|a2OD_bX8PykD{xvp*!_`mbY%M)TDx0-geJd)Lnlt+5!HpLdaIr{JDc*- zSC8Xi>I|YQwQ#>?1T25`82aRW>7^YUx6pqnEc_XTPC@I)-BJcvk8Z|2*6P@x z*vTZVv!=IJmyn?BDoA_x0qyq)6Rz&de(IE>vu~*2?^#>0GkXSD9r;yT|6?*8SlbLU zjCL|vj=^l#mm<6re~hfiD#yv`is&^Xn7{b4BpB2jz;H#b6SX%J3wx%KVf%ONg4orJ z(fw64;Da)LUa<^hu3bW>Q>W?vD@`E0J{R9?&qOkFA^kGdhkvwBo<6FcMenHxVB9WS z2*4GnxcCa4Ts^=(fa`F)bO={18(WT5~a3_1U_5=-mV|Pt@8`a z-6V~>gQ757^Af%da)$?v7Q}1EED&5#$qN&S1b4{;xZ|!rWCvblU!GMbWv+VEZRY@r z4u7ropOpa4F{me6JgY_ugirM{Qm&Lux;*3HTh~QAez}`HY@7~HHVcvzpI9)z zBSg}o^{DV8JJjqx0c+BCvWK7N!`bmp)*>Po5AWy&_TvXEI--sB?~MSb?&aOt&%Fy) zW->F~$N4>40_3FNauF)@yYYwlS8sAX z$osa`#&j3%ZhC}G?TU2yb2V~nbOrq;phy&k%weK-I8I@Q@xa?OE7hUK*?ML`*za(80hA?xOn=4DqrLkA|sJmT`xNj+@No&JFeCsUe zx=g^fqzP+(Pawe#vD97v4%;W&#TL{rr`tXfc%-?Dto>t+?C%yBa0(@`^)1{hod6FD zmhj)?rZd{+I#hXY8w^&O)A9m2=DXe{=I$=eDYI~wT%nUlxH;d%$QYRaoMd4!MKWLUs zpc5{f!8_l|YW|+#W@T#8czsF^^xBI+Zifd*@y0RxT|3kI>i}3EKF14OkqLtVwq)CM zc^Vcd2)z$JBj3^rzN~)8E|b~|>u+k&fGxHpu3Lk=RrdqWosv{+!aekwy8-%o^jT}i zx%A-ra#YqU!HBXRR;JmD7`Ub5Rk2eX3-viv+$&>Tdrk4?^Az-)at_^Y?I+)^*RWDm zzEnm)3FI^T7=>#g`0%7u?YF3EOun`jpZJAx`R|`hb?|9MJ8m18#{GfgmnG>7;Y}n| zv=RGz-ASqHe!{-8g!j4|ut~XrvDO82Pg11u@&d%u)sa?~`_i&jAWvf7vg1jQnV8Gh z;2_8M>Ypu2`r8iI%-9lzb_my5KoCaklz!Q z(HkcZ6R#(hw9)hgdwp3Vv&Lo=4_k-PJE0;}bqBD%0!Q%mx2H@)(LZ=Ca}vnN3K(@i zh5c`X$h#PM5@HyH1vh2kQRifS^p1Lb(K3fH|EXY~)Ju?lDMPM&OJGy4C$T5;4T*%5 z0;6%&ha{KD!vgy}p6b6ltWK5$t*?=#v5K>4hK4QfdHfhQy|!OISuw0s#%6kdy(uI|jk>@adccRE!_ z;P}r&8Z`#!4Ro*T05riqtXk_eMJ2Qf$TR zSL2Cxz9980XoP5)80=#YlGOTUJlyZcd82+ZRQ@^Jk+qjBXeq|tLK{rzPGL%q@o=KU z7Aj~q!0jMp$jbvC!FP)gJb3KF9+r)wdR^LR<%*1#lpj1fb&d6sHK)E2>ln3)ItbDD zjc?Z|ki9Os__9riEQyPyL8FJ!q|k%JoQ&c+Ma_(-oEcNTt_EE18d5vs4(Pq*Pg5Rg zV|HT~<6SqAWBFad1wOVYcJ>sW%03RmQxchZ4U2HSb}E{U3ZTHc7EHN64t>ssbj3eO z=wTC~TYnywD+l3v4H0r|w=!b(0GK76$5$R4f4e&h@y9wY+xr2PRBy5AOJm3bXD23T z^=i0tC4muLx`)L1rjTXZjq&B&`LKwqymh(hsHQN0X?6{zdfPx*0P({=%rM4iQ^9 zi4M=$3vzO*pGpsVf1D3WGYtF0-i#r=nrltkmusa{H|XLOMAxP zO!jH2yvT^uz2RoPj?b8;wd%0&Y&f#d9U0}S)>>wX2mairL}vckPp_R~=x6m@%>FYA z%x+wU5q)p=p`RTnXojIlxB!!363@1rR-ygftC)6f=cO3MDq#N$=wg0`YO!PaVsJV1CTO_qp*>~9&eQ$mEWenXIHJBhpJ4{V5L!bP?= zQ4bS(YcMmt0l7LAquVcmmu@b?qsb32^h+KqVV6of86i5E%%!(wC(#}KZ$Uce9R%5K zV>4Gr!|=SjcxQ_wk!ZaQeA`Ow9XLuxGIXiKW)>2-9qfN=x1wA75Oi#lCgw|h(c#=D zyrfYL65IFU%~N}*>7(P2=U)dj)_}|vRAN#JzTp#X6%vs%j|Qvl=H0LV0=EalAl7IE zHC72g)Sq1J@&5q4l~!06wFA4oeCexn4d}5_f?r%F?cc_C=)N+7`7hgvq%>>5zYIw( z%My>~&vsDd&=#zZ(W4(O9%SOwCQxIoa)`b65=Hv?N>hF$4^!nKQd`zpw#Ai`jFlwt{J}5;^H-fsHv4=$zaQ zw6B}%-Q0mc>MbZ3_YPi%oMiIF{@~jXRXRbs0F+A>V0&N|jGTxf6J4E1kfJ@m%KI!D zFHL73dsczXY(efA)>4hKg z?w25)e90MtO-?fUE&kTk9N*%d_BuLu)gmI3G|b*ypvf48eu5{RmUu166paNo!dIOr zVlOE}`Wv6KrWV}!H_?Z9tc+yW9x8`hiLEfqu}$ix*iwN>e__tvC2(&nkR6bdfQ-SF zAS7#tlYU3C$)4I!+BSxx9-J>h{WY6-V-BAClZqob*P(IPo-VnULU!NTjrOLH?S-NYGu+Vz^lfYINuEo#yDW!-g!IlKU5*=Nuw+W@o^Ve-tGmgW3CeP3Zkv z3|1OXB8~q|Ao5Hb40j08Gh1K58##MozVR*&&AN+ujz+M)xQe$UtOyQ0=!dZTT-H8m zDedxKO(r-@L7QW-1dZc3mwYf(cMoJq3*&G?HlB4+!HTA4s7fw^S&`bL zNUH;UZb^`XuB-5s=N=rqJ`E~244{Sf5PSIkE&g1GODNeK%Z$Cd1_5V7+4IVNWd8UC zRG%+IOlA(Dy3=1?Xz?1laLrZr@r-H^mSaFfRM%W2EXf4eDSpxD8YO$&0 zGE-R|K+pfT3#PQmGNsCC(D=&+#aGXzt77Y6yOJjT9>0ln#i)@vfw`bu5JyDZXQS5V z7;v981g#$|=#RGtS;+~u+zufO)TC`_U_dxMuNQ(oY5KJ5kuH}Z%fhbscJ{Gr61X~k zf=Bn}ll-|dbjFV)j!_pt%{4cY;!-zgm?A|(l>}+?jdt``n?%m^T#sQQZ!9JzPCU9ZyN~tuT}Xr$P9^eJ=hLnU z%TU->oL$TH)eGgycneBJiRZd5lzRAqHI==MvWNY+-#UTD7+EqGbZqJPdwcv!+c4sS z7c+hWQSqMw?rS^32+gZxljB2c{mU|7-?>7_J}5vF^a!le;*pw|4mjaj0_u4KxL8A% z8Af@k=zf>^G4&Sr3`ha_EAL=2#~2!Z^B+5J%TD-dK(Tk45X@6(rJ{=pnKHHMY@?z9 zRAp2^NY+}?bj5{p>~h(+!F>?6*bOp%+fvc*A7GG`C4<@9(f5rUm*-ke!&j7|N%?d< z(NEcsjT4BInkX@`oC_Z-jmcQphuTjDF*NN#ImbKehc%Bcf$zm|U>fi9XP?!k|IW=L zlU`0_+F33ul|Pv*U&VRuqVwQ4(tRz4YoB=S-?9ribr6#T&)ds8i!Wmw8-8 zMb$QVrVz^3Xf5Z7EuRl9*TRU=VxTGcQ|Q6YAW)V13tzbR+Q!e%(D!YNwbuEAiNF>U-vGu=S*sFde3I6CK zt1tv&Khw-q-}pooY5iy%aay*v@Qxdk&vwh*0Yn zPBdRaiWeEM1&yw9Og)F46u(PQ!NYTDOx6>g{?kFm`b#yvw?cq?RoM&EMveB5qzh(QkV_w4!0UI#Ao6WL(_lN17HXZK#WvB9@U#(UUC_ion~m_shh!8sECo&d zLa@m7B7w#m=_eHnXi5D9X*ZqlUG;8~*JHKPF1f*-a*uBcD;gQ3qWN z`k_{O53J4LGE8X*+hRu1prM~R@3acH{854%&x)8+31#s1Kn&ZzQj7W9_6e88c#^cM zWlX5tT{cre4y%{_dTEXeyQ@10BY2A7`@)>+dkz4u8ROk>u7u`xSA6fWh9r5m z!n520s5Ys_cWsRzA)rg<-mxb2YvnLd^a$Q|Uq34%;@8i^}QIKwWa^n`%XJBxVMCL-zz55UPnWi>A|Tw|#g{AQ^w&62RoKYfP%k zTGTnMN1Vc+LG+hJ%#DC{d=UHz)pjF(%XOu@UvHx;7RJN%gwt$tXBsnn{t4?47630^ zG{Nl;b1>_>f34nr8*(P+K3)laUHk813si1?3tPQaNQusL5>+#sJkPTSlhASy`{+je z8}p$iFcG|RuTZxkA$opsI~0jnVR&mdt8&g7Cvf}x`%`71^+F1oj?IP(50}$w!_}bT zdINJswaJ3RlgWVxn6@7^uEx=n&~yZl-jm#V=ZtubP! z3Xd@wW$&?w7Y<)f%%%5-{m6TXiR26=EJ(+qpJ*O_bJc@?PV&UqYZMgaCs5l~8#uHf zjDE14NsD#eaq@{@;As>>dT#Hf4co>sD^rkeyi&zBr_E+uXB+_g%*7;6PXVeX*oESW^L^Rr7dS6cJ*aalQ?yc@d`9AOe9q;%OLcYEU)FpE|4k| z;IHAF4zAg^(A!xJ{k^?-?md!p?hjv5>obgr>{cA_ab!Pt@JQxKFEUeaoN03_f`2!k zgR)2**&pqz3&dX)#O^72B;ZFL$BEY^ z1v}DF@U9?O_LQPP#~6<3n34+&ALV7vVCMBAxFz3)$LeN~To=y4Jy6E1Gc3XWWl}_T zPXa${aEO`fBf>u{Ak5fw++jx7W#YA%QxM+Pi!vp#cswzLU38+CnS7`kme$#_LQ`h4 zN6ZtL1=W+u*yuhec&$ximdKNVvy+KMTMYzsB;%(NOOmItl=nF)l9e;w2IHHR7|F(c z{NFslK$9`{`6dN=7LQXWfgj+>i)I2XG#K;s<={0~1m?9%aIWn}9QD&ABb!8Ns_z9@ z_v#c>Y+OPNHm<-0pV}Ci?pI8SuK~2*(kBOV@&T09Xd{_M@xO!k=hHl<=Yc)7xjPe2 zer#YlfGQs96~N9`F88PzMp_S4vsfp|cybK&)jo4bis52Bl|Gfq#n$qDbG_M5)ggSv z!79S8O~zouF}#o#M7G4WLQH}wyemqgqLY%*>r)=6OyInNT*o`?yb~5mp8(sgOXyWC z15O`0A#?R{>Nv-YmRIFr#2khsDjgyC_BojJzQvtW{h;AE#rjZFXp@YmD%>+q>0vC@ zD3v4!r+nx2)U;#%x8)!{DUYn(cmuLC#$bPdJgxj)icZTr&~-x;SpATq$%P)wl`$hS zFZCzH9r=e-pOv$ZH?^|;6VEd4vhuX$O$M?Xoan`W2Wj=f3^sag704;3NfP+z0p_0%rn{QMYA@%$W{zpek{`>DVxsFD zl61R;F|*%I0!w4L9AZD;yl^E^Na=@NQ({3l?;j4GQYQKi>oM^BdAPj121b+4z~2%r zTG{y8N4fhjSlYT@XP)YHcas+d$ib!I-I|O zNoGozUHAl!Z~E_d(z-8Jhl5pAmBU2PKz{so}X?u%CG!B83hR^`pU5 zf;&&o`UAME#}iyEvvJA$0LCKEfmj8sV|6s9Q}?!CXn9zWoE+DJZQQ*o{3VJ1eD@oa zN)ccUB1GWW%1g{f`z)fw?T0p0$-vI5cj;}D6e1LDg%;|0uzh+qYQ4_loz`2#wxoB! z0h2g-O-F;imSCu&@gL^?&?20Auz;QUgS!?Ywp7y384kryWB*;Tqi-@Z*>-J9IC^h~ zwZ`~GMqqX*&Y7MJAzJbvz2^>SDBs~pT;B%$&8l?K8xg!N2e_myVP7v8LC9k{tF z2jq`WBc(o@sDkuETx(?pa)Sl9Zf+(%%nPDZG_NCH)dm%%7ece9Ddut9wq>^g7l^7+ z!^?iu?1vjO?dCcBmj0BfZuwj*7OIbDS(Yt{J8rG1eVxty6$k(4eeF;QhkI$dd+_2X$=L19ijdqdnS@GCs6Upi+{Drn(9K-W=Ioj#B!*atY^mcb3 zKdy<=xX~zR4ygm~lt-ODTM_}f59c}EhVR^-dS_Z5j%Nzf^0*1~W4}DqrySzRXD*== zCT(H=`_jr~T2?~v^3AyXO)ezn_!BnBhv`x&#~j0M_K=?`0u+ z7L~yD3SZoE-k(ZHoB~gs$Kdyf%K(e^F%vi*n@iFm8X^*lO+vzS+dczQ@~9Z*t$7GG zmvT|vrH?5-63t4yVu-Lh=U(M{&+hlDVV9{MWlr~j>Wlr<H4uJGnl{;Rd;3|-=^vgp?bdLH0*8ZiihdKW4=;uP z;yWNiKL*9aq=<0MGU{IY4OIHoc!3Md$+Mg`9Oajy+sHDwy67VsvJ72&ES|iWat&iQ zCc~=C8Du|s3O*C!u;R-U`crr<`8aA%7}ewK^n{Nbx4xe-3>HO?a|cMGNGrry%VQDL z)oK}};b4g>lyrq~*^~j!fBX)+2J)f6cLz^MRtZ`M1&GbE1ibs@AOD(K2EXmvG&rLv zMbr(f=%x#v*lsIHuhe^yjzn2vI#H6Y7}`pHH(Vq?3kOijIRsmL=D`+@BhyQg@uYyH zwd%x`Xx+4fUz{Y*{;SD{`h!o{cDe~n*B*j+AMOlf>JQHGYQ$1I3XGRVQo)By$+LrX zjJ4W%sQ+b0l@)H|3)NKi*d-y_C^?Ckc+I2LdI!M6YdM|o=Si3S2*;3(i@+An@ESi) zp*ueO2dWYVBxAxH5^9`@?9&_?*Mu0Va0)ISW0~lQ9z=So9Tlsr#Kxb(lmzVp%`aS` zSw@ItE;~mLSpVat-A=?gb7r$Eo@el<`OfEiXi8DR=w>K&D1eZyto5tA`|;PqHuh9z zB=3uaCXRKLGiD9SAYinFu74U#&7v!qpQ@6iujDkIJ#!x~PMSbxH2Oe2x8Jj$C5a*2 zwVd(MjCOkn(Uc}bCbr5)z9dz%kkM_tjagxldaGvKA1PJG$|*sEibq%-#<$-LPL zI|cW`UTbf9W0fb;BWmRRF(+bVcz{i4wPZ&nqp*6|8+RMHpp92MZ(5ubZPk$hPw^Y* zRs5GNY!}Cn$Q&9u^%;(?+0Xw^JO_1LJyGnK9@(L=9FJ%wlBas^jQ{V0u)bfJo@4Y0 zzs8uz#+TyqoTGg6J!VMHA4Xm647B`}hOt@#`~^RonT4l4$ebSzWSy%r1#d-KUilgg zKJSI)K1X1yv^IVCVu<79rL%qQ(`n)oQxZ7Yh%V`?$HtHtYAsrHP0jGy=GJGlS9bTPjKMnZ+3zU3+CI(F?6{MAv!zhrGwo3v#}LBW=x~5 z(d*#yu}E5`cAcGg*$;<{HbR}xSqz=g1+BB@^ITO=!G9t1V4dzn;?W(9t-H42=Ndn7 z&l8~jcAPu)b0hQ9;s7)~zs$^Sk|w$XyXmzmaZpx{Wd_1*$g{nl;H}^tOjtR>J`-3? zA#qFXdLIEg>8>&zIdKKI`&rWzYiIK2eHv(8SEaL!Z{iHaU;Lp6Qyl0_WuMQVPdx-z z(58)-t>>vL;^t!&aC|_Xo^X(3SI^6aK+Rp4@F^XmCb^-c+DJz+ft zWnrtqZxEQah=#`rk%H7{vVZqXIxZg$3Joim!6_%uSY;|+YP$$h$L6q~ZD+vQR~{sT zYLKZad>Atqqu{9p4Yp~RyKxQe`r%BY!e?-Vgw{qboQh^A<=kN>Nn5%>+H43)tbN}2JjGTL|RG{-`$V(+zoVt(oLu%5Tyz)hjs z5Pb17sD;m^y*dwZg~1C@&C@||$w2(tdJ8`-2ed6#C$62QgzZ>|;o#ScQ2xY(J1iimJ9`St zTg!ms>{INJ(n?~XaFAnlR3dM1I{X;Q0s8~DnOl#3vpLI@=`QI=;?|{#hpjenT+>WO zXI&Q2-0w)m0=w8ELrpT@B@@;O7&9}*$6#m47f7eZQ1oYjIdb|cJ9*MGoc5fdN_7!n z`lbZ>^SVLrSP1r}?#1w+1g2Y(V{qh-FiHQMsgrgG>VGz%lG~=kY4#(}r&^1Mbc(@) zH?^$(On1%$Aw?%7_(4n7BKTw8jNKDtAYvm!?~SaZ#RVN~lF|owud*2XS2~h*(@oIs zbiG#P&O5|9HIZlckLbH`exgLTDEr=`!sX9AyeZUGqbuxzRD2CN` z-@s${N$hP2z@2w8K!kJ19Ff^Z@8oNP-r4|iFmfsBylzc^c;g+9MhLTg&L{=Tpqboi zlwT=IM0U+2-?TZ7St6fzwZNAEByM9COjk0KRrA5IAs? zO|&To6~!aOd#gQt=sARGAs%Fs7UxfHi-ISC+GBtW|2L6*c^zNu%N@pb$xm5b@vGq3bP_K7PDM%A2Fy&er6rBUP?lQ2EE-D2 zE5+@s-u_jr(AIFGJTsp8GqMw}7;h#XcVlr`ssqg`i(vajyK3Kg3sCT1jdKcy@Slt% zZC5p*6Af;o@{VXot`MN7wWMjz;&N2dZ)0Pw^XL&~GO>Q$gm?cKVdbM0arZG#Wi%UYxxNRx|fA@gqObEKCtxo|}_RYky^~1ij!Y)PM~FzA$boH-W>NdrQI!326SiJnP8#J) z;b_1rvUi&{ef!J|{kQETi>97|;KZLe-R>kT)6k^%)+y4SFVFGfH4P%PAq~`%p2FG5 zy%^zY3^$LyV0s^JhBx_PtPF4&yg+TbG^2>E2uh?$8@YYO-}kj0ja=_a=mkFNlA<-K z&-hwz1j7c(W8s2W@bW`|i@Q z7b7d}zH^+zQC>oSEZHqI%(J_e#UJ5jtrsrOLQ~^V+$$r?E-bzYPZplVo}UW{KU$vY zTxtPJ&T66V;a_ZTkO*UY|0&2lFd!qcZOq@RJUWR@2d&;J*s*>R7WK*y8En;EvNnO3^dC4ApN1!-h5^+~;!x?sLe5wsQt(~WLsprs+e#!NCKbz@#+HJh7G>zTD@y_o zO~XWU9$XKxq=)9(5cd~CYtg63F^fDX(d>$ z(I<5&Be+m!h$8AD;XoH~_5eO)QV=uPj-UnGYD{C>E@vaG9jAUT5tPtI=??H4c zuR-0QIm{Lfg~Yk@VfFkFxHxMRGmTBGgPfjXM9db_K3#(+{Zx+Jxu!+!m#n6@xPHLL zGq1s*p#lA@=QBV3tnp!^6M0enA75jA5X$OR!}vN8dbqL**Zs7n3k*k~Zp{ZYZbbR=sD|Yq@p$-6TkmL z?YR@ELuCVVv91gLIi8`x6=zWQf)H`qT)>@4Gng}1yWxn;Df+6xhpNoaVG5TDf=NLH zF1ip4hq{BwZ-qK!n^MuY@gE!<*a>0LecX5d5Wc&l0JzfSC1U}J)6`V5#x9u%W=J57P9e8z@E6y&o4U4 zWmCSw1Nx$T8wyHveX0M5U*MpWyUB^Oq3I@K=B`f@FsQyHt zjyI1pdmd<_kW>{lTF}nEIDZ@Kxfw_2Kp;k892=h_LY+OXGM`2TF_js^{~!}PGLo@@ z>(s;ttHYhOzu^BIH7yMaZrFrUp6CBq+Jy@mj?zu3Z_r)h3`&~Dub(67Baz| zrSN0xME2>eG1OHOpu*?&&;#PHdD-USB zImma2-t9*QkB71a`=jZsW4|z3Vjr*CARjwsYEl1TTk1PM7AH=VVV-V}gv0x0(Z&

ppweXV7c<>aAGqz&g8EI&XRi+)Y7UJi@7?|;E zJ;8Q$sySGQi5ycQaKU{rUZBsIoR_1$zo*i*6%p`2R0-oWBiZA9Be3`5PbUAM2&Rq< zVDQj)9B@00wLu9Gv)Gx+d^`!MM+C9(#6{9%cL_cmNv2750p#Y!R8)x4Czp4wqB#$? za%_jyn4;DJ5f|hk#A6O={gBJJJIx@$gD+vU%nfUY^l)c+3IraPqg&*kSqbV^bG+Tf zq@7Hpa$Re|OD&7*PtB!L$IH>4;~0sreh2H$o?&90S5wu(pX}LmX|#~_VQSa9z_fL# z%+Pqa_3l68u!r-{R7|jj8Pn1rXLA?)**?T1r=G86HAvK~hErm7CFru#err?f!F}xL#Tz1hq5?;RE z%1@bSN(~z27}*2I$(G^s_@GjpG!)6BWigL7S)5=tjy5wH@^@gz-vc}!g-Fm=xdG-{ zg#EwI^hI$hc^?o7W^X&NSuYJ99+Y4Xem9`f>6*B^(3AESo0F~&ndB441TAsi3KnY~ zLri89K9ftpOY^LVsI3esxa7|cwtvOf+lg50yla)X*N&c&3}IH7PojP0 zTFkBwd+7RGg?KS!8xhI<$P2SeM1>>;BDmNGP7mutX8fhvnd!b{L|L7#ng5E}^sf$D za2bR*w8K`Rsc5S#iE9)&KF_Q5(5Yuix^nZtEo%|>wtmMU>u~b*s3Bd|uTL}%+S5HQ zj!^dP8^|76LUt_MK)&8HBcTsYLi)ud?5Niu_e2L_p=2AVRm>;%g-WnKSC5T6FoVh5 zZ%?;=c?$=&1u(itH%(fp zLo73|9A3N^Cg<5djCZ&c#EKeYbh#HykMo<`D?|HsjJIOO!c zf4r?dHB{QEXqQpXecf$JGD}Hl7>P=@kao!^Q4wh%5mE{Doa+{e6e{FHvdJcevhq9M z-+#b)I_KQyy58^CYYCr+p3UAUsH4=GN3b@g0tIeG7`1@UT+I_>{a62j+lE8V+Vf3W z@5T&Nd^Ha~U9H3;(y^@8k>{4bcuz){E3kdUo}SR%$sS41g2C!KYH(H!zDafB%PuEq z?~4bQFe6GltRZ3Rbmn(7pU+hU!?`)TVY2cR`nl7T{d!o>XTgWTd%r6C^Y=2UrJRSO zQaivse;eQ-{`+z7Bku1mE9UdVjs9HqhxDo!Jg3VxSVG%R0_k0ZK@=64}C#1F+18E;RnxZ zj)2A$o^zX~!}Lohu$>ySU`m;)a9heQqBFP(yptyI=f|z=zY*J*cBKY;GkGyv*C?R& z)+I3U7|(t0-ijNPTuDU!F+ih#q|C{Wk-qa_=zanGKcvIx_?sYOq`;~YM>0d1Xj-)S z6q@tS>7D-w3f4_TO9f9DIM~S49JTT6zq$A$o5O9zZNRN`LuKWBC>8Cd(Ql-fy!1|d zzh)78{8$$HY<@z;2P<}enF7dr?*qTI9vIuC1-s4u3S>@e(5hK8*)7pyD4RMP=WY6c z>vrzNxS@$`jh!2}xq2oI+iOMdzvKHHN@Do)cLa{KALb5?_rWDvO4O#@lQzDyg4D=~ zC?o4j+PsV)=>AmBdHiZrY4yijA*%?C|H|cB2b0alitPPLB~2ttW3>7 z*$d%Rre_Fx8{Uv-cd}tbkr;bABa!`B*+YDEPE)7eEcS4luVD~zGDc>rNek~Td(^%_PQh_H}p9}e)sXeNpQo(X-c#qPm7D<7PDth=ED8@UUW5`NY`(ZWSdJ~VEW=WkUe`B ze$i89ZZ13F?cXxemg>oh)Yfq$AQE(A&Ozi$Y4ln@4^=vAShK7XGkO0GLmyUQh|B@O zqzTUKm1YE5@pJVpaq@U>q&w@J*@in5GEs8cET+3_3`p&{1z)9g*!P%CP;mJ+Y}DE+ zthjTSgq!~6LjT=sc=&q+?NkgU^WvoFV89O&Kd+LLjZQ?}j#^A8{|}E3oA5q{hosZv zHW?l|&#kt2&0Q9%!lfC~bmctWJ?N83;+IXJTQjb5Q;XlCRKXh9mUa=<$rVBKE5H@8WKy__9|Pqgnls7HKK77G_9`Q2FT`$V`gkwixN+FSx?}dMhGOa{NNRt`370 z^A#J!yY_*J>RS@B_ZYQZYX%;P#;pFLB`$vB!d``IvvbZmOlHa`4E=8$B!9n-=kJ6u zwN>iWWa$D_SiFK#jY;f9&08+v(a{EzW2XRXY?xJkFK${<39tWB_?Y;TY*iF6lk_^c zyZb7fdodsDe&)j6@ylTJVITbVyA-cdZ#H|hJQr7xKxawTp~A2RP38!Qen@9_E@hn4 zpFZ+&Yh5qH*^_dh+*C*QMv!?H8QAV{Cb zULKoGg{XUbRo>!c!Qg`{V496cL?Nqx3HgWAHj=^qbjfJAlxP$ zYuYbh`?Dk_KYReL=@*hQ#=l_p`8()5Wh_(cUr4^@97KiLJX29hfzF+Gms?sholW?a zMXCh_?A^2}So6Y{x&%!HHG3m^{frNkRae7c(_u97c?#creK?!9#i;C1PL^9H(rRNp zJ|7}VLK72d)5lbNE!7PV{^PT=&A^)MZop5d!>6U|h5kBzH0n@SgKx}bmcQPUY2=Bb zl7$aF^p~X(;PGSMhN&Jqi7j?aLXw$Uw*gjdBRmX;5waO8w@6$&g?M{f= zdjyUJ91*S&*JGvYWmwPnNz7^EY#!knpIr-qqvnC!l&x&i zaU0>EzIGUBEatQ{Zjt%wkuWD|B-iAX2H7)HX?#Qve!R%f!Azz@hGiJHZ@3-qOGUsa zvK(5Xo#-VC4_shv41p!1VCa}0-ZfQXy{-@OZqYEjJ{C-W`xRoS)k4xYG#i{l+F?StB$ye4+@;~Mlz}F zWJuQ>4Ozxpg)~D1vqJi?Y*QL@Ible@|5IX{Yg3(ndSnXv_+112nFIB;@1dY)Bt608 z*^c2EoR#KSdizs1v|WgWFwdv>Qph{_j_zbfFW=xC_4Bdt;0DgjZ$F&3v~UXFSs>J} z;m@l6*TLuA4p{x<8(KVC2+u!Bv47upaMSf1L8|CEi5PtzmzbU>6W3&NU44cS;&C5F zyIlv{S7Kb5*HuU;x-Qte>>Vo1;msc&6XH1{o}Rrp=zr%%WyN7Q&l+CwEr!AsGD6gB~JRkv9`jMV<{i z_ChVuJ+=_To%`^n|4~wP!VnC;%0h}x6^NXA3U9~lU_YYzK*Mku(_CuI{J$yCpEo9O z@GBO_E*(z~Ss2pJYr!x!;&6k=+@J7~SkoN7=lW6B0P9zermvK1v3uJZ;xFri$31&d zeDix$tQZM<7LI3`Ci3()pYsmruz=@L6X>;m0nL7V8p;FLVElI=vf93o@_QXSt|iG5 zrS9O+{CLPWctxJWFgjcdqOnm0Wbzkl{yVIadzJ14Cl(g4_e=Pm*yTZ}pF0L3Cu>s) zr@LgpZWT_s#pk;7qNwnjEt7N>rA1#ZJI`I!!==xi$|=8MuykxPQx)GMF!H*~1x{1uPvRa z?R^Jpq&(=oG6T9~!+0*H!JS^uKZ?m2`?$ZuiQMj$OF`rDNL<}m3OBwiq7B)BAjhOw zNZ&!&p8FZYj#ogr(ic>`c^;1ovtf3SEBiU@j|z)y>5iWqxp!{|xtKhip5VC@^Dp<4 zhws!-YrH=7wMygN<-K71?I(V`^;l3cdl=RPp9A@At3Z093%hRMkFBTY;E#t^IBfI) zbMj|GKo0{i#aDPT-H81*QGu zeCG3-e~nHJeL5~)_wre%nEPoU|`l>m;g#qDh{V@5u87f2y*vvJn z=zj|yk`)`bkw$|#Ft6nqXWnraW~O-I-Ci#+-}f5z%hXxR9z|>&^8gzb$}kmy4J!&> zN)v8}!yQpCTA>gHV`{}%YGn`i`ps0>{GT7ya4KZ|l{Y~(H;3F>AUdNBwmdKYu)U&NXD{jschNSxJ= z>~b!+5zF?M>9VuG6`1vv>3DjXJ4?1NMmr@l9o}afFzb!eCe1JwRzRV={0oSDvSNPD0@VM(vyrCpU6+&q z!NJUxG)K1q5BlFFXF_+-IWsu=+WVL=Ir#-=ZZjICk`k~cd=7?opCCV<$g^Erx52F` z=Rwi21AIiqn8l+SoPD4i%x(4vzTEc312$!xqjW7Q(m+&>(O_1CsbKWUh%87vh`+Xv zrqkY@5(W+KfKU2i&>0ZV^RqKydvpR?W^zO~^B?zYsRy3*lwplxyCH9)HI+D=$Tl)d zuvj^kW{u5Y$FUTxZ}r0L?WeGEoH=_DtU=A&uL^QjDAAdXNpMXx67A;k?1vF^S=RM# zF8`Mz?9X#My+hxk^-R*j;mGGxA3zgW+{8l_IU60O^#@wCDk0H~$m3%GQ4%|{N zvVEW&#<``_ygLOrm|jND$vLy{dZ&>_-i9l0qwv_~L}s&99IX!2a~ox}X?5^B?B{X> zMS%s_zx)qgTf?x>IvJ%miO_$Z4)ki=X<}113lxQ+)FC#H@7A^me)s6mExJFUMM{bK zm0Lk_up(O)!hgq)JcOs+3vgXsH_sc%fP&bObldMjTKwh+WFBY+(XqiObX)}e-Ws4m zD)3)|Ihhvqn7fy?jOxT+~K%8GE0v>ixtvcsQjawTlF^DS++S5Z8ewD#I1=ukZTPU{!YeqJ#-bMwlW)nVVRXbVc=O<);Bv7GTR9>cgMaSes#@}epZPh% zvYDdTG)jbyR5*<@Lr-wU7awEGiAwC$O$S`%L1X21(Syc=Ap755T&pa?eOFOrHxA{( zh%xt3%}xTuB0Nm7bNL64``81{! zG8vWS(`nhUBB*KNJFQY`+#S&jc>7R=PCvJiZYgtuk?w0iW@b38xogNw?V50lsx95! zw;PP)LYQf#9J*)@!o;7&um(E8?-t+rUUOC;KB&tsjFN}hTOLEnKq}`pG@lf=hhtO6 zFqG&ta8W%nutmF*^9}k2X7M#pHvcoZb0vnZTFB2v54y8~F~;m#mK;6l5J>xScpe!^ z!grS6@z5?anqRC!R@RJi&T+p84+}@o(n392I~+qF#WxC_=PR+}{QvRqzXOQU4~VJv zWHy8FeA&j2pfX1kp4xhGYi%sxQ?fHGPzn}YZ%V_V3He;zltAXE!8=7ay#Z(OIc)!M z63hsC1G}Qq>7SrS(3ez#Pw%He_v+oa$3mV;45`y8fu8ioYH{{*D*sFiI!b-N)k0?4 z3Qqg+2#nvf9WHlW!Hz0_mKp2jAMm@gM5! z&O)O}dJxB-T?SkivA$sb%<$$Fv3D_`K7Rr^&6Tg9te#NsvHQ5+1}A8+rvrO&QHthE zs%F{#>-3ZOSJf(x`yq~~vR2_(Nc)2?YP_%^7LREk}N-q&h) zY1wR;w`L`%a<=TOX|3?CSsI(<5d+zN01?>-=!}+ZI6L2yHD2t->=k=R?5KspHTij* z`M0~!Je)^kN_h_XhF&~jk<0) z>dIf(u=gm>E*4=mXKZQtP$Mi(F2zL?ZJ4b2QP^ZXk-X^XfLS%u>DBwD^ejKmo~PN0 zVW;B=_bY*YksE?wgHP}}-Gshg@d2mx2yw?RV@No%k-b;3rlUc=`?bxM40SU2~hP-8hRxy*LGVW38!${}XU@ailg1xkRf_ zl==+%ppwWe;j8XUI2$biI?Jore@hJT$$y$uaB~9nyk$jHo&-X1UmdKCbzrZ*XT!2d zbue?O65eosj#KLj)RiX9=%X69_Bl!Zr0f$<_R2^y#2J z9gOyXq!BW7!&wPtwr~pGidu-uYBNw)^9bJC=|!cZtmtemM0os74#xC7hYQiuX|(kW z`uV>#L=$tcz&{l_#;Vai`vs`_S<^Xe&tmlC*-FiiZi7l)Iu-Xz=Q1|^AUA%^V%%i(D5VbDtdDYmYh6jO^$Fo$o(=n;`x6^lR*F4UO;DA-0RQGa zz;DiDslpAO5qJMOj+Cn;yF;qMeK-d~8+$lARi5!Rq)6X3t3d1>UFOxFK(o)5u?4GJ zAYh3GTdx&NKFGa-dW9RL#npoCKd_KyHB$Ooyc)MS%;Rou5Mz29cSCD+A#?^N5)Jc2 z_S09AIYcBe89595pb)`k-Y}tel%p`MaRxDQnhAyGTX0pMJ?KYBG7S+UH2=W+?6l`$ zfYE)JqX)EMyawIXS%UK$qhY414E=CY22(e$5tKA;q(915^hI?(M12VsX zh&c#42b*E8#6~n(mPhVQY$y9ematDJe_^lKVzvXPQf=#aF!XIg#eV~M?Dr7a62beg zg?uK?MvPk!{H>kY8Gm67JK)?S8ZnT!KeN&j@Dr?v@ z91q+J52`zmNosH2gYEALX}K_tc9uz?L1#0!>hUD-5POUG6`tddUvJ=xT_ zQ59#+D21-y&2TGpKl;TTg--FWyH6Tt+N46b!c}hHJYb(? zqshi47okBqnZ4S+3!hb`pvCTKv`AHtsT?cCuI-}KvP6R&=-b4k?Lvs^8YY-@(T%GP zSw}*{ins_@Ip+7qgRMLqN~fGI#k)__!DFu+_3o)7JKZkOAFDbcPHdR_7of!^n*An* z*>dc}gcKlx6xQp12NUjUuyx-L1BxOy`sqGsTjkAE)=ouxhZcz8xgg`4%TXb2JzAyi zWi}OwBv8^Em-Ow27Y7Sq|N5g~wqZGODhLD5^i1AAt3iLyNnu9na=7lJG9*~5P~na} zw7>Z%tULS@wjc0@M5|tik?$q5cu#~@pFG3qW<2xUkoph3gv;^|u&e4X+3%pu22b9D zZ)X-$_{yvpXJ0hPB;Sp$@y>#cJO@~{u$LYU6E?vN4PmV5+-fA3A^X3GC7MK z+)V%1g0nj^@NR1{MxEm`jXa6dzFiwM7kkj)$QEwy3?n=)v5SgYPDGu0j?3Zqca9~K z>7+Ay^jW(lYntu=U9BUTR)Hxz-!`5dnVv+~>pQcCebz+$vIv!ya%Gt@eD?XKD#&Y> zWBU^aHu+pB6n*a_*Bx$S>2?dQcv}@bIWUD5RTtsTc3avnaG}b!?ZPnkLJW-5rz_?8 zvmi;sg@Sqfxl{&@?z9GrT;7|sW;TiMaH7U56NSqhCc`}as{r;j0-uw)@L6OA!x4U{ z+CLq-o@+W!vXkMC2>|X#ALgZfb9#et0_W+I$@zcG$AVdJWJt>j}ANY(+6mm+3Xx&}ZRqIblN= z_tyCe4yqP#uMW+j8rFogS~=40b2d!R+l(C_kYwP$8BgmkK#7oFcvIPmy4=pkZHCe0 zNuv}r_DfUQA{#tV_yRgN9b~qnG6dbXov3!#Ir1{u9H0x!9X;m(qS$P0Pg(=ciqo!hG%xSc&kz*kedi-oG5&d%X*tw!+ z=#yH9O5e=bo_K!dmwkut3@f6Jw+GHqkzlT29r%c!^^3;Hvkke|vBUZyR6I6d)5Hmw z@4X9$3KnDjU1k1k$cI&@-@qxnXDr`k1QSg}&P~piP02~*b0R&MdG{ir({|x;Ujq!Q z`pTUT+(%8{y+YN~lWEuGUKHt_!pSwLW6OaQc=lbFJ~CCuxDBK6v7!Oaw>Uuz>|f%; z^qWL$MH@C4w+W;&dH%~%HMpWU2`B#ZXJ&>U;iJV_Sf21o*fO*cwu}s-O05GVMu}%T z@cYI(Ie#Xl6zlw=kN<{?m;&>qjp+7ieD8N>87|%#fLr?b+41i|@^q~dt!unOT+8HX zZa422EU05Uo=VV=qk9{42i9Pj>mf4iFd98xiL%df8v3psUMhBk_{Vegni)|GP%pX=-qeE;l5 zO;&oREi14zFdMF}-OPD?%7pq4ZuGMeL!+%u?CB?e zT<+;fy=-0Z%_N?M{bW71FXiWU^9pHva2aPDc7U67bQ-pl@SNs_{0vrm4PNg4P82^+ zB^e6OQ2LuW(Or`aS-&T;#_BpO>A2@?a$p==@8*IDq9&Z_=oP}z*K1%XSbz_zcY@4K zeRk7s5fdH{C0Eyupk26;C|A7VvVU&E<4JSb^;PLKKV*jRy2o(C{-?57^`aU#P2ENI z@9iO9jd|x9E~C?Z4>`vi$VRnVcRC~)!Bj2WVd||hRL`!69eFj4tDF@|9tz)qx1JX* z`6!RtA+2!IcRw_5sK$kVGTCIgXzaOT!DUDnb0a>afU?y=BAs^uTk2P{A4y?M@=ZP! zgom?DA!Rgra{}C6@d!M2h_e(;Eqw6R4;(%D{+9U}ct#JRloUTh?^48JdKV2|HQ|!0 zuSu=cD=x~f8aqu!Qg;3y_jpmQ^FwoMR#+EGsp}}#xhw)APyWF8uJdHYk_=NW&`^ooJy7c|5 zy>Pxi7jl??~%<^C+!}rxE8}MZb8oX+-)xYrv}}V6^mz* zMVO?OCWhAkBsY9j&~ri>-zkk|YaiA@&B^8LZ2w)j`^yG2>i?13{#S|XB7bgR=m$nR zwPVR$fB4_KX&YwITJ3+NosAa8VzKZq^(ax-8^+bDx!5MQpF9wD7xaN{J2F46>4P+;d9kUf1*IdAx5h6^vu@Z;vE!gP;ri|JtG4-p5apjWD zbnr_J=dYN}@*{e06pwAMBxB$AN*nvPjHlF8{FKK+jZTWLlsB-Kp zzjLvH>n$NnYHBLUyuhDtPc)-QUn+R;bHj)ud*R)gO}Oq@KYGeUz-Z6?R5DYB>v(<2 zd1rf`An={;a*$@6WF{llSg zzRc{Ove4Ep7#n57!N2|lp0qxIJKt5}9}7L2mQlx^Yu+WEeifv5M+ua9ABGu*eyq8A zF}bzGl~xQSLQ+mW)=acxKD*;soWxRQ^sWJytG1)WlM|rz;SB0NX@Xfw1#ob-7^^wt zM#H{H(!Mxl8o_6aJH5t(hDx}?{0g&`t4Vc=otg*lV{^Vc_}O(_YBSo zv~azR25sOus*?8Yte?d6-^Z6Ii}70mSVOrNS=BmH_+t_>wf!}yI?bC-NiO1+oKoWX@HTX# zwJzSfkigEIN#=7?O*p1*pP*t}3uvz#!eON`Y&v%d9R6uR+JhgQqP{3@5TG2+zI(}BUwtJBg%g=X1i4dEOZ+0Fdi?-q)*PENAt3vI#~^rBW-~@YR(4! zn6U@C4>2ozIk7nm>{G}f=f+vm69y~z9+W8eI9`hyj%mP{8Oluch7SChvXK6X6rp`1 zZJD>@E--kX%aluh5~C3}Fk{LxY;ZY>YDb+|&u)%W&ic&vLis()nz3a6AqBQoX%F#t z?g7ClU6#~hEjW}b3vmu&wE9E^2`oz@a+{Q)u5tiB7e>QoBWw2EephZf ze~^!_(}l3zGap!}19!$>nl%sTvxqr~g4a6H=-YDvmIY=|L5CaFJbb)<@T@y23*V1! zvjW(rvU2>ss@n`dz75=TyXX5ow(E%m9rgc7jInKD_XECjI2+iT^^^ z&^c+71nZ9);qbOL?q}k4+_v)-5orFv%qDeaWR(lyBTLzPg$a<=*$(z=*1`1y1w<(F zmdkGAeU#7ZCs}SOfZ#%Z=rF56iMu^;>Cp#_sS;EijL4#nhkz{5EY09UGjBqd&+}pYIuTdd(uXh#ST7O5~`{K1q5?eKoycc^6tA zIMG=Poav3*ju`UIA5GWfaI4Kf;=q-BsCzmE^Lb{H3GZ|eIqOL^)|>+u(?x7lhXkv< z_7y!7ceCcD4ba%fF)_nV7&dVNAA>P$@!VE?W4xFwsrW_w9*GKuo$b(!{s7?$S-Rwn zHs2q(hO;+Sfw_|jD{8*Nd3Ijn_TA0^zmN=E;FO73;=|y3nS(Pv(ljUc5*`*UgR2^$ zWDoDwaSv3d+ujAjk&~~vwU-yr(Dix{{X_(3+MkERk9FzzCw=(rLMwceRS`a#d=VFn z*h3wEsFG#6M|nR%0{oi(97W2r$f|QIV6-Iz%c9^<;-3u8<5h(XCsSbT}^-S8Q+>sxF&VY=^VPFBz6wc@HbzYtk-{@yvXLDD4lKL3${m5tnu-Dxa$)LRVA)Ta++yrBBxTjx*gIkac% z(TdJt_#pU%mqU3jgPj52f7hpE*A3{4_lLT@FQArau#11jvd_jhKq9gZ_awC95P!D) z_2o{(<=p?c7rJ^}!hCa-iixFvN|G?{tu|d7M6u0Sg?gr+#QirV*qp!<=sK~3e4E5` z;`!a-4R;In@iw1nZhVaPlaQO!$G->cyWrz$CD0%EMc&++Piw9%qI0cVXdRzr3!qoI z_;nVvQsOo4+Q)MQ9`42G4gVm&MN7DF`T$h*G?Uv!elYLPII79-Q~Uc$1hZlT!TwSz zJor+;x!3sPoGTBYqIx`woohn4FQ)Y7&0*-j`UpnHsW3b1vF!Z7JSMyR7QVDrXMaW& zLq`{T=8+BM!kntKRO{Pq$Gm?0glE(%*D5%KCsvbFTMpvkNe z&YM}l`wvy5I6wqK&7|0fm?XirABVxIP7zi&)Weov+t~Yab*OF~PtCu*;963ASoos# z_{e~f?X~huW1|=9`KUsqyAPY;ro}Gt?6~k|-Z|qinV#al!3dZ4V7>PVd|dgAGi{@6 zMZ5;|Ijw=uH*aF?rlZ^ko;`lmY$2RAu%)|t-Pn{nJ&@IMTJVR!Ej>X3RTFAT0GogC#IF@(LjP9CyL2#hnf~uHmGJ$mkoZvmt z4jys5KW`J&nIlj4zfq=JTw8FYxfJD87dgw3E^blO5gb}BL4)6A;dSq)T>R}&?*05% zT>I(^@Nx1v=-ll<-R~b{*VMnD>EQ;j8f-&Po_o4Mo#B5cr$YSce>i&DRsQ<=Vzg%& zI!!Kw7S}!O#e5w+^>HHmWXW^$^HZEV6Xs*O5P$4|L{1K;HQUIG;Vo9Y z1*VAC!@%*EJrS=wgWC^`?_x^@WM>-^#6)35N2G;!!DRkRE614bT z@Vn$(n25`m!8qP!mS0EzYOTl5Yk1yW&=&SBEtBulhtu54)xy*wb#`A*n%PQe)A3<0 zxLRFV&{S6pTW{IXT6;g}u3W{1-iw4wrv8}r%Mn*zGk`0-I_$&ZaM0%8Sx;tdhaDA} z^nlt2_?VXm&iPWp7@KUcU)Dt4M|iQLu^)(Jhap#df+KZzG9meV9xnN>M%cROA{zJJ z2TKh<+SvS8z-_1$9&TB}9Cv=_T0=I&lAoe<(j+rzcDW0tAu84rz#vz;oa@bC@Z zw%&sUzB07JJc7Me)aNYSGw3PZrPSD0lQtQqlNIXDsA6&u%!(}NhuT7bG6&YZxR8!t z?a!>X%d^qi4H$mNi@w{X1o5)RV7pc%9k-C@pI%Wp0G*G$@pRj9?rZ%jIuKWl*CI+`Le*>H-IKx0)+*B&rw8Dc{S3Y> z-;X6}cetgV31Ar|O6?@43qFq+OD}sdsPvBIv;%Ws^m&3-3!Aa4s1)VQHsYI=rDVd4 zJhEKz3krC*vFfH^POAL~YCnyog#y0MOJ}kD_PHp#_yrEDi7?>;Ih1#}58w6qxuBaT ze3f*Bfa`n)+AWOCTvx>{f2IqwvyEU=l^f6EJOH&fs-elgo7?b9gI)=(C+Y)54wpgl)i+$4uQoe8do&#%G=>hU=yP%FC$NRp;gGde zjd~p!1$X9*WpOQU;lhOFXfip637rH2@#Dqp+qG1*Nif8T8oG2s(ipZ(FolaTdkbcl zcalv{me8Cmeh0e#BiUpw2YCaQVC=LMP7DS?c*9>K>kPw>ywUobhDSJT!4uZWgQ0(qQt@Wf-Jv z22$(p;O4-7!M*-svT)TIU_n`Uub_n_eEWdrJJUF=6Wd|#&>A#d-Hxi;F0x{gd|}kf zx5ClV5g7hsF1>r99XuzL3!mIf1v}Reywld!aJ*zYf2OfuMv;}UxI>mbvem{hE|RQq zy(KJ&@qm&k^B5~x0M5O8sPE%w5H)!NXSWxk)*n@x)%6SVdCs-Px+elh$=>aWvFY%PbPn;s?$GAFk;js8*mXh$1bM*!~ ze_}2R`O^XouSPJBo38At4)0r$*^1sWl5E{#YgmY(V9W1u9KVkvj|!Y<+xzV(!i|Ab zp$63NR~TiAnt1X-3^ke|LrvCsFqa+U(4lfQTeV<36z*FI9?(28tg9yJAO{ zc`OK0Qci;U^J6&erajy7*O1?-iP334%$V$+8njngLRW|J?yXe|INLYRxEH70xPU_q zSW!F%cD5ICp9?9w_%Mi*vpWuP;fLY!>anJHf5HczJJ!R!`pq-^R(FtP>q1fIc{NNON`r{*FPJi093S2n0nJ@|=&hD~ z=w*+24xly-?*ETx)s*0;vnuTFh&Qlf>T*~d_Z-%bECkyzEnvN+18-!H!mm}YNO0M8 z7+VKeCEHCtZ3$$9#2sW3oh`vJ7s@6YCnPZ zjqB{ipMCxK<987!`%@j7S6H)xVSaw$?as7<2cU9HDJl<}QeXO;q}=1sDyS8$gjw`K zt2LGGEQSZy#hH!YSE9W-355fCEF;{IJxI9*6Q3_H@Y8kX^NA@2pa{N*>7;k+GFM_j>|2}WGrCj~6+1{z&5lJ2^1#LjA~ z(-+@8&~?*K5M7Z%^UWODAuGbprkk@LYqeNMuOY?taxiqi7mnPjgAS`mSnK^ACL~6% z4O>EBEaSbX-H##Y^ms5Hl7r`|p16Eo8@YN_mTowB9=WziYOXYaU37~?@krhb9&N^A z$E330+YjMJXeW$1pa}0iHNo#YWoT$ChJD~hOM5FIvLOfhPngnLJsYb3H<|a?oWxx( z^x^eyBc|;Bn`~d<1oNB{z;44l7MZ#SZr<2LI&aC*I9*%XA>u;61=eE43|DT|_;yzL zX$tta9R#Pz#Zasy24*k!35@&*2K@Mg&(`bX`KQgWDgQP6zLJCq-by%7`veoyC&S+G z+a&IU793gG1x@vQhDBi<_xe!=7B|YUhnHVKQ&K$WT${ms_xAI@^GQ77wT&nTDBz>k zQ4M8l$6?*A1uUwffbVer!La1fEcG$ZktxcCi-ESxRc!@!JOW(i!0&Q?0lPwsxVz>- z?9^p5NDM!YCE7Q+jNUW!%V=#jQ|B5n8MzVz&n!h-{UWNQ{t*&c-aLB*v5U{b8Uy}0JWqqV#XbQ)Pc@*p5~fSLGug&?Iuzi| zjCUU4?m4A{dA%obtGO)9$jhOx<_{4;{AET9IGJj!`^2++M!=;U-mkOs8)s>r#Hw|8 zFRbb`cFw;IS3A3~7j3ig&+Km6e&Hv2v=l?k%PrJ&t2)6SnE@v)qJuwg945wZ!!UMsG<*DaD!uzEl&J+B zLp@^ys%YN^vmWk&?vEk(UX15;9Oqg3cO<|nQy!xeG9mojUdS+=N7qf@c|bq5qy6%G z_$o`0xg5`=Gip9?>6Xj*@BEQOBDfiK73%Tvq)&Ks?R30zh`)AHt~5zQ0zwKlK>GFD zC?D4a$B7qQ*!F_Y67w9^n9sQ7wF@J!{e(rL7lo4!oDnYCsX>)b-5^S1tGQgE1WdQT z48da#!NvS!fqlbb*jvQsCJ*Zf&*}Z+9rTh=$!EvSvYMbSK!M#IxQ{oV@V%KhG5FbP z2pR>(toQIi7Ti3QWtZ&6q=`47YTaad`K;sr?o|-&4rV8x--kipDkyb7f|sH;L9OK` zD12l>6P$Smt*aws4yw>Rb8Vs#r$SkE4t8QDee<;d&nD%fU%?PsU$A8Vy$priTuElT zN0W_;HfQ4x#jq=37jWt%ZMJruH7(&nVd}nl?6WvPsMlra4KD_phiT}3^*r>Nbm5HT zJ6N5?@1PfL7p{AKhWDD9F{cnW&ZcqoqIy=l-ki5O_FTH>{wX1EFYR@ z`-7?2Mq0J=8k~`wOiK6s;ue1>=DhjdbEv;6Nx0QQ>_(h~*e80l>#Ze*NB(vmx7!fZ z&a4Mh69d|JV*x$bG7L*kyEMG)v<1uJ4LHN<8BX7jE7;+;1_zebk;{*r&{d+0n|D)xFPlN8x^d zZbsN{w9jn9CtY#ex6{wLZGN3Fc25R1P>W?J=AFbkqk25@^9!1Q4BKn1$?C3TVaqB% z5@h5`e24Yv+Fg!#ID8C~I{HJfqo)(hGV(|R7XY@c7Tg!zNVeI`2i${{*_1(^d%N*3 zcdT<2v(8+{);;l81Y^V_g~;C7;4l0){Ycz8iCRFU?HvKM)@NW#i#fn&XVCp)T13&b1zJP8oYr7`=HeBdK4oO=m3o_ircX(MCYf`~#kLnbZGfOR!lt zPe7&Wew1983ghYSc1JxO|fz#Ww1+JXz!_Ul}Zgi%nz`ng=f3aHCib_fqIoq_ z=;Og+`rnga@prRTqOz+8`14s?@kX0O?wv%JP*PvbJA7|Bt=&{2d^kIk-W`6O_gN;5 z{_?#$TN~Uhk|aNhu8G$1u4osFl_lQYSvQW+hRv(#gm6jC zA2eI6v~!wx?#ng8Fo7<8bnzd0_YX~eebEN~w8Beb=&_pC@tYx1_MXLmd{>eyy+wsS z_WORFMx~y}?7Sb}#WYA%+~>$wt?{A_J$*${dsIbEYI6Kn9d|`1Thm29s-K8v4Ez!; zZIpOZ21)o2f8^^WC?x#T{=HwwF__a6ixAMNoJl&Or$8;q>{ed9mWp? zBO;9wJMr||M*7BzaK8T3sdc+_BkG=ik>O*{w0LtYPKkOC$npJ}6vW~w+xg+E%jjEI ze$zb$@9Ad0pP~t0Pl-n{Gk$@Rkk)N<TSIz_W3{O4KH^TgMJmPz(*eev@V zX>n!iK5>eKNA#Je#s6}BZ{1F9IZ4i?k(iOxI5tO;XvNV-qV)6CwC4&r@i15<(GC=g z{(Ok9i*fCtRX6F0+%&JycDl=WzE{7CF0lploDJPP54wu??nDbuuX>GWWUl0S^Huo< zb7aIh{vmYgvXym3+OiV=$_pZ1D-d6u+9N7_F;na}5-HlH7*m&Jb)7bL-Xk6=nIjrg zmFEjqQ~ccpC+Nldt!Ylw~Jt-ztRek@#9=JDsgDNO!+~ zCz9JzSeLhD1wS}En=T05LLVJZ5I?P5$G86*EXK{w@hoIp=yy^Hyet3x5S{u7#E&*F z;m1r-;ICh(Ev64;@OPd4%TxWiLKLX?gkJ0TiMR4cu&5{Tp6!U$EWX{@l{6vcBEHZu zSKLIz*%~`7=Wm)mP?yvr6n!`?$KRrPLsSx9!t)8X5Z{|rP&b5oi`qXheQ7M2_p$^09{d zbYYmAxW#IW{v7Qt^4#=E)Ot!ute5volru}WZf`|6t(z#rw?B82J`}Fa-~E{2r$0YW zM*zWBcAszh_@4K>C3YqG^R`!9=qqo3BLU5@4> zKSEsE8YM0{Crck4)aCClmKFc)I?QvrF43pm>J`b+mu=@Krt(7!bj1g$SbAG-htNAi zPJHyFvc!+;J+JFuour?b%g>suL4V;V(8pV{=&^Y`+nM&S=?*@_yH=GbA~h4ml~aPm zL;EcG4-+fsRg-#Y#Z5)DI9yhIZor3sB!(xtI>(+~8S#l8|ALFtZg`1qHHXmZYi0RO z|2gseCAIkAiWpw5rU~7UA1C^4u}u`>(@dGvtfhY)T*lXU{-^Gg?<0EIk78c$fl$8Q zWH<4yvH*ISX)(`V94cOQe6a2gZvx#V!CTff^+@`@%e3M|TwFOp;(y$=m3DgNEWSJ7 z&Hp%)Pp3_JAo`ejnjhO`U03}`%=?}#BR&={$uhq8hv&F8mR5>M5-;oiL$iLhq6hM` z#g;!`3g`4qqc0RqUO;H6mLI2Pkeg0h~{s3V;f>TM{GW24$rZ8Ew9|$E@d^x}RL6GR~-PvNjXWexPHB-bH?a_42%WjEoX|e#a8E?TpHQ7h!VRyw zlqj0cuM+LbHK7xYchYmWmWZmO<;C@S5^OUnl~yZP7u%QG@aI)(iLOd=y%(oN)85AF zv{o)pyheW#e~<4f2|g1~Cnuk$*$MYWZ~vC@?94@?qBH^jZIz(z$*pbTR`F*ZJw;md zKVIgdHbs8mpejF__7|`9%@B2MOA)QH3=j=ox=wRXN=4^xoe_09%;ud-m*h)qRShAi1#mZ;wyCit4lT< zuB(b&z&|qOjL2E9ny*!-#MirhUYy%8pAIxl<9WQTQ{rIR|H<-%_qkCj6}# z+eK@`b;T#D$eqYyVB~{wn0-A41tw;5Ue@=CMGgOPF2$z8!b>6CmTncK zb6_Sr_SBfW_F@lrM$MDh{^c=I!u;gok0vndejh?v=W>YyZN)cOAq>t7?&S{D?S9rM?Ee|}&DQx=8`c97L{>_T#d;&Yj3fD!#s)u8QiA6K_b(0bK zwDuiRlV2)yqz=}8Tsw)Z_^%M!TJ9kBu9(Zs(N7|jf}f$}!|R3WUKin@dI(zc?He5L z+rh2=xkz{|DS%UUUJS>4O1Key2ekV~24^?-DO57O!&yEw;T+>;2u=0}A*GpR(4qNzAOTTo-s#D-0s7o zi0kCsm|4OQ_YrpG#b?BgPl?EV-gVCXq?9n_`xR2NK9TEK@DP>K&Scvyg3CB~l-s^< zjB_rMC!ZA9kPpVEA@%!bpd%PS+iill(To3>M)PK_{-CWe=N?U@7_^{@ASq#^>wF^K zdm6`ob(d5j-c`<-UkM=0s^@XGf6F;tq{t;2^dJpd7P|NfQNvIKJgVkP$TnodQV%vNLoT|Y}?r0|m zTh^+;EujL+}k{#5r>-kxHW{rLJJDx%lQ2Hf$uvrzftB{bplWE2+k0PS1( z5*aoabMow81b6R+d9lmU_3D$v=;$1z>mLoU)`LO0QW4Hs3?>Nsb)r7|3a_0A0JMQbxT;j#GZ}6>x3m4kGnQ*s++_vMT-1&q^ z0&x$Zy0jgV{uju~cORt;u@g4B*Dn(KdM8<(uk}>aXA2m0?L1uXB1O8V7Xt^6IB+e; zla0;wptkydW7Yvlqk2&dIL4l!&;&cy-E%e->F|Tn{3oI|`sNVkj|jL!{v>s;W`qcYjxK<55k zcFXrDxaf*0yQ<_Da4j!nrrXAXN^KKcEdxg~bzld1F)$Wn3c5jZX&Uu5L6x%JydD;f zjRN7mOqK;3sQj+K_{IrSsdW$cQW~2h|91~?zSI@!7v-^F-Z|EyJC)Eb+(0!(Ed|@} zms6rmSIOHS9}@KIZPbps+0gicf$f@?@7a=uZjy?30Q-Fi(g#9nxk)CG<-3(k`D+LN zu2P|52A@!|0|_wgng_M`i-mpoH+h}(GfIuUbtvyl4thI27O z+*`#9U`Enu&LDEKu=MLAlyqnhC#;`B#_ztw-970l#OJ)_PAS@=C@EX=i6LKDBQIG; z_V>7xQ&q_Ai!9)GR-TJ}rofrB-$!nKS5ZXE7#yS1xy^!B4xlUGM~t5Euwy~wq-PbV%ad_nrnKEjojEg&5KOAb9L zBd0t}nyXGo13Qz%#@pN@zUtuG0?D~JC$H537T6~{7_ppk4ujCJEH^gxb6)7m(42+x;fXX zQ{1(C1;mdD2o}qo1kd%dl4toyTVUce6HoD~CCov@SgVHVr%U)0Ww= zN{98aQ^rh>-otYn3u`n3t}=2@&)`Sr_%O2v%WCgyc-YJq_SeqZ6UpFb=hXZOGh8Tb zv~p zti{68j}*S3ax!lIVkf(&?HCc$Vs2g5{{nmSC|ls>HOOdPS%#<2{w$cMtH1_6^kU`J zov&}EY_Y@#=NE>bJB7#D?<2Z2wyYrj)<3x)PVl6l9!c#{+AaQ_kMFRzwZfWpBgeO7A6Z zOd)V^+e1)#y%d*!Ivu|w7{aCA$+Fd6TKLnEr&!8KU2InP2fS@=38r!Pz96bPfz^@u z#;C;=;_H7*XXj5+B{UPhGZRa!YqhQ!;a2)uMAiCYma#vwFw@ye@UwpbQ8tcNf@s}5Ip(O?#PoP#fJ4q>iyOd$o9w3-T4+_)V$$%jr@;EB3b0)7&(>Ml zpf{!y(4YBs%ys`9Y?;Xg=o4Itt+=)i4w*4{S5c$jd2KPXYtt|IFkFD&%oMT@PB$?f z6V9+31217u#=MENN*`DNlrT6HLk)WJ|_dV2DLIR($;z zX40gB-zk)awFQZ!>#;Pl%IFb>wn&5<)0?2f9cf~UUKMnXDkbyv{b~c>I*{sLEwI|m zUzoue9Vl~5g%}RjB(*XU@N|bs@Q!pVTK(WZ*3?s)+33a)-s*sdeA;NFFKZ0q6-+*oB8>wX{4EZ>oc z{!Mm)-;3@qd=p$>TmK~*ueOcF>Psn@ISWT(i|d$@{|)%8@d)Yj8wtKS3}Y9DR*)aI z+X>RFO7N@Rt7-@5Ov86(E7VTL)rp{6=FHpNV|e<$K&wGPv=@{dRE(F1N~`&?ne)6!hB_I z?oN~?K#&nOXgVKzwt=hBy}FS28R$d=`DqaorftHPu93pqt54!izaQhOjrW$23D)p2UwNQ@Bg8JvLX*3S$YfT!yvu!!u!j?Q$zii$a`^RrQHZ?ZDBBD)Hk zc;_gt6kUkrpHjp1TU#;y%cJ3_K)IlS`Eh39Nf)!lZ#VoJaheJg|m@Umfql>mgZW*6ET-CxJUH=1j zyrc=s9LFh9CGHH#dzIvEAA8S^Utx{zD{Er9ZwTHc@n$2P8a^r%(Q`9c#!DD*c%x< zd~dP|JSgK!gxN(9Z`w~1{R8@hE$#>_lC<$N<@>STpfEB|h!MueRmtd*X8b|PO2TY< z9CM2h*5pkpgHl0K@L!TF-ty-NYzlh>XILu24gc1&lP%s8rrR}-{VXYod}xeI>Kw0 zj)Iw?)4<4y5psN2FB7opJHSr5Q|RC;XgtpuXuo91k=M(~fMvO0wD$?)*Qto-nXLgA zhl}v6GmB9WI?bHCbcJ#_;y~qdl|WGwk;mWefC2wK0EJUyz>fBpaBHqJsgkxC)Qft6 z;lLnJE^cC5!YqirGN(b{-zVUs;0cktXd1A7G@pE3JV3gfI{=lF^}wwXU22_@C$xRO zAIRQX0~)MOfk)nV!42)HY?-Azbw!{c>bycan-!!TH^B9;}Q-G(c@nOWmSyb)!J}@v*Vr%nt4t05<77W;_O_c?V z5n269sC(5);A_Y~VC-59rRrvYe$@cNYb=I%+OwbZ@Uo>Gm19AyWh5LcrN}oy35-Ih z1+}<#0y%xhek#Sm7{*jA0Xm-n7z`-H2j~Z2^5{}x&FgclU%Wh^J9S}|yaBlDy$;-p zN&u_6+rei47DmRplstRWl6*;30`}m4%*k|F_IM)!4rYC1)@{)whnFY;eWym|rUIWL z-L0vWqY>o9z!*4qq786|%GoZ(i)3NPbf)d|dU9uX2s0)+1U6M^!ecKr$j`Y3ptEu{ zIdM@rvC2scpLi#TOqm$LzFmBX9NAaL3NIM}7ae6Ly!tQ^t(!{*wz!eu4^D%{xJIO?=g-m_fOxE?c&MbnT*U!gwPDO+0Fj+Ejx&|oIT27W6 zq2T4uD@feR1(bdGORm{ghKKLBB7(;6u~VDA_Uc^ z$m=S^rW>gO_YYa@(dU;0!>1iV$WXK(-lB`l*`NjT*@a|#$y?%rsV3?9P7kP@J_BEg zrUBjd3B=A(ThM8s2>PdWl3R8sk;h-WWoMNe!UXOHyiS*r!Ea*lzT93I5&4yvw}wZy zIGkdK8_s}x8MT0Ryi5*{v@>V&?va&w^KBl_93Vf2>|spDKN0Xy4Eg8ma_I32!kjai z?7!QS@B?abFl*y0sQzFMxDYa%bouy>cx`P7U@9Fo6GkO}0LLY_mQ)l>pW1$f#Eb9qRoGTm#&RQ(xlY zmAa{{sm&THq|A(y##G4c)-G}>z{m^JW~0=_n;1h7;} zCi%`(V7*U|diu?uBDiew)EOIihe!sWp(a;wV~=2hN;ISKO@?yPnuho>bHIx9YG(Mj z7xn4qUTQ6-LVbUBnN;~ZjXc#!P_z3zNOa`^srGCU8y;H^Y!B?Bvba{%Rh31IZ5u}? z%P}efivh&ZP{QPiAJQ3Efa@%)A?0h_!7AnJWdDm&&^9X^M$Cd>|B@BRe(NSA7w=6y zKV`w3|56J29|p35OBBStd`Kx#47tc|i0N};;egF;hBA8v^aG|a(2XOf73WYtFMcAX z54a#n7B886-U;k1iz9cBcY@4w`_aO1cTgyo!#15yKzlU|iH8}n=vYDp7CE z-~4@`!_^1cws@j%#ahUTp9hXz*iY$A8D@<(#X;d1K3|Z$i`@BQ5}pC;Ay{s`Wah6K&&n@ zHG9D}m}r2GutcI>y`DTUB@t`!wUsN9GuW zv9INM=u6y1tasgY(q)e}PO5Aq&)q9TURs{4O}qw5{&)`>tL`F3Vx|F;t_Z=VCx>m4 z;&s5d_EMON8p50XP{i<&vC{4oTV zc^bo-BtKxA9stLV7@_gG=4@9@JUX#^IbiC~v%{`C*j>T5$e{3D%(HvB5V#*ezt5i} za%{Gsj_xGzyXXX(|5OK<^Q3UE6OpL+mIXBbHW9hqnM!bT`eS#fJsA+4SU^CWG@32 z&X7fo`30oWd0a3)u$>Ay6$9g3WXO>Y5qZ^aE_K`YVeRhgC1C7hJb37K8XQ!RBRBV4 zV1Gu^Zpq!HI#{WZu=8)HknoR{vloy0o=G5MU}z$@{sHqk7B0jR9{^Ja`X! zncc=^$V+H%j~aS+N)E2=9wELB;n36bB-kTY$GXpNC+xy9(EfTYWMyWJtaGjt@ADS0 zDPC&SD|2b4sUQ!&4!r`3_XoqZ*G?giC+CSI?k|+z#BCR5HA<;!a_BeTm%|9$zO>SP#raX*cCWN?{0svF7%wW~F)_DV)uJ5?$%t3;_l>yzhDYEXnw;{oVH9+c&A@%R{nouM>bRXI&Rg`pK}`+EzHVS~oX=veb)JXD2)_j;^tCO#>JYts6$ z21)Q>|H|d4ud@T{#~y)ao%NaPPjA6BCG(jbK5m#*jlSTxau58PGgcFwv$=MlbSZXo z$uji#+*UM)_Jg`rwQ$ega)C!@5}e=t96nN$Vm?$ou{rSaKCF|{fEib(*Jv-@h`n=f z7rZx*VSg^T2iMsp;hAsNLnENY^bbxW))~x(rR7(k(HnKNWP+ZJMt~Vo-)V{eGfflF zvcF)p6N_1dCBs#Drr2VY683R6?`&BnADbQkiTC6E5Ego;R=k= zB;6tDfu;`?ZePz?hLelMJKy*>svT`?-aZ~_Y=%(Kacg57eh6_NhoJ} zF_WnfEnK}WZ$Xv!ruz2=*zkcmU5gRc=YBKmXnU&A_*|2(fIQFp5T`>k7~SN$VDlg z10nlIh#mKrQVB11Q~tXc&hgeynI0p<&*ukv`IEoi?8_?n9g_1rx4Wu^a5H7wW;e-TF5 zo!M#V`qKG~+=4VP*H0wKtv5txj>%E^r7OtxOvrpMN+oAW_W(tU^ITE;C=pklinJe> z!xQKC2p$4+&ZDalt~aser0TW6&t==VYsx&}d_99b*R_u8)R#g^`U+g)8apmt-3pAm zhEqLa4u1d9MG)RTTwYf<3YFdkpL%2~yDGyV@`7Z!ucb%~U!RWqxu`;|)2va)@o zxjwcOG+d|M^yD(M+l_c7E(M;`UO z=_4?~t*9@HKCsx;f8bxs4C)ycLS0^Ugwi2=06v;RP5f3s-5hO$QTKVaziTGLCWTaL zEcOd~e|0iIHbJ(#7ajoWx%b)DC3V2gb|?GZYz}2;9?h=zHl$9jwy?ck7X%y<`hdb2 zXOOsv18{V!?fgAe)C2bopvk(N(k^`hR1XbP>0^5Vx+`mYf}Be|X}7kOITi@wFNcv+ z{!XWM-<|<_x9CwX9cS5|ox6h~YBy5HY;wpmX*lV(!@{=u(NwCf@|3OV^O=-Frx$hC zYZkaLZUJiF%h*=j-2t_&|B>y@zLciDHP!rkkV^S{1^zxRQQ&kIfag06V0g;}N~2>B z*poL%$*q|L=gkj*5oab+&-y=+HvKF(@n11m>YGm}{Q5>6{IS>edzBT)+S*07PL{Q; z{ILoI=%`Xtd9jQV=L^F4iUQT6%V5~%*P!Zf9N6#DNA8KHK={oF@XJ$=S(fYq8kR8R zf62|{KIfxQK1CTsNKasHWjzIdj!FaL_;GUMJah8L`axzjsmb2edJUp(sS+#TLwzkz>x51@mq9atIA3i2*b2G57g2!~!9@Zar8V9)Rou*Cf(Oo;6u zr|qAD63agUvLy{Z?_?w)Pr=NNi>pZC*D99M+W=)|x>66RxnO}ww?KQwYw~j2?^;=l zM2yX@W%kNU2V48MkY#7>m^xP-avaSf8w)3)XRGH>U*Fs%>p$-%2cMb&>*&8^k~azD z_go^&o6EqYq-t1YcLhANlq1Xi+@Wq}2MB^wNFS5cz~+4^Xcb-|^S;hPN9&J}3r}T{ z(|whw`9GeMZ?&BP(I^i#J01l~j9KXJnFyOs9sqvIE>OnqGtr`Z7Ql(#K{}?F0&5<5)1<+*oWpLHuG&mnPM)?@3!N)(WscQultgc}_wKYZve&S)&`*#bMz%T=r(W3yZ0Ar*zOE;DH0l%L!&+0hKpBpLG*HpceTjQLP6hy`1Y-a=-g4 zc$sMh2`@KMIu%{4zoi;H^Y=NWQ}vFNEsF%QtvlEoc@j9%HlAYm#Z;@p0tk;Of)@ib zC_D2wYJaOPDfpER>DyHxN6w#0Pideo)R)1aGF{4WK#E$eJCAyolSzf|4JPj_l!IsR za7uk)AlTOCEct(!lE*rg!2E!Np!8iHwfnUlT6106wxYR%dHsG0rSP>Ku2_Gc+#gHY zhP-$|62T(&#{0q;_wh0j9bNGpMJ65Hh!e8n#{#7TvbG?b{dnj_QZp?_6D{F zo0O=meKI(#iGrPxc} zaCXgS_Ci1^xbUZpTA$!cecSg9PA8qH?DBTR z=6??1L@N(Mn^PfR*wqz!KFVf|CsR;aD-x}>yk(PT_`S2`JyV5=}SyNXU`>tQ5WlI_2U-c~>&mKEnup z+w+W=ruhn)OFe+vnF;7~PaKgYohW$!$^<%Dc>(cI0N3{44%kq9mK?8%L8_DhZ#Dja zycRA2B?bpU&7T^)O+A;fr_Uk7C2QfrGl{HK-WQl|t^|)=G(*daq&d^UkNDR7t8n9! zK9u)*2KGUYVapWkF|GUhc*+9`KRA98_37p_`TszzZa^=)I(;=Zv`?2YSzCdr&6tXY zGAgi0c`v41S{k0<>mblKh}r3=vPu=xQE?+5HGj>6H@Y?Q z?Yy^v=t92&b1vmcZT_mM=w_J^3vf_Go&Sa~PwD*({`oYk+Bse;H8vSH_%FS7iERXS zI`TCXYdPAC?Ow^;TNj14lw~njmdY~u^9KbVORSMxUObCg_P{?jdV&Xf-=JrFE)x>H zhRxl5(`GqvWFIUFM#@vRvsF(r;kdG%;I{91oW6Y%yBur4tbc|>HTy5HvZ)A7E;PaX z{jxBf$uHSn{pAd`)E%krn}F5joMu+fbVXYEv(d%WEwD7;E9>u>U)!>9A(Jnq&HVh@ z&LVe3fperPJFv?cwobFcJMq=bCf^Zw7(WExC#7Sv*O_8VKggn0+SypuJXNO3Lk8K; zu*a=)Ly+k#4Olk$oK0#)BwPJ@Hal^%EU8)$&z|_vDNrvcBIA^#nFqHj0rc!354CN? zi}>b}?bDix^7kUi1?QR4^Pibx4uQlEnk9z1UAgnMWr1*GPtWadHBcWIh!ngvkMUsZ}rt z+ey;jA@G(AK8x&INSAf}%%=klAkFMMIHa5kj&6KT?9Y5b=9az!hc5OrJHK5deU>bP zW9<)_SFthR)v{9Z$JJ*Yn9I15Qh%Q3EWfF$s9{f!Ij73c!)R|bkQ2{P264b_97{ArhP0J zZ(jwXu7$GiRBYf#=5!EwwF|E~xB#5iie?`sMS<5*k}-4CZg9e}l*QuO*zNx&ftXNF z;?Q#g_a`yLzt_>s zI=k-zWy?Tfd!HZCh|-8^>#yX4HA1Cb+oQCgPeZ*cuhj{&<%_ zN*n62{v8bUv_eF^_4cG5Ui6f_K1X0$!1nT=+TXNw| zW1zVq31u%^K*^*TP`{IJ6QA2YkT-tbC4a{buuan<*gK{LK;Yy{oi&>dO`a^EF5Q_3 zo}NtvX(JT1NM|qmUe}58@o^z{Og{+bR=x!*Y6qD7d?VH?qnY@x^EOkl+lUI9^qRRm zv4&i5yo&0OUQ7Pkrb2A2Yb5mgrc-hM833O)87gNyk3hZ$sG1*MaQ@}*K*lZ_j=*$q zu%j8&zE%P6TO47#Rw%gW6N}0>eqxP<@<0@t58ezaQSE|lR6y}%qUDV%`{P0<$n9$( zU(N(nQnM7&wAKWhd>Bx;O+?Px-UGUI)XA+gjBOeQtD%FgGI{d9xujImR`6{~E;tls zNL7t{vzj7RA~32Id^WEIIhE4vh{{BGNwy3S8&1R4z0u_8?_MCEX9(LjT%**&5vX_k zjy=hGht>a>MD&zPgH5J3)N7?rM8cXx^!ey}M)vxAD&ivo0(S-A2;QKzS!+mP@Ey>& z*^F&YSVP&b2tg<|9NZd}205dDK#Klr#%E{)71Azm>wj$(Rb%p=eU(r}y6J0Bo3_6L zN_Ek=k(&&0Wsx!UWllY*6OW<1f0vla@#}339a+lukbv}AunBxzIiFkla1+(59SJJ> zJCXk}HCC%sjq>oRrK(rOQ10Qz?e zv${hZX;|;TI{Es6(6TIcUHf5>JJd_vD_jkNY?p(}H3?w%Ts0uQv4XNwilF2aQ^?hI zT9n9WIjUM0O1)5}VYf#TrStJ6Xxf@dUC6%(pw1RjWM6@XEybj4v!n*h%%v{Ol&1VA zM4^2pU*HuPOLW5G8a2V=Gr98`ZY%#{5qO?z50scGdR$&>yh>Y6h@3d?m#6 z%CNWJkF!ISB38jYqyN^S(FiipOtp zhr^?6<)1WW%}B0f4KIbow{F4lCA~1{V4y%+ClfAPAt%r%nj`pA9D)Y9YOGOZ8JkHD zVbYjB^QQ7Eyxe2Pj_0Leb4TnMm(BgyF5@N8D$og&nK^-Z@_i9471;eM>H^U0}dIT}0x{W^YW%JRed|eG&FW z54Zff4BPqRl>}s%hR<0$ys$PPj6E1V55qs`Amxz|6xx}91&=q{q=sfOR`GuLMfDjl zE=(HFk-aQfAytLF{e1zN8TjMIPy?=ty@_jliV_%|Uc)@BRm2RB=_3BYK8)1<$gY>` zurWOL2DUiuz%Jc4WnHgJ_~ZLu!Pe1cX0mh>^Iu3RoPN+3Uy+q*v%RK`*{}8h7PXFI z>SwC)U)|HO!(&s?v1R%QY%qleYL4(_uncKzya~3JX~OAdE<{{^Z_VG(D=@7i1r8?q zu$cc|{8OGJCgqef+;_HyT}A0Ix4(1=bY?uSb^oCTm5#54o81I#^x{l7ef|%u`07mv z-bgX`65<7h^Jbx00Lo%VIQ76;8y_ZS%t0tOPU&VsS68JOr zHhjHQ4X@?NvB$fNSlL-I;GS_h6*d1EE8QyjF3mQw_rfnwYWYj3MCV-a!dMPoPZ(hQ zrIJ93_bRqPsf^mTaD)-_q^R=TcvwCIqx732Slx#?l#laYO5a46BKkwXD7%^5mfZ-B z;I5R%TqjoMgfHl03t#cu(oBH;H-F%DmoJe4sP6QBQy(=|(w>oTpa3DJ6l$Olp%`J!l+z#x9>80%Sr>z&@UsVzM&Wr02$L*t9#q zFkvEz{N%vLcPGg~DF@a<8qH62Es1KKN7qSaC#8b_SmN34m7m$ZPpKVCgMB{va zyl=u|ShpgY8T_b)EVdh=T6CUxFvxpkz`k;|Ve+4U6x6^Nc)#VPpeTGXsc&Y0?=wA% z{`nn4ouNHw==Ty<!H;Tea7VZ zBa)H7hAtjDjDEJpDr&~AJh!|t~PJx7uR z{W2#R(^h$KFG>yE$T$eMyEu^NjiXuXWM|C8O%+wqHCebh9?O z@^Llu0GrM|+NLC|EQ}{o-tI&dqe+B~km2}SE_3Op>^Q4qUC{8;8B`yf%a)^CbW&Rh05<(?ta@!&LQj&RNMEJOv~KHoqrL_36kr{qu>Hj znKqmITUo^&IJ7|cS8Wyf)MMOq+R!b5xBgsfZr8FdMq#`M!@%h|)&iQ1Ns8A6avNA$OLw0<> z{Q>v!xaWs+?|Zyn&({M$_ou1S2Wt=wKW9M`E&PdE_u$#?XVT5uNAW$kF;Wvn8MxzL zI{lLQ8BCd3NM>zaFTGQlPP#`{1A{Nu$?sJ&Ky`T&+4ryj7%i&j7sDbB`Z!yIj*d&^YXbE$?*Hkc!wcfEm33<31$ zy5ZpM<&RKBOIA9NK8_umGaRUydr+xQEKRKEY4Q5QctTPl4LHhNm;Ip4eh=N|e;RZiuQ zgdi2vbMqm1vPc_+rkM-x<6y;cA|>nL)PJ#lF9-Yb(}k>+K(oj z`bml%3}KVz8=~9mNL2UiM}{_Hq_9_)Bt<(gENwuoijRq2KE+fu5_~$WPhMmWho3H- zLa%nOgm(5AIo>_Q4)ZU7yPq?B+w2*zdCmkpE9eDDetniVGfX8RJJw1T{R>CdrbcYn z`~XQ(MFN8L$|$6x0`A+GhrL`{kwNSX;>J+?c6ApX^O8a9S9HTu=cm#@?i_e*qfaaO zI1+Yc2k~Jb8kL|$d~Zvz^MCj7Uz|md)mXYI{4pv>d&8+r3_-}e0S2#mh&$ZRl8;+I zlMr(~a$&`JvVGJU{JKIOjV^wQbC$WoRb!lST0%HUzHN&hocxCuBrS)R^1{ixl79HY z-AXvG(TtCuILaBo)m*}GXCANBglhs*g-KhJ0dOVoOIS4La@w8!SuqQp-6cnJbh?Cz z6VmuQ>Lui_U{9w#wULgjR)ra}c(N?23RIQINQW=%p+k0iQ2B?Wu@60lZBlaSyhp0g z7iH0=oIG&JZWOiXxK1p7ETv_Wdw|A9C_QjxleABD3~fEo1Iiy5kXyHG>CEef(zM=> z;HOL_@H{9dUGcb$WSm+;YLv6Ve>2`mZyf(YZ!LGG59-r_W_GY}+)tp_>f`8e@isEQ z)f4;~Qbb=Kw32=v8!P<;D@Br_KWWYfYpHZZ9_if9(R!V+v|^tze48brH-DMauI26I zQA8l^S_8;@=>@vudlO|BG?LYeW=S{O&Va`9z4YM>Lp~>MCOy14TN>SY3eNwb51rco zk>t~x!H{2{$%Dt&LCWPos$AhA72NaKixorYRPR2lmJ~(QC&x*Dyj?*@##_;TpLaB8 zV}WpwOpwMHIN@h>v9!?Ens&_&lAijANa=G`5^d~9z2fpnb1^H zXfFm~%Sz$;VJ*aKY9;!j(!#^j2q+rKarXI((8**ilCU_KZ8)ZY>t^}WF|UTw?@{HD zZ+?isWF4k%zyIQkT3c~a<^b3?c&BB3&(Pj+7TmLsEm*9!lM}Zeqo=1WqDgD5$m@+o zsM>c8Jf)Taqi5uh_nPu}`HEENXSp0bDM55bY#0hCh(nyI5t^@NCS+_XBe_RpVZ$L) zC<=z$vjzrt&o%&~@}p7r`d>_-0!yQl$FLbiIVfPQ1--OG8Qm|r0Fx8fflVs;gxem( z^#cDC&u`Ke zj7zJ)nTPh=r>yO$scQ&1JGiS%x%r1wU+Blu2`Z9o`PxQco;+VIZ=cX0d4MSgR{r=pB{C9<;Ru?5f@o^aEHgY?6=us3L5`Gv&4(fk> z278Q{MN7CLj(XgOP5pfO$#D3rEChxI-+~6g1ZnG3qsNW~Aa{!~H+Dib^8F^yN2V9x zSJfSo>Kt8e&b5U?_UL>RXr;;3@1IP@FR$b;{mbEBFD?;%f7pROglyxJmsdbibrTit zQXt=gT+p+zW5t(+1hiWI8Jv+efozxD7g`^Ma6U&GP>bpWZcp%c_;-sI7t{9`J(rY1 z4TA$jbZHpQuNpw#JT1ZM>00>KH6`xr@A2@7M339P?~Wiz4+p9m32>WBgfNga2kYxb z2(N!z_R67HRB~WF-)&J%(vAQ@@oz#!bazf@LHcaHlHzsyWJNd6hGJC9!Fn>={Bc@t0qoR zZZt$KyKNM%MTScr{=L`~&R!5G04U>%dIu-nSJPp+UiDxx7 zl@gbTQ1<=hVM6!qc=~FY0{?YMEN)*8u-x#WRGn!iFQ!Bj?O7(^VxKCNQH{XHUIQeu z%3CNKAw%Pz*wNdv=SlayZ`gnLP$Af9Jl+$v1Q_hh<~RJ-pi7r4lFj+^sk2=+Ydp4_ z-7@ziF;fx=&v)+{tj)B6d&3g(+t4cF>^gu~KbEC|@!y5 z7I0wldNOZb6iJxs0FqCql7r7eNNoc{wl;OJ-}E!saodlPb>iD>wT2OvFODWY;WvSq z-Z)CCJ8dt%+X&!hwnrU z1`|MS9ZN<$ILX8vDMV3sKEP{{qeghKCqboGHm)ku;ZSaYgD$82R0j1`T5`7C z&(Wg>GtR}Y75Pk&XP5rk%jK7NL%muZ>ex6PzOfdOzur=k6z|QQaGcH=t$7I#+&K>S zjJ}K)78;Xv6~nlS(fv?v5i2G6ZVB5dU|-o5}eajGfKW_<0gjvd2P< z7hb#|WO%hn)~P=floA!#RhARDyL$F)z$F_T+rc2s>=W>Lj~l)?<|;m<&ZEw4)9BVq z(=dH-58p9V<#uRYMAZiF#HrymEND`t^?k#Ui^z$7zq1qRMXzErKb%9wQIYtqQxyF7 zb25EVqQw~m@LY87c(_mfC3w59lZ-==@OM|GequF-j4f&B;sxLmH3_dA}+)Ht{_Q?V zJQBdRhNQt&`*U#a^FDGPnxm$aVL+X(6$bKx*bfV5P^tcW6gnhHwkor;#W?6G=0V?yd66mbzbq#)Exv~{KYHR1 z4H^gp{9>PZ%c8IC0knI?S8}Lu13~#|WbJw%BsX&{e&_xL6f$o}di!OR-TRy@yrTd! zh8d9t%K(y4(IxzFlP8Zq@q~S~jKp}9qDLd02a&@?aLXW@V`ktdyz|;kG-wFJq8akt;zfrx54VBc$YPJ-hD35v0GM z7(Z&ZM;~vbPer)KCfC*SHgp zK`r&6@ykiFsy=YVmV~a;VUH(ygAbc0 zQBeE^H?Fi{!9h26?yxtK*e(!UE)0g)U;ZYO4YT%Zv7bY+$@E*E&faX>ZRk=b01-c#lCR<%dYhB>jJv~kDzmI zxRd2?QfcdGWAb|1SaLl1BpzvXffolWQSbelU`Ln=E~=sAMY9^!Iv`6e)u-T*SziQp zQ7pMsJRMa3XU-ONWFQUuX>`o|N#Je9HP+ojmP~LC1zGi!5wG5fybg}R!{0g|MD7IT&N(WPoLraR%PJw z?2AM$Rh~@vegS{z8uZevDIzzI*rNR7JMhnCX)w3Ap7oAbqgPK`kT>BTIPdOZGI`fg zd>oDB0-Mjk8=pqN^+Czxd#}Fm<&+$5Bp3KYHAAq!dn<4}ITYRVoQU5886bQZgsYVu zVbx6^;Te;U!W#y*;PvE0e9WT~ZxZ#EyEWY9Z{ItCzAS!5MqYDb-ze{Zm*;ZW@0cPx z%eM`F+G&hN&Y-||L@v=a{Uy8}-X|*k)CATq7)zMoIJWh64Y_{Zij}UY#Xj$X*s6*n zWU<>zwnEI|`jcZx*wu+RC7~EQhPyHkD-DR-#1{)(S;l_ zaUhmSG9dZ8hy)E-kgZSl;>B0~!~RtVS@Khbys17;=DMnr^2*Ij{~kHe`T&r5vQ^k( zQxthswv*rKy_3;Dw-=utKbg(>1abSvZy<4k4l{p>I(Bu7A}{8S0a@?Qkc98wMD_h; z*m}?#zui2SRo;q_%Z4PXla(xOLWo#@rm-(4#`7q!?@U<=A~{u_95HQ(5)kLxQ(bG@HC5hP4ff z1TU5-v#!{lxVJR2zh`b|9X&^Z9Tzl7GailAJLTBT7Zpjm^;-7r$5PhNKb>9K{G5dA z?jd89hp`*Rs^IvLUPfrz&MqN`@w$o#^5=F0d(3Pa**#r{+>TITr=&j?UbZCS;a>}g z+1{g6V@sl-E7J-khC!0h1u0O0lc7ho%CUT~8);f~mPn1_NY9BViDg?384b>Y;=ZM% z+V2HaN>HQ6i&rvAe`1M6!6g#;auNMdTnuJAt`zOR21v5cQgXJ@ik({-vTvi`-J6bv%Knv^c=#{8(a*Q^=Q_PORnl67>Dt7QA_# z4qd%wE#|EN4O;h)Y{_{6xJX0{=N=*F3Jt*Iu?pNWkCkN4N?r27xfCr}tV3jn%q8^qXJ=}a{e7enI{GRVcN66=R#>igq`JcNMlPS+;;aH^ZE2o64IIs3U)T( z+5l7XYQ|5Jiw($?loH|3_7RxROqAUJb)KkSyhh$$JBbTsJSFWq33xR#4A{C)pqo!+ z6XoY`iAzyFne9|fI<{PerI*h0zXt0F=eiF}V@V+^ox6m@_xlma_9U#4d<2fp)uX>J z-GWz_Ut&M59uG&!*OF-eNW{xINER(RhTqJLfwL|?6GCqnVv~@~f>PapovrFa^4?)D z{cvq9e!^_PE~X;FzwsnZpRSYmL!GR1=|^6v-<{pFAeAhdTS$UlN^o|u!1u0HXFc5i z!)<};xqoy zq-Ugm&SmzNt~EQ)tBNE)&?a3@99#9=k1ZIiM-p!&kl?{x_MVwpc<=D-OpetC%nfq3 zWQWDG6R(#FFOsErFcTW~Ro9WIwD*I<{CD}`CHF<3QiB|Y|PzwmdN z37@~ogRHKSGBJrNL}%nu_9ZkWZIiAOo80L*_l+DJ)*UJAYseFf!qjP|mmit;Z8Yg! zf1dO>>43i>_sL=t9kA)sX>!~A6CTp=h}2o-3Js4x;(;?GNE34fcs(s4Inw6S;a^Iq?CzVbnob*nR?=?JOfkt>@V@M_kzI%4TeqJrNEB zHuIbJSK;#_G4uYb7S(+-idL!*uro**aFE?hdR*?4r_ZD4_!DzsTbnu9do><-1;3-t z--D=ctubYCZ=m&Sjj{IP2PA4&9ym8;o>cdU530YpnL6bsk%QtQ+QAMIyJICaVN@>B18>@Pf}CI!w3* zI*mJs_t#NUx4o(4@4u1Yp7<4cvauBGZCZ#FU)=>K2dm)=oJgu)*GD#%%G0)|7f9{| zW4d=$v~fbKcX~VNjgM%3;pcVK#rw-2Zp20qFo1^q~XhkQT=z9rN@KLlI}l=WO>tcQnsZ+ zs0{o}Ee;ofhS`RsoX@8bvt#JR=)W}ShXW~Waie2CuO;6eh~NU>a(s4g6}h%>u5|7P zBd8a+8s0eRPxWsv!9lU(tL)T0jN{(-rhcQp(s9T{D9cR=)8nr`dNtHfazQ3Bb?p{nu z`+ax}s!I6zCpRBwhQ@$y*=M`qq3_TpsRbR59dL)U7wNv|1{t?=hv`ICkoz}r_29wiC|W_ z@8{)P_M!QiWug{cWpruF63B%9hEE#9_{Oh$UowUx3z+hX?1{FQ7Z0hz6GIhA9Jr)`cO#Mb#Yn zl-Hm~F*ba9q%&%ZJ_2FpFF0?f4tltD51)}5hbmPQ!8Ml~@cfi;RC6gz(E6pt&vY8> z*CU7WIm4{bnXzXjy8i(_Ygqw0v)+=uW^n}`QW^?}t($|EuQNtZk9wo^a|+oRGbG0XnyfMH}WO zqHVwP`8VR3e230NlzuB3(6edil+|h8;>Z>lY7WrKR|Lj~e}j#e>cN{}eJ~(X0X+tF zj1?QILDJ~cux14T@r^6cl_jzKrHd8d{rEO$s(uljFbv?IH^}i{a&3^;nX&xXX+%6> zxDg6G6~R;4E@a;I4$dnrmYjFm1#r$P_-Wi~WZkfUYx6JwtFk(w&wtk>cX#hX(Hh#^ zC(R|e!Hq}OBRWyDXe773dI~?PaVjZ#a0)hji4#6*X`TjX>`ES_b-9<>Mm@nxO@8zBk9z;FXg=}oA z!SdWY6!;_wUG<6~3)PEI)7tG~CyNZ!ST&dXqJ4(@&@I5lZ!*z=;N#q|#Xj(?YYR#( zHb%P?-Qf4HacF{{ANudd5HfE1HdyL*gk3erYq%Nb#5rjW?$6wfxjl@8zyA)Pf`M1O zNB#orFxrD#F#I4w_&1+nZz+W7j$q%hw%#ymb`UX&($k|4Pt8s~ZxRDbqNKcR8N@az5X6R|;pe zRtpOc+oCULiqW(sCrN1UST1gN8OncUjhxgTz>b!cFut`N$nTth4wm26G*&mHZL#b;+BNnhDdk$ZRP(ceKF~mArDn@jgr8*;Xq!^TSTg>q4|}JwJ$NHmu@Wtdr22 znqkDWd5ACwIJft_~&rZIt5{JSWI?GK)S;42Sgx zw{mLU)6sIra_&^l8DVIG1s9xr3V1mCpg8Gp`==3Vz}D7AxUsJQx$nKlC;a&eCybda z%=j?}$tN7+&Y7q4S%W&-$F1XW|5SNUsoKjO**A{6D3^o8!J(XdcnmQZw}{i~KZdg= zpXVCGUck!Ia;_x4oP9TQGWz{Qo!feMkWIqMa-%g*a(4SNQF+@e7_89`e%Hzq1pdzRwE~@QQ9}=^ zO}I(39MA}Z<3jH-Gbp+2jLbeB5l9gQMW4dSVXBpU36dDP|pd#WDpMbi^55c6-|?6$kD z|>wl$sxs3Zt`e=H|c+BX52=#|n1s+CkbY8n0bCIQo+M6%JhmA0*r z!Apxak#2W$FxT1ATuZ2Xa&j)_f;>pei6RBn664vkUI8ygh7PBoLR3YIOjW*Gve}+d0 zZBKX7@8v7;rzeo+47njnJ9=o+SO$!3e~B|2bBRpbOOSE+J-zG}k5A{9LIZ0X zvi)}e9Tjtou1==-VBch_HK=un8Z!*u4d@|{?INkOUo`z`lLubi-N**^c@f7kSNT`| z&&W=_J@j`}7)ZI6M?V->(RCez`VWgMWJAwsx@f+Nq$@E-7_&}XZu@Kse~)nxxsMb6_by<#Mfb`?lUYEDY7drq*s>`=fP4K)y&vSu@ChOFT1 zDzzK2ccP%%^4{*C>{rR1!9J>0xFmKsv_VvJU?(#xi`wqoE+^P$gxl2wP2x{pOcty+ z4Pku)Ux>0@MNDdV6+hOnoi{#f%dTY&*w)umL`4UgT%C1Rl_qCRpn>39LiZ&KDpD*P{#af77t-ZrfyO+*4 zjR+Qf?knWuCz%L0A06jMFM4iw%&0{C@}e=j(JeuIUhK%9l{FULI=b1t`iO*e+XPV1j2%_H0H8y)?nAJQeAd2g^b4zK0~|V;j)v?4X_JcTn51M&iHZC%J!58)v;x zrBf6l0SwZhYojI++4pC_!B;QwSLI-8wc|QS>nNvn3KwY;Y9ZYTsU*+V4sfkeWUID7 zHx8Tu<%b@y-`tYu<;SzhjpbK~%Ig!rbLj$Uk=spL+rEkxZI}R+R~XYtcS>l$u|(=N zV;CLwZ9W{SR!+^f{-uiF<)tTRH?Gj}q<{RIX@#E~U7?alFOPXhp8eYkog1FO-q*v) z53NZw>`)I@JiLrd{GLjkM&6*(Wm~~j&_(M_Pk`N4N9X~kz2L|iPvWfYEUni%!Z%fo zgbEX5$)A#oY`EQKn);)PooB30m+#e-CM}%{sc9^XY#IZbYJZZW%imH%jcw#$m@!fA zx(axuQ%YPQoA)%>C^v=w)U@2DtHrF}`3HTy-lH^Zn z*GAI7`dBEt^&2&tsUVH1{)SZ!n)0EC@~A629PT0#IP%~=V3ShRs~urzcO@zpt`k+uN6HWn8}`+t?ba-AjOlPO%JjMv{>ZVQ6E21g!J3M_)c? zOYFWzh~W2hSfr`}8&}+6&aHUGj&`d6s}`Pux?#(ZgZfDzvN;F8C^FFFr4kJ7y#a-k zh5Y0Qb*ApbBIH^+gpDt-0Uq9EuxR)YKBHF)1m5q5Zrvtu;=fzaaK$yrj72vf{k&K5 z;G{nMvfLJ>ZL5+z{`p&^{BDr%#*CKO`c)2kCRR&IV~;ak7R9i)E=sZ_GzgwGm*?Go zHbVCzfTE6i0j|LvZ0*j2?{ZU^znP2Kg)cXWV-mE`g&!+`*}8kMeWw?jWC@qfmC1oWQ*a1$l)54_JX3)Ffg zCeMx0)YC73-=kK^jb3&1QgJ*QI`;>dw{;}kSm4CmLp(RG6(dAdZQlK zq5N#WagwJSIz{&!?~5z_mVgPvhXI%NJM1&7VECUc2e-l@{C`0<@Qslvy74B7zZ{Xv zysnc4<16n7mwfg}uCDFnafX+W5f&lHZWxdZV(~mv^q zJ(Lv3OcG6NTV~r}HxWw~FJZ|BW7f&%Dr53ejwvX+!rp6JCaisonZCy(nO`ErA9g1~ z_RA)*VR)8Z-~uB&Foa=imrTQ6NoK6((_@v*pK*AIR)Hx(@Ll?NBp zo(s*7j9H5t2LzqG;~;q=FNrL%6#lE<&-xY3<8RzOjHOP;SviLdOjU;(zOi98Q?}a( ztg8|Wxtjlknh6?=q8cX}k?AhzjU6dblrI*32X+W!R2`Wn$#s5z-*jPezp~x#FjLm2 zs@|^t?LO8|bvo#n-OsFTk;5+|_1Js%H-)8_r{E)CDX*~fz4(PyET3s5$MjhMFyK%m zIycZNd~6c4k7t|^WaX-vuenyduY)VTdoh}ydvQEFI-!8y(6Nx6wQnqtHsnaIrcm+A zq?4jWf8AMpFaf-FIl;?KILaPhJ(FE|<31zn@I`0P%BLAaPy$> z_VrImpRXrKJ+P4p-oIY*xosSF>RTwWFjE&6)c!61vhgTe0Iu4}?hh13-FPK=Sd_*p zoXuyhQaSOhJ@R~Iua0QF>{_8oGM;sya;)NOE52r`xj^5Ix3iA&6R!F07ySS0=ksLG zuv=fQl|1N*;h%(eO4jK8nf#u6C>j;uBV5~<$V8M?ia(qQu-h{3r*PS~MZEW)n8~cL zX4_AmW|Vymg|$&LL40wLaQ>MR7DXPqB3xA1C(6>36-L@` zw#(|(;3wV$f_2dY(H8v~BCmvDb{Efu+m)?($cCFc*>NGGd46-DFkqNcX7}j6B+sZ* z;{uzSfc_-e+sa@2f zwv(+Hcb9QnRxdsf@sf`$>SGP8whInv&m}YFDzUpvh6xihu823jDiYKl+>Ri6-LJ=P~%1`p+bs{?|J4uMMtz?#!9pT&55(G~F zg(T$tQK2QoRy?)*y(G(gxTw0&SvYiR3%_e#IdgMJCLc1?jPIzr%)jgzDGIz1!;VkA zCRqk0>}~sJ6451r7bZQhi+wU%7#B@^CEAE@0Q+s^javtP-X?sA4O2m+{XkN7t{QC#-0)8ZTrr|Y;X{Gzq@wf3}?y{Td z<|LGx=?GI+jb?8oKIFBI1~AL`?V^Y0h6-6m>O#kwQfA+gGQ0V|O~eEDYS@X3lqGx4 z9OoU*m1Iw{|IVp^1iM#vTI}AJyjPt{P6)E~!Fj>0o5Ge?A(t^AWW_`hvDr6+W9> z0CP9>k;wM3oR05hHh6XSptm^-g=P7&ese;F2QpEl+13;6Pd7#RD>L}F<#lA5?h7={ zaW)*nrUHw|RorRy16)h?Ja(hGHaA{dOYk-Q#;KPa=h_|)h3{NUksqUupFNq*%~x~c zzFW(2se}DnwWR`dnRJo&x$Vpb-sQ*v9O7xg z4ZD35Wmy)$JcU%KnpKCdJadN4#$M!JogYelRV&c>Rb=R$RcMj>Diu6ngG9$T3mmC%d?Fjbrb#5|3&WbM-AL>Ubd(g#dJFwJy5Vnv4q; zno`H}*FejhW7woN3;6rprQ6fHa8gJ(F%iO`^x8{Yt*K8|b?pZxf1)Td7J+}BsU+QU zP+#r=sY*i-Ncv+)^%X}*LkhBJZEY{fDXIl0=OKf-D};KsSTxX^pWhy|pY8PHs>Y^z*W4x5q2$oHLpJ z^Bh91lp-vVG*H`r8Z`XFIJEMjE7`Q}r7#iA7}Ro3rg2>w)I_(GYRk$C^EI#2PMJ;E zYq31OL|W!BKZa@L80t4dPHwN`1Ifu zZXRVIUGe%Mz8$oT{M+Y6Wb>?Pz)UeMj5|R?8^W-~*Lb?MCIi1;b&h8Jt;RhMkJBsa zXQ_?JewxK6kTr7e@%5!|a3yWP`LzZ_;ZHf;w7`bi48CXNZ3A?9kgZ&9l||>c4(4uM za*-}5io|+@to|v@1H|yN6!)%7q|-$$AX2{*Ypwr*$sHYnUKCQrNyT`^l-ZPc%2O4e z8c^v?NLzUc4vCmaZL_jKCl?Q0C8o4w)C{n4p9;xRC>XAZ;u<2unL`E4gpRTgnHj^y+)LrCHhjUh3B|~0zAg84klp!y zEwVr3Zw~GE%;oC!5b9F8$L&@9Cb-wB*=tSTZojTu-hNc;VHEYZS=ceAg}WQWbGPQV z3bWqzuzsCW?A5)_pvHcAWK+lswP)Jxzsjw!-`#zayT5-p=hhoe4qxrzN|_!mxjl-E z?>ED@%W}D1)9+l9zNP(;;1F0l>mhSOQX17H+lujqGUKTA=3WDnG=Pmwv8B;IRVdCO6&Qal4o^ z-B8HAD3JnNs7dU4Hrt<>{Re>;)PBhxF=`SwqT{B;XtQJy+B0Bi?`%FGOw^o)6!Stj zk2|TH_P`K(QR98M+w?QHa?(dMDt;w?^sE+jOeR~?VJnw>wXYb`+$$CT0 z;53BGT%n@r8aBm+vyYq}Yd_Mu82{{ihc;Hr+7IQE$n%3o=)qB%tobE%TF{*$TBa#M zYsL%^y>CVo1wSGcJ>}%j$N_RWV<_v|HwQmy>A+s=2iZDq8t79_8QDl?vH91>(d6mV z(6Vh2*l_Au(qmx;n3`5JtmFyV-*tt3SLK9X6>cUEtu07Qmks&a?!_*>jHv(KI$WbL zf|mME#%l)itUjAXqNfw==++lc@c9$vg2S+5D9{rlhans3+}d6tPi`DlEX_v2>b`Vx z)nL9GGl^_elOr=-u9JILhmf(HI-S_K8)Z#s#BV2NqOQP$^wiP7@Avf-@)W1DQfC*?R09>DG`z#&S!DOi>5fZGuPxzl|NZRgF)ZjG|`e%xKTi z^K9qEm-uw-9qc=~LnvD$i=V`Vll|x*u1_|ghr>6M;hHW)ZnzC<7&oX3e|eY5*t%A9 zZD5c1QvC_Ziz5B>Sp!Y!f>+)vEk^UU+%m-W%*O zzagSub1pJJZXPJBRyoNQzuCwq=_c?G4`)fdV-B+RU?IE7={i4V>@IfIkWBG%iw?Hk zhoO!-#W7tmQR6Ph_oE zZ)6l>Y+1+3IjrlFa`Ct~*H}mOq;k_8ZH%I{wcOX(i2~9(^WQFs z{uT{psSKD%>hveGQC^RkLJt{msv?F7uur!u>FkmG#rBe&x@C+)M6(U9y)vGK^4pkw);8rbV~a#d9YGS2yf(A<%Mg}b zx{dYEiWjNqPT=S4eaSYTNfVXDikQ(YUF@7y>FmFnOM<;d9PeK3AZSIdXNFYkXQR2ShROr*FM6%;;ieAGlx`5&%pQj6js!MW z%}`k1+bj(4Hf42F!`QXwcY;W z_+YTG{HxPw{$$_+yyCemula4O5aRq+SQ|c5;=k7#-2B)tJli4z=ZtZ~qBvmJ_4$aP zp&!qDy`c?K-u%b5t})%mSfCy9L|fVZwOF$Lzl$=Db5_2=GIjq#I^=lW{otosP9>C;DVGvzQhV-s>oJPOzA4i|d2=mHC~ z*XXtBQJ^>JBe-fJ;a`6;=3YFp<6J^yxj6kHNI`x$Iz8tJYJ1m@ZthzMistDGz zy!Zw37~u#$qzr|#gy%SR&KhK|`4k18;t|k<@U^q6aCYr=n0K=m&e6nZR_Oq2J9{6* zsN|rl?_!X~OA&swY8-d(2*-CiC7}2;8R2t4IbO2sExLNY1!f*J5M;ln@JluJ@b=Mp z$gpMwpW-CNyFX3iQVLSwYWNu&eZ2yMtL0I+W)j-I_$rz zYM@N};9PP-4EpQ52|ie-f?DbXp8Xw)7I}^qhSf44Ab$#4d`F7H&NE!yz185c)(O6( z@CgbHOB4bvRJeJ)y?D5rC4akF5v>Vrf_`glki&pju+{GbONuh_y5!TaBqkBw7lO33 zmDdg;uek5*f3J3cxU_3HutJ^fTQv`qFK86x!WD4{*JSsj>O3qzr_CsxeJ_|*SYz5G z17+W@0izt%CExF-!oUzW!SUt{Fy*-!_$HYHvkXs`d*BUhLZl)Za%&y3e(^=97NxT1 zo+%-f2hIFF^Ra@(%gcPG|0=lMZ-lVL%pKCd`^y8SU|1kt0YBMg;?kh0pwUPc{;SQ0 zN`v__sUeX-f5c(&0gqA8d(|!I*HO;s?DN3Z8@{pg(x)P)(7CuVY9G$FoW&-%P8GUM z=MU=5ieO;9C&t-3AWBFPEppaD*&PuWnXeJPMIMC@njc91=}8oU!Y11s6{oTq{uTQ_GR~IyQ*}==eyY-eN+bx17j=3VN zJgSRBcnaE63xK^S3*X;7jppt067B3N#x8;pB69zVXPTt28MD(^8HpP16XQVF7-k6D z3JZm%;=Q|@{a2X%+KB6YS0-FN@Q{Y3N0E%XTVe21eGVL61>V(&>*UVMU`@weZ0Qmp z>Tv}?ZEq_5CS6N)$au2K+YJ6U`aYFi?gQUV84qI*8`8%u2~6L|1@Kje6^jiu;fQ+? z9xxkZ!j3??)5nTNb~fTA#v#;3QGxZyC-`viWRd3R1MHE9OG)_V9ikD*yTSq4F|3h& zN%g*Cqkx&Lw{UoDGTq_ZNG&JMuX%QB8Gf<)7?=|{z$)oP6K^Xa zPX^H0-y%VPh?3sqK4x|O1?qov5nJ|J+#l8qgQjgALRU*Gdj7OE1@DJh>vPXRZO0|X zv_9YHcFrnt7LWL9S7786?v*^d*1ooO(J$o(bHMcow2DCH3 ziJ22g3@$OIE(PaVclQ$E=%2{TtZ;k=j=c+7hvSdy}cc6YE4<$QprzRbjYk}+D6--$e3V$g1M2_TYy z2P~GN--imJLHKdzz_PPA`P~>4Vp>D;3+rKJmNedBVrBDv`Wf{8av)e5_nst=6|gWk$N3CpjVll`jE=<=b7He%TVI`Nr+fIf(C_gUD?TDTToY7521W-r-SW4%en zv|8L9J|C%cG?0k6vFM9tD}FX3A1U2=2x@Lb)7@oxXmo7?R`v-&v(BEy3k;URdZ+!U z&ME>H+P7lI%cexLypyy1CH{>&K63_tTcDnlvdxjsMsg_B04|I)fLo6KgnbW|qurrP z;ZBJVI&IHny8q(HIE4D|FF`Pckx!k zWR&UDK*E3QLo)HB@gb)_Y*Ls88kr?cT=f1R#}EWpxlV@@SB{4}`#Xr@%La75B#o67 zI|}B_bD}wQebCeL9x}?GK%X=%MA-TOyfn8I^Wr@oVdEeuZ)~L3kr6gfEx|K>T7Uxe zOb{5B2CK~NARcGWe$#ve<#XE}9lR4EL_zP$*JdnnSaE4*>mU>?j{o5QMl zf8bTL#qQ?rx#+9;8>$o*NsbR3p$~-mtp4ODpxhDCg_Dj!(A`7tS3y1^*qcoa{Rscf zA$;h<{k*QF3U3^`nY_I1#V=2hrqhfpu&%8x@eX3?O8YS|Kv#+X`NN34`6iR^`qagL z*t!{hTl0a0N3G>W6$-WO{+nU&Y!6=R8OK>{om#7S*|K)##$=lC^f>)9d>bBpC#ZFn zpTH-6FNF)%6;pwSB>3vN8u?mD@G?jf{(Bw4gF*2ElaqF>QBx$CIqnDOR9eHIYRzW{ z4hQl*&-F=U;!+wkDj59tyPnL7>|pn+Tf(aBJSP80EdN%_m{W1oG7T34Q$W z4N)JLfb3VF1AiW7kzHGidH>P6yu;$Z{6?QcgqC0TcjiC8l_AgB7&1ve4xaCsjM@jz@e5waLdkb$>DK)(>As8*cEktpd;Is& z!HcD6jlm-3aA0~(&PY8?7{TNeK0$Y7Sn~Q~n%SP0oB3mtlXo9I7v+ZxR}DbtBR3t3Qy^iL(F-{S~z1t7_|>l zK@#m_ne9$CNO31ee|e5a?|#TaN6&Wnbn0yIHR?Ecc>F1BKNXDH<5*-GAO%OwG(_^* zS0SFA2poH zjyr?C;*H3E)(N=YA_XpY@_{Nx1SHnw8cH934&|T#xYe0KVeRvQ(e9IIuzDI~(>+i| z(G)aStZ+V*kqNoO|5&GjXRumToNZqC3PwZ+qon>*=#7sXwK%9iJlJybdTJvoeccXQ z$LQGHD%lQ~C5YWp|5?K~_U2&pA0_zxTnw>ctf1?LUZ@h9N5{L$p#9&};BdSqx^&3~ zs`xqL;Z2jkMUn!nmSiAbJ{orpsguU1t_UA-W!*Hii2S_yRQddP9Bg?O`6fL=_Nvzy z3yQ#6?=$eqp>#59bP?Z)$AHcHo%F9$GFy<-$ZwUfqSw{O@|z9>)5@RuA@~SnRd@ho=@!P|ut*Yk}LbLemAt&g(Z!_ty%aFj32b{sF$MjWQ z6zfup*lM3<-mfDDe~PIknTtKxb?=0=qH|t+dE9yaj=l-^#a%#W&bH#GsC3a$y1&Vv ztNB>Np5ZUmhVeQU<$vYFOU{1Dc5f83}rJ_h5Y25P3-C&aWv_ZO6?*wY2dSF3fnD_ zOf>AI*-^F`L|gtBb28)zn7RHfZ&S*XHjiw2X8d*LgUMq4qVB}nw)gt{v?reQg|`}i z3^CQ2^5bZi#U3&~+nMhXzhl1kiFoC;R&?QCHSWidJO5&i8<0EXM|!8a^2vjL$;VyK z`H3H*s8JP*ziIM(c>7IkUedywzq130S1thufde_Jlg{4FuI01!Yq{%%3jl?3{E{+` zzp&4SZx%c2lV{h`td6-=anLAeYaoCZF)?8 zct+rqK0gw_{4G4X;4AgNa}@MFInBDnDdXYGKjA{X2;$VUjm_P<0yH0xK|e?Drz=J& z@MV|XNXy=ECPhP@!ptz%@%$CKc+PdGye^n?JRAa|=KZ01LE+@=FGc3(_6J;U4Tf8M z_OPx%78d9)qvbNO!t09tLQa1@c&e+$8E+j6b?PNW3XjAP3hgU!VRQ@r5PBUrRo`U4 zI+uYRKl_OBAqLh)Tq7YHPm?{L^N4cG8}^aEB(;@$0n9xOV8cZXVk9l*vif>~^{d4* z33GW8_)wMHvyy=E)Ro|*?Icogn{57-B3f#HfVf?~&s~<&LIX}3@O;n)&^D%mc|HF? zb?>!BkaUGHoiLQKy4+5#%0z+u?KSYPV>VWC)x^oScfutX8bl+vR|0Q7o^Fz8r~Q|g z3FlYW*M!>LWi7nhnWs-Y$Y4|qz58wv2%e-s43t&jdT>#A`Qs*>cR(4gxvzw>2V&6M z`YX7=XD(dTH3?5^Jc=xCWg`F29dPYl9sJ`HGV z+fh02&+`9p{K=c>dQdxh8|epK-bfIfau$qhdjO>b4XEdpKR&d}1FyRshXOUv!p!rN z!RiB}aC@ky&6yHQr1~lWdcU>9h1*6LkLzkE^4Lmrv^Ef&`m+oFT`Z4WwHG5vUuB!z zQ{P3&dw8_Tfki9i3_!2u5KNbBhLXDp*37GgI}_vJ#%s4>!U_$fHthtwYIF^*l|6x` z%FP4w$_ZM#{T4a#RFGvLDeV4T;^ptc*}b();S*v z)r-%G`O%JC{^fhH(c&)CtuS6JbknnO7&ig!`gH*|=Xj%9UpK5d?i^~ElE!@~d4bGz znxW|=nfNQH2QRCGfH2IMoPAw?~t(iNRdLMt>V}Boc7W{=* zM*gA7jAppiuL@TGYXI^Na^!3(k7_Q;;QrJQ+^BREExaR(WWjuts5F6u_{gBZ>pb`| zsT{}4m%>R8Pvh?V(`cJX8J@S+7CXO<1KS*O!Q2Eh_-n)uzWbL8qDLPzLdXqVLX&jOCz_2o9M(Te)QYS-*g{1 zBT^poAHQecb8Ha$1)z`x(Cb?qf8gbP=09&U{-j?Bs~6Et7xqqurAG^amSHeF6_9~% zSGF?l9(TC3_7MI{MLw$)KSW=Boy<;MdWg5)AkA0KSLBVlFS7B)->5_1Ch~1kDE;{H zH+8H`0QWw0QlsO}d}X)}KW~Ey*>SBMsLr0sTjdRagAdm818Z}LW>1#52lR_9z5Wfq z`lwA|zaDz8dK8~k=^)dFy?E^)M<}!I0q@Z{S+pv0Iqdpv1nMgm!iBQ=ysp9|az`?c z6_wS3li68})2BRY9HGy;dTI0d+dBBjC6BSPb2q##s3NUFk#um3Cx0$O%z^*C5Xbsn z!mqz1vAH4)Z67Qr0jdfJOP_+{Z`tw3m))RypNVzXj_SO7-A-0wLkC&VnGfsYkJG$0 zvbEd&8tLz^wgubF~zOr!PYCZmfbP`|Io_IFi1m-XOn~hg0^sh+GQ_gqtqB5Y5`V5gl08K4q*2w3 zR9GQf&7FzvVn@b21uLG0f#S^@Ke08h{59{TF#``Np%g1=3f{8=m!?ZwR zeqtl8Z@R-69-I#km$#Cu;vAZm`DD)S*H~zFc0B4Ol1Rq?p-{9W9A6qY4+Ta!lkLjN zc--@3-0T01s}ld$Eh%~MgaDIeu#`>Qe3)~Ywi+I7T?6i(K1{e;?0te%2!g{UExW%#%&C`Uho^I=(Mscu4+N! zngRC8n0%NXHidj`^I(r1FlM);*9d8Z8%$8l$~LYtEEK+Sss`1b3+bEG z_oCDG>7wIr`h-h5%fOWf4&rabBJc&cVgKKeWV)^#^1A+viLJlz@Fm*vXm|NR|>gIc*^E*mWFt2HItVtDz{_aMJ z7gEr5n-efnVZF`Ifbk^isicil$q)Qe(*ng9Z?I9C8VQG1wBmO0sX4Hx0pHo3ik5wS zk26xL@Y#x8HgadHVXmSRYV*1V%cpEcPoD+bJU^{wv)I2FK6cf#dGsI_);SF!F6Fei zA8TaeJLx70@m05}n9&0_g!HiAMx~-#f^qQierx!o$l50VF-Ae!Z;+{cG?=(_hzt$5 z+AQ1u7nE^@Hot8(q53oglLa~mjd{eTRjJt=`Xcsh-1!NH_s>QlGHK|Hm$J>L;c_U3 zG@>_V!Dz>vbwugbEOhi;6gph6%Er2XK8Z;#A{B9`kgwb`kQWgKU6DH6STP39Ei5Jd1p`3q6Ctjyb0-Kokn&|U$_~WnkcHt6h&^G zh$JH`U_@{QE|PJB$rEOx&)c5@t4s1Qx@jF<&Dz2t-z;>^D^{G}GQgT?M&M;*2{fF! zimZGpgG~Ia=qleqyiVi}LVT8?MD_ydTnJFqqHLz39gBCD9Ps8fC&)mU_qCn^LS5yD_g~a;v5cw%or5_cG$e4;;c6T z!1s29;F1XJp_hri{~jyOOn%}nS8paoEhe<(j~84clZ@WHp25v^`3nZTZg5S%rI41S zG}ng`6_`U=Y}Kg)@Za` zRvnq>FT#tq9R}{QituvJShVe1G*^A>8i)T`qPKfCfGww@!OHiw+$lQ7rskVEYRrBM zcMf`R8xPgtJx!lsZ}|Yo?=T^c>$(YxNZbfbXT_m$vd3}5{OPFW zm?jg=PJ?Ox2-?H_0*OZ)aq2G&&Wh@|UEh1a39(pLfaXBnxB&e#)Z*0b-vZN&FMJhAH)U21sth+B2jPxjqJmpIV4yX6t~q8T*m0`3;~OsRa@by2Hgr zY9Mgd3-FKnqeq_tLC4SoD7)JP6d^6LH98t89U2S4y$odN-~*@rje=Y543G_?_uO6C zbmUU`fi;`1jqm>&f;r=Mpw=rEXwTMj;NsUQ2-o>Tf&WRYJlzILlRW4$#vN(v18jHa zFn9NJ1!tbQ9SrJth`G|gL0_F7u>N9#l1Lgd>UU)g{?oj*mrJgiNo>>SfrD0{dHY6HEwzX*wJ5w+fV0^s|}~< z{E2U^I`4*&n?ZKeVQ)QYJgo-9J4j7w$6|8*Ic5{x)ETc6E}U;!G96=3&j?NL6VD)H zVRT9e)yjz%dtg>V$uZ^No{1NG(eMc9+y0yFSX@i8%N3b=C2N}bOoMjqxlg=*l!Ebm zlOR}f4i%(}lhJX*?C8@;61X_y^W;`- zCJoa$PnJBGf~U7h2|(gvXlocqO|PU9US%iqvT+>z5H<%6sTwkww~9c?gF>uzZXH=xQVkjZlThTxNku1!L*jOS9PKlF!0*XHwZfWjXM5xSNa_hwu{>GvapOGKl?< z#`J@=>}~n~X!>k|o4<@^_Vk&M5^=sEwXQ@U_}oJd>d&Nd+F8OH91j}*uB&P@Qin|O=V)K{_F5aZpHUaxRyzP5ye+^}2NSrj(sGO`|DJQRuM)kgF9Q{Q zX9Z4I=7{Q?o(pfxodVk8!>b&nSy9k41)zAng?-?<15DcIA=+JiPw43}8C-en0nTrb z7PHu!g`W2dYhsM0zzcCLpSr<-eST4r1PO+i3k|Qiy+5?UqXo(AYpXt?snjplcYO^W zr;@@3j5PxeVlRhs_7v_)r$49_JFNDaA7BQTX^1BJWw2YEota$edu-W~JwUp46nD08 zwHTrh!G^Evx6ZH3XUrE%RI|6HiEcjJ0j$2ie3(3*8`ADzPs?<2)dB}*^r7>j4+CNzy6oR7Rdp9}-p~X5b?snHKfYiatLvEl z_Aah>ra8MYpn|b-n=X2i^#z|OYi85Bj}!I4BY4!se%36&UZ^cUR@BA_!J~IJ?D6~} zkx|$J@K4tmSUvcMm&^XK)@f$BVjG^7{_HHW8_>ev23KK5djukn#l7( z4Y%1ymt9nJlWqBtz+H`X2QB}`v&Tl42rZ{=WUp*o0bHxg=&#Tie&@$j*7@5w7-(h4 zzFL2n_a9+-=b2)@)$d|BcWNUr8_uI~p}wrgU>g7EW)(X>GLA;J8qqkFGj!?Z`D{{0 z4X@JpiN77cgc|4qXlCe1f?j0No{|7wKU>WHeIyG&OCi5$S{GT!Y=F7iuNl=DKD8%? z9r(;O9rTgb9w3*gk65jjbmq}JG(4mawmvLjpC`$&-XY8RV57%;`lRdNjQf1Pbphlp z+#;X|>%f&hkgA8D0cv+g^QG%!Y00K-;vVJ~I;W+EBxPjcd7hYVmj1;~o%NWX*Hy$C zq|e~>Mn|)&Fp{=w|VYs;v!`vi8-NC_Iso3phg(scRlYy4q70cCef z(``tN&J=T|wf9b`J>|5V_Y~`6^P3;id+IH~roe+=`f>-}-d@2^eKv}26iC+I*b_{E=?DRmT+-a_sr z#6YgI72lSE2M7ntD@K)-d)r?xFtpjXO+ zztnsRzLp&ZfiF{`$+<1urLr?LFgk{{-2a+LW*vdOsXYK)TfsKG>IHsw)}xz5f7Jj^UZg=9lmejlmyO`0;}0%J%)JWL{RX58eetbG1$608 zHu$gfCzRY~45ij-!L$0xblUCjtl7brU~pNmu;}g~5E(Ca1HXL(BsM63vpE;Rs_6#g z!_j;6)Cz|A35oYWAwX1NoV zol-=is041K=2-UlH8t`jdJ&l4`;Cr_PGj6g3sF(pIoiys@xx^+*uiP4d}*K#?QR=O z!?Trn33W}-wEZXfc&mY0{+*7_q)sCF{_^O+8%-(!#Ehzo+I(k#4LrQ)5tp?j542t0 z0hD7V)AHZVFy-?~(TtEH^3c)C9GaV?c>` zmsIp9oxJf;L(ePoxPtXd(Z@ZHfr+0ry5hBn&bNI6+SZ(-S$rdVd9oP{Mr%<2_zPs7 zo0#QZSx1Zp5c}j)1(aT|46nzep@>*7SgIWZ;qwn*>BMr7p|Kd&uVvXhEWWcfyI|J+ ze(D)K8Sef%%q&;x#odo@lG#NP?7>9`An`lIANnn3+ zA51*`c`mi}rf9C;6;jr^l3k_wo^yRF?&&#piFy{-ai)AM`LH|Jx>D*6p7ADJuyimD zTe&q?)pZ@=mN0T;;rlh^Y_1IJ|0Q1KKxJ?=T087N|B<>r=IP^Z(6J9Q^PsV zdOj=jxs^HjVho92;mDm>sKN%9sB$LqgII4>3U@tm3ES%tZvDcq zTx8mW$Zu&4Y^&bSZ86tjB|d9ol4*e5Dq2JzZ#IZlIyA8++w!?3v*SR-;Wk#sUjc8~ z70-P=d0RAo(n6Bcs?9WCnrB^H=tUxDCKH{2L+sHh-uPd_fOSvbF`T{6PN=btVNV85 z5xFR5k&QjQ0^8pSHQRPR=Y}I=8SAMrSXFU4o?n|J`aD;GWX=R2Af#6G;TpjMMV4eB z-xn;)m#e*zI)%Mv9tzj*;8@=piQ4j`Z^5>WdSr{UDXg?kp$(Bosk<>|jph^nN5?Ao zs4xTnntPn!on`!z^1ZBHNvJe=6aRr_;cGqxQ*24cj0>l^i{{HVe% ze!rR`ym#ab|0pDjrn4rXRN@x>wN;Pr4-4TfDPec{#Q~oN9b)=ilN=uVjW%yhpzocR zf(dQ8{GKI-wNpkW678yXTGmv@!&OJC?fReA@WS!Jwd%b>qaVAfyvFZm-oF_VNUMN_ruPzpx%<&e^?Rq3!dP|P!Yjdn>(7(&rsM|3bpH(^S zn~#N0cvWW92w=M2&*s8%mNP}JS8FyZD6>_6bl6OH@h*Uuvv6pS3M0r?XZ45wh?+KZ zh+^`Cg`9MX5NqKVCFt86xOR{ z2s(E@5jI_SVj2b`1h#Z~NnKGr3nrbgMX0-PS!I%O=;lYWy z%&}lm&BqN++*s@JLRsb6HD-c~>G_x4gTWyY0a&`tLZi$m|bucgsJagR`#nL9w$jyN6U; zyN_oMj$6+dM}83KM@d)>opKbeme*w*p6(UwN$3^6s|aS^B-#n`_m_)eR*z*Cc8;wf z&FPFHDx~Z>1;Rg5`7fgIc6)cNITD0JYf0dDoVU$k~l}E?ZB^TErsvs zROZ=%op@i=V!l3cER6li`qVceM$|yi+Ve8?lmGRepS3l(0ulN!~%Yt;#ua2cN`sfW>2&AgMsN%v1{fUqUMP3u7KoQos0})2Mzhbw(f*!0WNJ+auQpni|5EM4zfMzyVXq>2 zX0Hc5FKVEsH{KHDxRi!JOyo6VrqDFMQ&d^64fhD%fT+c**^sYZ@SMR9x=rT*e|D~X zZ9tqZ%dE5lwO5}|*Qp|K-9ffiWN83HF1W%q=})M@w}Kvh@SHkc+QVwC?IL|UQ{m>y ze{5=@1Apjt4ABj9py#J5^78^)*#6)=}Y))RnUDEmirt zGz)lRx*{(UBgHN{$fa-}Ei`MQJ02b4 z9SY;&tF@mP5C;;0MGOy`2r$sO56E8z0fzNn#i3y=l~m!DO3L4Acek< z^_iE7DijZ*zveUG=ebEVaz-}UD>W7!EXp8ZNA{xhVL60Pm?N0AB@%pbnI zm578YFboEvaZS;1$i0leSig*hb$w@t3l&h?K~MN_oW4z9UJO*5u7%q@ z!of+?^EhVQ2yp&38jUimqqiy;#tBYC(qVWFs6Vo% z#phI+=Xs`7e)oL1)j$&D13#RlR=}zoZv^j)#65$?SZ0>OSr+?8(UFDAu~tk6*CX{% zIJ90ow>fZugv)QDCxRrg;rMvmDbWiCyR+y?|Cjg*dMwnOx|kGOZ-WX+#h}TwODO$B znYOq5fSucBazCeErQ=5K;>p#~+}%fYc=JSG_-I=ob-#9+t!)b>bJiY*5mS!PnvyHH z@Z4N_DRwru`ra*2*gsrT^QM(K{I;KlT~Y@3lxjtzs=wd|dg<2tGG~!8$pqorPZsc) z&=#y-6U9svq=CbK+JM!f?c_-1ahl^(Pn79X5N_<+@v32Ozg?8?8gbVVPy z?RN}pk17Fwt7G7FjTE%%#~eJn#Ea}PQo}xBn~_2KRk-!*LAXlHm`yDl1pjSwhQ@XrN8b{jnF%YZ5!I?C}>+P3;GUO!Fg(-h@N~QD&E@^B&2GN$$S9uW(-Q|R#;6RXF+Ftk!HkU zRPeK&99f}?`n`8><(`fBPMI=XP!|rLPd$ygxDXt6ax=Dfp8^*2jRA9K`a+3|flR%w z1(%&7iEhn&hJ5r=Nm0Q{7=I!feP7mF(>tpPCi)xV1`TCw<5$C_Ju5v;u=L$-)#84phE=1y1n!$X%Jz`HvlVbFxn zjNbH?8m$Z4L7vTab`2N8)w_)XC&hVvbr%J0Y1d9pa_~QH?Y8O2CsPOYSImXSKfVC# zc3dM3%lkocSQ4zbc!7bxthlib25_eIba58mk(-`v$(r}QVe!E-w!!l_7_aRJem)j~ zeJ1MoPt8eCRjvp_*ByYles6(GmbYl7NB}i8gIK}RaL&WQ3i+Kk;C!BH5tBj6l|BsR z#_^@Fa(xCE+qQ&z?0H*Qax;?)?eu^eVUxK@$Gw;*Z%d;u&3Ls) z4aK!Qg|FAvSPjJ1fYAHPSy$sMP;3_t^8Unv=N5IWY55kI-e&<7qP4jEZhhbrxS6|J zCvGw4+y?=PPvLL#8hCF;C-8L35_<<#k$21}W+LZ{bjw$AqbfBSCykHf#_&{DQ9B>( zR{D+2%6-9+r2-~%c>#N3PXi2yO2LlF!Emm`OKyv-I$j%+C%XGn>??B{g?{b+$kkpS z6kRl23eOsLaV9rUa_jv??BBLo++C0f9}elDp6Z?4cX}2}JymBDeY^Eaq1ybQ0(MGuH$S5i|946fRxBxN=)?nqk9O2>scl?~uVAYl#s|lN>2me0M z6m%_J23=It;e`9U>8@G9c*}ZO(C+FB&x|pn-ZE)GzA{quc5*ya56Xla7CZ%S3ysL1 z2}+EQ(mR;2D4H&sD_(smJ6VHH_Tv?fl&GXba9V37wcEW9DvP~NWsB=z-7ZO*mekh)8k4S5&?Zk{;-P;ogROY}vbQXb-hVg+jPyB(~Zkwenj#rvkW+u*-} zJ78U-7kIe8Ns5{a`s2yCeje zK-N+k{%)3`tKYTL=UA6BA8iQWs1dP0ZV0Z~EyJ(-wH6u}X~D382-;33^3}Khak9;i zpz6W^0Dn2dSKU{bW2M$$^y&uAM(jDUIUh`HSPeQ7I0E*M^#DrNAIX&g4L;3KNu;is zjxT(TV3+(^1e)hgBE2&YbKwu(Qejv>e3f_{olKF!eajZX4c@f!SJI zW`;eSTa+ifg_QY_0w*%#p}aV<^A6mY_=x=O`USrp`bTc9$%acC0i5^e8Z2{_hu@dT z@jKe8*<-l}NDi`t(K1%NbV(T*-`NMeJ`Do0>Apx}sTr;1<*C=}(Qsm)1F}_`OuFrZ z+2V`OiP|WR7)hR?chU~f&-&T4&&wG9y1NRsxwm(*w(PPMNu~|4tuDDT=49{ zbx5XaE3Yuoj^4?+MXd8R`0Ctd?4G#-Iip}4@1Tvk-m=`(;pOz(jtD9pE02~KuYz93 zZ?mrw4XEv&cxH3l4fyTcFz`N}OOk!XeFaMZ-GZt`1w*M&S}TVCQd&eUn!1Sl<4fc^ z`AM~dcY{fO8}U_*-!%nxr{D(F&7kFxH#j@bkYn>*_>&j=sH%k*n)4xq1RILSpW`g~ znJ$v({OD~=T(TVL*?{;vMhAJx6)W(KFSiI6rcGAvIM3V7%7n5GAt>0si*$P?;N2CP z=-Z|1v~fux?AW!Ef9P)q+S1qY^GY32B9Wvb=RctE<#skm;TBy~v777}I7V;Xc0xW* zdSup}>Ke<_Kk=p2x=h8Ug#>z+i5x`PbS(dw`r$^b@6bxMgUZQEHxGKn^eDvZV(H%9 z6Bwy%3nDN(4eI{5^O0Z1L7z5t{$P@rO&^s&M|n-erZ?x(wcX)p!vG7)?=+LLN=bgP zq$c^0BZuxZ=)r*n;_QID58RS8ikhFk$RF{rpbM4!>G#~-v^Zbf@BF--ZZlm?GJqu4 z5pf16OrL^^Bz*YuRRuWh*94*|8$op=7IVit-qZ1+bC6ne4H|RCkkfd+42*q{NcW%d zB_9vflMRD4P_J+?`I=h*cg>o`-!IA`gZT_KIGj%-YbxmH*}__*+EfgGtMI2iU0E#B z=RH6%RsVH^>JPl8`p;vi>5@TOxqmd%jOOqwI?t0U@z-E9I03uFFu-{=Bg~xnMf}{^ zb#M!*q7o|dD6~%%u9{W?ou&2pyK;f7^1@cuPqLhMvUtK=9B8F-erD{8;fMT54^t>U z5_}KW1_Su>^vI7aAU8vjKeZ{Fb~_G&6uo}vYpuwm6%YA?jR9;=3&VflpVOzZ{;dOa(8zi|>uiM+>uc_M>Ulq6~++~3!HFSmnV zy-L8vfNJqsGp=3ky^VGsxXXSTTZYLNkziwv5tV7!$$TnlrHz*P{O;8{DX5dL`)2E`9-^%f!pZT;c)s9b!o(Sr0W>P=HV*b3|KQ8LVR4{0^fj@LlMO-(J z=KEcQxWVl{OUhK)6X}k8PwY(On3D>k0w>cJgPruAlmI6G*}&+Ja;B?*1{>il4|BAH zuxYOrpL*~(6F1`(_;6952SZ7`{1X}a7Bm7G{w_UpTn`x~@8GnjOkf@QGib^$O~@-Z z(G@cZGbL~bZ@eIwU-(}Uov{*Q<8u#4ca%TBLMxqA1#Y4pPcLw@&K{=+|K{;Ky*OBJ z)=o~N(WvrR5#Q?sPGOM@JptE^w>}3mH)Z`A$ zo~?l9?-ubl^v^Oek*BF&P$c_l|5kASmJYn{Ur84#>aj@|mw=0dh0H4#dEV;kJ0{XH zj?C-4%y&Pi2U&VA;O%k-yk!h3ROetCV-{Df9b6OJbk^v#6xPtEH4p! zkg(+wjE&*zdU2hQtj;clEOc{!Ok?+$g08t3S5=Ne4m(2VX}^j5gqnlk%;ph#@rN2+ z;kSq_l#`|(xIubo+HNQ@_(YhPxfa`Q8B6}@ngDyX5wa-g8}<#{0m?>yrB>1B#Lq=C zFw#t?MMf)N+eQnjb0C&~DRymqopzSGh;!ZSZk|rLaF|BFapY}nFOisW9ZbhDah+dV zz!cuL=kWriKX;{Ewb+I`wZPZ|)++-g`*t_ZPWL(#1EVbEJizaU=rEXdGp) zT27#sSAS>xLeuEiR7G~9+g$eb?XBXxoD8*ISxOHsl+$zNAX8iNOeoC`HTTVCtO_3j*_wl9`d#H@9iA^SJgK5e$@rW@{<{@mS|#E9P(rz zj1`dy8-2iA<#b;E_c7k=uh=`Z(~rI8{*u0^Occ$Qt>6NZ76{HA`686qxkXU2yZ|qK z5ylmJc8ZE!S*Gc}V$FJXGDp^}6PTQuiyH@a3xYp+ai6=qxtkWP+?bCG1$I5sI4MYq zBsZuYWrgA=a#z!ICdtM9V;tJeV!rw^+iFj_mU0CDtd~K zD3)>4t&ei8(b3G8p$fdjs)L)|YR$;II@grth2x^;7M!+z4t~qr z&P`2jW!hfM;+!0RTItV{;gqIp;wfF(oaOs0{PK2zV6IXg{^ipoEH|Gny47|LYptyo zZ2WI8-sPxN^LJDM=e}|g-aKtK=cTbiU@T}7)#}d>D5^@}aRG9Iw<|V?>d<%WbW@UB zKO>Rbb#(!ERrN2Y9G!)$zXoCLne{bw8b0_!tfQ#(L^`%i+A7iuNx)taVfet!Fr2f| zh!YO=ib6N3GKH(EL|e6Qh|XNA#+7$}a8=`?xlm1W=D#bih4wdtabvp`H{&@VzYRZ# z0!r<!Cj1&ibGr zh6_($f>ZbnT-p|QeBg3~NZlj@YZxG*JHBYWdH)NnKahrdPP`FLL|)eU)8&Xu4=fOmEZmS1NV9EJagxs`F!5**NY7~ zJKIwAyD?RMzL|aWF_F2@e36%3unbrH$rJe36f@?Xi&zWyd_i(=sUS?NmpvgK$PTqi zu@79MEmO8I?6qD)-tH^Em{${%@p<1{f~Kw$)Mc|MUWe@qi%4TpFr`+?;{9JCA65DU zb8Wr>W9JdcE-SAT!Je^vOBY`SASa_a^ElyxANG7v; zd$(F1BX5{X!yoyzOJ?EqL;qO@47|4VYiAg96lbYBQpSwONb^42T*;`-)1#2B6`Nl? zQ=ojslo`m>z()_)PI)$Mv$7iqs5atBw7FTTzTCl+^>hJ?>dg2a%?vpHE*3nI6a(<~JAu;^QU2dTM8mEx?*6j4@`slEabOM#SH z$RaAw$wP4I=mYAod;wS`Is`t0jCwIuH{e^44lWBhP3C&DfJvDK^>x>3!HB#fm^tD} zl@z__`4{c5xa;+ur@nQ9=l?VmJZvr%{GgwMh2#7AHT7D6FHjI1*1pXf-K_vk)(-PT z@@n|w%IcI4$gaO_lE#}@HjSS)rJ2$gxer?Orwg1UF7vZ|dMuKy%c-DKKS4l`DYfE| z3gtcvQ$@#hd5^D2f$4ulc~J}8f#cDa^;o49yqB5aJrc4Qo{p=57acX0<98FN2W3Zq zZlOKHw>$-G<2@+vwiwF>xhh~Z$C+~ZuTc0LKS;Iv9H!i4iD1{iivp#eH-Mt-b<3=# z5<&99Zc5~4637kR2`(873qadE0DbcX!y(=LHLmBW&1DWCoJj(rvtsxmH!3atW#pO7 z49)Y{P(j5TO$H;E&sjd0EC(cnu7g2!L!QS0C2H{IdGPajC-QppgwF8EVMqCzth$T~ z`$!~?&RjQ)e!gvo3)Ui3V-}A>6TFeAv^*QJHix#V?FTM<>*2XUal*9)(VH%+u|JfZ zX-+;$RuNKbDVl^jEOyiA`+jg6njmlpN&vvB>+X3QODTSk0W_ zMhp12k!EQk-q75`ro>7MnFQ16U#nW-Ch^I5%kxOWcUPs4_NUWQbIk?Y!e-H%%~#VR zv(MuG!6)czU^MDDydJN-uFp8me~!un@1p7FGg-~n{it~VStJ{!N2jJgB|FxMSw$X? zVN1S0gqK?v;3dmMNpH(ndX3OkeQ+p*wd(Rf(`&yo^Iu#;HSWq!iEIjJyr_CNYT-!%Gn%WV8KdM`?~-2>wmO3<=c6Nst~psi~s(DI5Z`d9ZX z&~bMW8G|r78uYu#@B#1uLxwxR?#0;FzDeYDXVhjsr_lW^Mdz%WOBt(vgcl4i3i?deuyfZwhkGZI!MO7xRI79e?s-n3Fqf}_3w`s* zo85M-nC4|X#b+xn5us3rl9^z=;v)3+N;JuhsA2o&<$#j~zU=PhspL;}JmdsHObdvl z&aAn^YHhcN)w-I<sLaI=(;~_XW^KJ(ZDI zxPV>jy$m&8G-*9XXBVzIou=f`P8vHQr!F%+0>)Es-($kB}tX2Av1d4knVGX zB;9F%3@=*4L>q*_jj_|oW500l{nbu*V3s&{dP+2<7c9>CTvtHO(;kp@?0jOst`e>a z5OOEQI?2zgebn|iU3~5SJt0#OLSNxd`P#v1N^y-U*K*+kk<-43_g)vnJ3p3_vg|mp zDszmabnGVc*Lp%pTT}K4_lPJcDRHu@=D;tg0av~LM%dG{xeXV+x&E`iut$6uYw_C= z-u=#ye{K@o$s1qMzc;I~rS}BZ{cFSd{M1CYg)=$F&(j6_T?H_3XD}QQn}RfamvEn- z7n9LD?obi0y?7 z?7eTPr0tv$x6wn$-DEY1N6-klUiA<7e%pcy(&X{5%yD8bFO44CEJHDUStO^|5vDiU z30jUe3cKeHWTRRq(Hq_fn|CR2GhQh0`f8Oyo4gc}irC8K>C?pGodo5r+J#%!?Zd8# zT6jsjCW$EQBYRWQs5hJHNH3?%-HTsDe0rYY46ixFZcaXyw+-S}C(NU^#5$qqU>8s$ z*w5+ym4roeTHx}Ft+3zb1=L%p2hZ#20i&g2-0S$2AVE(T!BKDau5cFiJXjIP_6(BG za-Q7Sj<5LI@P1_b`4M>HAwxWmZ^mZ>*HWIllVHx_1)QnNcX;~N5ir;C1r_;Wh;wDs zIPC>riS5idVP@$ohm18*UYkO4a{(%yT)<6*Kd7(e zgGAM{jcO|H!iH0dIEOX5?4iPV@N464D6N@K8K2I>2fkltik0J`{)cm1=wwq$_u^|f zdgKrrzUiUR!Jf?-FA*j7@Bcx`&ZA^*mOlKRl0Y_ujDWJ@RFc>4NA6Xna!JQ`qBYMa zvAGEcao|KBuu*h`ibh`Cqc`~|J>8lsFad1-UOjN->3mMCsgU(vCE(__s$;SJnegd$ zC-lo@5-Plu$i15{5Lh|*L!lDw7RW1k;@IrkZo@Fj!Ok{$rPNiRUpdOeQsJOymD zmZVF#{cKOr38*z$jy<3Z=|T4poNXP6#1!~&dzA%Rs|DevjWW#a?(OvG6G!;NKLGvR z&j-krCn)Sx7SJAYw7m5+6ivj`qG_jc zV5dtgmRe(t{iDN>^6)t|Hu^uL?{y&~jOu;x9d7^KI3hd;S zQLsDdAbsY(A!<@=fZf8my?ROzy463E2ff&kpn= zDh*krWujL#Cy~Tm7iu~G1za~{GW?i30Zz^2qdl&Js3!jp>fa-a?%(%>n_jxn>*|%U zm>-{htGfl)ABcjy@(kSgMh{;)eGJVSQN_QCBO$Lz14nzup+HwdTHbFGtQ<^6bm|t= zBY&9P)H)k)mhMHwbR+%H-hj0<7j|_(Jqn%RgX0&)QAe0G+CN&%9C$pPmLJ$$?PYBHX1AL8?FB!JgQwypFB zo9lD9DYN%5>*Jldfld=5HKN9S8BqgUbx&|xPRTU*XeDrAgN4N0_z^zyjK^hnn{ftG zbHJTPhuBq9!ns35<;3*ud3??+jhfqG(-2afCUkZ7<4bpi%;1^-pkTHFXSL%xxnXAx zJ-^xD$5p3@R$>zw3aREqKhMCQ(~fa6{mR_$6jiM0upJd1d_uM@D8VaZZ0X`>*OGPxyJ<;QKM4^vIoa58BO^2%p_Me^qfSPG*yhRw~SR z_&qYi7Xn)I58h{-2$KE|Vby1K++v-bWX8pen4A=6Q=acw>qQ}UZ!8E7TV zO*L@2eFnE`|5E6AtcAOBNsm)K;?K=Lm`Xf2oDDK zpc&0)ac)W?x0HRu-3dC%Dp-1wJ9#Nw(n8|3tkk!bTMwD;XdrjklTuc~h#$-AO- zdht_KtI~w|21~J#XaU^w*qfEQnRIX|t~d$kWt~%rN!$|hpWhL1P1tQS z3_OfJ4fvvMBmwXJ8Abmov_RgD9`u>aS?F~~8?rAykGwBGw3JX5kk%J-(98B&G*nE2 zW-`_&$95WBAl!jH;jJJ=_dIyd|4V{*_)4@#b1Ve=&O)`wI{c}&5@oc8BeV6FvC-2K z#Q(PgN7Wt#>oXy#`!EMht^R>83(r}{pE%Ijn}<=_VmC%NSQ71#EQT*b-@>9o%vk8Q zvvyZ((Yq}%czl%+-cU7{j5cq=uFq>}jT7-mu1y|QTy!N;HmmWKY4gyAy@@3K*lFhO z9|dHSV+MBRmvc3%#?bv8BIuOVK`1$rN+znl!L#y?K*@a?r?FSa>KM5IH}C(B1490i zmFv$^wno{+qv9?Xu;Dtl`J1?~-@6i~EQ;b*d5h7Dw8NMqLP)J*unxEUk~C5txk?n0 z_>}U-$qj4c3c0@>*T`UAEVvsK4E;=5?)jZo^siKvNJm@+Usf;X1TTMa8G$@1_KDns-Q5yP}_Zi525oRmh0r$l_5q(bD#r?HC4=4Esb5+k?qAufL zbjP%e3n>T%s!rydy5s_QHFW`T*;g*?#GEH=@+qM5<1#Edt^pM9J|qizZu0`IkHH() z#2fycWT4t8MIwEdke3nq+-UbqPPh@oEAz>`W=EFy(qnGEt5$6h5V3fIydsicZT1hF)_^VAE7RDg0I6CZD2oP?voGYxv+JzG36ReU7>Wt?MPZ z*8{5DvBO&I&dxG^$k78-L)txTpk>GGTgAemIy1cXtuNUJH^Cd5CgIt$Wcl_p<#!Gk)G{60poi3m!+N0Y&%a2VaT0>PJISbCxt-glb-es3@dT5Sqg$1x~7Oe1GQ z0PcC#AdP>J^;bTLTuro1=@9@qcKl?)X+E|?ZI=qUh z_-;m8vR}h%r{qx5n?}&1_#5sKW;L%&QAOco@ie~S z{+T2x%;a?JgTQH*K%kW@(oknQhM&w>Px9|A0G7S!4O-oPTtJu_S6Gn-tK^g6MV)BQ zrv3tqDp`uv;ull@jXxkCN7}g$+OiEDb=t60_c-URagU3sm7}dZpW&VN+)0`8CU*V6 zDehnRB+fe~h+Q{7l6zmTOO9BJkrOR5I9vTB9Q)O<;i!xpOjwi2#q2!=kW@XXd~eWj zBdCm=X*dS<7AF(!R(tSYy9gQ!&j8P5QV1og-{A8j9-q>PC6+!~M7d!a*EhqpVO!8q z?%}=^@+doid^1>u-j|qh*iIUGNpRe}q|+oJU!tMroCisr6@fny4>DJw3_8uOBE_3; za|&J-sNC-W_tkYKQ4>GMt~oNwEjklS9A7y$O<4@_le7AIic(16Gvsd1m!uR_@aU& zdHSgln|Te8C);C$?=3>F_}|T(Sf5UVhHxL3x+RIMpZLpt0MCV^L{gYqk&n5EIxHFsRNyG)q+B5OjQXaH^f>jmUo5nF)}=d#8O;qR!Uwur%~3Y zUO;us34Sq}L?TI(taiuj>i0&Zcz!7pS{no3ehYyEW1HZP)u!-a*#?-9!DhM3bSf_SELwsj}F0=zcCgUlOie& z#8DrzHLly8l&VwsbYYgC=$`^+i5hzAg(oWJU@01@5TVOLV2qY7l|Y9mVg` z+#npVSfwPo;qy)vWptq3kzv>Yu{R6u)oOaXrucr!rn2T)H|X1-2Mhnu?=f(1b~ zJjuzmQ2pvPcxYIk@fMRtyLX8Tj=jAOPYRues$XYN4SFDU6=JCK7RIhTAV= zAnDJ8+QZ|N?(9Zt?^ki^xNoebYoj`o{5%^TIFd~zy^sf?Ics3PWi#9#osRUhazOc{ zt-w;c2{yL%2?BG9s7Wn@g4pZ9{66c;ypjG~;9P$RcJB=4uWuJ;E{v$v^LnpAg{Ohk zzRq8~S;d1WV4^2sRzN#FKa*3|sn?X~m*vjPJi8oOxp^Yd9&0MjCGTVv`a& z6mQIknE|%AeFlllp36!++e7baQ@|JY$s=SP3^H!bquuf*7`%p}GcP32E1mV|44W>- z&}16?F|3VdhtI|nj|-S%UzRc|y&m-bWz`_*RW2NRcaIr1eMJxJtfXZoH0VpN55Wc( zU*_uR*|e6p9aJ|}f)Yy?ne&g|L3gT`)9S0r&_SfgYGzgrr}UtyEDwE+D->RnZ;0`K3U-x7!ab?AxJ_P$>H3^P$JJP~zx@>H@k6Cd>j^{Q zIei1&-}M8WD@bH4$YJ=(bC_Y7)yT8$JhME@6F*5VrxUn7_&Z<#{Mhy#{+UybN}JJypeFgP2MTGt#C)C|o4N85DSd)A5IAJ>v z&s{9sSLoZIp!mhK`bSH4;ZmXbINyopvVXAeJ1)}q*Tl1P=kf809RZB%;TRCH-i(gF zZpCc8+s^bX34=j-=CsQe9s1|@AB@B7jR>DSgw`x9VxOgMfH7BU&}}-FjudrZR|%Z} z5pC%(?_?2Jq#p?FmF3X)1;JpWry*@A<3JnMFgQ?l9AXvWob+-ol=I$AuiXEV=~6h3 z7JKNh^F5sCx_QaCDdQ1z@PCgi9u|Pm=;e$G^+@17Zh|(>Oh6)gx8rA7vFzINN%XY8 za_lNL9lg~r;_Xd-iqf2_;H1Z!aKjhjJsDw(zO~+Fw7;h_>kqUccd=HSG1&)Q8y#TQ zo{vO{(uzV`RWFJh+k*eNUqi#O3iQh_)pZQ`awFD7lkPZ?sdGYiRKgIvnea5Z}FnohX7cu?AO11UwlLCJ|r2skQA zZ}_&Ax*8OK8t2O4B|&|-vT_mK?B)(6-x#w86sJ*UL2m>$dz5LOiX77~rUGwm-Aaew zItk9`&L@8!E@1}k7Ey)K?a=tl7qC%Dj?4)cW_Arq(Vl@VkSVi7s^6kW7B)tv`**O{ z+~uK)=w-Y%osNLdKtDuRk|E4?3`eay!il(Q@sH4 z3u0HRUB?@{_CpPq!$PKl94p=CZ`svYPP`;fAmh!=?82Xa@VCHJ)aFnM1yjt}xU)0y z2WUZy?>mb!zbi4a=OchlPBojpz>u}q)P-J4$5H8^Cbr+Vl~!0`BJ@#sTUcg&X6D^F zgNuBGGv*6I24RjScx2jzIhz6M=)4ca-CCae_uGsZA)z~0BN_Hr3Ezv_b18cDX<|3o z5MK21#)+@xvAexLsrP+HEn6~=vnm)PVSBAm*9K|$;!6;G7Bqz|QTN~!9A^W?ccyI5 zZ+ULUm^_(oeFFYjS0}{SH*iC{ipa{-!@{n^fW?%SUEqUn2mYn5&3$~31I~;UfQa;P zy!lrQ(eqB^76#}631eB#C)Stz?kd9%l1hkbXEnKUkpSt{sc`q_N|>|t3|V+;7JJtH zJN7YHN!ABBb8S5)aH7hdQ@K7J{1VP&c6myIXvcI6U=t@XvjYyqP6aErQ-swy!MoTf zf#2@CL>a4`BN=v@+>4fQVII2~N@q%;@XQ79ZgCnHRdxqQst;nv&+=UR*cD*5(wcjp zl>pcyi@CC$KUv-Vaol3tXgKsz7hkNYBC21~@z*PD#2{fEXT39&ioVnbPM@k{|FvC% zD%nabX#*p$5 z?B?}d=2QCi;(T>k1)yib@>I>=P`jrru-xq6PW_m#%4hEdgFm~zQ|&9vnUU@PQ4-#1 zmMyz|m{8+z5ZrcwZyQTleuJi<<3&1^VDpUca=*B~Lb4Xb7(U>=OBDfGaf!SJx7k#C zdo;5*ay>}=CMOsM(!BO$f2REB6xMlG4VdJ0Sg>dy3S{Q0vv+1mftJZU0A}B!f)^z5 zVpNl;qAg>BTf1igsj)_$dy*eDzQd9^Wgi0K)%H@y&ng2CM^V1-jiXdXz^i&U#jm`E z2nqP$M=Y-;FX>W$SRG}Qn0Ki->zO6omRf)1!*yQhiLboQA!}Y`Tqe)0I*k9^T8rsS zx(VcSGpMLzH>tf!GT_fKF>3IW73kqt^Rf~{f%Erl!ISITz|2f#X7H#8mGc3DwI6eN z(P)^u?;i;4OysEF_K;C;>F33t)uI#z(}C0UdsOk#=hW`nwbZw5%3w1iO119n;&}}A zP>X^m2^#!%@{icsfuOfvsH;tKjBV#;LzP2VA9i3o_}i!;~irUf`=uz(-u{n zc_)Icf2WW?zg|;&ZsrSfhCZCvi6rv9qMQUSAAy!92pK=^PX%0RCLQ9ELSI4v2{)iLCHNR;bJ$O!zSJzV2*VI)kiCmogq2s{jLb^bo?i5V}BjQiN>OlngkShyNb)O z`U0u@aokk55;S2jg6H@;aG%;VxaC_Mz@KbgI{4I5bVO8%yS=vxDOFt|y}wjo(W^v` z)>{ep|F!0Fc9l|LoytJ+hct7183RQ96dLl6M!?2CH?YsRg&bJ5N}ye8NUrU!5fq;t zC+>3nb_st@H{dlJ}*(}9HSx{OcTUE%p$FXiqop3iwL z;}ct(D#FK7+?0>!!D)O7WMx*8N1>}=yIedt>w1S=DsN<;8wR29WF6#q^A@Sgnvbj( z&IWJK+=hIo3i72Ojy%p21!l{~c=ujC04Bnj+U_A$p)IpY*c+S-Z`_IDdOls|G$Q^9 zAXkrGjp}fl9&A7!`uDkMZ`6S6msFx5bnuv2t2X2=7oqRix)Q@*4@h}!BUsjv%YOR( zgo;jMI5G7c*lZetq(Z7dm`FBPdMOX|3U1_|rwfL9(b z0Oh4sOvHu{T-LT`AJ6uyyZ zw_@Prne7~>A>Oe4yFF)eI1Ngk{EO^zvp7*TF79c*;M?#OekYDp18Y2C_ zk>`t6!C5GgYnW4wWZ%5yX4MF1v1uPscbu@(;(miYI;Vp3aV%g@YIT4^uRGDaXIb39 zvkI=>GeZYOzpE6{7n`7rb0S@Oa9E%(GxsUd#mGmtp=j=iDsgUvhmoC5Q1k!#`g zT*X!eSQKo;z205Rl^jljBj-=BSN7U)e{N2N6S7j=tw-@p6j=g7hD^b}$BCSeNIcjg zwVBB>xJ511nnQ9`jL4dl*+6by7n#@ck}7G>1%^-LNp|aGt|?RobU*4PTNN*HevZD} z-QZ8u!A)Asrs*c!`?bO3)!8GwH@8bD^Zh!U`21{YzA%G(K&PFGHV|t#C+yolHod{G z=?PBxTQBOr4D;GREb^M^hhMG3z8rni<^F`({uh=q5pO7Fxb6;7uC4DDk#SoOMa*&DxOrW}nOjhl+9%Us7Ouq41vnlgS+#E$4!* zec4gr^{SsR;JWY6<<@^rf?p(_S^W~$XPR+jN)%EtoJ21FGUw*hRC06f zy@7cfzj3FYP66GcqvVtRQux5m3-9zYZiqcI6~#bt*vhNMOJ5IA+Y_C*oA!N_?^0_Wl*r8y%_U2lWw|inZ{gCzXGBa^ zot&iWxpBJ`l9&Dg{uDTJ13h;!81*H04sYc`>a@9l=_(DTCd$1EMCGW_5?CA?n{|_ z^;qyX*aJGG+cU$pU2uo23bSbOX=Wnev0$6C3DnxfLq`0g;P%z2uwjKQRC}Akn4QiA z4-O3Rzw}uPf^_wuOvM~n;QfFZYt#|gA8|ozuV|s6!?$2;^bOukSj5CHI}V2qe1_si z_n4R)_W`4%&EENJ#UAX4W165lhVeVW>u?&*j7>;++U;^@WH}}>Y@Cg zeZL1=9>EAi+fA6ef!|=-iOFzxtTEd8QI9!m=>r8H4eRAjZW4S}bryVQ69qb2@@*LX52D+JBJ$9T= ztNk{nADoLJ)d!8}N0l+O4yr@jb(H9qZ$UV4-BG&u-%q+`RKcpdvK77zx1>v*`{L7vY94W z+5a8Bzgd}Hv+D(IS{_C0lEv{BXK&h7QpoH$YDJThMtIOshZgCYhZ7$S)21i`=dX*# z@C%QIUV6Nhtpq)9j-o5qTaii5ldb$^2>MVXiL^aV)4hlPLs2(p&;dpT$XMn!62E1H zk9^gHRwEzjRcQ;LM}`>r`!NpbEJ~nR%83s53KVvBH`A4y&tS*Pf7!xz5jv*nG(A_% zgO<&VW5afogHM0XkUB#X_{z2&$=y$<6ZfdI5%Hn))M;<&h&QH4AezV)QuQ?3vzU#_ z*-!63^w)A_?G^Z-U>p1N>LI%GR5?5&d?)B0IEyB#myi^s3R6U{Ga|1w$@K0J2)8`J z2`!GW_USpKv2P8V67mCuS685KHLFSc*XgJL$U@$3Vbl27KQ#BlH|D{}RQAhXDP;eo z7N^!#ApiY(?6trD(PP>6^a_nB^cF=6lD3GVWr}=hr_U9rA$cnOzHEE_m&IQ6VwcnO zxlglc`)R`2i%|2p#dj-x^06eX+hb05p7n(fWvkhoDgn_{$s^x$@?e0FXL(B08om>e zrzO1&>B{UQP=Crx)W2*YW8?#hmLjSlFqUztU~n`dO*(@%~p}5FWpK6 zRj1<64<-frD{9kL|1Br&zcz7fl z*}0`4{|X=0G{O!o)Y7BZR!gGq&gYq}+EHwpS}M6WO&Oc3RKRCCo9QFjQ?bUSgEU*t zA;q>1HseDvmU_^LW*r`8^K1-YuuB%-SAIMEny)X=D8Il4hI`|M9;MLf$0o2udZEB= zk~Eax-_D=5P9DA)2nD^5p+MKmnmJw>LVbE-Ao!DE&Kji>aMQVpI(y|L*t2swpsydL z@?}=xC+1rOPl2>$rmr6r6BY%hFE0~_Ijhy9qsp=fuW#dBF$ z8S_uDd`c8Er|65I?aWd^^e%BUt@tJzlDA0UEVh_QnA*?ITiwUZ8B?K4{dQ2RHVU)c ztsRWp!>7pDDTa|b-VPsy1*3}Bz3|lUO_a{rQ08FAHyG=T;l3Rv)QPLFsBQkI(ZS9p zM%vv5nM_hf?_BDT>S9%toN|ZxQY8xCRMvtArAGvP=HeivUK%N__oGhicR(vnR4^X1 z+t8&yQgp|KVbuLBoejQFft={c^m?QJ(9VDUNMM)E?8**B*ODjEFO8K@q5KnQb89WD zZE^=?3UfW9rv>O|;|aLfWCPPDi4+%Cp{b9$qSkf8) zteNxIwZY#~Nw}LmiC%7{U}Jay%$*m-v>9{AcK3QTaaR-V*wh2teyD*ji@w9{@=AE% z*gN35qn0uEzXDoK}HW?Wtwo+Xpc3);0(dXC|ThqX%Hs^IZa6ku2nI;Di(ddzl{} zc0!AWespz58rqz1$?Q&E0q=!NV3(DTs74hzsPK3(5;E?Xjv*a7vt1Jf{mU72xMFmzK^ z$n#&0XX(#_rjK8-l_m3N=hzxXJmnd>CI1K&M${tOJdB*VzYh$|y#}pTb|8nB-x)9c zAZqD*C;F$zO#I7rIbywo7*V$^wC2SQc*4JyEVQ!1uI5fC_0UdiyLdV}Xtfk+Z$8fc zazilOq6$4{Oz4R~3G#4FG?M!85S{wxMRp1^uCQ2Bh}zP{qQaSf)&rW#n?=Ebqtl2q z!-ok6Q_!RlIeKPAEE{FMk=8t7SHDE)EOsJDSrbhXHh z-~;GO#7TU1g+5xO%!h2i5_)xU6G-0wm}0L=qdcF-c;oza=u1N<>K`w|FI4nt!J^HG zmJG&n>z(O0cZL0i8boJ)%!0r$0)Cqp*ChLbf zSI~IF`ZTl$+L8@x?b$BteU#M_1zILt8u7nYG7T4|!~R2O!06Dhp#S(XL~s3!UUWH7 zhLg{u%+3fpO-z?jHq6EnYXxZRXaJd(r%n&;uAyGj8&F-}8rJ?~8tu2*l}yfUC8^c# zP^Rp3v}7;}P53HNcP@6rQ}-p1rLqWj=+_Kn+GRoaK8R=Tr!B-rXaSP@?;Q#Wd<}2^ zp>X~UDcT`y4Vjwl!kjpp2FeycLNkwq5jk`TG4b~q+4uppB~^$1rY2;Eb&KKoj}>V# z#Ta^-)Ni8xLX&Q}-+=~5NKoPtl&vF4tn@fs z7iR_&50#+qL+Rv**aEm`oidrcG=iSVTtX+Mt`WHvv9vaS1vB#}MAIz4vMx8I96gWTjaAolz%!*UNgZ2@?*F`mcCNjO99{R5dVC)5@QugfBf|Yc zb1EtEvP3VECtH2Z4o06wmtwsZXL7kFkc@>$(0{YM;I^trVr@^u%c;dMd9?+dci zJ{G_Tk7@LOSOV>?x&fy*g)$O9A0TUWN&ZcThj7osGobi-DF_)5V@LbvqpeY8%=8U| zs4=G;Z_a-~v<^z(<@;6(3XfhUV<#5SVmb2c`5kE>DC{&+TXYiICFwy6|J}@rP&Inl z^eT4yk7w{=@o#pAg%kSk-&}Iw@&J0`+6K>ER$!g@;>hOPaVBo!KU%J|5NsZhr>}){ z;$;tCK%3lQG=n~Y#s@3eeUh@o_NqIPYYar_U^{8FzX++AMqCqULw|pX*qHoRNbk5j zv;Arg&;IHpcFL3o>|wf$X6DplKPG{B*p>s0c6jq{ri&qN+F>TvAQ9QFwnWeKRp8Z$ zRP5lJf=_;W%MLx8OI!TbBKD3Cpv3N6G^AGsb>hw=o-Tl?GnS#f;|0X#=0e)=?rQwe zL62>^c>ui~V|lA4okCgN)kthr4OBsW=%+S~MozTB(#jdMn2I+_eV2#}Bb?B>q%u^; zzkp>P9f7X)wdl&Zk5t?G8Tf^G0NTA@99_sC$JSFlan_eqw0=Py_MCN%(VnLTv#eNj z(C-X7rCY`{6ii~iYY2C0brHb7w;i^x>_aKbUod-&GSD;O?^V$G2S&LV5%l8;nsM$v zl^h;PEM^6<3B?ucewij-e8+ks*jE5J^a|#^y$>jp5nNKn;Q#WIsJV+Yp!cgd;V$$M zEIDR|=aW1fZ|27Pq!U1H2)UhV6M@9H_Axa5H3{l2@gXBdrT8Ny%eJ*)s!s15_Idvd z{QhB2?2okaWRmxAL(aR%CEjdwePlLLu@y%VJuI>8@Igx)m*91&x54Mtp5(CU63(~m z9SNHw$KGq*4x?lDaBqJkpiiAi?0boeP(A50P&uGPp8dN>%o=2nkwg)`6O~WtQwPbv z{abNAItLvqUXfMR&D1imn&{~>AZ_k#d~b#vQ3w%waG6nR+29MHRoTINd+suLcrTfE zcf(w~j-AWtUVQ^xx^r>nuRQ$0OOj}72{Z9#jnHAD1b!(k1cb7| z%oqGBbDSCzImB2^7?P`UTZNw)gn~26Ehk;LO;Vr##L0P@WY3a!%q_uL)G=0wEkbx? z&QK*XIPy<$zgr$8Oj1P8#1kpc>vQ3zw|#iv(gBoVzLK?2nvTAQ?}qE9+!9pwN04)) z(_vLfBzCzcP9z>0;}0YI(Czz&CzE&amOzn2sQDd&@#7bl?Yo6D?=VH7n>H;`R>Y6_Ovy^Iz9SwO?7n@I3O zJzU}Y0u>Y`!>+m&?2o$1M01iO_!G>K@X}N`ZT)i?;iU{OFT<2%^DY)NcLU=OsTM!T zLp*%n5E`tWkEh7jGUr`RL(#J9>~*2DrpP}Ny0?WOONWQ#d>W?8rL*9E(~Wq|y_M{L zt1*0d?*LlYuOwK!UijZ7NX9Fsu7JzUJ>lY2E6F0M0dQ$Z=oWW6OKHrWNAy0Zg74~D z+eOIZjBiC5F ziY??{VLa(>{)}xTYoYCrLh?^N5j$-=$XnldfXzLUMwaAWf$^hLiFD2>O26|4aT79; z_Vs+mU$-0Mk|twfkR-}!>hB=~CqLowT1nU@V-)hky=Q6^h1%s_N&C}T^Y}H z{wCtwH3JHCB3MIw&i~}gt6N+_obr@;O`onXroB>}xPmIQ|04^f z_8NnJgKqq2n**slG=^tmVg5|x6}god^b_EXSjejQn{a~Ph{d57IhO>md6N0*wSLPQ3YNtlqK z%2RG7uoO_)5Q4#WBFK8x@a~uUOYiQX4#Qk|8wm0be2i${0Cb36U>y; zs&w%8?aZA^-`VnKyIHrvSo-AQkCe)Q8fyF>S7#bc)%(72B4jQ@nU&eu<1-x2A%s#P zUz%tZB_%?kStOaq%tVF;QD#CUMMY5}B~6+s4H8m6|F{3M)_!qb?X~xM&U3EkzOVcG z#3vh7e4J-&Gf%z_k1nhUHeJC#{4lbn?})Ckb)~!UhP+vPyuhetSH2KG*~*VE1bcZK zH``ZR4olQX%xI{CN9XarruS4I)=912-)G0Sx!_al94}|2bz;1_*ZT>7=Lui_zw0xc zLo&G9XZbuMg-#!S&SF&_?RU~R+sU`)t~KJX?|0`rsz~!|4=t+wWAxsrX;_UvnFEa7 z-%S}uyT8Uyljs`#t0H{YwY4>!@6~yoPYC|mhznKJ;(NUFce{Ag!y9V-)Z+M1z_jM| z8*TpfA?q35@|f|vj0nD|%X4FV+Nwsm%ByD2(vs@MGxHtu@GoxjJm)%3P7?olb&>Jd zqkG0xGrS?`{B)jXTO7Yp&yc?&{496?*@%E)$I6R(OKi3pp-{JxH_giazlS+lrljQ<6v&&kH&zm>T?2lh~O(x>CuLsZY9NVUi z>$M|m#-9fBR?Or-ZdxD0fAsQ1&C2eF)f!RF#wWLJuW`{hYMiMb&3kfB$>?_bem?hy zGe7+71*5-SGkf2fyS#xdeKm#kEnMZnyH)SbI@Eo=*f4_x)a1XHP~z3zQLf84aMI|3 zVL}Z@XfbzW!P{yylUrNAxZ5~;Ze4Be2{)dHy!#@xJlo(>*ng zlPX3ZS%2QGJHk9EU-7DPcgq@g*4x->Pe;xAwVQdCCTi90@7?+2%)GnF`FF-YH!Ie) z+I#bAZd&r+t0&YQH9x^ie;8l=@jr?`=C_}(BqG6Y%0FWC=J=!9$m~e|uR0B$a}}t4 zyr|GfP`9JTv)iF+M`pgU`HPcvM>0S1o;Pr6HW|<78``ckUb@4nR`Q(_&+VL2P5(x9 zew)^u8i5jLUT~-ozhp-L9pK2+DA+sJ%9=P-=@IMkyMCaX_f+RQFP=S8 zmv`wwjrucg-9E*SHE(N-Yn^{CXN)eSCh}xQ z%BpvejXWR8raE)+!aA9!C#&CoT~)K!?@w)S{}JO)mNTB{ie%%Y3HR!s=|^}053lp~ z<-IrFy2G~i@wF*l;Jleygzr0k)Z0fj?#?H8Ta~~SALS?pNh??`KGR6!adJ3X==*kO}?<^d8NHE z))83C_ZreLk!XmoNzN-XQZwx4E4+Bkn-IEJD=x^X=_D&mvEhKxi^&IKr#d~Mk`!>GyQ-LG84 zKLXlnKf@LLTlGA?%)Cq?hD17i7S=2Y@8bU5++5)@3fTh6all5FPBO0KUt zIqN6Sv2U-5Kzg;YCKRoGHgi4@e=k+@P5)P|_J4ioBOkBQyw#r%H(NBI^B zuX#BQ+l=!r(SA*1a(k5D*mjzw19+Az=XlF|nC1|L-F$AS|%+fS1=+hIV(|?@9x9nWcb0 z$8Q?sL|bA#&lU9HU|CpeD^A<1ZO5XjSKzJ06lg{4fcd7Y!G!TeD0l5THHXuWO1cKw zvxiFx?h00sDi5qHWf{$espg$p(*cYjd&^ALFqbuVuJthi<%gQi0^JQ_m zb}}BHHN!+WQpB#e%Ypm?S8Vdl77ZCGqAtN4P`~aYZB}iCB2fr*e0Uhj?@mWOT4jvw zr!4e0BN^c*abV6!I_|kQpZ3|?h#Dm&8U0&9&|+s1Ube%Mm9JY$*9q0JKZJ(Jmu1>0 z#D<~PnVx_{kD9TG<|wOo^E#X<^Rlm!zQHnl7T>(eMF;KOL5O+-a&DghuUjvoJkBut z_OmSR($hs;Ejv7YN(}0DR*7lYG zK3|{?8r`1Zzd#&Bnumg`F&)6{YaT1UXE9c5zsg+SX~={Xc|rYRAGF6$2=5>5Wkc=) zG@xD#-+jrZQSb$rHN)fS;HYAQql)x(AuD#sD-GQKAP=CXKTMPjLH>a(Gx|v$cW{&N zqp3tjH`)L?YbfEioU7C~_g1u{^DpJ**abLG)#!)L%W?S@XXePy(@?U|70xleNq=zO zNjHb>q9$rL;KPT8*+xwBP-8FsAh8>OiTP?J`YVn%MbuO zip0^!j}U#i=td1HIHIIV0{z&y5xhJZj)w+blJhQngjZCeXwiyW>>+6xjFR@SKVDv< zM%=xaC-uGLv*C>>#3hFejF+Z+c86l8eTFdNvpo2-<~h4Q!vxu_QN}W#gOOFS1BkEn zM4LaVLwUC(*!hzMe@)Y1teGHs6=#a(9ytjaHxu@}ISpf8-J`U7zp(~Cf5Wg_+t8vt z4VZQ>2l89iv%IXYNO83kYtK7_+}Z>h`5Dk)2sT_cYPxV0UKzgcDobL9xC8 z9x!R+6f{0D#`33f;KH~Rc-iVCZB^|{Zz!FOT};jJ&gqYorbz+4E3_8INsm&>@58{K ziV{@$w}}c(G@sFxFHy2?HsyIT0Muqqfa{wasn0_m==wl2{Z=BD+2Xv0da&m;atp5l zb>1XA&{@Xx#!ACIOYVV?I!9`W&;jIkc@F(8KMCG2<-t5-7I{T8RE2^Zitu*FCPW{a z)iWEa4n1Hl#_dDnNh_hVj6G@wrZ#b}C1s|#kfyxvG z^~R&v+Tt?gzNsAQs2&C~+Zt(UsvbqmU5(}M#-o7Q8jQicSz!I0aD2)04wUk(XIHyu zg2s*0jQM}Iux+U<5@%;-zebpN-(tV4@AexVReTL{le-jbkC@VZ}+;OUT}oU z&F&+Ql@-C~&Wd19x(1wVu!FZX*HH%_nj_~4N) zMmlE*wztlR@v0uYJ2(Qxe=|WR?=C=Of+dU?Gemp6jp)yhEU@pBN`U36p!3NqFfDRg-*pj-8 z>ucEt0)3T`mh~K{v9AmX%RI!dhaaHuk7+QtXc>+PPK89tG}3Xn2C~2+T=`cDUt4<` zH&=VZmH-*x7gNT4kc}0(r7wibBQ5dut1V#J*%#=?ZbuX$BEYn% zD51S`*5cLW={Q4o8!d0ThYcDUgAHC;;In%!tWvs<1k62|D;K-5(3U57@peUUy7(sa z^0&q38lvbW8J=|d@m7Oqely)U+(meARHswk7&A#r&e151L*725PSnpIrxJX{4VN7F zK^+Btq+pE*Eq+;p)M>v$xls@GM~m{9!47*`dRrnz8*<5*o0*23lWB#q9Kj!LjD(LmT|Fz6k`miOZ+iQXh@f2o-zf=G zyE-yy!3rr(ymc;hL3@~hW@* z8TJ!V8*M|$U7ttXo`0Izd~-KdT&c`#R8S}XOY@tKhB!^Lb@c}iD>VSrEeJWgW(T%*i17&gHSFzLSH`F9sS8gUtKfd$gG9R_0V`1-o`#7w4DmMbLI0 zfT@m9>bvxHYOz^2wR83aIXcG;#Hrd7N7ec{X<=)?fS?-fVl79u=AYvzp3i|g@(bBW z$8F$Ry$U%_EoGuCQkc9mI$)2uCwc5h59d(m?(ow|b`lmDY^dc}!*iy#l=D>$-pNP_! zagO2iJs_vMg&ZY5F?;u`fw^KC^k%0PpjU6eTqkxCVt;P{)i1FOLnQ$Fkq~B-A(+ef z3E7>WMFu{L0jhSg#P7XX#2K^eY(n}FJC}UI9NS(?{JlMoP15*7_84C!D(1M0e{To+B*bBDqY>e)AV%K#R{$0} z8*#d3rBnO;pXw*wKTj};ruu7eI8~J*OG?IXB~{D330qo{IP`or>G$uqp5G2g`9F5& ztQ2Sv`l=9vK|7+N$sM{Q}`XNYe;3Y6;tdq#x3%Wf&orfdG)Vq1AD2W_0odN ziWjnDQ4g4`ozoyL!yb%Z5T&$&0pr`g8>X9S!iN(rpu6HFQ@Q*qc-d|Q0`J%Y-}EU) zYI1-H99ls?Ke`O&hUSpt5ntJIwJk79b`}{Sa*drMA_NSgi@{5c`@nf-eG5C~gV6^X z%x<4i*5dMEsMV-TD#Z$u+Y__d57wVKy|!{}k8dXBb1sv_JFVdyqkQJTpV`2?q>TD& zxEDIhb79rT0I+p?BG`R>F9?*mPtNu|34-huh?ctxVE|47H|z|-szuwu=(R!CBz!J- zwmOZeJh6h=aHa-?DhdPR{#59yok`p^5GG4LJ_R}_A2UJXR&c;3iR5An_Pvxlm{+Y2 zX2m}MT3>3JT+*Fr-B1c_`UZf3#sGUjCxW$G_KuO?nhib|+K_X6bD7|r05IG8GIaA5 zA&=}4C7$}ofn$TE#H@Wy%*8xUFbIa|NR?keK`#;5{>>w_y~MzohFc&lq?z>@xQwpZ zWK+SRvOwZ%DD^3|0m(WCWW3$fznj)=0$gN>qH zpmN|V+63dNnm~w}V&*d64_*b@r$q7B*Ky!t>Nd*yMl|a+JVWr?^%s_HologIT>*Vl zd~C-#$W}zy!wYslSn2o}=vqI4I&LjR0pFUz^m8B7$gu?aix;7Iat*7~9E?P+6X@Hf zG$g#W59p2v0-MGRkkjDLDl}~e(^lzdY}Ghid8HC@Volh&e?G9GA~(?X9U8#({2`ne z(8-Eav;d*S(eO!xH8c?qK@Fd(nc>wk?B(@a;9{8osB{;i@sdU0_L35*0pn;|rJnpQyb&7ro~7)VOXxbxWLAv0z-?DA!Z%-o*a}rW@L}nB(lJ^S zd7A0~?#33TwBSCo>VgYuX*Ho#j*Ua9`or*|c^jnGX~D$s=j8mwt)O=54B+oqq<+0x z%qZNELtmZSXz?|JKqf$%%7598dZ$X!x`0dQ#3nsp^iB$)bT6d-@im>TX!2&9&6 z^gsjR>FC_D63Cy^%4Ux?v9WpYVR+36w3f3Gm0Eg$%HKa}*(PhqYw2T7jzmEmV*y8) zMU1#rBlMkMP}}lK`s=q!v^=bX5EjmbMGu>(_+xu%#hQ2Mf?*G>`@)IR5B@=m-TOu; zD)CXvt(ghQV>F<3M6jX2CU*UGVMbu@c4mD@8{F9}kG9NGgMLnm%&5y!^y9f6o*QY3N2i3xlLA)9d;Uh}0L4V1f--hpL*2};MAz;U;Dd7{*c~HE^=;AMW|)g%Ma6t{`g6R*fC1L5#ueKq+}Zvp&k5`s6DTeIy4@52+)g5dkgXsGHQhI^K-K#^4a#L@tYcW0eu&bq!yr&x(;d+_YnW2BiC z509RUKz7UVt^3rVJ z%nNssSc5{68xgD7%`TFfgwOt3Lvo=FeL-*1bd^yW1c)tpKR$xMKez9Due zQikFWe4w+mEEB!wK3aUr0jC;GF!FMCFw6EOsxA^`3WG#&`|sb>rDx`_ODvSq7Ii=s zk5#}&y?nSb{sIhtB+TXjIk4b-59zi^7h3P4LF$`NV9$)6ZvUu^)L*ZrVzP8lQKlxk zA9N9Zn(7AQH9D;6;`PkWsyE=fpcFN296&z)6AvFMBK9~P3pNOdQ+w`l@XHO|D1Chc zicOYdBlDlZwcG#{(K!ooPw#>1si&Bqeb?b=a}-)MZxUJ_X<_XWKZ5&0)zH7K7&*kb zppd>8kn1kU+?+fC3MdCUt;Y}gCd`Ln%BBpsm_ zSawhzX$&obD|*%8pj`@bIkOjz=|;eP54Qrx8y_GiUK)r;&4L!B1wAT*fY+jESnhF_ z{S@W~JT@ty*Yh)AdzUJ1xFQCAO&$WS4M8aBPZ%qCQVLnm^P+4j2iYv`DR%XiPptRb zFK}OlJ^d}%iZVX12B=3}fWFKU09O!T?&4wSkyiuHu1}zXXBE?KrAg>Oi!s`w)Iw(M z?q?o*UuSs(A=C^!fQh|w5k652rWB_PapA(x@NDx_Qrt?0`lZqddiY}?X8A!}TNg$D znlA=tty7>U1D!D~FNT5w3ZTQ<87-x51l78xq5IV*)HDB;cp#^q(P`wtpg~>e?Jt7~ zolBH_!2%qwpNd1QC9r;VHXuD7GgUGEs6=lQ+VZ)QdTkrPbgOW&*Xwh%r9&KSuUbvn z7|!ISpIVFU2A`sqm-m6TD@tt_v z*>HH}!v*Hjjw&eEdXiC+7l8|%MRDrn3mC7Hh`n3|p_KUqyDZQF4_YRGBTjPM+H(!S zzPJVa{L6=x1*Jfca>xDc4{7)MBzE+%FYJUjPy~Mg_PA^T+SQMs$A+(9)npTGGdCZG z+eu?tr=6JYL-fk2ORPnG9Mmq70!uoBp`}4Gie0*Z_RH7Bt)sr`WsM)4GK>&%B@@o(g5pj)runrQ(|E3wQ7#XoT2y5~-E<02Gf`xevbaETtqQqf zbOAWK%#+h6+`#JW%m(z{H`M!W`P7vxOdTtDPR((}ze6P!_fy>}xP$sxPLK z4_*rq^Y$MFt7hj=wU^I8xgSy_Z-E}82Flr`8z<Z@`STX)o)M%6hPCm@KD%E#&cmMdfJ?h*S-tECGOAI)QlsjpK}_!wZ@^^Llx-dMi!c{ zjALr!HlP?~d35qWVRTRS7?Maa0{2IJT>ivAslrP$BsV8#bU?xJDYng4wX_L%wuj<^m+lTf9R)WK$x#-#UzpV965v+C65dHVY7N=@1h1QZPKoXrof_!Z-WW5uX zywJseNEzhbR)**9Y6Dla3fP8U!C1qT3m0?5xH^SL!BQg*d=Qudo`&au1QAbs(V&Xy z8okZT%U*z{+`5ph=>nX;#sd5rsX@1xH}IZHH~n0QgsW?na9vtB7V_fKf3?h6x0Z!a zq;n}d7O)J?z!Q=5gHn3>MlgPUrvleq(qeg38mvzd$HQH>U~ZEJH%ix&xxVND%+XJz z54jFuvGen>neZA^`a=zYsc4YD<~HJ(?4e8E`QlI8qCm{p9r(`uFTD9-8UApt^G_UOeQodywh04MJW+S}5y77_v$h!le2)u)Fj-lGKTu>1F%DZ3m3GsfT)K z3&h|e<7%dKZ3WD=OXP+a3xbt>U+AwdgJ7u02C5w0LJ!98Q;zTy8oBJmRq~4m&oz&r z-*)=IFnku$7Ht1HYY+sVyn(&xf=}h6SWoW_P~wjq+nOMB;2(98LRVm3^1+_$X6>NI&Y!E_8W!* zwXfpf^q4vNS)fD(JTpLBZ=XVo3KyfZ?M)zjRWtMIWGTc3*I=f}82Rl9&9pEEsKsp| z=+{aCq3`aHw`Xm|`5&s$r*IB>5XP&H11QxV9I_}p9YofHUPmes13FWi5jvqvi1-FB4 zt9MAYGM)9B3IRi2S@5{Q7Wn73G0Hdl$yA)pV(KIHp{i3NjH&N{=My%vsm{4Dy!IXF z%D6)X6_^8+u|tSb^+7gu8kFb97tG78yWw7(%C!B`0Ud=in&VRfecIp-ii=J~%1K|D zN6{RRw@nN^k2ZluSsi$B@O%2rfok}qVL9#Kv=3KDEJ45jokAz4&%xn@iy+rS5{b#a zq7)O1u~p+D!1*bH_MeXgD_+xQ8+qZh*qmkhvk#2^%%PDF>F zXw$)Cd`7Y)7$>|d01l=?u)+8u728_K-L-WllXj9HeO2nV&^L)qB)%auRHVzz3eGNhKK!Od0;r(KcmIG49>u8b0;)D zm5H*u3)oh+6is>mL!E~Gu;T z;(YxPaMJ%C>e_9JB)mrG>Tp@56II)V@#1>*@tMC21NIJbX#b6|%-28Z_KCY64?= zU7(wN7}z~N45r_tQhh)8DBXRS*^?yW7zVOoz(K#!?W33Pvat~2D?aJKXO-r#%ViC$d9tM<-N}~-f z49>N$gk_QOa7f_?r73HQH@?Wg2J1effhi>*X>B!w$cVxsMdnD+NesEoea5~#ZAlw- zheL~ADKz?67kb!VLM>~gn4>Q5QM&#Jyl=IaUC@hh`o(Fg&%FTYNEK1nXjAy1N*tFe zjRJ+YG~JQEl^y1kkOKdF5uJ6F6pqmVX2+`WxRD-pa#I()Yq1ERbL-HwsT6LL5kTdU z&Ftogt4Q0x1bBT3L(8m_*n{uCBF&=9$ntzUQdZ~$WgX2kwXQ2OIzSZQeLd_Pl~?HG z@m{E38;x!JO4!yT&aA$4G^%?b!z_&|#+PpHVPDP*V*@;I!vCU|!Jb_rSn6*-GxI8_ zpQ(n>XXAT#arY;LvK?9cNCiDF=D}SDEoiZ@`!FuQ78zT)p>>CIDNp_FOhz|`$9DvS zTHV*c?35l#`xnB@fHE<5UWi{yo@Iu&n!xvQ9cZCxHCc71mafi4oE1au#O(=pazWq_ z%?1lSR*2?MJx5@m-K=p**R zP^Hly^6&CMw{R9`v~nec(Q~PyhdVej;^NemH^;%Ak!WI9+;;Z2#1EP8yVL( zN5S}DC%Jthl})HhCufblfLp??z`U70X8s8gRy|&hEZHr>`YC0RpXPc)5zTgb8|(+` zAMRu2qOSs*x)gFc)gLf>27>D$y@ZWI#kFjMRN4pZ`K_G>JB=>TAGW=R zUJ0@AiLnTb5Z}p$O8B!OerLdeT6yN<%0rB##UT6_GaGKLI08GJEtyxnL8NfdT_`Lw z%51q2gF1~bFna!o9kbdE1QqwNrQO!BrXh#k@x_jrI@Jmm@0tK-HU>a}UlQPPnkCRK zT@GjRe#oE585olRpy0PUTBTh^F26QGd{eyxA_5C&pF4GQWQrnij|*l_%gjebvr3`S zKp(YJ@Gf)VrV+dud=;FE&BcBVrSw5693J?*mv$)6z;5$@!Y&^^V%qOR_p_UU!P#8s zG5CWLwz9y+C8FT1+%VLY;6n9gHQe`m0gYY(Tr!rAmn2Og^UjMf!Sn(9L&5`wx=^xkKH72iJJ@%{lWno~K)KIO!x`y@ zjCH@DtjDp8Qv6-C<7xxi)>i|6z8=7d^9|_BD?-e=0IA866Nku2MF z2Rq=eJ44`)I*Y_brDz9oIVPVfg6m>wuvGak$j~vw|JE{e%!D%@x}S?fPK}}KzGtAV z$thMP!~zvqRiF;;YTA9Eit&2tj5(7J*si0#Q1|Bx>R(qDH&3q}|E<`8FKyWc9d{CF z(;7eg#Jvk0-+cv^+%RI&TRAw~p$1zf<>50ggFu-fMw^3ZFI_mA+7fr z#q>1v=5raO(;QIJjvweSw}gG0_Y>KjnvcDMZi91&C-D_QLt4pw4xTru%e=8sgl`Hp zxP3P|K^r%KuJj*er}BI#nXy~whFK(?H*Yrj*QUi4{gww*$5}Y5I|;b>Tt(+^zr%Mj z@1j#*xzy31V*i^&zD{MkRsR6)s#{sD2 z?}q)h7N9+76c@MyI5$2AbkUXA>_-o150vMsJJf+)XV${Fw0`L890vV8L$Ie)DLa^u z$SyCq3%`Y98ac@=SO{SQD<*1&|}R<9uS8Yq!<#J!R$kq$Be3dHI*o0QLs@v4%l1alc6G!6Qixr%nU)9XFm6YKh(fMTkGzBUy zc`|Mehv-lHN@zK2K^Bh70spum_Lb2=V(+VXMt|fjvEbNt=22Q1z4O6A=3Z9@L&?ao zTZ>AVw8b-Z#;YPsJZ|9Z>(!z|Y&x0Lnj0+rP!!Aw8KyM@MTur<1E4`ElbzG=fp4xc zF{}A7alE2}23vjT!Z(_Xila6awk?ekZtWpCjf0e75zRJqeV~ZH&l&Z&GCBup59UaUUMf@3X;I4;8ya&8WkqYD}jHCqKQU}8 z7y`Bx|2V{!k96k6JJf(@3|Q4v$}zPPqWLE-0AInYAm?QkGhE$4hQHYelxtc^dXA&v z36E6j(DCI!qCcLP^0uOzNkh(%LnK(;A_V&l)Yz8+Nv!ex=gjsCra(nspK0C_NEgv( zIX*#?fXZ14?k45ZhBC6$;cr8v!i^fX&-@B=SW}VOVje_xHJfsbZ}>6Ihoo8ZxF}Ol zdJMG9dd0~KJ_`i&5Vee+O$L;A0)K0Bj$G7Cye2+Kl&@7KU+hYyT}3*W(pNQ{^~rXG zk$ne8Yfl_&Y42dTclbK_K1v9-&-l7F&ON}46}(}-^bWD#3$C-bw3 z<4859^*Y6fQhJgV72*>%((%x6nJ8H-JwubSon}4j_kj<9X0SyJRcn;d*dQen(Ij2U4Mx^Vqp%p$IKx*-mK=xoVEim{?nndW~ots zUN$l*3seaeG6YD5cCvCWM>x^tFQ^0Yh&EZ`1C<{kJZim`W~KJPTc+7m>AmYn$ubu0 z<8PnYW8&C(39?j#P9)?AbyA@f8A>g<53GGvP?*LtG`pVz3eSIsJiAQP>7EQlU-{#v*@|@TK3~+gWGO$Fq90R5_~@W8PsP`dvFoKQIk6fQ;p zNykC#5q$;;{r(BJy+4CQl`NRyyc@{pcs={s$ryhL&4PbD*WuZT_F$J}Jg^=}M3X*N zpzMzyT-9cW3v#Al?tkLw-gO$x-&0BH9L~X~jaET7$q!g!x&yq}eG2NiuLjC>V+jq44dQGW?4sTqbVUfRzX6}|(_=rs7v{umZl(xQpI zYSi3sYhYk(C95G%0<|H1c<;DB{puGFpByU1|9RxmgJDA8&rI!py!i>WAvGUfcTuMd z2c^MNw^B+zLI%&>QcaC~Jf20jwIc<6+;;$8$q*uCr%lic+qsPUG9Ed;BZSu0EP?x(6XdU&BH*9Z zP1;Qm=uzh&S~?SFULdsvMt)d@QUX7toiY8OX>=j{v2ubOS+O3AxAh}$UIBYSV}iYR zkfC=uFlg7FgeJ{qa(Nlxo#sI_E+sPKf4qWelE&_lmSh&K^k%lLO{S&JRii)t zimd+bq#Xb~2HvP8lO5Hg5*nXJg5q+WS$$ z>0zqGu8C|gXZ#VDodh^Fl1Sg2+|S` zZC3c}Q7JHNRttkO8JME@8u{H5rBhVa;VZk7u=B9J=E!^M zh*ctU3>o2yxx1jseG7Pmj;DTokKhi^^m6@@)iGC3558-C0EwH5_+QE}+L37q(+$5c z3x$>O=Q*C(+OYu-GjqW!VPPDtWQo&e`V5;b_oKlZS7Bjq1oQ4uC=z)nh*oDiqRB(I zP%C>M{McK7WNiMRuh&fA5v4}l-DXGUFYiW;MxBh{J3ILBjVc#7$-{qlmeT*yePD8_ zHf8(w6iP0(rB8d;z)SZZVh8C8uv4WN?pk~R%nqZ_uQxw%v1SwcuAe#6`uk04)&@WlRDO!{$s(Iog=eUdq> zB7nu`6(aB6UFey&AUDI&GMqe#{dp8^&{$kH{^lt~-4YOg@umyBE^B$bkdx&kq7P7Z) zUt`>?m!XA^jj_Mb9;~`62rSK(#F1Yxa$>BQr^|%Uzp`>1Eg{3L-&{Z|R=r^t$Cks= zHG2VA`5xY^Hp7Z5+UQIF-r={>v$;*rMZnFk;%K?FD}FDS4u9m|z<;$g=zrsqFd(do z@>%JKPyCujui+rnyOqy&|Gf#W4VI&KK#%5~zJ`9aEoAuBPH^4E+Yq{+M&&Zy)cMXZ zToCjP9}9>_BlX*9UgQz>&W>X!{=+Uj=qpZN=_sdOsq^sH5f+}mBmozDI8n2=zU3~T z@pai$%b^d?Dk-lcX-s6)Hx%I?i5i5x!IiHM>3`y15gM(>C2zt17&`BNtllt=+hk@% zh$tD)Irn|;^;ks_DwRTMSna(uRmzTxkO-m7LMRPNk)rW!qEynLol2CpzRy2!emU!Y zU7z>oeTldApN5b2yrr)DA22JkS!BUNBO2iGo^abP!F^#Wv|7UMHGByp*(XoX^=mV* z)7?6{;HMFjIq?o3sO(^ttIolSU;n7X=2I~2)@jnT(Nk>YpNMbI+zmrZMv-5~Uh*5Q z{7LD;Y!J60j3ytJ6`Rek1*S?owc{*t#^F|+q&`Y~XM!WeIe}#9z!z$>10ofL4eWtn zgf`Zfvd_k|=~BmG;)$`t$%A=!QP4eSTB4bYKhBq@VKUd)g}?S_iRo6Vb^J40d8!oM z|8$C-D7Znc8QP08=0y=vxgKpZJBU&DE0|q)n~Aoy0o`u|PP(&+4wucK{W2Sv_0DWG zbK^t$K+9V)M>+*vR*s@O4?ZAY_B^C1rXFzLicwH|o->v|bPl(<^%9NX59FosaiP>m ziuqo57b~Bii);3rCsPLRF|VE{#O7x=OZ2)8&C`_W9p8!Y_=&yD+WHAqZr@46)jY_t z(EViW$1urRa4d9DjbXDAKO*O(jYQ=B2fIB*Oiob=+MY;dLnH67H9jlY)5-xnATR0m zOg=@88b>g>PlsUH#CGWU*q=E+N++EGGW00l2pmSWh?7IpS*P@N=Fm0_A3VPgcm0^b z8v9yl+_xwUbXEv&XBe`kVRu+^l9JeTU^|*(s>o&HFU;q2ElHN0)da%TIelGZ3Ru&V0ItCUvbue& zXG9-q8F!MYb#K5E&4%HC8CO{1`~S%K<>q4BtLsVipgw)mw-lQ^o`jdDH!~92Cj2RU zEOc9D&^eRMnfEDsCVG1kZ~m&x{)PW0UJGOdr7J_}vJee+HLQ;{-3^BW*-dcIcLUO6 zs*B^x4wC-rBNSw$35q|9*sn#3;>b@I@SxXCQqCgSv+vblW5*V{%~@G6BG2$Aa0eu& z*|31cdDv2qmz#D_bH#?P|C0{>#D>u_ z!{uxN$)mU1AdzgHLB4^}bfjq+QS9sh+|AA4e%gLI%QsFKaF-(DZ#tlc$cbaG*|6b* z(bRcNEuLg#MgB}1&bC}FBZ+$+;ajh!!+#;VOk?j3cDgB#isv|^S2s(L=GI{LD9f1| zrbUpEX1QoUxluS=^qMG{NwVFn&E$yjJvwK3KGb&ZrVFbhNO+tc4mUGl=T^N3CVW11 z5RBo>wbMw%s+V+x<{`YQ^ExO>I}azmxX(N5Yf+|q0dz0UMjv~VSjCiP1W^tdR<{sK zN%EKMjap1mF^CSZ8|YZXVVaY!Og`49(sQ+4=)&u4F2eU_8o+k@pp--zLf<{O##4Xq$ByZeKp$hAsW9a zILZgCct)e{)zJMTMbz@mLF~g7li1^D=^Tp}`0kO{Smn3}Ot|=iR=#{jpN6>+W7Blh zwIW>Dxa|PF_wXm#zD<{W+Nuryv+4tjMuw2QzfO1#K81$|%%mq)oB%c>7U9r{-Nj)*2G%zcxa*&cvgCwOx?4JJSvr8mA@WxYkaTrQ`buP+=N45y<$8K zU3wbKzU|8wDtsh;O)*3?tBwTD@If~>OyD<<+=V9^dXj>KdSW{Ek#KBYDSpZmGS726 zST*lAmb=hI_SfstbJ3^yzPXP%i@JFvV4Vy&emhanOwJ*`50YSuRSAuZP9UMZqj{p9 zgED{ml7K^g*f07hyB6OKZ(Xyd7bf__Qojrq96d-ftVYm7xr($kLLHCw?j&jhU%|i$ zQ--^uu->d|SntUw;`msN4ZP8SBc}SX!H8*+h2fr5>1YvIe_j(+udXC^n-|ib`-`Ao zt{>RmJDTM-N8wEk@?>Y!18{nLkl3|o0lQvxfcfuEK_x+QbZP^~uI6u`dCPZ`Z4zeW zYfK;g*ci_$p9C`*`QegIIG~dTX$hmp+ zQe-4*(HKJQtTdVQ5RBLV*T7t!%EQ#ydsI@4EuCxIIms{kQV~IdEYX^I7IcE)E|Mww%wSo9n_*c26CCT%^U!zbnxt7P8`Jxn)@Y zRfJIF=gS%&@53G@+3fL;Aly(Ch$m%dW4s{-e_9yGb_7METUFuE|E3%re^rg;bX=fc zsts^a`BI9=UGm>RC;XlD7n2!tnI36l>T||J^Hn#53;s{>X18W^_RtDaJf(%s6uc!_ zZ7y@(636nRSHoQ;vq+fl2o`u{sj$kak@m%iVEbuZvUP?wpO8Bw>TNObx&9YJI-w9@-67BDUU7EMWzJimAf`LQ~XJ*ZQKe|*{~d_#r!yJ2LH+!7Y)bp^fA zP=z|<6eaxOPyXk?I(j%_DEMlv1+9C^*zxu2knPrQB-yDLJ)O^}U(z;abv}wt%2gs< z{dKB+NSFLKHi8CSc#F!G=rM!0>2&v)E7Z#>SHiybp}=hkNz5?#GayZyNlZ=pbeGHc$9{q{N~ta6=1 z4y~L*KVH5==S%X)#rl`Yr62Fft#MnRrBy1qFCRryWUN@XtTwE{hCs;PLV*85ytZvS z{u8c2uRKR^Nc#kK%fp;4^;sr7FOvNC6xyk=dm9Nm70LWLZK#-%O8ou5f<05Z=(7dK z>5f^G>Gsc#fiGA&Yo_?bY6~VWt;Lqt zY{d;TRLRSVEPCa89ley0fT!qw7n0LX5ouOK3mP-o;Zvj0OpzRuZw#g#r_1QAnphgy zw~@@UmqzoB5-NB%V+S>D+V>XG{AqERZ+J+w3ZBuT{BaU?brT!&OB%NPi=<}U95|Lzu8MqMJ&Ni z=EWpK7qa7WL+A(HU$k8k>Nf{nLD$>&Fz1$Z@>Mt{VKc>~cOaY$E47r&4KE0pA;TGp zxCq|azY}U@eW=UKleEEdH_aEV!S{A-pubMPCMv2y(Azj4kN&fW8p|$W4Y&26!hbSA z-%grLygpBe(9OhB9?fLqvRy)&$2KL7d8n!A1$DZg0&Oxv ziOr}$uvKLb{kDhT@Hbn??@TMQ<*6Eqj#eOn6aVA;@7y9+U;ae*PZoBWdrR zf#$4lhR$!)>6Q=9*fs73ij2)AGiPg(dpi*8dh-j(Z%IR+51P}2j35|tMxF%U{towm zQ^M)7mxS}`!Kh&5d>Z(&R3M+d!Pc$`*M^=ZzJO+a+NgH%CXsl(45{|M z%1N)-#ci4&Dg4cnBCj?JTw&m9y!81Ur2M8BRhpRyD?Go6iiXw-#mnP`yn|Z&6NxSC z{>z6L0LY)1+Ae%pO*q4FOmdsHVB)j}hnIvyhch}@&e2X1qxc}WazFCEbe`M4vkO02 zt4uQ1>0!fJPVnnwcYfY+E9|{+8+t4gkHx z#Xo1bAjn=&N_rsR#);T&T^y2~T*MjpccJ+jah(4v0Pg$R3RY+?>J087b^-r{h=xc` zA$S>XDS0SzmdqF9XJv4;LM-=Cr&{O@P88y8BXDKbPUtGC<1QDTfhF#mxNgx0p}%hx zH?ns%TDZ>vl<$k+6Bn4luj{vyKtEG*iY9Y*N1CDOwqQY7qmWzv!x|+>z6Bl!u5tH! z4q{_(Z#*e@Be!OaESl87<{x z>k)Ty;K*pY=(Rc2o2SW?l$Q&cC2NTJp8zuNh7lY2^$svP@5{#e)Uw@mKCI7QLD;&y zRML4`NjFJ4l=2m}FzvTGDpH-v`s%dEo+m|Q#_1HGTvH@gzqx@;%`2gEfeZR+s6wAs zD6;rSNr$-YGWmJd1P=Xtjs~wNVO>uzvxoXqk(Ts5I(2_FBXa}EktwD0UraF>T@(Nn zMpOFZ?s#gp>7{M31Ohf;2~)!A1xkt>oY325J}<+FJR|&J>lzx}=|DZbFQL6hE|Huc zfh?RtJppv|nGX7|e-c}v?}EBN^iai~p@iMO4{={LfkDpfz|_f1YppG89`YX&uB70m zZB6Kv-3qcIEruT6Cyo3XN3)u3D&pzk>(O%KG;%QCkGWc|Bo*@xP@Lon&h(Vwv9t5} z6_e%YtNl(ibI_mM(NlxQ{6FsgA{XLQp%3c4B)M1p8(8Qvgf!&s!!>jyiHo?-hZH8$ z#S`=B-D{J{p(&Y2Ygx1~NA@7u-+qw(TVV?J*VXcFaYod$kRuh>Mxe(A<9VAA`D{hI zD!ue9m#h!XM_o${LA%ijVq-LxN+f_lanmwkQ}ze4t;Sg5+Zw^XpWDM<;xlQ~VI%tP ztSVXAUrwG%zVVk6mJ99!m|U19OTg|KL~7VA5`Sn9Ua~Krq@50=VRKUO5YJc|wKyJZ zwyPq|Ug0qFNCY0H6v}3tn2lQAe+FCk=@HBM&D`eavUpTY1wUa*BJOKnE?FWdjW!O9 zAr3DAiuGjZzwwq#x-6c||DZ>#$`$G8C0WpXDx||U^#dcXlXOjOB>C2SpZ=M7SxBE> zfrj)c(1Ojskn`L<|{b#BqJH@y^ zVKt2$G9CDY+3~+-L+mKkf;^s|KvS|y@!UPdl7I0Ax+zJTEtky#$3*?8E;);StWG4s zjmF~afW3ky8BImAs^Hr4FYMfZ#gfj*Rl1{Cn*Pe4N=7H8(89yJ;b@a*Z0xi&JbRV} z^?e&pVixUVS%q8SPwQGXe{i%oW>*|LeOHRIF%77ay`zup%vt`=i%=)&q9BfGVSSIr zk;Wt$`ZiA=PU};!DgLS~-d&f(cFwIL^(`SZyzVg5Fc!0{@p5#(@f%^?rc9Sh3a`*m?^WVPkMV3%{a<44zMA2ly`-_ynhi?M`+rN4 zS$dNc)6RU&;!}^1y_yTKhwFFh#93oiUjv#ETfx$GUeWf2!^F7}8_Be7`|zx;QR1k~ zT9R9nD|Wclh4)XqPttd4(*7OQ#C2N>>%M;&HR*Mul_`?mlMZ1P{xM8ZU7l>%V#2hK zZKG#zxd=&Z&q<)_MmFk%o;c>n6&OHX3a@@*+MRq5n-|m(R@h0^VfZRb&&Me zdEn}nI2uzRjnmwp;5$JoNn{$cwBLf9zC^|$*Jw6ea*f2zL6A?ROF}<2%syL zrUG-(dAKRy67A9$f#q(Pk;`iY(EQg?EWdgJvpW+h=0Qtu^a1NF(= zS}UP%tunjU9?ORA_hu95LR2}so?KYIg`H-BRJ!>E`RMlr=lZG%{}n1xm*i|RMtd{K z`cO!%xpX0NYzH+nUrT4tiog>C7O=%fWns+fN*XtK6SC=ZiCahxv!kc*oP{DdsyG2f zyEOCa1CY)y9}2EJ6chbT z`6_ivy^G#W`A1DU_fr3eiR>`U#w`ywqYg<9H};hea?z~9vV%tK^{+yrde?+`kw0kW z%>ZQVYs9kFhT%05Ct%NwNW7(=BXVB_!da%HLMd}L&vl{D4u+$#`oSb~v@10l@{Y<% znM+(C)2Kp01G#=M0RD5mO3rjoq%YfV(wcP-!8nsPIAz30GGY3A6gG5E3JDZ z`HvpUgnL(GdKny@Cv&0HXA5H&*ah z6bxqaWSWh>(7WG(FSAqz?#RDzP)i+M$c*C7NZ%kclYSEC@&Wuybrq$4gcG;`Y8AMlLEs;o1dD`fpDYUv~bD(7kRFQTy)`-adLOQk0Gm zHsUj_8z{qnJmQXU%}j&Jcb8PLI;&f66a+D zm)IX<{;BuLftVzc)j2>O`WX^U4R!ihO%}fEwP)FL^wHb2UD!vfig-R7!CqLj0@ryn z*-7s_7Pjs_4gd546BZ|Y&R#;fscv-cz#uqWab39l)s4l4d_iSRD~a`!98mc(K^*yD z1M^*I%HkJp$4X}fYLj5fa%Zbi3$-?)5HuSau6j;0qN>=PHIeMY{4+>(aw?e|9Lo$e zN6|Q;mIgOu<3NKfAy1}@s;U~%xKX*}K-n`oNg+;34K;AnSD*UFP)bue4u9g%3(&6yRQZXHN z-Wl&0H<`xEx3YI{FH)URr4U@LpljuRqY&9`v=FG^q5yMNVm3(HKCEUW(uL^mtORe5 zxzVGR&BCwc{us6BvgSr78YTaT?U*;4IGrAW^=D3DiK)tH`#oLpUH#eksk0Kn-I4h2 zoR3(+ERNkW>JhlgNTdd;N!6rIDsViTwLBWx_(f9DK1}StK8Ig7oFGqbtz$)H9qZ)M5Z3FVT_9E<13L!E|Nq`omQoDK5_-|MhQ5f+`sCzk* zsx84$9w05Nq>C*a#R(hL( z9xWxYF_LGUq0eYup$hi?Z!`%#8b(vVK^k3j7MIs`3cKbc5+$jvv}WQ&_T)niQu6%*Rg&33HkB%{ z@^KeHXM#7adlf0zJ{ltF`BgF3XVS2}XQ{;ZYedfe&gI8#647VK3^c4S#>%hsSx7*I z5HnDZ$yhO}ZOJCCAd!DO$F)hHDCIRskM9ts?RP;q zg;(Mkx$e|!l^9=*h$X{LyrKJ>uaY^_+bLgBh;G@G?$GP=x;oypC{Z#LKy zvjvT)diN+ae@i``V-O^0yvqlx*SgTmogUOPuZ?JZy@R!-H0a~ZUlO;>A5gj69#>i- z8e=eqm84w<7OFq^o63Lj!#23bl@FbrR1-bEGut2Otug+@?PQ{UbR||ePmN*7!tK? zptf6m>4mTPl3uAP*)ytHs9xzoj#_vKlkaUnA?qXPI=h!7;>9Eu^n>A=%yG!_csb3u zd_&0FpTrctW`X5HU!b+FS!7zNHQ8GInf`TS$mzKm`dG3aFFD1ictHl8y1fzE&8Q)< zhYk>@QcwMb2DbV&( zXG1%5LWGFX*hIRvVhCrkNEPyfi>#DqwR3P(qUDF1m%vZQ?R?Vfy}YjUM~?59#@Tos z;rmS|TefUT0A3eIiascGaS0zcapgM$!Q&%NmMY;9AUL!Xl--#CvUfe^wwh*GyF_i} zb%j>`Ojm~G1+^rrxnK8yS;loD{JM{Omhi)3oN^W1?_Uqz9*PHFo2PN^(>(Z92jjrH zrcSwY6C@aT{OXbHZ?)toYcw+Cif%3an62Xh`W1$F0XS z9^htL%>?5wm+_iTim*;`DF^>c5JgFy1&X3CqUL?Z(5|~v^!E504qtx9<#g}kLXMpQ z!l`4{;}h>#e>GF#3np5CG4d9m`-V1G^z=Kwz$l6zYoTfNZ=j2#>GQ$5WzT{8^=M1m zZ=AJh{SQt77>eA|pL4TATlpZjpO$qpFTjU0gCOuxok;J^Rjwv@BiP_)OCEnHXXhQ) zL96;QVzcC5Vrj$9(ix*2$dsxO;cUNzb(nsWzS8&&)~&iLzzbh#N|FINGdqHO z5ORQ8ZGc$KFM?Hc@vMFK9b6-8MZIFJm}EN+71!S(({4%5cH6X=jBhME)1S@Otmho1CY|=Lf~@t>r)F*ksmI%8xJ~UDHJ(3&RlPPL zYkVZ#7ex&ixU`AxlJF>J(#Dc^o0P=QH9D{dUkp=r^x_E;j`b&hh@P991WF#Zljb!~ zS-Sp6$}o3nG7eVhX=TrVPjBZjl{7E{UMHFxO8b31TQe z%WK@Go=pU_ll(ZQONQBdu%iFW(EeXWNN4?M>T)B4auJ1eGpfdgM!D2!yD`1VqVYZZvJ zj2at<;|0;qbLdFnKX9w<6w=Mkwl<&tNw6Qf5y`6Oqx!M7d}cS#ZOk2yx+PD#&e&!_ z|JPVSzSlwEQ`_LTwd28ugYqH+|1`X2`)o9~B@Q&eFC6P)JaPZbFP3<z7)aOfn?He_s?<7N5qUw!NG(cY(jr>xkAox+vsCx$xYOpTH{m zA+S0ni*VQroYP9-{rX$z%MZyc`(d=OQ{^E#^jwxd?f;lt_4_j(d;bZ4vvLl+2tT1N z)9s>b!KvUCHN_WbI4TGaMY)QVqOQ~{XyJn<>vyV(sDJx){Qmc8PO@5x8>fkFk|d!(bx+dzwO9tVRO(0QA&L#Qo}L)m#q)b@v0_l)0zvFzGT2P*{Nt^!aT0m zCl&bBR*8Tp4u8sz1}mQ2L;Z_&`S;DCeB8YREO%2~aFVX)+7wTtr>krD-R_5=mx%$_ z0x_2o`W(4GjN|OGKR~4)X}})V^BXS}^B#&(ywm!H*rc!&YBY9=rq}PozMmybqeUZ3 z+@Xy=G@TL@$E%?QT%suSpRX`$Pc)dNXhQr_1kNG#kM*MSgm);`khoWu0+S0j_z4c{ zpyPEvRQ~jq@Z4$**K)*47}mWHUsP3qGcDAh^6Tl~yl1drU^|0rPo~1XlTYB7fCF$x zZzFeF@rB4vyB)65@3D5NoWf?3lIK6m_8>vQL3fscpOg%e*kaO-L;tk#<*pl0nHcx87GGTtQO z68Bm2kBU-+1v_IvYeP9_w5|YrI`fBb+7KnQsyL&wNA7|@S0@Nb*GED3j3R!+-^Ea6 zgDS6kX9j;o{w?}3r-oa0nedrawrIhu>7tyeP5i`l^M!(rse=E(6e$15#CpEbYC-9t z7WX_}PuOl)Ae7q3a{QWO;Ln?AxI5sa<&kIQyvDt&mfi;z@HaKBh4SN0q6b^93waOA zMQQWapcSJiGE}q#=B{;oS5G0FVr0P0R@VXV#%vZjygw`KS+f(IS}E9`{Q%Rdn>28Z3`U;95Uk0y;KEa9Fi8e&e2tbllmvYRez3y1IwKF!Z-6ouT9KBnH&JB&6g~{pIu;` z)%+1?99H7`e13AhRrZ$c1J=TX2u{LY_5dMYpMRSs2SUkjP%-i^Z|sBkrr}Z6#&SAv z!{4#+t)COzNwP#+B;K;{UOAW`6%K@~31HREWG=OAi0JC3Bw+G$KCh~m!%qmy2IadI zMTQ5G!G*a8!N*&txCb|4;F0SuE#H310R_X>S*6?>%Ils#2Ndb};5}D2PtN&`;5W4{D2$^q2HOh{sw{ulz1fPrVaNzCRK)>_~+kJI``a z+3!T3sELG&wB_b#UxZFxaokUvYHqlq4A=_K@lQ{hLD$qpqSI|dMTI9C`0$fiz)A5W zcy)0U*I1?s_Q%)ruJU`V0u#)6cb&(;)7Bpz*{x!gt7k8&^l#v2{N5+p5jTW?wA&Au zG=8-XO%TJh=0Lb3YlCQ}QZqNrTox|;_E;os@DNxu309%Ys<;59Cd&@

Wn0ZQj;A znMYhbH)qRGZs|PAKRrF&QuuNf^b~oE%FVQSi&^R1+l(C`HZRM1S_G^YuIW!SlZqbab5K zF9(Hj|J{kVUZtQ5yc*5;TJ1x8PfIFz^HR27uYT~9n-b~H|(8v)Z*{2#g@g7B2YPx1MZ6wa{ziUKn zY6isZg?emVfHHZohzcHeKd^(%dTig1ESmfAI#!4|CtL}cFL90iA;%1^lcNv!v&>O4 zLddRqHt3s3{jckz+Srq9>7Wbr%bCsEC;7rRiHAwe->qz!eZRyzyAO69TnP<5gTN;} zfxQjXhE5yRh;F5~c#eydgeUAE&AWHt!Ip*0Zre2WJFN)ImQwVf6{X;s&viqAc*=Ji1#@i^uf&zI~_A;#f!dEgXTrzTeDx{?u+B_ z(44n4GbA2Loz@V0hhBh33$&0|r7Lq!kz(EZS272;MC{u?fK)eCV$Iqxda>1%jr2H# z#@TPBzRJ_-8G~2wy`2^vx_%qmf8301aUKEF$Hbu`hwIdG1;(OL)+DiHD9bb8gzcF! z;(?zt*$C@WsG7EmTycP(Pw6?M7A4|w!!D!mPJ(7*h zl;lRkE|8O#PYA8%0z1CqE(>xx!b-lo;G+7GH2CyOR=CT6sV=-q(=JOgz6}*ZM|v3j zdM%vVwnb3y3RxDRya2r^v|%@^Ld1`hyHv=_0n{m*LTZ8?in+lI(I`M~~Pyu;t4i(ZbU@ z>pB|>qSVx0@fFB zn=Y&FVzYNDlfw;LaAaIIbH8;T$M{=`8{a>~&sLO^3jH&rGgu~InI z`6SVlaPdm3tXNLsHGKTJG}B%-kqY15!S_{?T)M=GMGu@|UM=3R!aEJgPgbFSo0PEE z_6Tx)RwW&kvRc@n(8p$VJY!2sm*XcF(nztI30wbM!tvb%Vk5X%FdXb96%rpw+afLT zyR0(myrP9h)fST6oM&XpgDk4qp9RH>`q;cLPf=H^i00hRBby7$SnsMhc-EzjO->FI zUpc8DHaoP0>>G0!X%lz0YLNxgMETInB3j6vEGMpc?n10WIQn>%5p;gxVUuuloLJXk z3$wntmCOv4^hNuwFs*HR%y_FDInj7YSaowXOKETu2WeV~xBYv9I%mJ7MP)O^(kb64 zJMfJ9o>!-CJwuRz)lb^R_m+};=M=Ho*%<2aN>ea@Zcf72o58k}X32GOpxb&+D%W;Z?0)kGo~$v9TDS%h z#S_U?v?)<+R~f<?#h$NYx>FOy(>uI zaSJlBdW1MeJQA&VG8!+_jik+8^Vrdgy==kV5#;xwNamQnTXLWRGA z=z1TN^HxO_CnP>Zw+vkCFHQ5p%jtBL7ZM&*ReWrGvUs{qDIVb_(5jo4*>?j&V)pJR z`>g&BZWTHtuA*tsa84pix-g%f^>U-?Vg=f@R)+LcxzK+V*TK0aYj(-S54#+2B?sRA z#gW^LC9H@dyghF`n=)eqTP@k&R=eyW8DF>qCI8w*#otq@m$Doj@>?0TMd&ey1(kU4 zNE)d=aU7VHEE7j8$zoM0lJ{s`F425mMt`0f&m!MN&^Uh;n%$x!%&U%Mb8sZf-hPlR zQ-^rhnr(DY!Is^$c}}N{xJb*p#t`Yr8c5mV3XK?fl=z7aDZKld=F3K)>(0vTc49Bp z6s};`+%qiek1|{zDY?Jz^I^b#S%M7vSmy1IIJaynZ2qo;yH`4bnCMgVP){d#7_32M zC-t*F2}AGnj1sv|JpOgFkp`I7Fg{2!-%F7rq8wRv_SIA}Hzt9OSs0He99Cj8pFXF} z(tgbL=yAdyy(5GsWzmeHqv*e=#z=JHaxSA7#aNBJu8W z2Qq8F0dxD-C;GEa0Vze!e9nB>Ei%sMHicQ<+Yt{+D(WQXm7PGpO`Ct!s&6fy_KP<;n#bEu z-(~ryt;*_^e-sFPbXb%=T!vRyw6i?=yA&qJ7{YPCYr(P=l0N-?72v1V4KmMv;D^w; ze9_iat0yrEkS{TVgF7?8%8_41kGK)MV^0n6iJSnUmK%btK9jk0*Y8%xCO+a_XG^lK zlqGyZnl~^{loD|cTfu;iBS`7068(`ehoL&&mQ^#Rfg7J+TVA5$xnGAZU`mo4x4h?^ zrI%i+=#h1r#e;zf;NOn-ma6NIa1(cgL9^&0k$K8U^1Ro)i>SBHtBPAxg> z?K?hl8(Y*t%M(Qq5xiZboYlpD-Y}itD7LqdbiISMeT^^3oSV(eGl|Ht7Jg__!A?(N`B-hX-57 z>)%1)MP)*phXz~{rY+Pfgp2f&F7u&48#&$T;4bXmAd;W+8gBcYCR}^=oOAy(+4`=I zC6QKI*v1|~22)HCfqHiMS$ps?4qDUd~ktcWK;9qDk zn8@F7&Er&W$MH62cX7(0#VBc-{!mS8I$+B&A}(DjWqEbBvP9ukls<@cXi}`#L>P%EQN~@#z3s^>={0TYiY|^qfjFs+6h9q9zH;RD~@YyafXTV{&%4Epgv* zf_IZY0hH$cB`b8(P>$#oqe)+;3e&u`QTXNrvifQmt$oXHsILlo51DxM|?Rr2mW|>5VbE%C!eF@ z(avK|G+@;jI^@6gFikfA*LWLI)v_dhpMo}ilIRJgJZ7Q|9+ZE$_&kxhYAAHscnaXy z4Ak;tp)gcS!XFf>@e&Y zOmYRqhuz6H+>VA0QwPPE_ zyWxv7oY2v)j9;g%%ZoLXxKg*Jc+AD={PMNVLVubJz1njWj#;t*4?l25Xc@F1t;;ou zdubXjl#1Y|%vB}s>AJ}G*-KnF!UZ0G4ES@; z0aocWoKPX2T4@=H^V| z_Mb0puz!g{^7P2uPqnyhe*{>#-Hm9LN1_o$n^EYZVswkY1=DOV;+Qx>jiUU7Wwi&X zVFm@4>?f14_eS&Pd)^3rK-3x9OxeFziO}XF2=Y(3PdA$CsGBOY5(98!P zxg29#;d0Y7Ve5;1c>kwX`a`)!XmA>e491L>Fdi|&hj%9QC@ z-}YpFdmKpHo&(%x9HBo{@?gO%0o-x>4}Um&lDy8ZB0gJI!vxj)#HdE{eg-ZFce3K} zJr5m{!d{c>epmTTy9>Dw?<;t(-XzJa>N2h$CQrgg7(-Qu=_EmY1lx4rC~7J7N89Em z(Ld}$To_u^ti<2v{(}N%s;t@*SilS+H^=%LplPIV@ zYNswQ)$z;Wdx@u#FGwQ`#7j*UvUQ`*(*6uj?3}-p*i{2&XYNevL)-|FP8DumkYT=! zrEK=$rOesK0=@OCAiKRP*}8!!+Bazwy>JteAngcYsoHRA_)~{A9Bw3TN9$>5y)23= z|3c50rBa<&Ly69RT*@_FSqn$bNR zuh$&OqFyD_=bzkJY2IDDFz_QjN@8b zR2tf)km{WGdEaLpErk@KB$14kLQ(ceXz!)8mxff7O4>z6QkjvEBr}oC&-OciKv&mw z&UN1BeeV1F{d`o2zDOdc+GRo~TqvZ$nHS-chqLkWvs0)%zKsMGI)d0w{#>d~Ki2j; z!OrO)qfQF9$bHXLk~~wK)IF#~`H8p4&NViy*Thg7KkpQ(*B9P@g>KREi5sc!l`uB& z`%xMjq$;?VZBC1FZeZOB`smT7N^)!UJSsADh;>}+$9>zJNewNxpl_;KIL=m{)vcd6 zTl}S@;1UX;YP|$6;oQknQbrGd`$WE88^Lw$70~@)DP3|-RnT#oFZggZ9fg%HBgZQw z1;eH8^yBhNMB&PNoclflZpzFe4fCdw<-fNP*_N5q{JJ*$Z`(HdTxJ!O`yxqh+%Xk+ z_;;{dB3IF(`zrA9lRJ2QVvyi39z;H&w^-SPPR$a&pI9m?!gwt5TVua?uEFh>+QQ*D44cW?!!M#WS(PKCmgM}f2g=Z4*KOv9A z*p4H6j(@;h#ar6nnF-0;q-}{IcUDu02*MZ9 zhV_M1vp6przGf4`+7`CcD@lm#BATSVq!d3Fd=+{-6iJe|IIESuo!d3)!OB00DmR?dFQbGcqhlF^dd`@rrCK?bR zJhx+t@bvyxuycNfz~tBs`u>d)EqR%SZ_BJ8gEX4Td7mamr5X6H?o7_tF^bBhU8gQL zBkAUxZ*W_RBiW&Ff?94oOHyV;k=;K}V%@W`T<~8b@(fHTqAjz@d>>7ELqP|X+?zw4 z%I}eqqQ}Tu_8&DFUdleZAY?ud4zmTnWbq?qaY3C}JU%JDpUsS_L&oRgfcSrf#J>L) zm{K#2lU_rC2K7Pj0z9$Qx?VxaYwbxVKPkgfAERK_#&N8SyJ5$c65Q41MCW>)BB4)4Y4-1z=wpT`vQ#Rj8^rA} zTE0XO-`$92gzv|(FC2*5ivO@thZila-2z9BUxtA{FW}0cT%xmvN5iXpP+imo^21P` zT$dVWXRupw_v`nN4P6YA-*P(p)v#VtCV|{$ zcE405yJ*K!I^E(bO#TspqH5bfZ|pXKm4_E~Po7KnHu|EW!xynn$q#aO-w~n_VT3om zbm0yzdq{FZ?dXU_9yLAm4BqMeg8Q5vlL_uI#OH4X*`b<@&rD0>qN5*?pLV8bt))15 zkQGWU^{s~Ht&(J$u@23AZ~=+dkJ2D@F?PprBDt3Mo@Inw&yzD%1xjKs*zg0#S^Ft< z(0E7&+!WbIYVY&_rbd$ZU3^cY;$zWX_#7Qt7|o^GMiR94A$|9H6)8SA5%2x}gp_(* zL~(YZAf!`UtSn!3fR;hhc1Vjx`6gsjF2B{Fn6!eX~}iV=iOpN-m;U&z`Mni^Bg7CV~33r6l;|3_`sz5uFo{ z`d&U_LG%VZ;a@UX{r4m}GyM(MZy16j4JJYP%SNO}Bpk3RnnEwgZ&E0(h_g|f3RG|{m+*nJ}_N3wXO~M66cLj)gYC~ox%EATnB(N-cLzh%r zgOy`u?4@ZRQOmA$=E!bmyjEHdNUgny{-$ftPgCRAI2S(@o^_q;>2bhcE*z&wW>DDq zFU9IzTZ!8)RrIsnocQXOK#|;GGPZUQO3CR^v$MC^2)nar=1?rrTNaO!lPz(%$6Jzi z?>=%6F(Z->#L?NVk8t9?IrRBQ30w%R>7=oJXw!HpT2~>&6%neLxT+}*#o}VoF`&ad~mU;C2CmS$UF((D_91aNtX5j z9B^wn7?j9nw{B}7eNDlHf65xhs?>9|@(y{HVomKpIsLNp7HeWKm3Dg0q02kE(SdVy zSYmH9-q$3{)$JBSlJtM$S$*MHT%}RiFS?IjrEesjJ=p{vv%x5tN1GP=v+<7_NrmWn z?q^gzmi#(MOZTL}0N3vz?NtO`=$FVS6a25bJ8qt)%&pvdfk<1( zv5$3UfXDa0!S&vE(FT(dq*Bm<4!=7COaB%VRpFU`*&&3L9l-eCi@o$>&>@75U!;wU z9hWmJ8$WbD%t{G8F;{O|620yN7ZF#QL{AB4a~R4`6Fibuz}-b1to~3udK+^Lta;Q#+|NyCe+7(U(`Al= z&Z;Z$^Y||EN~8saFR~)(VlxFI&!^EMn>PGHXEtROgsclXNN(Jki9|k!(PdmMS-z^A zu0ajB`)Ct7EMq~QmVbazJ13#3LO$QywiQAj))(q;E{7NV$%V%j3wP9Sr=l-j2L*G# z7a;nA#g0!I+)-bHOjcZ>U(Oo9z8Q02^qxIrOxTS`%?hM%kr>`9eUm)BlTM!P*5Yze z6&`Y2OYi*}q>izr?AMvkV9)7l?4EEEJ-G84I}f#xO_QSGh1R=tTKq4X^1=sROhCkB zZy42GpATQ}sK@K3hyh<=k-OoVJ!7zlkeSj(xS`({{rB)E+fKz{b8#t3{~QhiXfGa3 z=7GrNz9{d`QoJ^q;E5x~3}^5SGsD-(dZjG9F)1IYX;{GJLYCpN{H^%Am>lyqq@6wS zT$0T5H0KW3jX^I#JpZ3qFy&ppEabbsg9m@l;ba!C1s1ySgrjSjVFfEJ3)qP8+JcVd9AtaBCm<2=0?3Gn%OO72=ZrY=RS;42W2ZD4M%bfUTV3U~8gqZ*U!u z)Qxw!N_|B2s(YcHWHS6KwI6H}vtnHpy@UDaUUQAj>HAT(2l!6|7Q*^T6s-O{T zG~8k*V+WLLSPM31-zU3Xma-TKJ*Nx31?mS!P@=mx$*+Ef4h0pHx`hS;?FWQbDLLYk z%iXAb3&CMkQ|L>%{iwbygQ|;3&?@HyDi+y;V`uikhS)6PHn9m}S9|5`}o zrAdN4PxSDvmPj<>+(YGuWzo)}M8U~ob@Z{)2>;T3fHlu<#p|kty(dvexGJL^rUox3 z$?YG7{^V^`S91v6&wNbMbDW5R<_zwE{&y^C7f4^-c}&aN>e!Jdzu@WsL-OuvAsX5q zkM;OZNw>Q{bPXG%Dr#ba%N_2hRkj^}k`AI0haSQBIwKlTW5FHV6o@a~83FM>RcQ0} z&!}e4QtT#?iN}ZjgL~U%*Y?NNeUi1$_YnTrWMcd~0{?w}j&)z5K%a|Eq-Dm($el!re0J(%g9njB*(ieyx`hy_ z=3;cYv6NMGK8kNK0yH`jfd$>#L?_D3V()uv9@c>G{4KNs@9W>$b? z(HL0wZ2>LStmnS}y#vPf=fMhTJ*HWIKe=e31lHQA;09^oUAMgvKI`s-U#vwqnX<)1 z_hkjC5{<@Poi_0E-B_}c(ZY*v>*M{}i_nrFd;D|33KDGZNi2#WwvIi?F5UYK&(T`T zWxq;AHad;?!s|C!WLp`vxgCQ79W`LAmIsN=o`yn%=X+TIf%>P8!`_UU#I|f07sZE@ zlX+$E&ZImLh5n$QOZ5rZyaC6n+~kz+-N()!jPSED!gkJ;f#Y)D$)Disq}SXPEK2#t z{mP8Npm+$l{MU~5Rfdp}vj%KR^K9B^lSIzlf5KR3bs>{9c``+#1#zH<)Cn2Gp6AA3 zrRF{6_+k%o#qkQxQ5Z!NJ0iKh)dx|BXgOXw12TC&50+Cp))_%Gf_`} z()#{T(lk3C7q3!c`){goU_6`@j$eR=ukB$A?qe*WF)=tdk-Dm?Qqvq+$h-cZaGs_| zC!V|rN1nH%f%`wWvkuK*>yuoZI;j>{%d^~olq8uwEXVaL@JMpkF|5DQ8L_pZ)NJ4a zaF8@5x=;TBZMnmR0FZV`^UVNG}0|7N0d z7`*X_5jw5D9)EIDr^l=U@I|q3baCA&eEoY4c)3A`7#MUhlBRy-@#{ZW%k?Sw@%a%f zyPC|c7c%H~{&C@6`imh+|74MyfM_Vd%s;ORhgea&jznKTF`YUZHqR}-02Q@zN?UUhiv zpCz-(_%i&m(}(ot-D2GN?RbCfF6^1T5Pyu^j)q@)FftAT*z!;jWkON#Y-JWJcMuYo zZ^dj^Z$(QSJD6=*r-_#YCOZ-sGWpt6I5@2b?-q!V6LPb0tZN|tQDp$&<@IE6b|Uc% z4Z#-9=I}_IJ(v@77Rx+nz@-V3iS?UkICYIN>n^<<{}>o&?1!ZBkYqRNudV^+an;D} zF(h8==YmZ+J!E`|3ey=d1FKap1{$tYSPP|eB7P`_ftj{ow&Yc2f6pF%+^TY{)4r8C zymkgMXnsWc{6x_Kb{ZSynaX@+1F=c19tjt^KSVzNVSr5&UMDgJ^KL|PCQJyFpCW?J z2^|I}Ez@!Gj(F6V@{Fldk;7*k-!i}FEayxDFdFp3_yF{xI*+1|*L%Vd?Jn#Zk<5>9 zmn8f2jljp&Q%r4k8a!NZoYOZO#v?)=x71NSXlgsh`uVQJ==?PF#&tJaJW&Z>mHGhJ zD!l+x-c4YC-hDybbb`rE^~oSPRQN$VmcWDs5S;(J1qI=CWadY05GVZZrqo=*70*VP z;#c?Jdf~ju*3FD_{vD3OY$Etm*B^mt1IKyFMt(3<_Z57rE{Tj+hXV(;kY{3U0~wn| ze2Me-q2u-oz*s8WT_ay(@)5K?T!(Y@ z7~*!NX2L-76kxqxP{)Ri`PQu2Zi9M@b`P^@ONhTNIr@)&g4g$`?0xyl8~ulIh%T65vM%m2>PN>4=PS! zHfO6FxYMW24|I5d{+5b!{SPmow-v(o#H%^n0=qSgxBV98;-&-?_p=Tp&S3bvYc$ZV zwg7ZUyBNkZ%elt|UQoWw1+Hyc!SC?S;U+v+=f*5_@jGoVzOE191;c3OYKac}YQ830 z6w$-}$==BJ?Lo+!Zz{ux}dt9L<<#PFoi2WLGO4z&pIV!Ic-&=tE(y zPGEc+XWmc31MeV`8Ewad#hJkPg7D=h`W_6An~qmie?@!E8cF*7DA2f2g3jEkMCYtk zC+qrep-*4ez=NzIp7(n#DRaCEj4S-Ovk9+=wNxfTwiBEBk2JHTCnMlkwpPAwC95>Z`WZGwzVwv1Tdb&~%^~JJSQf3_#=f<#| zM>4J3Btz_k{w8^I;j=I625Rp!Bsyx>VENgbWLA0%iYo+Ee6b47(^5w+1(OMR)&k$0 z6vO2`&&heR0YA8Vgvy<3MqfLcV4|8X9kY6fl5h-_%h-#ablygDs~*BR6ZXN#&x*8m z$1^S&Uj~P&Ug7Ah7&87hh`iHBNJ&?lEb~jiW+lOFFnbQAh){WvJ)3Sh@I zYgC>Q01s>1;pDDZ5~EkiDOJ5Bt6kU8ueUWgvqyX!oAsW&_pL$)4c5`99>UsmY{V){ zgrfYvyQ&~$ZwNi5m07r=TLaJatR_la7jQeS zOMUmn(Z8aZLS~LARsc?hjy^vBc?rFGxe~tAGlNPN^N9qRM)4#e4rq5woYdUT5xTU5jkXU5(A$rz$&SmP@qDEOR?8v*Z&L3fGpdCi z;tFk6`*6&xsYtx7 z2HOQx3OfM>f^X}O(zYe?^vPyb+__>tN%`bJ=SO=AXEwL-V}}Ip!7@sh3%yl8t@-=NIUPrvPi$c&qZ(lysKu@4q`amu#*NgR0$;bc^h5>MHXR4v*f# zR+1a3o!STX-hZ+vzT+1!zgz?row&_g?tc@?8gxS@u^rBzxP!^JuHe7zX@ulY5PwhA z3wU>rGFLy8$3>rQhbuZZG# zI`8J^FE|fxyUc{=KNd2tJuG>##j!X-%73Ik;)^1X(opkll}mLC}7XX$@stkROX zWNRnm<3-Py!)Mp?OeB+l*4ByW`WG>Nn94F}7w`k@vh$-MsDA{g!3j3=9|@JczIhbqm*LF z9+RBFH2rJl-~2HbJt*dwJ)UAns>+W`cyG_hB&so$9ePZ9b`O$Bp9$0wZ29hCIcUH5 zIFfaVgo~Cx=F;9!E?1aIQqHUAPy4fmTdBE|HK;m>efSCdkC(;xbIs;4@@j32k4_~= z^jx^*OTxIv0m5!c(G#ft%8k!&tm9nYDdOW_?BTw!KI;DF3wvjhE-{)OD|92AqftqX z=&tWu-0nD+OgYKNSiVrH1z!{HrX$IQz!`K{dMzH!^ki>1XAn76 zN4U+s8EMkLWKUNLx$>GX7+$gyyLE}7e*zzRy-t+dH7Xy((w3_aYz zJkh-fgm(?Yk-MM3U2S#t%*x|{FC(Pv4;1h^1}`xM>8^m^(`3BKd8P4@!DHY=TR#8D zY=0&(daL0H8)x5#@?S#1BJ*+#!b4F(a!Y)Guy5imt}f_ z*|EhSxzmhMlU%{>HtaG?bt(XpqrVxcW$7`sL;Kn6&!hbC8}p1~F%bs-Pp~{)Ki;&T)r?Io$3HcA1pHoU!G_u@0X02Grue{Zus%_lIXsmG?jIPw z?}{4W&L3hfU2g}o5|=ZY(u2H?rA8ogg#zDGW+y*xb1x|0{h3+qcZ{7pmcws)CC^u# zGl7-LyTh9&*u@?SE#=)f{f)1=^fO;8^)i3k-l=T*rUt%p#TsLKT@{c!r3fqwO$2AQ z?d6{xwE*(bLriXwmr-}w4(3~`EPL;Z0UNuk!*IO=FfE1h&60 z@(Fijo9`>KLn=zVt8-hKH-~S5r#lpI>*{bif5my0ov|OEF2rnciyO7dT0{nB{lyEE zj^h84vr%Q42$4V93*2A-B740yqLS#txUuRLn%Z}td@%b5O23HF)u%$Kw)JFsU!n%b zRnCQ7@pk0EJK-4}cMH@mC}o}9eiM<}NEGW3j;Bve1cQgx2ttH2(Jdzw>1;Vq{B5-` z>-it0OYTGxmHIdwGPa3p@t33i@_Xr)$PoHa+XRg*SwqN%Rdo3AYf_NwNIb91!#s;^ z+%Ho~uC2O*r$oz;duyslyZH%d{$&DPC6Y((tcyX4zq9DM7$r9OM<+Q^8O*MoH4#6! z*-z!ysp185?b*jC-BE~v5r{c+kz5Eq9;ezY|kvMXm<|`P!(>#+$C||A%n?J9=nkFFG&~f$y!T!4b#^YkAF~FH){> z>-P1-@Bi*#PV^+%@#_)kb?`ucre=|SZW81{L@LX-bih@UTS$m-haB8FiB->9&(-QQ zVfBc^P*ztSOS zHh0Nus@#xCuGQO+YM03*e{d;gFDeN$4xX&ctZj6Ss4klN=QBPSWhu-8>eBu>rtJGo z`{~Bo&ot=%9NILRhripeM1!MONYg3_x^nS4)<9s#_5KT^kHxQ|QPHRPE%OkBCA0|I zGumly;Cy=C8shVoo5?DbbgC?UjwHPu#}j@iL3${bz6O$lC*HNxb3_ZBT`$a7%)CKk zziCp78$G19FcByGsNpuNb(1mvTvBmy5wS*;>Ly#E!c&uJ^fn!;b|MPT{V-8*TqJ`% zdzzz<_RB!+#D45>ev-h|GzjncD#qPfBZ-|emw|$py`=v1KCt`VCtMqh1#h0Vp!_cd z?4FA3+iF&d^qbe ziQEfe^WlB;R@^nPNwo(5NDBvXYe1ljLhkz z?Z+BA5RwWvOgRc?mmh%-66V7FqFFSTnT1DtMbJgV24Q_*BIuuAMD#1(ajk7fNzMIu zHsMDS{atF0oZg6VH9I2l;vNewO>Q5~)tg9Fz2lI9Ae$7wd4^_pI0G_&5#|0%l)we21jIqe#_5E4K>uqXd!R}dZkE`>l{kgrQT`}?5^$2+%h`~ebsbbJ^a1p- zh)3F!R4I=qi7j5s(O8#%;PT$*=(+!PP;FjHQZpu#-k>dba{UwZ=P5!j4n^ZW=S84? z^Imeo^fEWuZwx672+)C6D^l4lG`_T*A@Wm&dE2wX|8aFII-n*3(MB`8^4UsKY_kg7 zShSTbo}Ec*Ju1=Nj#T6^@R1qqc||q!I>|$?5VE;F1>!g!t}GYc{T?fm-w&!$RrfEp z^rsYwInhk4FUr%i$P2Eq6f&M0b4irkJN%&i5oTvg;LI2;PU%Xwkk_MvZA;c*r{Xp| z?WzJ=@%t4{R9H-wZVX1L4!Trspa2|GQ6y5ytRh^+lr&a8N@k5-(MByAJyNZ@H%VFx6Z zzxnBRyc;&MSxZOxDMyXCkH@azvl-hN1#UIE5w?pl{9s5n<&~4G6Heeq()!q8&vk5( z7*4#}Pa_akhqkJuG9`<}Y304$}!wqu%_Z4{Nq6}1jq7IMWMCAVar8p?_ z4o;ST#<*@ghEtUyxPa|HxOESrxE=fp+~^`7(%Ni_M5bF|sp~$>zA}GU68N5}H*4l@ z4S#{{dnb?wyQfi|1Yc-+CW84Bu@wi$1IG4U4Ka7k2eLy}%u~*Qm~0avmvll=qtbHt zrE)SX9$W=<|LDV_u|agPauK_!$qAj@wGbWE2?Qk~nS6^&(&V-46Z|D9n{mDC#LEu5 zfcNmeGGDJ7gS-*n}p6wX_*`psr-@K@H-vJPZcLcd%gLhmMj?+wL_~@X92O9FYz+? zp8xZ26<*jkz`V$pf=}gMB8~Pl;O&7IjA-I(rgLpFzdPw0-mM)5R)zgyj-=L;qi3_& zl=cqpDPGAg3Uwmp_7l+l3MHIAMH;;I{fFyUsG+9AM z9T}5i%H%h|EjAg9UcMybX&a0z4a)IN7bAK;?>&F#RyXD&Y==x=2S01+7*-SJQ@&e_ zF~|BO$eZ*6Jh|)z`k8DEt+r{h8QzZU1!*Pp^Kc~cANdWs_KPC7wPolwvlysfOoy;q zhvcWk;3S8+OvhCbzSZM3xUOj`8{vC}t*?2E5Be?!U;PtFTE`5uZ@o1WyW0tVb-fFB zdgoD2!7EZgCAGR;p@vkVQ@bId~WX{Ghf@l z8e2__Cj}zq?g9dLM1l29iR5%TqFP^XlYE0yD7i=jHt)KM&6PRwCU7zE&{O0-ow-CJ zKiuRdU!Q}?IYZ##r6cJ3s!A;#PLqlUim3E*2tIkDfi#;blIKEhIRBMIPPmKtQu8fB6VR9;`)~rM56oIGF>;|qyGw7PkBh+Mt zDvDa9gTD_}lJAcmp{Biu=;)1Zc2EBaEMeRO&aDxpC#PGJ8*e6(!rUb6__+?6FjL9y z^GCt6?IC2I=@=Y$^}u>Yf6x=TFrs^-2qd~qqAz6xbgi-oDFtP@lae;jj(?u4tzQ|m@92I!k0*`bP!KNplh}fnfA|rhQ)^0qCt&SFuAe#_U_Dcs> zUY`K}ZA>N((Yn;pC7Ieb?Sm)%&B^q)Qq)A4LwReKM?zXWaB}!Kr?y#{#LltB;~stZ z=QkVT{InKc6A+T%{+1Zk@5jvN<&=B<1@s&YB`X~tb9zmt_{Y6rI#v8VCq97K3pVyh ztZfJ5);*2Tdn>@vkzRa8D^TdA^y8-4XW*LhY-kZti_PjYsj5sr{?cQGA0=NQy{T&W z=v5(M?!U!I%Xtc25cw3>X8F?+(Jd%JyAjo`bRz5KdLW<03$U}9A${4n1^XPcq$LiA z(4}uB$iI`&`u!i#ew#R29Pt$e(uH{I4GEm5n}RHadB5brPHw90OAzFC6>mxmA`g>< ze#OqsC}PtZ()_9kj|4fg^}&Joq2)~yQma9?a6{ltsyf_0wHYOiNu$$~E%Dsd3rIMY zfO86GQ_s;9`bcCqG`*3FdZK1h?GyKqQni}kLg*D%ap`1YQ&P*mGk!p4h|DDsheFBT zbWLK?V1W&EIU%ZqL385oJ&WSOhRF2t%S}uD|%149DfRA1=HpQvs*4rr=^nDIkB)T9A0BD za2u?}NT!qJPVGZx2fDyrbqzXeuL%2L@^c*ge3ziwH55&nI)shC>R@=Lf^1P%7W`eU zN1NP3u&Tv2`X=2OD~rq0b#pq=^W}atN?{UxC6+;L4X$FH)z=XJS`!Ic#~`bL{rKkn zI4XMgJCPe;1iw}V;#lSgS*r5*|nK;N$L|i|3@y{ow*0rcDj(3 zS9S1OdOSXUX^3P``p6}FC5p9t&dvRC}kvBgjKy5T|J?_`&E4Tx{M zLc%8>q9xzwP|Ih9IMyo!UJ@6c?O$%-Td?c4bgE%h zLayg(k|W9h{o6W=d$2K;tb1odLObiR?Ym1v#K4c0+5el^B)gIwgCf}FWD(sQrpP|e z&nI2J4eSjY8T`!8nQFYL!II}<*x11cDDSHdTCZji`&Z^*Y2If9cS;D3n#@Jw6Hj58 zv>KGUAeH=?vYQ_EIzW6|#!!in!ErFsYJQ(YwJn@fkVMd)mp z6WoF=7bw8c+wpL1doyW^TTXt&H&c@gMdTW@9%_RLRCk3stortp&N(s}tu)9&Hmhfo z_u?aXtihBH9L$4R^OInS#6>J4WGheGFhqRkFGH%@JBeyh8y0mx##(o#;@qYeKvmPG2Jen%d66M{o6kpikd8IiYKK*4PWQ zMmHFoaCyf+P-jMePf{l>rZY*q)ORSs<^!>hQ_-{h65RGimR(uc$ZAz3BSYDp=>3mf zgC> z)Dos>ixbBI8Dui~Dg4*i!hMR2g}cHZl39nHu~qLSG$k+*|1jRkExo=9hpDZF)O;~% z^!vm?tV$|Eb0BNIjBQ9&AXx>D$h^NEUJIK?7TNN#*NkXCy%0~FmoNO{XPa6~|zTjtT$s@0TexR*Z%o^Oh08hOB!s&}6vOR1&DKR|C zNC<-2tj%NiNvI!Racvyy98_W?lDnB1NBTzpZC%A)IWrZw-xy_T=chB{pFZ&u<5WRd z;*eqJy@#MlshHQ@wV1h6_J?04d}b;bWRf=tVw1KJpPm`DD7)r{C&;@-PY!1;FQ04Nr^0|} zg+EM?lmwU`SSBnHOY#0y+ybX|od*{D3;d?U6t;D*u2F);C7{(aY;=09G$XsBoh=>> zW)|wW7?}iz^Hh!043~Pvg2FHh!}Y7~G26;svu>@wd5@Q_XZCzAUKWh;r~SJFyyxljUETizo|%x5{&Xq3b=5U~c=tJ;OQ<+FAv2k;P%@qQ zT!+|SiVh$uAcei=+R9h9+QC1ZzK9hemHdB3_gRmYF8;-3naq~r#f(v60{@WNBGy`} z%s5`jnOD{n&Fs9e2gHW-g73R`@y+~CfJC29jN#^FqkkEN%qYt5l zJng|)#&6O^o_&HN(>glJccdK*GAFLUh z6A9eAG!16`s4Kpl6~zsUI&$jK*ZJ>c@_CnLDRHj`8hKH7b@0T|Q1(~#Og8siBs6&v zkJjF}%Twke;mmS(K?2&rq0Fai~e&i;Ykv+X`J$Yi|j=?=c2f6chmXb zkA(0pHStlvo+vc*Y8)!;2!nT@Oow4FPNA|t+u3lx@BFs+Yk;14C61$Ys4k}&F5kTX z?Aa2;tvL|}OJa06=O!1+oH@p`UoDEwOKPD(+EP?re4A<4TnhX9X7DR*$C&`*SYBl{4@#3~ z2x^9L;~$TssJau(+8c}DYIouH=z5L+p~9b=8>x%dJx|A}soMOGn?3w#Av3w|(}Db? z@gL~$&9C6^+)jR5T`SV7PD0V5JK>OF3z%VS#FLWB5WhO zk*@|1!RH5~pw5|7eB%BE{B4djv zUNOt?(br|5YQj_FM)x89mR)=J1NSH(0z1QXyK+FP`E77{-%RjI> z&BTh_=IgN+jbiksfug=MfS>pdsI$v?c=tbM>~bpDwptXdY8+-RDR=UJetKu*=AX^n zE;nG-{d8fXRhyZ4MU^~P@7v7qd`l2?aWjAWo{4Pgs~AJ2i<*G7I%4E$S#wF=afI`f^bYXPUnb9rS4f`DXe64Tgs1xSh6^IxUs^W0~rGHGug8JDi; z=PQUE1<{U2nS0)%?6X~>{6Nb_W3=P~D2_YL-+9e|HCkuK*R{XNKeHf-|LE^u-r;#C zL0QFJBmEP(#$R5=Fi)4M0DjPHuzp`TZvwf;sJvXnTu6~H8ksl9&vSJFIZ5ZiG1(|X z1C6D|3OPCauY2rx`G4d1zYMQ1&&>WBWu18e=AM>gRku&!#c)UX>ejJ9@p3O#npH>H zuY6ADZUw$D7|v$2o}xb5U1WEhD)DUoiACSY<0s#TaDdA@pwZ+&)3hB?__BKZ>5&qi zZfH+edT6jO70jv2vJCp6CWh)1wBWDZTF6jknAESHLf_r|1>PTy<*rICrCzsVajJDb z{+-qZ(7JsB8}24u>N%T!`do^~_7sx&9}}ppng|UMe}Yd$eCGxubEpy1OdqD_&_}zL zqYg_|nro9nb#;Fci%UXRcwjT0x3-)!-RDaJLiGq9a3|_jqSUkMH;T?#L`#MH%2O{d zV-JVNR43Dn-CXyI)TDNCb_Jf;SVv1>xj!E#>NT^=eADp9d7D7aLn*pAItGY8NWmdH z^aa*!6jkp|#pBycQ1g+i1p3{gMbn2!!y*M@aYlz`Enb3e?|Vn;g#DYVS+l9zEtUT% zIuE~`-Zzf7_t2tJiA3Xh&N=seU-y$jBqAazS)r(mWUtIp+JhEaO41%mq^Q0|LPL~M z$gC)ej7a>>?>{)N=k>hKeeUb}eBN(*aMN}w;r@uwo^->tiVs{7JhF!Nf`060=td4L${a`s#o}o?Azy} zC?`2GHh%$pE>$Cbf6k+TZ(~XF!D3E%zBN&DpUJ&Fu!qe4Cr?(~QUUW(N_h5yquj+K zH*of|+w7i=Pf_y8B(l<}1}E+?hqBQLsAQ}-Qa9@*TWt=Z!T$n4e?t~peDerys9B3G z(*=0v^brz%OoIDp-OjGqx(JW4TuE-;NhVJh|KqlQ8BHGCB)D~{8RP$20}ptIlcQ~7 zpb?)TY}FrR6SQpc!|qeuV=Ey}$yFwsrK1>&s~1VO!9p-{;X7?t^>A571BqES4jp?Q zM5S)&uwGrUWMcMiHe98M?$weYvC(=^b&%&rzSAU8-nL}*v@+(c=}a0g?SRFrl8MTa zOV|Zr`qasQy()YQQT1tbC+kh$zN{l}wv?joxw&v-Vi=$0J;(gJV~FlZ>rt1cR8*u| zN{rXsV!j2=72TZGN|U63x_&-Iq@zJItLv8_D-S3urmt=}k1B ziWj(=lbgjyso|wjv}bZ6d~*7NuYb@+?*}Hri4G|+pJD^6@|0i7X}gJj zy`IQ-%|XnH{$UH-4BXg}4T>(CsQsjV$es!0zi&D;UU-@;lQ{`~vs3WF8QHLLp)!r) z9fWVr*OR$dity&N$3*jA7V_nJFKREOX=hP648Kwo?Hb*HeQlz!x|##6UsaEuD`<&2 zCFXJ;UK$gx{n7C1&MerBRcZUTdbE6Ch}*mREY8sO1SuGXlEqu`tARpDm@^w*)zq-D zNP|2)w}6W8*iLtK>9JwPrRekMMc^xjP~|LRQXPL4o~qcgH7aeiZQ&6*u3!K;?bt$^ z4d+9lkpiwe)<>@fPT~Hom4^%0cCr6`kD+HO4w99bhe39?E5z@RB5`$>NuvK_CedXy z{V?q`c28SQ2CEn14=Sz{4w|vc>m2BSnKKkbwiI054Jb&OR3av|{w>}=GuWY>V5$OULb#@N55|lvD9sck0NeG)+&-$lA? zrGW0bHp1N1dh~dTB}r&)r@e2VFu$8WK;c2)W-2lyvsgi7f2kC&#(}Ky2{G*0Ct~t8 z55jA?d(525LNd-|tccq&AA@xz7XP7w2QE6mchhW2|62i{gxu!7(3yY2`^Uja{a2%!+ zMr+1@M_n5)(G#;~aW7_N;SUQAVe8&hypp)klx&av4V|X-?M*}ZAev02}KskG%-)e?m9aet4L6CvL=_${_Q1Kcgav68!gUIc$Y3; z8AwaauW(8)wvaWW9>eEHH`oWWUP0~a+l=Y6Y@AT=l*#K?p~@e^d55DN@!McP>Ji{= zb~o_H%$dxwDXH-O{S0(mVi%sNR)nXblb}oXGpEkjz~;ekkh3KWyz4&WSu)A&)X3jN z<%v2;{XT|iW#hQjvXM{_e4S~VdLQSC#xrxov#52Ake=P02aP#T@K1V${Pk>r1Gb&y z0Zby7`8|D3P$xX{)}j${(_wFA9Qrse673DX24xeMLs3aRaREy_d8IMurnaBhMzQ3= zhB&fg^%7VTmCml)y9=I-e?@Zl|K)@^26V&o#msfx*e;xj2TJl*a-f#K( zINU7`!z0~S$dq#pNOiU*?DIF{B_%UqL#-64&lzC)|9r;{n!J=FEepk(Pla)jrck_N z9hJLigVUdk<9pcYV1A{SJ9OHM>P}Nbn}uCSeoqLAdu>SuJpIAhHHRB*JsRzMtcm?U zm5{vI>U!V z64uuk!J_-$@uc;;pefRZ)oJpiMGF-Fx?sW(AS*uQTYfdUH;5khP@^0fl zhvq;i;^>yevXss5AzM5$xSfi!w5Fhh9yu&7ij=y9W<2}~N-Yu8X3aH7JU*LlUnB;S zmR~vL+h0LT#t{AvFM;FA-#~V0B_3Dz6t-?VL8ZQoC*!j;M6By!c5R6qtt~HN2Vz!| zpEcV>W6Fg@`a}tPZ;}Q1JM7JztqXyorWx$>C|$VIZzQ@h-47f5{6oSI-M}*{ETCCx zvMAfoztC8ZDaJew#a?!@}}I z4eVMeZ4u)c2v@uEA?ENgSbRR6w2RGy=@udE&E!%l*kXkDuB7l}>N8?jo=(4<2x6Z! zl+cAvrlJeor)cUadANLMGJdD@32^LfxFw#&HolvK%DVHZWN;BaJjM|e9thdT`tlZ6 zZL~$3=U=A2r&5WBngNCEM^wA#A@t9^0E^iQA(v+D!wVs@Q*-$khTi!P?jPZ~Byo)9H8XW@CC z*3jhFiZA~B1_{m6L_SCL=!92_@O^eD%}}u>Q(!WkCvhJ?x|>QT-_xQy=G>votr6bW zn1ZJqxCwveV;r#ClxGMOQ-#j=&@eh!w6wB@ypDW>pA3AUvV+OE`CEYKMq(;H%x58> z;s~@9G9Z-yP91eWqR&o7DCya9m^pVQ#hHP0D9xVe?$D(EE*aqd%ZXdxIu@=B4^oL9 zWl?>%N}o(*{+1w_ORIgeKDUz3#Y4 zNtaG?i)PQ=kt7Lg9x^5C7E(EdTcj@_oP;*U@Ld5%BAYdnl>O{s#vl0x+3{U$;^NuF z!pxmmUAO=qX(7z3gYV$CK{4$gSwyF2*yCj%b|Q_pg|Ko71D(5fGxH9Q;$&NXz-J3J z+~jhDMD3W$#5QjiHFT_}ZCPcoIF|22?$Sq<^@Lg)jDgKw8u*R7H`mzR47)a5q;FrF zQr){3IHi(ma;3YKn#=x2y6&DP^XA>c1M>nn#@PoVr-wi@&lZ2axEYqX=pe7X-(Xwk zEZCkVL*%N?(VvZT*i@}caJ8?QGuJ;%z-c$#xO|w5Ovdc{)na(4&zw2GQU;vPz7!hj zKE{DT(xQtps(6iK7a2-?fH!B30`qWw7vXgT#M^YqyN!V`xQzc_^PO;$&>?QLf;?@V zp9zln<}^-5k60C2Vwso@BAV)te1D$Au1(6cy_fGJ`>N8RbOpRQDj9vrRikIdOv6_m zsEF45X+?gFHpx3*!ZYV~aC47))3M7ZazCRwxpPV<$${mO;2B^+hhlAT8*?0j&Zm%2 zpIA0-)d1PFgMw}RG-_9?&KBjaX3k2;k|igcFtk{atXVh7nam<~(zQQuRX>X6KbVSl z*IXrC`&DSfjPv;Wmzi{^wS=9rXe;lNRAob1W9qm4AGxOeh3p^6At!Q#e8tZxrCt>LLjJQ^ly7+y_CZJ~jBA2=-&c$vUT6G;bh>%*fCKwt{fX}I z(JqHuUFr|deb+#T^fr>Q!HOoRmNG^E;$a{#mb|H@6YOee3=0cbjX09?K% z;5j?(z=@HA=x8Ulpg@m!T>c0}JzDfjX&DnC8^pEn=aaq5K6F}c6lotf55&sa*&j#3 z=~J+xcfKg0bK*)wGO-56d~YLW$0bC69b4FEI*$ol+0NP&U!X~AN1$-s9w^L7BXd?s zkZoS4;f}Zq>pYd`|D;8seD_G=xpO0Vl50f|uVi?iNHHDM8K4balj&?VW3nseHroC) z5WIL_@LbnL?Aq07+|l1bwBm6DiTtsQ#9Fj5FH*jXUR7t%m+>cQ@SCxC<`Y%$&Gw=> z@og}+FP^;CPviouC(yQ_I(q7|zR0Fa6}ygCr?-?Z(YmLNV0fwu{#o^qdzVtU78NCW zY%&9HMB^Z^>oq9X6ydP0V)(j$J`MMsK)QP9o1<;)926S&Pj(7*P25j=RhY? zUM$JYyzD`KTkd46lY(KprYd`A)?zs5L_|K3$M9U`ev%Ne5nnbBf^EIFqEyR9*s{@& zZ09iDXCOs}6ZEO-K0Unuaunre+CY(~xM*G3GV(-A3A>2u;jeZW*6RI5cAm|lul}0? zTP$u;w6YVYp8AX~UHV831<%NY$%{o)a@KAk}H~qW2KIevXCNrr-5SO<ugCFM2=_N0hM>z=NwwKk5_u<@>l($tH~bEsTcp6iLcaSXFTwL`{6Y4Y75vbf2iB42 z@!AS8ZefW8F{-Ua?p5aGJO52nu`NPV~ptgAJWWLzVoJLY>Z~~o*@e_ z6@zJ?4Eein3sKQB;u(p$8qxU&`H9=PKb3F~m9-cjXKqxc$`_YI|9u%oF8?YT zOf5&@ZUS!3gXj2HnLB872XTX0)!>v{0@0<$s7@^swfFIJs<#<}9Uccs;FFJL>1E>h z>=b#S>Ay$VF4Tq3XO|-7lD+tMK{(7e_%r1rC)V-{`CUjr`L|{Z^!5b{BMhTC-xv?UBpE|tPJSth7QPWgTN$AbMkfUK z(jMcci>9P;rd9V zeLXonS5eUCU?&tM9~ZnWt3scx2y%b-m_1MyEb!oZv389S&Xm5#O|!H|y{Ge8^EoE$ zgiSZtw3tG{(7{;(%O77*e`f*nVpIUP^kNu#Ei(qMk$g&IpS5xOO>?;uT~?U6d&2xV z?|Lig8YNWEkYzrdWf>F}!_GOahTplSnFaDR<{>!^p~n(^+^(j~)LSeS&Ra4CkE}S0 zIu}U`Z7)9&l=05x`2(@orL@(&C_0bLtX5#HoD77o@2Im}+(I0VM+Dv(Jj-XS3;L*( zZ|=7=U-0bHDaOxa3r;nmR9+^637R5CMz+{7OCLt?xhgU6P|6^Vkx@9OZw{IoHcXCq z%wSdx#ej<4V(!D*bo{G)kY_+l2W9?w^&+dms{0unI(dv}skd>@x8LV1zcix9CTqaK zz?u2G{5ZR?Ar=I8f^l~71N1NBxlpoET2#gagBv*vb9U_I;*K1}f7@RX|8E1N>6jV* znBl+My_7he<_N&Q-joZdzDx>k?P)>3xgk6zt^v$1bYM|rK6pmT zV7IlGxCIB)soc6NctYZA8fjF3@2#6d-cG#AthB3Tqj&T{lBFhd(*!3Bi7Fj+vGS5KkhznCq!g9tjJ`-_VP*gcUD?g3?U$hMTJ*^0soHR| zsg;~~Fc+1>Av}4HHgj_y0{^=~c<-?U@<3}L$}89f_ZteCiQ>+%YyLU7r#}`t+V~xS zL^z65Q6+;59Ld|MOPKs{Tefx*1N7o{{L{4qOKCYU>-T!lcdGpFH zx$GSqwe%h%r!@J>pb2VT6|l7MAcmo>#57fh#0Bbu>-BfsonBqG zvNeVTy_^Woa}~()#&fu{=Mk}%(uE`GvaH$UJ6!*l*Pt`}2ksQRF_wqEa5T(?M5WX) zQFDmEEGb*{cmLJHoPtmZt-kR1P=1n^rmcnfFa!AU^As#J8 zuK*ywe}S3c@{vjMs&Q-%`=Z3^PdmY7RFx@p{zToiMfOBEx|!cwRH* zV(=Y&ZgmK~UfhU|E(>KQq^9GgH4(zKM~wKhs6qI6O*XmuRGNAYoJLN=cX4fCAG)=7 zFLF}0rTNqU5KXz`q|06x4Els-GXwg3%dc@F>)Ex|>5p6HAn{F@(dmDmzRxMYj zPz^hkY?XWjnzl7(w$v!Q^%W` zB@ri-Xx1XCZ32ESl82Xni@-%|XanX#>L63IN6~be^Fp(Rg|h6#C-S_< z{J8K}d!&g}@-D73eIA>cKEiBZ77J_&#hI5e8f>ITI%8FPMkszO*{tVJJrj^~lHIh3EH!-8q8qk&NUnIzXR`>$YDxua>Ug1WF|eAndh(cX;n zjl(7iNyEYiJKwWPj%Ur~H-`uXnVi7qyF620e}&CoGlki5#Y|Xk{+s#pKv6iqrIYaq zw-vlOW60({<~z)4L2TYI7M>MmnV%|}!TeP@ZLU#XA$<357HfX}gK&~~8t?q=7kGUW z36AS}vAf$(33qI|!%999=leC+g;m0nfcCzwZB-)kTCzx(^D@=cY}N*0$k8$EHU&Gj+f>!GBrw|CKE6lrx4Ydu@14K!g`_W2 zc4pYrY|J4xN41u9{V-Ng`5{DDk-)IX$OtBMR?Iwvk$H*)0TyNx9`$uQs1_Y(cZL3bpELb5^X+!kJWaj zMm&>rSv@8zA4}31Y3oU_;|9*FEuReB_yWJB#6|5~JW^G6rgF>jA;i6qTxE3V3MDzX z(>uge?9Kuu-mxL-VuULG3FcC1!|Q@=|XMZr^? z6u3mR@Aok@saTEG;2x5p`#Qov%K-8!oxj{T$ia<{V>DQwvcEgN;oR&^+^};F`K=vzWM<@nrutYm=<%I^TR-l>#vA6q#%+OkN^2N9FZ3cBb$${RYz?8JI7K#cH_!T2 zyT(p#kz%VqEF_1`Lt*{h8{F&;Q);)mfQk*PG0#rKl0$So-D*`tyq#@D8b=ejwT9Zj z4n?uw@=NHQum6FC<|gR-)J)DyRVTqbKlOYD!{$irq;+*WGu)S#c;3sh9TyUJfyDM4l_(o!dc*ZbO-LiojFys-x8D2v6iCSgU4CZ z_p;QvFO2)p5Js9!3Pj-_r;~V(61E`2hWvJ%&&*wT0`_T|vqNddAYN}H`hK*Uxh3mQ zYIcU=hFJv0sjU>{*DVL9uyB&wZ%xw;ZeR;v9oiBw6Uzn!(bbcL;F_o`+Sji`mPRMw zkt`Lui@)pNU26&xO4F&9comtlM@n=_DvE5}8IL>l#Y7(3AIbhQHPO;$O~PHsBVX^? zVexTextn5dX_C1ng0lOpXIvz#_~uCMs+_3m%6L3eLWA}TI>>~Nl&ifuNF*l)Q@Tb{ z^t=2Lo4fcwZZ!{*DQav-xrTp3u{*bP}Q?-wRT>z6b4)ORvdToUlIr4xzICsQVBpq@Oq8^Or!EJL!1 z_GHGd|H$|DRN*?l#~brOk6xW-T>_UWowV ziT}ovj%p(G54}ruZ|;ZhajQ7*g9XA+SCsqzWQ7Y zp0l4Zty`HJ8}mJDguhj)wi2>W98fT1)) zrtG-HHq7pZKOr?tiL@r9zSm}E^*zB-bA6%o>=!KAn89>UFA~Za3xqC#_i@DHKSEF5 z?KJ+_9D4iJW#PwG;dWg}P&GoS zp#e0eD1h&YF2{03Tk&<#N#<;59mtPSXXW1o2|XRMu&SjI@rtd203SxU*(-H(i zs5aD%oODZqGs7z6nZ_&Xaq9_dn|hb*{v6JBnH19Z{W_4VZ3FMy#KGXBAyJo=10^+v zO{n#z5-We9S=ncZPNN~QTI@t`7n!rq*Y2dfZ(h3Ea8+U>QMmqsIa6_66czV?j`?pt&DEACL5)kn^O!%MuP=d{#XpFy zV;c7*oX}~;uc@=3h-UcD#NQV#fvwYS(4Sx5fphGA@M<|mrdjHv`iN(+xpOAm>z@IC zjap$YpEHTMGKwxbu1nMInv)NmqeRiiwz5-n&1tNdFXy+4BMNvgU(Y z*a^a!!@KH1p(=xkaCk_v-pv%9pYMhz#ubsZZ9RB#V>o188KO<9&mdY$pICcKliw13Eo7QCBE zc57whyuHQLOZ5ys>Ln6&4M>o6KemuVTiglO!9-zsF2!01bu!NAzwfeevTYn4EEm%B z)1mnJ^Z}p?jNpQjBFFu@L^hNMP`TO~I#PawegC%)>E>0CEu9>`#Ix1R39FCO~} zJy!GzGQ{Tz_oTE4{%Uojq+wY>IiHEKbi65e!_+Z~^L`38srBIV=PJmHo03oZWGu``;|?QhX|-yG+3L`~E|Ac0mH8y<^GWE8UEaP>K|%k6|XSKZ^pV zm~oMD4cwQC*}|-(lh}gKVidZ*F_-HZjjX!`%+irbq)E>f^@d6bNByb9ZA7Zl)b$U#Z7@?{P;?YkEmIH-#i53y9J6r&kK?Z_K*koAX2-MPDZ*71wW<@pgixF0_U5KLXU4& zDBL4iuzzcvS=C4ec5)VAg|`NnDeFaZ2Q|={6%)y7|78Nx^{(vJpcF^;*`p&{52;z|Z4P9!(&-kO~_Wg_%w8;vjTjl*Y&Csi$1 zVSfhiCGGo^*m=hd>FSOgQqu5&Oh||#E7C6D{;FK!*%!)em*|9^neuqSJ!`V-^(Jia zx&mC}%9&eTo$&Uq8bx=~z>Ig8wT|D*txEbtZd;lFJZoSAWKMF^-`$7TPv+qBRm+IX zKTjquPEoXa5Yh8OW;P; zdY+-o(Iw}T!Pz+&c1&Z*=*68}*YC*??N&`Z9TdRukQYGZ3G`<|2;7&t0aps*@P*XF zv@bN5DI@#gY7t^ROWW{ku^f7J7tfpE-(PjF#If3vCZPi}4bCiB!OXemM!Hv=p@GjF zuuIQ-ye@qkeoIHe&*bIwn&}j1LG6rX zN#Ol)NP^FMSlNhpo-5C{QYnOGBMekriJ}*6-{573KB5WlHK;?!e%yS}kIH3Dz{?+- zkeaSl#F&3(bq`ItO}mB@B+uZpCSgR(CmfF1hk>hyC(pQ_2HvBe5x<*z**&=~WbxLo zu)KhG)8GEcTzt~VJ?V-fPAeCnb`MQ5$JH0+guG=9%3NuW_7oap#Nqx2X2feuIlQO< z?&hax+R|}`y&G3d4u9OtcK<4%%6Yl?&ATwtxW11pnS2v(-glFvZ%Saw>-4Fxpb(uG zTZN|tea3MPX7tEfF@9(G23|xs(m_AIryGBa_+_ba)6N$|aFP*7{#Iw#KAO#)ku#tY zs^VCFPa$!NzsOu49xJ+BpF#_tXi;JtLAE4?LEh8DbVPPFC>{PzB&#!6dgUBV{#Zr# zu|_oF*&*Ecw+;JG-$#94oPn6udcIHWMBXJ|Wcz0!Q0%!t4n*A`827;v|I_HqW|pS4 z{|0V`D(?QTl)Cc!{eO3F!>E5@>_OQF_~prTdM`|cblBUn%>Ec|y8jsF-~Ov`v!IGO zbT5)@RFM(6DQBW8-Z`MWm*VdJR(RFxNcXj!1&7f|$nE4$xX}3-&pWIS=jV^dljYYz zxs5U%@@$OFzk;z3>^1_zERb5In{#7s9 z9#Trx*Qc_ovXf9s@*eoJ+ysioYtc8SE6~>WFHzwfL*jTO3>;?_!PiGoXm*e@{Pw#* zPE^;jtChAB>4tSQdb2YfDw1cdH&&u0y$%rh`#D`#>NwgDe(3t*z6lLg6pR&mP? z-4W;|%*Guls;nUXB)=2BC}=slhZFO>COG~~j65tnLI!$eP(*}0+SJ#<{mRhbf_b)m z;(At49XDNY+tv)fPMU*0*Qy9Vjmi$LK4gEwXZAOsQm0wyRj36w!*VH>u)4`} zQfFX&sY^I(il;#AK@NI)wjX^tn2Yu1&BYZfn+1m5$+-Mc1K+FR{hxPll7EX@grhP8 z1xnKc(AO*4f}`hi(Yqa1g5NJ}gi(nx*w{Kq*z`Rfaf3@(|CgC;da^&!ynh-iS43lT z?>(&T< zWPcM3zjT-Dn|i zd}fh9Hh;*-jwg6hVT&+%+&Mh2DFc`4w+izvxw7uFddZc|%a|V_rhEr(Q0Ou}3le8V zK;0={5T0#AGMXCv`+NfwRvjif{M@WbcN){IGzEg%^FeQ{EUY}%g|<#BVq~=_c=Fex zr7t!@^MTd4e%cyFXX+9>=iW;c$Io>?@-7+a&7-+^<%>jg+!@TS3YpZ2Ij~VlS%`82 zh?cz*b55wk1Z&j7bjegS#^N~BRWHp9El3e8HRj*XOCJiU(L`c1phll0RIu)n3)t0Z z`#FEra-uz&=SP&!!WZA<3m;F_1h=bgc)fn#}uSUA^7?ge75Vt z{qKRooX$eD(ANP^3hZRs{f^^wFFqR*?aXXCdmYN|eI?4gTjZhgJ#=8=7kti70bjSu zrspaY**8{%*>6ec`Gt&SOCFSmt;F6>ebC}S zOJtNPMdOoiG4T$g=yX3LxF2c^PS=CTC*uihr0GKZ>c8c1*u04ukw3+qS9kzA;)VE` z7e~7F&oS3VJ*D0rW9UjfOB$iJ4#yksgMZT>gXY>0(4N~#Qk>7QZ|v?t+Ill8KF*e2 zZVJX~Zoy>63Kuvp_Y__>jiL8k{{MS7us@o7_-x*5cF%G#$h0|4#8oqpoa$H7=YZ(0 zfc03v_z(@y8^?Hstblx%FU;==48CL4OzZdZ&h}}G*gESR@25@7>1M^R8#V$AAw_ok~(~%>nZkDL7~QlQyTSkb*x?k(9L*9Xe-*H|iKb z%xOy`6LJ`>P`4+KEhPw>`3>s!w{Q{*4cLpuPl=U%39Ji#fQK)9L$&NQIGQt$Z2W$b zRZQS#?Wgup=`ZW(53zept=oNMdc6&YXz}yNHJ`Bf$~WLR^D4JOaD;X}cnL(bI>$Yc@ zC`E=I%pGA$U;0B%L$v69embJdr^0FPy|{Qo0GvE&Em|?s16dX6WG>IM+r*zCM$gyM zpDXpq4%4&Lr7s&KSIUXLhs2Y$WA@-ZDanvuGl&FP4g4JBDK)T31=nat(a8;&`XQ#yy+rB-b`iG0iu3#0YGYBUd&2D6wx43ADff!n}%L+BCZvpqinl$0b5xVWZ z0r}%Kl_q?21?_Xz+`s2TM8V+(z0`k=c9x!JL#!s@c<*R(Gdchdc1rMm7Io@dU^LUdN9%xNsdgeDl^_cO5$I}y=Id}0k zK_X6VQy_D!1k4K62#Bm6WMv-Z^YfFbJpa`n(zjYO-Ud@)mHKZuKe`$wzq*Li@>IB6 zi~Gp-J;_9U=~zamU^G`?bO=s7bwzF$Y>D~15h2X2qMZTqbk=$|Fj6YS$@kUCI+ZLa zY>@`3pC$NPN-pd8ejDK1I#kBs6wG~OhI-^C6VWMSy6DwEG8A7*bR_HXs*q0BC;m#HW=x3{wK?cfX&s;a@4~g!Tk!X)iy)ri!0HBn<2EUU zVZGRPV%)L;$lWxw<-llY9}*EPufwK2QzS29_QI22C9wXxAEU^g=9mz5(lKc+x{K5B zGf_8@EQ?|SRR+O&$|tCHxsH_Vw8(=|y0Gr*dS>yf+hm-|ET-mZG@E;$Fy)t1Ami~X zu5#C2d_6UjQ?5FTuP@z-VipVu_xtDq7qpsbl6Z}u2m0cUcOzuRt1rUcwmO94dAOt9 z>!4=D53fCK&pmYDxdQLR@W$827;R$_({Vx;22(z;-aBPTQ0E+BNNgbO^#2O?@7j^+ zlMToi3pMh{;529q?;tYGZ_q`dAxlU)jD7kGtROfV`0wc0@yh#n$rxpfwXnYAV|T7nWrfU?E{2W zoo|8Byh<|m;5_2u%@5Qn7qQ2$r3e=)<~}AH#2cBJzG4t(t}VO=Pe?>-EcCaRlHmijIH;B2BLnQ4zIGA@$nifLqIeip+Ir>`zF+?=nq^oVyAcIwS@03zsq7{l1V<5yo0aRG>DJhsU^fyY8siEL}e~>0`ER7|}WP#EDGL=*8B~8O#a;dsud9JBRFdvI7y#>851D z@+sW*cQ&N@YcXpe+k_uSXM>a5LHzsuI(nr%8)sz9L_-UY(}?!&{>R*2d6DTgZo{*!tw7T84t&2ok(s5u3FKm%xz|P;*%IANq*LcT zlqGw>-M9lx+0k)m^8|{92jY?ak^thh(hA_Gh&f#24nBnk>13yT)S%2;r>F7E)Y+|U z#3xPQQy;8PSUeuOw~-043V^%Q)NtU|MPzg9Aj@g*iUPX%T1HZy6RQlfNbtWa-2 zlIhIvhoG||=-;PQoMAYK7C6iz5xY--k(w$vZ8?KOCQk$5&>^h%LJaJGM4_lTsvukW zk7Q?tkr$ekNW$VVn)JOFUt6rg9bbBh(@z~%}Ud9%t zw{tx2w$0_%{>VcfA^S*o%2V*%>(0dGzlM@Wne=Dfd-yy8=+DCf_G@++l#GQ7^>75iPeT0kzDO6 zc3_naeOg~l&CDiJQzt!iX7C?UP%5BoKsB=bu0WR6oMTp4PG?s(orhB^yx^T{Do)QX zfUr|6lazS{Hk%_@@1f71^_Qv7E>qUx`!$%s&o7=mw;_jlKGftf@9>(#Gua0&X3z9?hZzbBLm_6T9+B?H@Qv zm_u%{BC{>A6&CxihM}tysqJtri3-(07yQhKeBKJ~{45chu$8}qzIEn%)3d1Nob70K z<|k&OZao;KZ)1gKL)2!095;1d5NB~K9?LCSh_^Lurjhc)oa?)jjQi(B#Anqd7oY@f*IDpLR(9UV_@S9HVqdwERd=L^7gFQLODT2yb93t=)& za$9;g0`#9C4iSf#pZYRflJ95O5TM9?4~!yK<5x3kqxD4=3s%!32cE#+&Ko%AlrhL@ zOrtKfPe@5bA=$mDfN`%S)NweLCRa()^nhcyS!pzbMv8*aO{FV^*G1HgC0mR zA*-n=dq<&?tICpKX0Hl_jTa;skGG-Z?7f#%s!A3gsai@(URYy~dCMR`*Pd=WITxO# z9YJ2kX>jq&Eb?wF-%YQ4h$e*xLT^w$47dIQF4>cu{Z-3$WFg{Soxr*5d4Y-^UIgy3 zDyZHmrKesemh6OBCb6lGy!q9&t7Z--70Rn9?F`nDNO zeW42Ct5~$lgXa(Sd4afsGaR4+G)FoH|5|f~de(-}Hk~+fwqujXPhXyEcTS_Nr{;5` z_-_-JFBe3Iwcp{}$;|&)d-t#!qW|wZ=}aYuP$Zp8Y4)C3Yi8CI=|F{u{-{W z{aI_Tna}6_dSkC!R^qP@U!G0;+zOILMq9q-!-(SA3i!*aM>xMej>u?!Dtrs(ftxFi zz_w{-z;GZRKXIl4SWGOyg;=6g*N`h5H~9saq`VtEmbZp);vV9I*Om+2Gi!;)&#Q%f zvdTp3O9lAt*jwrIK?D?J0erAPSLl>D9d`I!!2eFJgzL{nlFd9X8tqZ=Xt;=sKR@#`aRMO07-UXJ-e3a<>rAT79tf;jV$@w$BEAZ@bLWql{7PRSS;(R>38y?qM86FX)p|7L3O5SbkX%!{zj}(5vPqqIjiO zXnejO_jsiyciev>b7XoX_ov-c(w&k@t3OVWyk3vflJ_#mdGgn7!qJnEZI*tz;iIQ9;Y$diwAJS`w)zEsaQOxjC6N$>YC^4I*E6H$NL(2{5 zum_ts@zedm;`)PAX%%fX$;zvznF;pFeAA~J@T8U}i@z5l^#fC>T^q94^K)C!E3K9M z_|6N+YXOw_X*N*%)F(0a50CJL%b(Ksw-z%~Px+!+^A_Z2x0mzXw3_OL(k>FWgc2h}ZYAK%Ku=aUJkGTJNTda{EfC#pBM=udY;5cd=G}bgn$V zc2P4QYV=+_eS;EvYU^mK?ZFVbCupMZdY&`z5b@ZLIHY&(2cH%wKmonAe7lSa*Z6yt zq!w0jKL;2(^kM@#w^bI6lpWwrj^~h`lCAuoAXCZN;8MQNW{l))xiYQfr^;CRu0dc* z1Xcchh_>wjD09*%DrGY1H z{~Pg3{3m`NpZo#rhDyPYTdTmApL5~Rgc7Xmhy@;SN88f9M1&{AF9vR%zldPXS`ajL zK)T172yeum7oJX;33XkML7%2^KpxJ8>DsBF=%Xhd(-cM&UNnQLZFAwhYXQR7_ASC; zI1IYG&knN|;=oU$4`Qy6ABNm*NH0>^>)oEvyS>Jy?*{wcV&Bp#a1K(KSgENI={0t6rK z11C{59Lek=($o@R^v>nrS>SvyAH5@ftOZi;X)_4!_zPS_)^KTD{NbNLaIGG2!bv}6V8^)iP@VAKnTNucghRyOCuJCJr3)Pt{Xn$Lc9_^$1l1pY2Fl0EfX%fyxJ*$M1cXn)7qv-si#ry8 zxsp|G%-7RrNF!K+RL{rK z9jElrH%}|ZVNnF9_clUWLGg&bGTMoWTA9eu^F!zzdA)41OFVk9L;>xk%o*8anz=uv zQv7e#a}>5W9El5k>5O&>ol9&(m3ANLw~I1)(3(i+Up|fW23FDA8uu`|H;$tjD>G?V z$6oZK@GQPifn zN0^eNVtPfuS`MW|A-&nkyh&paqtjxK?9wl=<2swgvRg{YDHEr$1zH2*v1~~naGQDd(iPehRl)+He8>Q9BL+Y zQSE6t)ZS)@e#^Kp#j1IdDMhyY?969e*oc+HO-7H}v0RTTJu#W;i%+Hs7n(?vJ}%%F zKHVj`QhNggYFy(#&0R~L%^WA`Rqv6!^X2(~j-!&%H>+v+6W6JW>WS=HvjWMwMGqtg zXX_N$mkaO&Cla9oq`mW@4#%>8$QY)GNK$f2%uHdZu&v2pN=JGF2%#n0W zH={#5ELo4zD}3`dz&jl3luWsxEm?W#GdFzRnG?6TOGb1xk^ic3)P>_0Xy@)$_WcA0 z(&|JK)yf>B@^{H0!Nk*&)f1mf=<*`IVM!!q`gW;!?O2WzxpMRaOFMqxbFajBiX}hC z$_Mdh+$4?r$4YDh+qe%>GGpD)74H7bEI!|OnC`+Cb1e=1?9Uu`-l^GH;@hDqanlQv z{1_(0zK!MF4l9g8N}S}FvW(=K{TBY?_CJ!s$Zgz>jtbg!(J5B8wv9g}lxev0Hy#zA zFysVEhp0!n`^2y5a7s2fPckEErsRkW%lkckL+j2e;%+T|+@K>@JJEZ~Ws+<}aq+{S1|4&iAJ0 zbQ-WNAHLE-SKjcKKtepAUyPK4gY%|O27 zN!s7pm^t5(ByM@FL#a=Lm%YU}?_srX|2)zAB=S$qE>HQ`K=0NoUV%XW-y z@iThN#xUd}7esfzi)Uk^^y$9|Gnot*Q^sQBE4D5rnl*TbqmAJ)?5>8T%$^EMX1Ti@ z=c_#py<790CPPZORF4hxj^JgePd^xK`sYedA8KJ&WweU5uoAk=pc1*%C!%w)&9twQ z9dgH`2wX zYVw@Z?qqTC;3;m&sp*tittX?*O{V*Q#?vIcg!Cfyki&f?{;rc2Uq!v*JPMVNe}^l& z7_G`T`!1rrZrF;a4bjNBvyz^?%ZMqxHH&q~>_F`vy5f&xzo7Sf_n|pw>$temMpVDe zfZA>!!msy=N=M(UUH)&sUrki|XbxPJ6Y{^t*Y;>E}`O zJ6#rCzfyw+cehH{!K1YCxe|27;tIk~WYM=0)x@zsQc>RI!>Bc&n6~ww&CYLpLFqI~ z_~joyf;RJws1Fo~Z3dK>g<*l{QQ87_ymKi1a!Ws|JE_XZcDA4u-Q&5)YB6m+^qm&p z&F0*73+Nf%t@Me3Ig)?-BI*7*bu`W}TEgC7sCQ4(#aHz#sKBGY#QuaGuhOcE0!&@X1a!)+gFM(H^`Hye58cS*R zPJ%gM)A=^H-&~jHAn#FiP-41kkXO3%gCC#piuMV4%-Up_Ug+Gr}QrHgc5 z+Dq;VCnXzoj!7(@8%dS~Jmfc&YETyUq;OyJ2kheU_1xTy!)(RLYm&zy3EZ5R2wr`g zs-$hBHDB{)KezSQY2I_^a(eMBH6Cl7#d8Ob@s=YexyJNAtn21#zI9DKe?7%oVmr%< zx>|FW8~tREoU`)+pL*goZ}2vTw*rO|<;Ca7Ckt6_@!VCMp>HL>T(dw@_eRWDtqfzQ zJ$*_3`goEW|HzbbNTem{R{1=0T$c~q+r&2m#EEXq{9EPDN{ zpWCkcU9={nnscmKN?kTDru|b-ibYo@Fw=MLqmCTNr3hrX!n%j3l72BM;j=FsS9SbjuX6xyTulI??&+DMd69tNPh?E z@27v2Ujgr-NprPCF5WrhnT;{@>DnNwKKCx|`REusqwg1;o>D;T+`Z4`cyEyw+$f;Z zhFlQoU&-%`?Lja0>2mhI4*a&KGudw+CrOT09wPl~zLT{(S@M&m2Kmssf*-rIf&!ZY zpy{*#3aTl~|O>wK+C$%PJ5`>rnKH&_O7Tgq|%`;HMR z{UApF(0L>7wNK(Ubu8yAKC5%*`$y={lma?X9>bp}Hj~r7#qhUb4VC}=C8^%<4Hn3g!WT;fgNIJ!0b#ExE%L#O>csw7W*vjXdj-xgD6u23W49O?X zX4Ifw82Q@NollD2#Va0J#b;)#@U}1G_^#lG+|Z*1d>#IURiPK~nZq0S$(!f#m%cTT zi#I)_KY3R1aKxC`d48X~8D#O|O5)jHb2a#=Cr6O0&QoqhXDIi{ele;K45tbSdnQk<6a7s{0Z71Zie?s=Ntfd^A{^qMVyE&fc*7qXQ*`~|{tyAb(3=+HCk>_fo>P5f3 zudv^Bx6xl`E@y_G6``rQb5Lj(j{0xuBgyQ3v1m*cO74zitLG+hWB*z6g>=XR^uO@Art9V*Y>?^9%67AK&rpl{UcntpV2{bZyuU!VD- z+lUJHmY|~EUue3V4w}+9iq|eLXMelLqx*xI{2%>ItfS9cu{bY@N_SX<807#q?fXmm zfa^q4=DQ zOsJCuitYZ(zEArjwiW(HBXbhP6{0b8x#W`g`uh)J|Cv|0-gn~>+pED_nj$*4Z8FMV zUJn;rD6qpmHb}`cfa-jkNOulRMVE@?sY_dG#S2~hQ9I$q72j5-mHn4d6Vxa0|5i8C z6#A*uH?_n-Orf? zujjViIE6xt=W{cPXw+(Qf>qBtg)C1Li8otnGFF!=se+U*@F8X>I_6gaeq!Iz>StMq zijU=7&s?Hc$H|G6R(eodmu;mx@_Xs~HOkUB&PT~pV^L<>X|!mi2<7ZP$t}r!KsGDX zp_753+_Q*FXfVMJT|WDqlDXSUWBMuF{M8fDR4;=2?tX-R*Q5h(N#|qTgG{hu;V16o zcYmb&UY1V@59d|w$I?rWH_^tiIy{{ng&u3tNMU9)x;JeG-7g`@tFKI{#B^10_lNtm ze^V+A7VKs}|A;_C?Jwyx>x&rT;)6m5qTx9noTu!oukVZzoSELJfbTDoftG*zz0cjQ;TQrV@`j`VdtkGhZow@*~+9k z*2XiM%u<|*6cwK$^u~s}n`XqkT6lxCF!_K=CIvC`LsXdHsV^AYO=FPmY-`p=ZHUY1 zi)7k!dYNgC|JVnq*(}rZmj3Z3h)SK2&5T`hm+4FSh|Kc}7(Y0Zc3l68vg`khnljor znOQzuhzdd*N22KI=?2WbPrJDNp=C^6)jY;?^b9`JPmZC2{E+8K9cJnqcXnRNQ6`U+ z;pB>{#Sh}+*kQd$R`uXSW_I#Zrc+$V^we)-j+(AzIkSsoN)nl}{8pj0Iq28N3=+MXv?wx`%J?AjaNs08#S(VH?+gSEmstS`d z?7}SE7RKP}Hdd2=M{5>;^>dj0op+G8W;=UE`wXRSyPJu<575DXpO~Ga0vX{K z2`!(OjMjbbL|x1wCh}T7`+L%ACPsS#*ZKP-+xoqU)iG;eGwwV?;amh05^#&rw13RJ zZ^&nNB$Mo)_zdb!vMQPvQBMyXoMQDjHHVoTK9A8`*H0&RVn}cG4%FXV%fzfl=!s4( zbAPHfe=#YR5frT;y?vL^=`(T>J7xs&%fB#*iN+xxMciR(VkcnFs> zAKuU6&E^KQlQ_dP5pS3`a+ml@I|aTgeL5=mH<7vM|5E(O2QbjR#3)nkBN$iQgS5f@=JN%Zr zw^3QuIKKbADqoNy!(Vx5jG7}pb7Lwp=uS~NYFE94MCYf_g%@hL@A^i3SxX$fc5@tB zIy_Ts^y)iGRhOx|F8`aeu6;-6cmpYEqJsBXug@(m`zD^(C5trY2OxcY9tC<%W2iA^ z+{9_};!KYs_NDk*z53-n$S}~AJ^P(N<4RYcy){2*+oacgap5Ay@et(Qg5?+{W)w3z z;Vs>AiJ+W)hWK@ZchJ)db9t}!&*DvAGDOFX_ll#QJx5jHlNiOZ@5IN3y_vC_r!pt@ zJP^y>{7rXxb)$?EŀDX8q)Jal4GCq4K2DB7#?6Swhx2$Q=<`kpO1g1g0M(D}NW zY`OhZ%0zpH_{8uD@!|W<}0t{xR?4fyiY4ReEvI_!hym(<7hQ(VpV(e$T1clj!pV6G@o zok5H|%CT+WGBp%w!L?|vXO{=>dO40~Q&g$^_ukZ|-e^R=ZR6Iz?jRL(`}k>Fw zPdI94K9`Wyz~NVJk@t6mb6RDs)T9PneCJFCz+}gZW{xvN)p||z6!8UatLH?%cn<*s zjNijU;TPBt)jIlKc`vnWu_3oW=M=wrQWi37oXy9}{G#-+iD+-i39a&Nlr_6P1&&{4EB(T5ZF_;43;a>%D|&xs`0jH#S*85rlfj+f+oK!rQw_<-0$ z{Mnd8w9SlSuD3;vH8dQJVm`g373(WdyPgZ`a&%@J9G@ZI8X<4K;xZkyc!OwjjTO!9 zRzSWsx2Qqs9F#Z75siJa1TDiJ(euLE#0I*E4tU+p&Z-XMTQ6r&9~vyV$;BL9=W@QMn9E;1FwPFHyl$X$g>YyuW* zGFMQLRfAnsS|*TFYXM#1xx~ore_(!+46$|b2Dt0xFxHe>0v_kwf}J@Bz|S9AWaN{j z#OVoV1^(#|aYv0_DE@0qPB9%61S;$hE?bfhMwQ>e7sdUA!bKGM<#!#>@2Q2mu)D;Q zb4@rIS56#e`oX2x*`ViJ0`WUlEc{-Z2sD?U#Z#B{!7P0PC>SWhnHMv_-{x#^*}@XK z#;w6@!c5?t{Zh{5=X2Pt(gF{YZ%otrk6`e?PoZCv zB5|g^3ip__gG~M-=C-n=Q+FJPZ>wJrnH?H8QBR2=Uv2w zzgFTM8wY`&v{tEBMTUIuq$;3r6EH_!1KVm{2=iYU!Ndp8h%wsE%$Z% zs=NU|Z0IF^UcteY#ag8Q%WTZh=@%yd`6niquPYc;H3*8uhlo%GHF#~pZMLY zwoD?A=SGkwc6#vH#V>FdkPt4tVfZ}xd&JMsF5s1454!!H5LtiR@h|7k0a+g%VyH=l zd_I3XJiB{89xKuUcPGz=3vRB134&Ctx@;p1@beO8$~t0y2THMpd16di%)lI>Ci$Yu zfc$g6F3&3k#J5Us{5XY3Is95`70L3JM&Y6qJ{N#VwRQD*b)z}adYb%rHYblt1 zAeeY<8%8?rJ%aC(!3f&!A2IT|7_1&HAa5UcgF^Wb;pG#Vm~pY4;OEt5%xuAQGS*@` z99%mAzENg@ne_wEU6}>Xjwq34cOC=9>*{2nV-_5~Bh5b>Rb%!{H>{I&1cQFrKsZPW znlB4VPCPYQf`*Hjv_quU@CdvA_o>r{X9Q> ziXm{%GNOO9)Yqjv6IPw8gDWoCL(`RSiN2+_K(+1@WQ=^U&FyZOwel@&$bJM97F-3B zZ)_u8@2UZ(p7`R6p47q>KDn4{e<(OLVG|Ue%mE9Bw8;r49EiVkmB3Bvw{|f>j?9}j zk8HtW1d7LL;fmddf&YvQ{Md=<4hyCc~9#T2J~|KLYMX5qqFn@Li2Gt4m) zfVKawg43fi2>kvKZmxJ3o>-rXyJ;svYmXA5s(dy$DCLbU+OYty_6!8I2gZO))`q0x zj#O-(?QZbGg zr&MFUYsU$i&08=HhaG~T7c!8drV%68RpFh3r*L9Q1!Ojz!*mB&AeU7PTd9v=zr|8g zE3=Mp)$v2-Owwd7JhdZG8@-5tE;$%{((38CUn+GSpG(v&s zF5&B2j^n9gfSX}4IQRZ2F#F&o^{95laas{ZRlmmjl3v2@1q)!>vitbRqtoED$!m~f ziou)($1$a?>tL?H3U6_8#9rKt!_;4=VYhDrnC3K!{I)=jY<->pCrm$rH6~;U6dN83 z5AMvvCmfrHTRw^=Z`p2#j9(GJj#|PnsV}jpc_Lvsc^+)0GVt8k0O$<+h@`Mq5ba)x zAIlEJ^=dhgXk`tKq|GEZHku0XrAa_8Py^eQ*8&&$Er4;~UlBPEZOQZvEASnMj^MjY zEJ0q-Ca_I(lH7A89HuUG5NhSSV(<0G312Bnu=fhrVJrUuT=sbl-X^qz6z(!ek2?l0 z{ZuDqOs@muA9`fbm&34DTgtgT`4YQV>jbmdu^{kc7#PK>3uLT&@M`bz@ZZ#H;F`g0 zXiw&1-a{T_A5#e4o>dd*ubM~H2G)RaTf3m`lyKlOD13Vsl z4`y`Cf{9^^;O5&?ftIzjj`_q#DV?tpMC2*}+eyoals!N2NLv{wd-n*Q zl+8nBXe5o_1Neo$I8dZz4f5Am!}3>Wv2blKcvny&ocaS`Yi=FH&YX_LipD8I`^)EH z=eFZ;P`ebixLaUs>0E(d?;D}g9~HtcaZsq=znon4ek*iLJq}zq{RYP@#}W-b^2A~r z96BDIfh!!?2%kQxAmZ+eL6=7ak=a-vT&fiSKDT`)RL@N%f1Otlz}PTwbxgPA#r{e- zV~-gW%~l|`+_xY-&J%b}{3|?LCLFvfFakGMN02%5!yxT-LNMNT2bR;^BybU(#eQzO z1y7kPLP>-&JW(Kvl9SykY1p$y#5TmrIu z`ibbBvVy+!FuZobC9vyv7kIO!4*vYU5i5>gMb?oq!0w;6Ajw{vNW=ZX<)0#GyRi`7 zIv7D5OKT(+?a3tOo!d+J1oy%EnqP3aRwSHZ2wIFY1B+)8A0v zBn|3rmIWQ};xKfbh8sIE;23BJocnYHOK&g3ed?M3Rs4x~wDK~%@g^CY^}&Y>$hZMq zdNQ%8HZpW7UoW};%{>Au>5#YC!1^M+z8o2)NDBieXD^xBo#dHoV0)Gt_!piR_ z!2QE&WLc6a;bl(?=IEH<{;&*=UiBOPIHfA=xqA*XKP(T>gPXYX%RU(AKZCT};srML z?1oFjod{b#9WTD4Eam^K1Ra3|M3253ak@_vuSiS=O_~>kZ)c=IjmtyePTPR6bPWye zYaRus3TDA;BOchpC;o8GoI0WD&mY))Lxk;Xw87T48^FuxJlv0`!R=KmV2acmX7)#c zaFI=baPzP%er(!NoLgv5CiUCHGt&8=*?bcewNgaPN2v$f0~%hJYsK%l*}#LthG1`? z5M&G{;;BC-;w7UqfZ>X2V&8;6klAqyTN=L)^p4{#7hem4cM`SX^xgzw^3R`8Ak@LD z>~9F)JSiYHJ>CG^oE=H)m1?kK(*aC)Sq)oP%nQag`(cvhr{HO85hx~4f~#iN!I=pM zr2J-6*fi=Fbbq-U{BwT-efBxSJkd$wvDYh1QArt2V&;M$6~%-(c#N@Ev+x;NDc~J$ z25LlwQ0>4RY%ZipdB$C`4{yz{Xgjn&VgQTBKEgjPT}ue`t%>t;u>=a; z2cMb5!*3hU!iy`Lq?QvMMC8rK&@O5j7I#uf*yxsxJ^ZL59JyN}<%Rf3IjWC9x_2b* zb<-Ih*U!h+^hW}hH+P|4Y7&^Jtw_!(Fd&*$4-0}-l!>(lNpR+zAt-*lL~z%4uP|+` zDjd{5gDdZlIU9kg5q&~ls%8v#-giEy3ILR^h)iS>nLc8~DBvA9C7^OQ3$uLGbp2Bb@wv6Od`K zAhx{HfD=e9JPcnBD-U%MYi@dix&4)R-q&$@#7-CYHyynSUk z$|(=l%rSxLUtI~RX#!bQpotGg=nw-X5kyr%7?`kOF^S9k1$FkEVCOlAg~%)sd~?}_ zg;t26(YsM_F!Ul&C@Tk|qsKuIPQzS>TTn-~2z2krXd$xzoiT?QeGZck_zKYqp<2j6Uc43`M{!J19lrOCAN`wfrZ-@7!#}x zA8mPxFKLb?%BcY27d?)sQ?!G(_pOBuU)|uLlv-l$Zv~(bZ$WP4Td=W}wt|0$rV3V5 z3k2!w6kyNpSmIgDcc9|+7a!6ofrq;|Ol5C17&%o4<3D`{>n+{MNs(qmzu{T|rP_jr zRcn%Y3hT)gQm%PFC-r9e<_)@pN%;2Vu4H^!2$@Ib0mXp=*nlbtmfVF;shA0D@3FwL zgaF$X)evBBF24WpBhVV1f{TK$K(_<|9N&HkztJQ0SJ?}Jz56cM^|%JRk#QXk*!chi;)$vwTx@gIT7`1}`r#H~$!gJSf?4>KkyA?PLpDezBhsu$w|=mnkOml;DPrfMY8Q` z1(Z4Yick*g#A4>_!N*~T!Sf@opyVAc7~d}CScHy-cTx&KW%Mu%OM4;pv^+wZ?*9e~ zJwIR{T_cIAn#*AL;xqUx-2(;>B@kc8RKg|v0kK&_5iF^UgU?z%K(8%#;a;aN#O|H- zV5y%QSr#@yVEfQqDEc;9U|o|V___8xyz07}__);;dNNY}5xNLVp8`S9K@L3ZRVHUm z34kwGbdWz+ydp9W-x8FmDiEda{$$0|G;-u^mw-vxB)oa~0dS1?g*ye!C2#fLBUPtv zgTGHHlj$zoz?<4Wyrd6-!Aa)O?SVh24D=ubej2#N^1aZl1QBL8b;#q={ZqHI5up)o z0;u*1;FEX~zRYRD>g99bo?K42*7i6SxUmCUz5fyRVqhM0x^7MW0Z!ya-%s%9frr@m zr;7v``+9^eXVeJ)FS~IY=jYOQ3TNTBH5fc1TnvBSnhcVEiijoZ74WXrQR2JyBN#ky zm~iV`0MCuQ#GfoUh#RWNLbEBwz-(<0>6A5I;C$2vTyHs#y|^1r`u)BQ-^s55Z^m|! zQx4eS`?qW+zI~qpg4bOFJ8uq?YpyoIO@ADPO;Voa>m@aU?&<1+04-J0d+%9jzYW5S zvJ)V}Vh)TdyA3Dx8j=HL^I$4kO{!a+fos3&flYNGf`?TnV7&5HVEnuf%&rR%7)M3p zx`nGDA7ls3Rjo+f#gDNs+4bbMtU9o}c#gnjb0QJ0dLQ^7wI#=mj3PtjmV%+cHK1_b zZ{nZb9N?y-M!Hukk#c2LaQs^z!g1IU7zpLbx@{GhYni1W`|u4+XHz+*7AFVK&eA8y z7FAfk*@)C*?No68v^uiFY|Gld*l)iUspObRjecE)#vax-fF<(cRlzvP7@rN9!=a_ z>4-n6JOjQ)9K$u{SHkdqEm*!a6aOiR0-75Qft%?v*l(JSJ^mU6wMthB=QKUX}j%(z-3<!qXTmI(ZAU#XSbR@-y(YBn-aLHX^4crvuG9%4E;a8BjShk^sYm zASw3)@GlPnaW=ZZ*!U0TH`5hAyYMdPsJaR+yL7`td7+r?E_;&RT?baKtH8QlETtU7 zaBwB>EZmc{5EdP~LR?$nPb~N%BI4&M0)5X^*uCl|T(nF8hc0;%=YEU@GAZ|9W^@ro zIzmiwdnIPoei;i^>H)78tS8c7DR{KG0H46mhm9Aruyvo71AF;MSYMn1u3Q3S&$+v} z@j(+|`ny~B!D)}7Ba|a+bG~5nVmAwCQ4_&jhYB34ehOVP2(qdA3D_}jH5{E&LI~$> z#0|#pCYm&_0sGdeAWJEP*r6|j@9FpstR5Z5S?vP2m2`Z28#=PFn2U!(AEEi8pg`#8yxT{MG)I2sJ*L|IgySw5J7_ez25W^=6cgpFXs(|GJvM=|uAt^%b3dtiT{5qQ2o2IveYc#*gO zQ#2ca#p+fl*yajLM?EFxDC`!HexE>)o;6S{HUM|;jS>*83iz7-cHr$W6@*in@LS3X ztW}mEUrav^*qM3Q*-tZwjYI1|?7JsW^urE9KQW&3pL z5STX7{(q1^p#Fc*KhXbO{exQhKE`y@L&@1+W{iA5yyUOyB7=~=s1`BM6h(u($cuZH4?4C}X(svEU8gf~pgztph&U23DB%4RFu zyb9~Q{Sz9VZVqjHFEMSn`8%>PV0?mg1eszTu}rP;W9=5}j|rBIwTbVoUiThryjwW7 zaf$3n>*Vz7Rs{#O8`J!^F!QX68dv>_YBaYoYqZu0mqgA#+%V~7XrtznEbD21+N?Sq z0<4d@5E^fBA zzH4HQ8|PSkFrCwI{L!BV;}wsr^d^-x&Xg^(-m%8gda|aHgdGmEmb;y1y*6W)v|B&x z9F%SC|Jur$Kb_wg;$bF{l}l=jj}|wWU-E8rS#qLLS_xu(PR^p=?{S#7o9VXgI9oASnUNi!Ovnx{8f7M3>NTwUBa^VtGx->4Ytp4VR`*N?bc7Z`r! ztz9Fnk8gh6pzqw!@GLs1p~LJ}!@P5)jfr_N)&rSG8j7~XH--dFXu|MdaeoH~g>t|2M~9szLkjjsIoYdz@jpHML=KJ2%V3f^K(l;^kK>A<85|vOjn! zQx=|2J()U{*F3a?*Qr{^A5iH>+Ji1AP$;50yUQr|wJSNJnu}UJArbG5jWw)L9s!|Ni?xq4qXNlBv(=o^Ae5E?AeAoZu752 zs7+e1FL@~94QzJs?{2)}LLAL$PN0DxX+a%HJjcJ+nZU1?LENL)CuqL%82ZvS4~?EY zMshH|fzQg*rHq5ekdKUykot75xMbWpZq%n2^i8>O^jAAeo=^YHDhn2Hrb=P7J{`^{ zJ^sZ}1|0fuI+cBI7%v{L(L(QSDniiAjUWF*R-!*x#Y#%#D3^(?^z^nmBsji+@3B;r z{8JnfZS3^mR_iUNyS5+V>33f^2mU%TWO68zjSpF`S4%jH9R$ZN7orNSyL{jK93G$e zi~p%?Mm?sE(Bcn)e1iUaO5vjnV?W1~^9sSN! z?|4Bowe|dh<&Wu2{48ccnh~#^^c|k4HbKE7Yx$i`_i4BLUr^5u7v3|P2YDKb^>t5w z11%L@(W{0l(0*hR{Iby-DtXk1Q#!(k)aVZ&L6lx!`psMvZtDUMC5<6_FnzGjbbS3V zeO_c#=^#E^wun4D&Xl}ZR9(OHfj^7`&qe#@>WMANtjN=I-N<%RySm`YB$&C4sE;sP zUq2(+8Sbe$3??0WOuU&3h?g(k)ouSW4IaKY7TyU{5{aBh@^y(ZS*Vg!Cn-~cDOy7K z&rc6}&#e?q3GER5Gw15qtMc^&^S^?`?f2jWpXDOux*)MkJoVP zjK!ihafrBnNnxGGnXBO5ubI$!3JwohmxxyGN)o|TM>e=MTQnv$lx=_NNp^ABDx6qYu+HkG_=|3lWW+0*-_jtDwC2~ zbe+x&V<^=lE#gPEPsL>s>QW6!IhCUDj}Fvwp*pW5aC=!LZr|J`{ED|Qv zV_Z~q5+6RtnE&@woq3vSjs8Redg8ids%OVe-mf-<{^|DuwcTIBO|)#KO}_ba{d;Zs z0`oY!%H}b8`f`ACoa{{3Iw^CaH8Ffw!YeMiUy&J5h(aUlb?FCHCrOnL*C?#*Fnuy5 zjP@+_<)5xHWFk5yqsKZ!Z02r;I#a$At=J!f_Sb*mj~yE1xvGEcm8t}Gm zU#6!`4+oWy3MD>b`g{rHYc!L-`y!W{79`6=l@=oTh&pym&q6Bk#{y)SdX&B&e}iuo zRdZv@<+=6Wy~N^3Bjl(aAs)0V=Cf2x*`aNo+`tD1GUD?%RBCL*x?1P(aWB`fAWN15 zr73i=;#{;Z`6&G{qmh@4>f_paJGrNRhwItZy=-^;Bx>P`3H*_@ySXTjM9FadYm{TL zkyhDO%E>t1;L}G9aDsh~%uKH!y1aQm{U}_Ic71n@&x<{X=GZGT;+=`SkKH&VY%SpS zZt&nAb#F%pZ;fK$$1=X%D1jciGQ_4Xq{fImD`@@clW>%$fle1Tycne^F5DtUnNWDbm;M^ zy8fKc=tJU&1&9k;vYWOWe}UWZNP!P5yh_KEXHovLLu5%%GIx10MIRgfMt03vi2jI9 z(NW4ZXm++cr{7%71@}6j;^dp$8@n64&e~Yo=GtVg>$Vd&b|4gagyz!wWB&1Y_y8BQ z!<%a=C?nD7J?QLFG5zMwM}AlGAMTI!MYi%m9XD?bhMo-YT;P!=UbI(-o;x(1S`-*b zDvX}RmE2aLT^{&RkV>PS<&tUjHU6}PWjt$O^PG%Ye~HeOwPrVLx99mE)7jq(jE*D0gHFausnC_x2RywUm>PDp0+AMTEa06aaQd_a{Kq#7dOJRc?G5ov%-PSZ(Pe-i zOvr$49=*W9`YmZG)dkrqL3sLjOJYBL3V9@HgVXAN<5<_DZ0ch^Xv>;S)+|oNCrcZk zFn$&=_&r9F{v{C9f4an0=afPN+zlQfeOf%`JnO!Z!@3Ey!G>sk$%^(ssPv+Xu)jVK z%f2XJJTew=Bej7;K@fRhe*;d8egNq-UD+Jo7LXDhizQof$SNa5k1LoUn@dS(!Jk=R zWVsVio?SqKuOjNut%Kf$=b`_o>>gl!Ecm17MvNL?L)PL3w7$lr)uL4L)%*gR^zkR= z>1KicHyOnALlv<5 zrAtQSxTz^R@>CbK`Y4OGsL!FX&9>6KNykB0)hg!5*a0y6WGnNpR)8O@sDT%R9cW6h zI^Cluz;PR|fYv{c;G=F2ICx|=^~%U0WJw}6e5Js8l(js_ae_OEzq`kQXJwg=WdaXs&!YhsJS1OX!-oDOT6}?`# z@Z~ANFXLEtD94d4zU9bVo!kfJe$Exjw35*OK?8e)$}^%Pj$o>5Bl}`=o^W~eU!hIe zLH2KEQFG;9L(u7`#k9P8BP?c%CENRw+1KMPNiOdl0|qlwg`+lY6!xua7u21qW?j0U z2uqzUWSaY&#BXR5k;~~}wgqLtMY?H{jqU2R_mB}vntqs`oF6XIj+q2Q$~F_x`Z4r^ z&0-QhJp<*)8NuC#%CM*1iaGVUiGUpiBy`*;6f72@i92MW_R`!Yd=Bv47o>;f@qw^Mc|?i=|Y}$%qD#CunV3B0B!b9DaZD0DFwy zLem_igQQWs(==COqS3A9uc=cN0dox7r>v>1P6>~9@ESuY^F2lG% zo(o>DI*Hc_vq? zoJD^>*@L5PgTc_)+pu}30nqVVMi2fTK@Q892h374cAD!o_#~i%xw2_KjX3iNC*GZk z$30R317Znm{CWj$L{sU>-pRBoR~c*$uaTH;JB;t#Jjgh2cm%3~E<@k=da^%m1Tiw% zkAF?w%Tk;3;C_E8Iemjq#y{(U-y?UkB?h|q;=C)MWBXkEzuPI>dR&NOBFVWCxl3`0M-{(DB2YSZojwkB-T*HT)dpziq{i<^kxLB$PZg zc>?SHj+FX*8$>4Ws_CtJz2NJSJa}Z9F`ac(PjvHK8M2NFm-hcfu&c(A9GH(=msx8G1lfKdOone1)PV)wkLCrQ={mf*k$yW2{K~OfhO4 zA1O6F`3OvZ`<&g|asa2#eTW%01Mb(JKvzDHLmm-QDs3;s9B(n}AO9O1IO_*BT~?Ei z`Cdff#3Za`K8XFzLWIY9>HyEK5**Q+i|vk&B%^+B0CmI3c%oeyxc7VyxO&_a%&b3% zUk!P{z8HDf%J{>%>3-zm)a%4FVJ!Tbx&1jlZa z&B*(`1`10TQ+C5w9Ao+#E4ogHug-mdn`Q9*+~&>HGHN6U3%mm^#1AqLqosI7O%2%X z;K&&Nmy635UPZ%_xxg=O0FUyCW1^%JaI6o2jl&3coOvgd1T zpWjArEHHsh15=5|%frmKVMny&`*U2=&`h62YeA30o%ol93f7y-L09MAVGfx|Xy0oy z0&GG_q8sw15kEOhmL;u)s8v8;1)di3Z)g`yeeaVGyFL8bQSln!I60S&JNk;Y- zhB^_#lz&t_6{UC=Sj*lJf!N=6L1kI zBoP|1?4N1BkdgIxWO6=Mx{bX|Zau3YMQ=68(Dv^r)YcGnL~N8^%pWaViOCVAn?#;(DLCu-saSuJ|CUX-t(7 z`|U5z(uoCX#cI$>bdy~6Y9ayM|6uxdIc%oXE8LWr2f2Y6cw34Vy&m%l9L}CX|2}R3 zqpL2G4*A9KbKW5u-*Ov$+x}JhO0h%qGcpePwVbD#8_MXG*DvX#7vn^A^HoL0q2ch@ z1_v-Z`W_yN3quPO!br&|W84_)hr-sar4@}bU3ic|i$^@h1JRoF`2Ab(sOufN!TT`H z+b<{0me&+jr~8Y%Ppb(x&D$+lsmu|Y6}k$CS2+o@zLqi17R>_tnwK0XAT85PuFi4j=Mw6Ta_7DEB9m z{@(GJlJzCz^l<_XdnJ(LzNaW^8YbtzBT;()G~}g`4i5umvSi_13NQH5;fbp>FKaW&1pU`@J+v#85=GkiBR8XGS= zEqH%!khwQcDp~II0oPg|B5v6RkghHxxi;%T$=^yat(8X%{R*LX`$@QH|2<+}eu9}4 za}Xpq*pm<2PJ^DGrSM$;VX%MVG0^*^9v?MUCd!I=>?&aaOfH`Y8u%#;XDS06ubUHR zon0_t-%)r+H<{2=GkLp%d&JN)OH$JKL-^e9jqq+vH0Uc%#K(_t2^>8`pqVq4|4HUQ z^GT>`Uac`CzS34AxpJvdz`G*PiaR?6osC<-N{2_1w??B$?wE^$&(Su_qLjHpkADQb z3A!!$vtN_+{!tP>On4z#f7M*jJY}b(A#t>1bijMbSkw2wEo~b9HSB3p`a$=?>f0b6W5tkO*g_Re;nXD-tm0A?eEUmZYEc29Ki-;ioP~h0_hq;oDRzyyod! z;dbl)_$AW|aM>*viL#9~G`YA0U;358U;HirWOW?C4?XWN*8dFPy8aPZC?6wih<4+D zNh`){cfMrYpXtMxv>Et6n#3L+QHmE`ItxB+s3h~Z{D6N-yEU;wu{L^P+6ZF$ z)`Cp?e&&(#ZJd8b4PFmcWEXu%#sZxbWL|3|%AL0wr*>MAuYE>H?5jvN43$%-_L7e0=!61Y{4E%oOmBj( zcCI6;2H!}M@*wzXZ%$)(C6IG7++joDO}MBsg_Nh&u*yctlJn6^Sh2-b#x#c%-S70{7-V1{7ZPVF@&IQcr_F~5H`5Wvq{SLms-3T@Q+Y5L8X8{L` z=3%<)DD>RD7yI;K*j%VaW~sHH^P93LHw}U@r@q3}$RX^ZHVG*@rbCIWra#dh2Xa5Q z3daZ2BzTVr622}eI&QX)rEj}fC|2}ZnL)kt7i;!JWFY1#2O>f!t z&|ljM!M-m$=<{2f@SFT1+G{n1Bn&@6X*PktY|w+brPT-~z3K&jJrT@v`$9Y?1tMN` z4GQozVY`*maqHzX5S+gVV?#V?x5+nh%lSS#GN%sfUZ{Z)=~Ky1YD=}wXTuJqBwUkQ zj=AHD;pa8^6y%E|4}wAO{*e=&-Nbj)JYv@BVLwrM0q zV>*0kngS^TtwY>^$&&ijO` zACG6{W1aE7amT^Eui@;t`A%fBpECI6FdY`bWKiIdkF(BH!OO!*WPjBXIIexJ=zE*L zXmeIF8Ej7`1%*9mXGA#}vD8<3zpqHr^Y#!KD1HDA#5_Q56Rx0ZQK8cHjT58+)tEe# z&m-rj-9#OJm(h%p0BNSkUb@-Xo$w}oz?zk9NM5s#aML}chwc_Y%cu7+bLJtl;8q+S z(l3JNq_>H+E(aAKCUE@1BWS_6+st9C3M-5Dkdi=E$Y1#pYUYK}_`7SF109pVuaHT2 z{?-nZV5J7!E{~Fi?l>TZZMie%kKxPTn*^tdJHvJSkn6lq3cIwEU6T4YQI*>h<0&t?)c+)w&Qwe>>Uh_ z&gRkE+(>LXatB=5q=eQ>a*@)GGJ0Qg7DYvY&?zQ?aJ(4wN4NzY)Xt?HDrxl7Vj&3e zJ5BEAD-qq#B36?af{2UOc=g04{KKA}!DZ4SXN|uvuuYAdD zuqJRqp(%yBP1v`%9If^ChVLu?GEdWOppx7W`8zNc{g)7g{B@6zdyU4>#q|xCGohJ$ zfG?nqnisn5d6VoGM*_y}5w6fRrn+u19hueI=JRR-wdy_fY8)7eg*3N_qyl+Lv~2VU|4G|cEF%X`((%f0T%ts|1w@e;wy z+{<8U%2ML#r3zdwzD)nc?UKRy7=O{y!kWt+KrsA@ABHa{;@$)F)*M~nSN07ks4f5r z+54Ge zUI@i-n_V5ARx*r@->-+ugEL9F(=)QEr3Jjt1-JtOfHoXvUI@+ z@?&ruT>fz^T$lC`fV0O**V7boxAq*Hsy+sLTv!Z$A225uo9>gn$O?$c64`5gQOtvL zvA}Xk3Vv1*L=FYi!TE#bxbH4TL+j$$RjW8eLRVqjS8LuS9Dsjkk)HT*6F&*2U z7eYghFNsdQLy}bO(8B(sOhoq`ytsQIw7il{o&{YXJtk^sL$!#R?syZQQ>LJDK$9xX z@F%17_n@gxnXDVzFSgCHXYUx53ytnSU=M}bGM`dS@rxVUbV~4X=AD@se7-+|T-7mw z1qw3OV@o!nz8;LZFo;<+=L?=#F~oSIE%5Y3MRxl`P0*t6$^>q`i4V)S?-paBcxpiA6#IAWui9qOKj$2j`W>?WH zeR(uJ&RH~NSet%*t`1eSve+AvWGH#K3s0@ghP^NEVx_xvNb~k$Xm!;W_rE#Mlo_PM zmrpf_qJ})pp4Jat>VHW1EA`2#Yj2rX+84>~@r_J`u0Al1HX}`1O(3Qw2X9DDBIzFz zg{}?p(CVBGj+`|U-jMaMl#G-ZU!~7P=Y|2?+3s6He7^e^~J z<>v+x(tViN$+#DHjgBI!C=XNR){y5H!swj&2GWnWMuRBDX zXV}fa3BAnjBO22+@b?2fOu4T;tgelNzvrJKUKd8vhGk#at5;K)X`ck}!bHBNlM&j2}jlSurn=AGFx6u5YQlViRKwOR>9gx;=DMTS@}pw z5`THVKxa>$KrX;SVlupixf=1G@N;=O+vd4aIR4un$@dU(^L&k!%=Gu0glC^rvcHrr z3)IK8Nt_pqU{fkrNUmHBV`jg-Asq8a3v9ZzPq_76Bfe31T;gLJ#l#m#fa{S+SiA=j zC_c?fT&9Df4|ed))R7o$JWlNO#=(Gi9lYl+0;$Fmpo{w=Mqzvzd9r^ln{Gc3uk7>% z<8Nz1)p_a6dtM>Yvrl4rCn#c(bKGJ&5jfSMMF>6#_N^q3QZ+moHK zC`Tk5m){K>Iv}?HF+n1K&bYe1i|Mvj#;dzjlaBJk> zF$8=*O$M`+6LD5SA8GCQ$$k%Ci;f)rMzUZjd+UUZeRM#^WBoA?gck*%sfv`4oBqt; zfA%nvn@hIeJkKm{F+sh{yvdBGx%l4Zuab3(Ut#;oxmYXXGd7=MhO$@X(gorwdKdbD zBt{MnOnXN*zsw_r?>3;A*S}%Idk=8ep$r_e>L)52CxWLA^AW%064hUzCJK!J|#$|PEHv1A3Vsae zris}GwC0x=DNa1khHaCv{?Zy@>-JWfnLVEV^6AF@rDMR*1`*PWn8j>7-A=>BW66pn zN1=m2C^pwtWLhn~Bvp=z%v*U)c4v$-$WK!cp0!U9j5LlD{(0)gSIZv|ZXTs3*lAWP zDZid0@S0~SS#|rb5RnRyJfY$~R&we;w7)qNypN+vkn z_6I)M70HZO%B8-#hV)6Q0+~3b3Er6&fSOiLM<(yDQMBwZy|!`{8>e3_9?<}qffRLo zzik3bz!KAm zu;I!U@ukdFyweZdnsc}Li#M;mDqaP*2y}wBur2jL!Z9{#0()&uN$!s~;!SxR$##zw z!o!;ygkd{R^V6nwp8DstL_A*7Dd`_yDDc`9z$msC3*N_^5!+ll*jz35UUH(jQlP;J zXGZ9&2t2&0`0~|<;-+dN$wBW$!WU6gsPs7nZ&YrRq|5Vw^3ZQdrcW%s=go(cz4p*O z%O;_KxN*QtZX_`{l}*OX`-uIuMk9ya9MvMZ@WwIl%poeQwm$beYR3I+cHu46-f8adKGk_4uxAUN#=Om~jMnQKBN?ln5h z!K<6_m?2wosb?Sl<$j0E3pqq*FW(CuUKj))KAj~#&n|vPc6A4kR&mc2MHZo5O0) zbU_E(*8y$69kN4H+Ku||Jc_saPA8(K{V?zLNx0z8T`*#=h&JBe zkL&+j!L#Z{!&jr4;g`OV@IZ_UHI>RVu(B8N^`8Mw_hab2y9v<9Bav#Z zwh%qIF&cDhK9-T8PT@^0u_Sa(FE}+T2sre%jG*NgvB~_E0)?fC zVsG+FxTHjj{k7jn^88wire?RE>qpS6aQ z>hN8aDY$EA%qYoQ2t5aO;90sW+5ANcaM6ec;ULeEx&Bqc_TM(a+h_g4I=fuqh22k} zKbb(swyuDdf33mdh*#{NCpYo_5iI!^xfZsJ=b#l1df=efSc!b-IuhZQ3Hk> zWRIagv+e6xu#6W+g7pM&ng0-szED86Em_S>Dk5cv7#11O*OTyQ{Q zCmua9R;W?6ND?s}3+tys?Gm}+fJCM602_}$<*(%t8XAN+EVj`z<1g>Ie1d*glZR8%n*ybA9DBaSwbt)oXHsg62L zePE8#>~El4pIaydB$EmbmVCh#D6PaBwKdyF?9ErkkJu%z0A4M!5fg(j_(k8chsx?;T zx6+eopKnu0$&y`+(wV8~U!Nv{ox4QEC{#L6DkMLSBh+SIiWZcOMRyqkY1S-bs+GK) z?C+TbOM~nX&0bHI#AVZ!`&8*J^2!xa;e)+$JxcK@RvmCeWiu@eQ{NFXWaViCvoAkvI4Ld!Z-q}PtfNe^vPXM8>v z3$?Wz;jy zp&hQ9A4k)#^Kf(T2-qb_g+ZxHVTAiAsy_AznRbAW%`G*->OErYVUMurTU%3f#U7mx8EK^#4Xe4UanM(xM?U1Xgyl6~LKHYDwPprE$WK7%_NMoff zGMlqOYG;;2-9Ock`#c}Gp;SRMU3~@8*pw!vlM`u6N;;t}Uf9k+K{PdG3QE2lCw*pk zgu>#P0Jt@E zDXyMx3D4gTr-ys=QF_c{%G_EZy87D{KE1k}Tn{&=lgSxk@Tdq)QaJ?Qq}GC8a?{}H zJ|6LSa~e6{EdY8(6|}eH1suxNp#Bfrfns1f3UL_%Ii7=bBgYB)Z@WY4RLtn;c{Wtt zHw(>EFGD%^Sm9Qqc)>#-c`&FoUn1juF-s*s!8+5W;6!{p?p58-e&2kO)yvuslnX5I zZu>DLb)zpBI+Q4}v75%uo>U258;-z<$E=7&U<8P$&1A2xPGir%C*aUN6!=3w*2*9r#E(eFwHBkuv$#%hYSK#Vx~U1P9B@KGv+k0R@CtZ7X)cW`ETk5_ zGmuK>5_r1qC!Q=j6I-Q{FDUxil7Ol_Hg*hvKGm})Z>Fr-RFf7SLw8Cd5@tQf4S>{(E31k7D zr}0=gIc5*Yjy??Leo7?Y0#1@s-#@bBO3#b!Rb1HLCLgg%>o^d9a5b#GahX5uK``gu zwFp)z$df&!mHhDoES@I0!9T zjD%cU(LCKk=@;kDu$Mg0WoYqmKrx z&yJO({|ba|Rfh1%Tiwb(dL^kR5C{&I98Q*Jx~ zY2R2(&tA->;}4!dEBundq~19E*}xphSe>NSI20zxvYd3J9*9>_LR~Hdz|=hhaKjod z&C)&&o4*kh_`VeKmk420Z8Z*QEupqMyXmN_rlP>xnxdc|s_<3jePNG91wGqzjjp#F zC$cd#6dBj=0h6Epg-(XL^!a@Wy#Bcf{nEB4cV>Cu9}i#fb0)tAJ{LV0iQGP%FhK3uU$pb1SgR%)9wavH>}lRRK<>fZo9itpg<$Q00jcN5)b{+h9=c*G`r z8Df9Us({Apw-d!sJ}qpih4jQ&98)rrOkY+ApGahLS(#SUrXUgiowbqu#r|WG8sEZE z{!L*0o0atS93HfY>J|E30}@NWMzG&04+KLQ%?MuQi6(H>kr!f4~1$~1K5QQifr74ut;N%yg zGyo!=@f7Jidm!(=DY%&Va+D4T91&cuNavfdxpmMj+c7%K%ZcIL9z3L2&bql4fYz`%Z0c$~az^Gk z`M5V5zJET2EI9s~sdGpM!}bQGXwgqlvnm0WEFTRN_FVugZmE*s>L+;2!tcVU*jQ-0 z{jgAX(PgI53xMu&B@&dY4s*jZp{D*<{Fy5c&)j>(m!zmNO|DW_ZhJm3i?xO$#nm!( zR6_5%#NlrRDe!jgO&Il9COowQsKs$R(im8QowFpuRGm`zbG{il-l$7M=jy@hzf8%+ zgXe&f=T;aKiOA%OTJ&wEExh)q5vzBuga;h@V5O2H)C!zU<#^{v_L4#&$ATxmQnFb1 zAYNI#OUy88L(e5N^Ao+NHK-f3FQ{oov$A)ivA=K9MWo8{1FY$Q}nM;z#!l)m~ z%-b14wnqLgJNu?DMAb@6f@?X{EB`1QxVr@E^$BR47e{nP&$|;U^Z7HMKp~unR+v|yFUK;RpQAA0mv2+S8q&3f4 z(H9>za^SrooP8(^ExwqIJTE<@zDMuVo7#rLY14EWiBb<}y!k-#e9Rx#t7{{vQBy=y zZSEmS;WZ}vOCZ_XwFtV5*nsD5dP?+u%!3^h-Py4X1w!3xUNG>c3Q(^7M6#Be!+r8+ z8H1+9Wb?!ouvl>~e&F$d6vKFM)@h?Sd8{$3%khUHhPtFW>>7!@wH0o8bBs*Phy#Oq z?!*#(g^M0;qAA^lr1jDZx^(dr(bC8q@It0l?GJvzaht}WS8``T(ZgXXd^R7H=*)pf zFKVDui7KM?Rww8PcSq^6w3Bf6F?HHrI2&cwd`IV39;7jQT&2=PRd`CYg}SAi5%K8( zxQ>$p+RpQ7s8ORNru#Fi>3x)xJh}u9@o&L3UU#8-xQdj}NLrsX2Ya~bVEs%9**+_d zZf%%@4CkIeL!rT-|I%nE<3SReBN0&kXsRq@rIkuvzQY|GpTQD=1}%7QkB$uQMjH#N zsfE^0CeCpYuyj5}s$SU80%Z|;XB38*&Y5t}qVJ64`w_6rtC-1JBms>&wkX5GMWnDd ziYh*lBXKbTu-a-bTCr;tn|4$|nz=e1j{j&!&Odp~eoYHO4`&YJ9RHWp!blZ6N2HLh zyevF!k{41N^%>V~zefYl|6*sa8$lwcz6X|LqmZFSG5)^k2lYCo3fttf@Pr$ag2Ur<(Jz}O5-A)6aW=C_!1_4yc)EPC=06IhHMNeG1k0#}%q01WjaL&xPc;L=rx~+5#-DcB=cnCYo%9wqCN+||BL`tvln@nI7|{0p2>>UjgH}9Dl*WG{8hOd6Zq0pI#=pkwT(%FY zdMe4X;XaUl&1f{`>N|MX;UHu6I0hy*mXiL&$MBle9&I0RqW{a2h<`+ca#LkM1=;8S z=b`-H{BNEtyH-waOWhl;_w#J$6CaHElOhJWQHu@v-(8&qcKa^~wRaT>r(8bF?f)>E z@AKJHFh5sLaIDu`IA-z_!S3ZHT&rDwxZg+F3(%Wc{5%0)n5a_CpD7o|+xcudUo}iu zP+&Em@6R(4&VIo1JN9nj7U%rtSqT_{PQ!iv9bX_6m)sY0RWx#MdJ3Fnxy`(QQp&Yn ztIPj)izAryF-z!BeMQD&%;%m|9N@J^PZ9jQ{*GVXHAAR1VnEP!JAs>PH^epfwh%l~ zn98#bvJr+(PUoLBUdcOLbcwfdSWU3}Od{{{{jtIsA8q*y->u-9E%?BVDz+EIn7`$J zxa25Y`?^Qq=hMNla#3;8&pXDY57u(8?`!AsyEpT-Zyyq9-*p#!ZB*c1+*ribV^{Na z)I<1^xNt#rm{1@dcaejhe&#slhRGPnk$lrh{|O$Sm@2qEGJ*TnS&3tt*M|A4+6A;5Xb8N+rB6 z@=k*HU!Mp*PuVZ5nYxWzxZ^bMoT8c_tON4J_q2uW&DH{k11q@iNhViXqANJ$>&t8N zG#4H>+s~gN`Nc(^oxHQ7v;@fuD|jt)w1m&PgZX)qcbqLH$-E;$U-+*ytoUnX83>=g zTM8~X2H9;rmu6GlS8kuen%S>@cGo^)e1PM=fPGGT>P9;M`jKvz7{AeBZ>*tXo{ft` z&2v+y6Qh?nx(=1uS^A{ey_{m|sEHyR($+XS`L^je^7fe8m+w+@D0!{xNTT8$wyWwp z{RmWZ91`oFZ7i6JDA5Cdw4s~y=j}%J>3DPzXoyK>~rbP`<|xq z6x6?Q-0rM#K9{D%Y5o|@ebnpBdANH$Z{xy|T)_!@Co6*%rw*TZ?$PeKT+Ls5dGm|E za5Iirad-0%In}hx;muy!!Eu=&V|VH6^YbQ75S zx1zeAqgg+VC+}FxH)vAfCnp^f*t{MuSm6Ddlel!0(ZNBDar|fBzQ8M1Bu{zf}+CN>!8~x>}K2 zs*}$x9-7CU)9=N1b)U~^SQ;o8Iy#c;8FHR;*FA#kBi+H*RY~U`PlywI%F7VU_4eV! z-!yWPAP?@+W_QledoDM7n}p{$mJwvk-6{xzww&Wi+1#m{RQU#Y0#9}2C_%8H8UNh~ zPtL;MDV%A>FL^V*w{fDc4)Ya0z2WNqkmHK2OSm&Ddw6T1CHLa`d;FLH%yl`X&*4q5 z;3{hW;wjBh<+Vl*^II1f^0Vt}xOa3mI|G{@UXfW8m#=z__w0Kif5l+1aNU_$p{zpW zZcDw()76+EINcS^*S|Gec=^#n!H?d3+^$O(xuS>Gg6-@2d9L?`!h}1s_}_21@ZJC? zzO|N~VBU@^yvNHY2zBh-_~Um>(C z_TxVtwNKGfa9E}A&B=Sx9;e0QKROLIYuGE^e{O$LKhCk&+23KQak3MfTJD&%OlUtn zq}R?cHN(+8=%|CDNsiNu&numNJ}k8V%9=Q+e%xC*Ka|Y-?Q1(cV_UTfv*c4@&*WpD;zh zIq{>2YiwV|^9?fQolZT*Zx55>ztVi=yig^MqiSXYgUM^CU6mlr7ES{gKz^%{W=e-;$ckUb# zJrRW4L*xbPb1is<$FDnuZnSW000%fWRT>^%hF`rl1u+_QqhpDr` z?h*I>$XsWK8P9lAwcrflj(f&l9ZdDro$P2)5oh&v*x%(_HYaL&fxUMjpo;1O5=$_ zWM}33HG3MgF3n zCxyDYM+Lh#{dL~YpX$`GVK;Z9a}EdFm~hSB$@8zMz2=9k@)T^$e(ju;=*PA7yu_RR z`UsEBzsAq%OyE0A8^_W2Gv-8SpXKeT>gKAN_3{fAr11(a9p-rdv*G%>Ht-f6Yvh)1 z7V}eIE##%!_BwBh&*pd!ig^vynY^V7PV;k~?&3QITy)N@zwobKHsn1C`>UBGeS1u<2qOAzv5r%`h@l9sxAYu^ETqK;%DfEU=UzT>w^#v zj9z3JAnRo-@XBpdNX#pZ=Hov=r_ow;I3*l$)LrmU&3YV=z8s3|zCq1wIu4(7=Yv+u zWLPBn2#H;jVV`~7f`8`rfUA9{;QL=CSpJ3|a+x?y9`4A+&oyM=+iw)~=Op4krE#$3 zb_%IJW{YlbsfCx+Mc|JVU+k>z0@vLLCj#RhXye`U;EnS&_#^!UE*W$~LI&w%*>oTd zKg>bNsd8Y)#&E3h^9&k}yn$4Ar;wCsGkqbMB=%;o07cgQMDo!cq`l3RG-usm|94)M zJ>jQ=j#xROWjzhVWQP;c{K;jjEd4>&dG#ZQ$qd*uRm9K4^dVLe=h<0@#n}EK-Eb(h z8_iBsk!>Q@WW7xt``(uYY`?HIv=UQ*b=K=PD1Vqk6+M4IZ{gSUuZxM;ETIP7dfiNY ztM&l$7H?t5ZF6{Z%P1NS<)A^wg|v*+eY(=L32sgh03%Copx0kwfaB0jdVSDO@XW9n zjv9FYC;B2<5_#57Fu^4Aec?%k(}{ptpAGOUliwn5n7c zNGTqlpjO^k4Ql@u!7_nI%)8U`=+$$&Y3*;nsru9Xpkn_NeR8)Ft8FlZn!Z#|OGeqU z63;&bm*!t-=2_NCkvCFyx}GQjEQ zOWMRy1rFbp1pi+9u$uEOvvkE4@w11GsU>NPVbZTcmVx0ged&w~b)JEt-q}R3;)y== z2o}XaT8j94-6wjks$l-|H}LePM@a5;9V+`VjCCr?@a73^VBebpa)TeERW=#WHtQR% zgkH#FM93n`w8k6!ydPtqowh zW&!nN-43|RZ4)R_FNV*2tI&y9OH%x$7iTYB3b;FV!QVB%k$K=QBz;MU#5h@FZ$mwh zjncv6pM9uc?`d%D$ZIUrn*|vH0`Tq6ayZa)4GqhPLZWvAtJv3DqO zWHlO<`ha(98{?qnDB7=kjOi~s0jfVX(JgT;;3%gHR`xB$%EeES`QHO{{iGjoNm+s% zRPVq9r{(zg{xe8hC7P~s^P-0)6p*=YHCVB15gs}b1N&zH=rn*pU2GQa^y&w_#OvT_PC%hw_t|=3)^l|R;l73-r*&Bx?&HeHW{-0b2I2w5&*3UPC|NmA0VSO z8^6M1sL zpK;{J)f0HhSR(sr14WcWn=G)-jUl{tT?AMpAOyEDEpYqcP8burnh3tmK_&f30LI+}w|qHxm@N;( z4>%LA$9-@~^?z{I%@(*ph?}Rq;n^I0@=|jUp1Gz7iVkjs1KTOQbovBT5XGc!=>fFd zvKqW>%%C>^=ZTtkrGe(J0!VLT3tC`OLEh!}ks14wpm=pDii}UkjqxWDGxQ{p1E(;t zsR!eu!O*GT2;P@j4uWRWh_jL|8f&(L9Rg30wewzVuPP1yemX=(y(N&Fp(WV3OBYEj zkHLT3)}d$G(Il$F7jG~9Ot;iYQ}w+c!3wW&TBiOIZN7;{8@~z=wKErSv)o^LccwH< ze8@#fJz6k&`UVy^nvdEyE(MIL0PyR^Rix98K}K2!j{6k?FTo3-VZA;=YL>^=ltcb+j7k z^p9f8AKb}~<<-K#6fyjxLxni~+lr}H4fcgU{^W9PCfs2oi3~3+B^nkK{=1dQ&Xu}^ zJJqcaN}NO~Cl$ycS!3LGWf7aSHe=z_+OYlkJ#(Bp2U$mn6Y@`L`T(2?S>{ zDMt#EDsM}?^#h+(vMdVN&;CI=OJm{tQ<7xdrWhR`dbYO8>vD&yhkr%SMO?Fw8Ie}_bR z$q^snc=-I|2ow%~hc{`KBh~CNGFz38N8Ej3*y03O%J;LL`s#oJEM(aW493yq@i8dj zTnE#{|KPiv5EOs;FX`}^MQN;e;7GIx>QcXjM>n28zs(+z<@2-grUjp9|9i_Qu|2u4 zOmY{Hmnw#ELo=HCrcN5lF`%BNZ8f@In**v-%nHFaKfu`#)l`;vQ< zgllT=Ag4J`>FjA5{OC+WVy2g&z}!N-xZVWq9jF0OLo66_=m;`@odCa!C*TEUR_Gn{ zqvvt20oL<;WSiavHEj#gQrD5#OeszWGvuWF7X4+@Ci;sY zpWl)?gRO$t?7kz%$kP=Z{S|j?*jI~^ka_Yiq@l=QtCm;cgPA7!7yIlfQ?fh|FS?Nxp|P3@wl1VKpQf{#tBXLGzBuh^Z^rsN{e|^*R}I}6 zCQ8pYy8jVvB+XDY1Cr^n|5`f^qYcrk7Ol5P5#DXZ79+Mh?$^R?Ppc`7Hs zvNQKsaZ{yWZRayOAvh5^t^Wmmo)cs^@(Ty?=M(CV3GDF?hVWYBE!6j3l^Dv+!Ffz= z_F?H+e8j>J{<~TOH;-$PaQ?QLtGOAww<;FzP_Ksi25~4MZaGm!9jJ)8oUH_t@Ky#7 zET7GVUlnACp7$?wrc$15GIS1G#8*(%vLIH1)dA4jY)FTQu)*{a9i&_kjXXvJNa!v^ z+m(bsfks)hQS&s^=~2W1d`9BFA3v$o`SZc5x1#9Xbrw)~r-(n=e1Z$!R?`pWYr?z! zKcW930a)lLh@U)bf$YVbsowbsbc=*268T&P&CwiO@j?;Ru6Lpi=;g7Dg`UxCxhZs~ zS~>ks`Z7$PwFIBH4Zsf;h?cuAO?Mn9hgP32Qxfu3=>4TuTKmju+S&IH6(iXVjVrGJ zvs*prb@w9Vz-gf0^Wy2h6IY;r95r=!^I5dgZ+^ABn>UE$;1}5KXIhmJ>b;e02L?mu*nq)8L&>1b9y@X zozz{hUS|#LQpv*>HCG^S#U&!2xdv_ZcZ1r09s%ol*?2d9<;VKkNm8l29!=>};N|Tn zuz7nD78jn2e*Qf{N@fF5>sMjsRD~*2C?<(+OkB?L36Npk*(3#%IP5bA*8>YHbiCfx4@XK zCMc}y8SeZNO$74h&>Jn=1-vKDOP?Q}JkH6_1Lp_0U4!8Lg9eMk@A`qw#_vG%SOXk<0*E7YiHQE!IC1haxVKH{xcm-+n_k@L$_GmqM zh_80-zy{urNpUYl&doD|ZyIu-$H_-{mqh@|8+$|K3#_pFqwoA4O$*&R(}8_t0+AE* zHu)^5i|ZFW2XTjXpok}E zp1i(-UMSm6;U(Oz&R4(=xXT^Qh3V&_o*bZ@j%KU?nyN2Z#$1Aqt|0*)r9FZ0i*(z!{sz zto-*ruwy|1P_2uC5AENgP3`7{1Z*Vp&&z<-|Czv>{fIX16(%?Gxp=3RHkh_t z43>1iK&$uN0FOsrVX?1QAmhy_aFfu3&UFo_fVjfRuQzZCFAHX0mIqM+m3CpcT5@eyJTZ8{F`i9wu!yslq8gkU5RX7UcwE) z7Ps46BS{rBSt23<-vD_S{QDx7)-gub6IY3aQ9gb>lEbeDBeb4>E-c-98O8l8B4=~r zu*{;HV4e6nC^)AO-&kpd84hQNe}D?H6wacebY+=`3SQIZ8%|NevvcSxJp;f+<{q+L ztP2aw5%75;f1)U7O}W!N$(;@@5%0`zEx z&u!}4mG@wW#sH0Ve#08KNKk#znA&gino^r92fGTcg1!U=v~xTSYR9Gl?=^CC@*aSs zmqo)5pFhLB2UBo-MIF)KQ^lSs6NBc$XVJOQOW4|05f$HQAm>+X!rg}z;D|*snEiJR zub}tg`9Al^3O6%y%J&d-yIqJzgQ~HsObULzr`2u9i z+F9hREzDlHBsa9X`E%e3Oh*(um#T1#D{(jo_PjQ-pdoAc&P$RO<9C0 zmfpja^eHlIeUEVZK7!1wk1*|KJdW07_YjE?;5-^xz1)n|$#?OL{@k_fy#BhT=xuAUr zi2OT6O)auTV&@IO`Yoj}TuBAngjtdmXXM$D?<&CNiF`D4FAKXXYa(UILZZ|93vs8< z1LGlUxNmJd)_S=Ho}MZsHa%si@v#mRF6~4IYoqYdm*=77`8cAU7LOJx8-bbXZRl}X z0)8GQfbPCcAZ04E2%owM8vBn>6RQ@X0LOnoI*Wx0>LRfBgdb@LwPUv!ya&E!*=XuO zIF?gfhS#r-BsC(kU);ML$7>r>AGsDmJ~wl$BNOJzBKqtDF~f;W`k4C48U!8 zJu&^6iZTz{1A|j{;NK_SSn=iubg63_X>X{;2k#is+1njizH_&NFLHi#i|P{aXvsV@ zv#%8`7I49qUMaN2(`aBAB7n@5;=wtyIoLO-5|(Uop%vbng1Q5L;Qonm(04-|uM_$J zs|r8Up*3geIJHmkY_l9(A2fkne?5dLn8Vp_q>VqI>_rj*6SCi0LiVhsZBLc%d9UWbhR_#v>3_ zC`S)CYEiEQTEL{m1Z}^(2Of?+4V3FFSqCfT(JzFDfcmYMz~S(F*if?q?i3@8wl{}# zg>p_X9XkpbI6s>ScILB^T_ow0@t0I=t~O)M2`eV!?PHd+ToP+?-w>rOw~peCF&F~k zsSMAEewKFP0Q0iTFjdiK!E&m9!BFa3#k@7v&NAnHV9r$BqHaX2XT=x4(MwF*z&z~H z&f3wxhjq8{4)rH>74$u@OF8WmzIj%Hl0Hj z)~Uq8g@e88{lQDx9nKuufX_~xL)<01i1F%=2a0vbO4(Yp zj_n3Nxc5U7bx9nS{~aFOB2NyjEfst*&C^=1w!; z-EU_q>;GeAwqIvC8?V(97JH$$>hm!36NzQ!mrk%2{t{x596^R)#BioC zqmOl@Uxqc7HAjzCWX*7hd&#_bsD`Q9@P@VGYc=a^P&8ynCebVYbfBgSqR8)R6uL1X zO?DsjX1D(iWS7_+gF9czVzIX}pvsI0U;tc?tZ=356#@Ig0*3gUZCSl4=iL(EdV{^UY@E+v^do!|_51+roAnix1OSBy^4N6_r4 zOH@H}K3zPS3~#?$NuAx2gEoHepkKJT(k>S}KtW>!Jk@@e`V$a^%nygsb?I5uA1N8& zosqzw$t;GNR>|nh+au^VR;TR8bQq$ck@QQc8S2%q9h6+pZg@uM1X^&tlq&a0Vr^J( zoH7{?1pj##(VV{Bkmacb9f$s~gnzGPnRl!K^bRi5pwgkL!Wm z&hJ^Z@66zn)h?8**J0KM!F809h6P?x)h6;li8=&T6t)7@ABWK&>ACT8}IFw55~fnmR3u-#Ld+MN;&_l+(C z4jJc}ODdK1e6HAo(h*^1`pHgcUd0=U;6LBo>9K#ledoo75OM|NN*!rUd#atj{D*pO**h+T{1m-OAlP3kKCE8@XMJv9g<%!c(ES1I94n(qPAMA6+5kn{s_}(7SriogjBe1O`B5kJ zXqDbCsJx>EGhAiy^%6~nELTF;?6N=8LnVyC0Zx(SJ(vuafE-#HDvPbh;dw#uaf}a1 z`xcAh9_)cDy`vGw$p|-1xxyJ6YclP604@Br2h5}8(Vy}i__b6&3N7*@HFgiMjo2ef z?r|3*_iH(g{fnrKHF@+uyXEk;sx6*# z)ae)RsR?`#>U~tD1g{67$H|+iC5O{!j{Ps{n4TRpTsg)1A>xAC;v8ue$0jPmr-fb? zxDCR?K5+Y$y@;)|7Y%ve(QV&epLgdu z?bTX9u5Jt}dnVvp6?<{XlP&ae&z+FI;D$<4wBacqA3Rw73-UfB(H%)8fU(0CJ@)AX zmsfh=2Z_=%H+lP zPFEf+>r+VU@@wOBcrn=UHWa5G=0MrZSa2dX7yNx;jpWW;0WEtr;HWBBcxE_+{$BBx zewWSn?nyGyC(&?x?4%Gj+ing#23Ao;`y|jM!G&Nc?F@xiN24#BOo)c+7qaDn0XS*0 z3yFrT$9aMbwD5^1`J^w5*T+YIf7doaI@%0B7|#TCU<>I?n1;e~+ER*LEtA{M&Q5dxncnCRCG1lgqfOdmNbc@$YZ1avZkmF1kjV$@4CZ z2i6tB3Fq5r9Vo>!uP&h@$4?Wt`<7U1Uo4o|xr?tG z82Ufw(qm6&sSU{)tf@8ss9Z-0SiUb3qGNNZml_e&n7uo25)h#jV?AN%?Iz0i5vJ;! z^jX_2f`Le9Gmy%PfXnNX;K|tI)E6mZmY|ax@Xu`lVuPMAc+3+P31_k5r{Y*iokk#` zMu}P}Z3jc_Z&NNR+gPkM8<c$q1yiY(Cv~8Wo9oz@90kh z5wf0C*t<;le9Dl1rA|}xr}L@KkutDw&04y(rVKtUhyvy9=P3E~P|Epp5(v<^K<^bu zh2g*Jz}vi=tngKmw9Hf}IO^6*Neaipq^${*Kx+^E+x9z)yMGXHt+YUZ;XiQA(jFNt zwZV_gbaBT|Mery@1eRC?Bk}Q9(B^a~ZeLr0ZuUrlXZ+;5W}j%(-Ea-WRK((V))yF~ zSPahR9sr*AeNn@IUqJdtzF%qf6D*I)r_Xq1f-dQ`X#LweFq!3!d!Yq#-4>*G_vesK zKu8(GUrdf+NbWF9KfGlgkEJO40YU1{lN7$k_bh`I@E_~E4x1@1rcM>TGG`gzj@J7! zJ(uw`L!Bk)smDxH{ZTIOMOHO7R~PKH~_BG!iO%1j57|0px(8%zaXDZQ?F=?u5e zb6Kw|Ayb(#kDB}^%xdFnMfAQ=Dz#=F$_T3fUzEzA$8R(Icy<$8+iNL%g={nUxHT44 ztsKVBZRPR!+%M$t2WhfvL>+DlaOBUQ+i|w~U2ywzKiOd5jn-Yi2+iz-5f5OSr~}bD6pnYTc4J5I z?H;Nt?a^kxJLs%9Z zEU=LFND#nl^%G&tf_XTR`5R|cRI%NEH?wOylAu_*Jzg>4LR2;O;CWSB*b)nUNhnT- ztDY}JEA9{y`D-;w*=EPS@ys2k#yX=~i7fnAM4SAzIEvoBqu5afG}dsjfQ$r9+@57Y zPzu zfsJg5q-m_Na~HH;Hy?{_*i82Ceu4}3c(Gf;o{_ZwEKs1YGFWTvh41$7K&M_F$8LAC zNcU@H{qBpJ`q!?=qVk3qT-n)7##Psn9-Zs#e1FWo_;3L#`pTd2uR2F6FTLY?T&mfM zr>#kT#dCBb#~GiH$sjSppRnw=TsAAug?O6}z*QD3ylwFXa(Td%#CKP+%bK;>_~t%3 zUwr|~Z?8C9x$Y(1u2v7m4o9KU&$vUqnd2=jOk`6Lvg4VHbodFC~*^PCxpdkqT`U>mUi+gA-4rA!g%2 zVt4BSa(Tw@!MC1;&T)SDOW|WQAQVEvP8Z@zl?C*{x4Dc(kEH0b_%|%WeFOB@9uIIc zM;D223&Q3Siu9mRSimd=jT5ozJ11nJGHr zaUZSbdYw|ekOWsGC9e=Vu48uRMrl?{=}xo79Q+c^*`^w#PzLKRJ_` zgTsyvvXdHf$g6l>gGxOQGg-^4^xTkS4mhYpoWfhtB~^h zElBBr7CXH$;6Ap` zOf|dNvJwvbk;2|4yGZzB8S*(jn60(=BYAPS2A<7VLTyTG$!tc6ie-vNyH>EhRBqr|k0^LxTPM2yeLZ2H`HmG`Hn1nEpO6Q;6X6=6WV)sK zGm<|492T`M#EKi;i2I=+ww;WfzED6Q?DO%!>l)Qb+U_#`d{v9R@4qV2Hsk=KX2+l$ zpQ&xu<%Dhfl-Yl~1W8*M18pni;B||H$adL6X2M6ew4l#E297+yp~v~LcQ7LcUVYU? zJMjD8A4{)*y_I(1x3EeHHy=V>ac#aswQ7&;{+y0qFSM zA2iU>rM4TX(WeG|;n7xG5ZDuny6(h*n{{5G*>E$Rz0Ct{u6PNf{A1wOh0Zv@$&MJ` z7ba`A2|%y0EAZos1nk&3j2aEoNQQ42F0on$lh#?ov!5^EcfSL1Y}ge71ApL&ktlc} zR|pn9D#kSjz3~!OF?r`CL*}%`fj+4u7_es-b`q*b)%}s=h)WEnK3=3}-pw5u+>18W%}qvt2z!W zTZBhdP4ryt6LenXjWM>~JEk`tlF4|$zQwHY-a^gS093{YKRvlm<@^GA!0{Ay(Y+ zh19d!@2vA@HtDU(zo|FoC&ya;;65Y#oC@VWw3iu@^;<9RW;Elx)Et)4usBn{elDe) zy^rZWA*8n?J%X_=;UBYTd>$)*izu~N^${za-UI>*-RM1c7NViGkKkFq0nnZ%h%J4E z$;K92TppqV53KtNc0W9gBfP4?r?hh7=3@s#;|(EC^)h(>rW;48)7b7?AK81I?*aF& zhU}piG_Bl(--N4Si$g6W$LJsaejpXxK~KQCSbiSr0a=LUa!Ks20g!r25Z-pBsH~JK zSTPa^wS@9u?%8eFu6USON~Do3ze<5*j~OZpIEJ_WHNnq!93zK2eF*>b0qq{f@ITrK zH#kb;v55`*w4DmPDCq>0(YOlMJ<-8I%fzvd?+W7bUn7>SvI8xthA`c5D-Ni^_`btd z(vc}mispR+qdgWh9dR7Z6R(AP6feV&2hmt?-B(hhqe)6F=D{nOqDb&?4z8WKi&Q;N z5&7C|Y|||R?~1I0ETKw#HpL3(N7j)O2@mk}P%h-Hj)ONp7hrL7Ka4IGk-1)@_`ysx znCxSs{m#enfhz-Our!J2wB%vAp;}t@!Dd$8s@>3LofmySc?8JgXK;&bEPfl)gynwR zpr6{RK-m`u&<5Kfm|=4aPknrYka7df`|Jq5miVAWl8Yg8(Lo&bwH`YB^8;yiIq=hj z1G?YR3V!Qs#LoV0@VoD3x;CZ<7*~0qXs>L@{o#YPbUvZ9Od-&ETbxRqcLF9fi39UX ziE!hU288y~`K^_yS;Fan|xPH7G$@gr8bAm798ym!taAF)id?^#Of4+_?VjsbMi*I1-HJK>j z^*4H|Pl)0)Tfv7{m>{O67W`Okg|i<@6P>!l__5%8U@LkME@``uYVxa~hS(Fl%&HqL z{yIZvl?DPYCm#R#BoEgQKf>c%51`49X&|qe3pvhL(M|R-xczk#j`ZJ(Ce`BTOKp5# z>eCjKGuj6m7q{ZRcjc(1xgG(B^C13cAFeEajVAg2f{E=yY=gW6{fo9+^v!*8P|Dyv ztidp2kLNN#E zJ*EsJaZkbG-v>Kj|WeKLv2%a|`OW#Xb7Z0v#y&sexJj5txsa0)Tusv@Pap@*9idWOe-+;lZS$rUIQzZ4q*2saqvyxVQ|s^J^Wo%haOxX z20=QFcsz!$=`+%4_S0R^VD&Y$u5dM6)zX9$@(-YpE%lQ>(k@ajhgBgBSmNlL*muk$DVd;8F(bDfDSm{GL4Eeb?mz1e*-&a_gd zJ<`-FK)%hZKs?)na|%3j!uMkc~T(F?=g};VTvXL=3wQV zm1M{FqwIG*iR}HcF_2m0fO+>KNt~nrb_|JUd+c6F%#ust!?)|u>-&);X&HZBlAOt2 zQl&?BPc27bX*=<<$|K}0uMFS+dX%j#ZA+4}(UX9h(;_HV*_?cI6=Uxy)6~!7YfR2{c6jjFCp`C@E!NhUC8yWeklxsF zkQ|u}AMJaL$Hr`tQltQT2a+QdmxJNAR}i;^J;DbymGH^5=cNAQ4}9Ka4=}d)0hGZr zeB|>+EV}d;RJsWS^}{2FenO= z!KWpB;9n?9N*D7`b7llMACLf)oIawfX?KCD^aM`-odMm|RN%v>d34~?R&?dxVyNW& z2w!uqg#B6KphL5J$PrTf}gZ;mcV?T>|XH572k%0}e% zPKBsF$-^z`8eqs&mpa700tXk`fcgj}bl9)}rP{EG-PI|aa!efrY*>z3uSnupqeSG3 z77+W6?Rb}!4hT^=2a?SN@X*OlSjwD7ey=t}ap_G!VfZ+*lAS;@wL|dr{wXX7^iZ}W zm)?+B1XJ)ol$j8WR#So`rE@3#pZtLLS6|-zzsL{J|DXH-0fA%Y|MMNAI~E=n;lKNz z>;IHNU?#9VG$6o}rhL8kdGqa**5)PxoBkhO(q1M_W0GY?N5zH=TaMmrD$_kxAKs_U zmUuYQ;QnM~;Lkgwc!3dyNMjlpEiJ zy2g78+M3dKwqARbEpC)9GJ5UT8?~m>KL!kH>q?p`H}Z4WcXAtDAG;a-gOWz+dG8GT zv`;kEP;%NzZBe>R#HS{d!i{BG#c ze7aG+ZOowN#RB6&bH7G4gK9(eE#oHVz_~_AXrNIwD8;8XYe`sDJJ^YxMr5 zsB!I<(?)G81{&{{_!xz1XBmpnr;Xso>xNT_2~DoYb&T6y=<*qU0!?Wn0|sB-&NjW{ zN;aha{!<^IL>ZTUW*YU*DQ}XM)NYh_5;F=a-rhKQHPDD#QfRQsp4~Wp{HLM+dI9#t znm8k8^Fl+1KMjVu(~3>DThAErNy3dTErCtq?-l-6{zV(E{3Ia6FFgMBf2uu^|GoAM z|EGQfYAVU$^=AmvwGS^8i6xHzvRTrX$7yf60Q)KlpzBYy$yCU994{1zJz3S{wA~*T zZLNy0|4YQLr#(^S4@3491vXwB(uvqfqD1Mr4m)Ms82L|HgIN~=;uBK=^nW^FRTWo! z{Xi;u9L2#ge}+(*hZvSvEzY)`Y``%_;-u{ag;^I;$up-&Z1;CBj<~;#1PMFiE%o!U zf5JI-x#53c(XRp$Jei38lxd+muJT0w^D?*~T84JmrYTiMO~de-8?%vcd9!{&*_c3(7CB zq*NyU;w6`h@#!1`BC^JCAHuj63mpeL?$o@1nc>nGXy)k@mk)r0D+uZ_ZF7?ygUP_bpj?iuDeaP-(2qS67pNb~R+LRT~NU z`1gy-?7%#Lg8dB&y%#bm>5Su zV6Vx7@>iU_*C}pud^X4CT`HH&y1`ZOJHm7F;c;@L4mB&>ifGBGl;W71MBAZF^4n#g-EDr(AKDd%;4dC@$o_LqCTmo}YQ7{_&;x4&h*!b{`a z;%v@`PDhSQa~9{{J~58R#YyAoKg)P8tX>!^_lp@1_#)HmeH>obudAG1&p(`&DoxJG z;|4tGfal!yCmVS`Z_jdEH!E;7cPeuHtsP9apJ$nttx0MrJ*UX4opCaKu)UcRnLfg; zC{!_BNS)*gJpak%_3dr)3%kMj<%3M4?-p=-F2CkR4~`mNC$XkgZ}v6c{c(~zF&o2u zIaAL4I<y99V=Z~x|8X&G$!sC9vJbH#8=oL)ZXOj~TDqP@JSOmZ>T{f>qyJKB(2 za9Nf2NBRTj)5uD$zEcV3Nlz8$*{Lhse?wxtx_1%WEzevybzKcDB~F37>GL~GEB}>o zp0Xx5$4BP#e%|olZI!vr)w}1+`K{-~Yt?h+)$1HL7LKpv=rIeqxfPGNSxGXc!_{8A zIm2r>f}QHT@sHiyq}Jbt)`5LSzdT2{Vt3A(XeURS(jTo`uAfrog?caNMW+UFA~XxQ zR&xxvb@8R#=}mxp-Eynxc)c|5iA6Q1^4%2o!$EJ;4SP>AmQCvmcabChZ@$?lcn9PGZ&sg#%D3?+)0($b-v z#-kf~I=rVQBfr-0b~_}ugq^y^S+r!f$!GtkmPD@~Vg%?E8rGAmKi@-gK7hAECp0*{x>k5+&7gz0uV4+}0(g>tpA0 z4;qYfee?sH`=<`_Qg6#}7{-X#nlNdcz|H_+o~Gy0odO5(Xpg(Tx8 zU+o~Xd|72qXyw{v^CHgXF!H}bykTh9|7ENU^KesMqlS8Ag6N{TCR zNS60N^$usGMA+1ZVaRLP`H|~Vw3xTk_AK|MSOPc6(v2Ilwc4~obYF|;4M~&ZO10cf zhnAMA)MXrKY+@>*AJTGfqmHSK(|b<8)&ED@ng3()Mt$7AZwXmLM3LP+bIrJCl4KX9 z6xx-vY0;uZ*|Mb)*~(gkvc^4g&F!9vP+BCV5~-w8Nt?cHq{s6gJg?XD!~8xouh(_1 zbI#|S&%2(#?FcSfGX992NIA%lj;`gFNq!_6Vt28jO_l7+Wz)Iu&keacDLL}ryD4wZ zLtjMyy;kOQhxN%YKYdPS<5j+|%4J5G9%1GFHIr(NuUW0?NHVNki6dr&bAiZ1e$M`0 zLb<$={Zng4{xLM+xXuZ}V8uG8$~9+1WjC7H8M3MTS0(mDW9A~#^j-k_a!)N0_`TdI zsWrH1(Z%J2NsS^Y=N3-kJm%kgxs}_Y<;M?x<-$$QO(sA>45wAn z$A3ac^2MFBi3*iy?%X^xa$ye7Vf4AAc;#A;^|{(GF*Uy1WcnR%z1VrJ`zh7`TX zcX!SZ)^oH8?0O+Fq<=}2180j0)PAwuzQs;|j~kOSnk$Gy`_hPgm(~%2cqh?%sbw6b z64{IhL*j$hNjBG`v*}e;IsrB~uv6Q~{IKP(i4!};*<&4hNSm#iq}s$s;+Q~9w4^G7 zm=QCLtSaA53|geK*|+mJCe)QR>^w(=>pv4EyngM}*07NycmL*}@hKE`6#Ny9olqx@3heyIXQCiSL%h6+pxZ zAq27=#1zhg-PxDLH;l65#6~?xUrJ|hdzx}!<#2{=O8xqNIR$y-%9Uu0F}~V)XpbqoIWCM80U8Yl7y zIM3R|DscZ=pNT4~%!sNBsqC$H^F-<1Mr6~DNT;POE4hB<_beSckKFb8DQSKDD!;!$ zkGwaugY$j5oitpsl59Pe&B+fNa-Xfw6I)PE&U?Np$L|~xr5WuM)fDmAvwgbU(F5un zzjr^eE7O5JGG`Xy+HT0{%Uxy%=~IN^?i6DBV^!kQ$QQouO?%F+?KHdMXDsnE(2l*K zYQXKezl89;8%$arI>~nY_Gdp9NRekoTZpmTJ*>j8C+V_OnscnIWi3o2SWlI7{^E*{ zA{$(W%Rn=@+O@mcZ0!d`)x>4uH{wa&kP;`CsyDGm%B;EmhnGd`t;D&ov_<3_uaAUE zrihhJS;%criX-l4SaO!ryI8$jl0?g@68`1wLxijBQdTnjD?b`*CTd9^Qp|)Ss_GQk zj)nvLwYQ6$v@fcV#;IK*zn(-+VdN|k{XUr8v9yatBNlM{C1<(J?HJqITuZe4(dNvy zT_T=EVPvIX8P~6t$^X0ImuPRZE@}N-nl13$#O_%*pWo*{Au_u8Ni^YVO}@G<&v~Kh zoRT!n_iyRucXWOw9$Zc3N8C8aN}2uQzkVaj$>(U1anpAZ$yy4emz*IP^45a*^m+pk zbhe847IKn(_fw1u|6xgf@eg39FRK?h3XQnStIkh3;}5c#ix^h@#d$(LyPOPV%-E-= zE7*a@i-^+cN6Atd6*jiFMD*s6?NrRrWV1$9*vHi>{FJ;{?$M>o?6vV#9AD)U+tr-T zEz>sPhV|6Rh~>)M?##p{?^};q_18nJ_lzF)(Y!-VX6JEkJCVc59Cjf)J5IADtK+85D4x2Rfx{g17wq@6!*fikad^8Ow3zeOo)ZO z8w zrqFz6E82e}v3h!31?y850mj`Ea9`_UYJ<0B*;)7a| zxLTShamz_|tJW-b^`}qly6B7SZ{B-i9oj@3`I|Tev{=c7omJpA9VE!3VqDxxA5Qd0mR$St6kEMWfrvKBBAh)8xi}}mZLbmz_pRP3LF1~po{AG8aKQ^vTzI-?$(yMD?pKN`}?oK^G zjz*2LipI~0gje(UtDlv#Hcf`yXvh=M`RGC-yefvMkuznDH(QamwqN*0UQV29%zCb8 z?^bRwVIPaFOd*y{>XOD80mMP=Poi2)g6u90qO4mk5PX z6-{o@8QhVfKcd^+ll%pTj<8+!vpA*EFZ}((g+$*(CLwjIQj{1sNi1sf;=UD0b5RkO z*}wOfvUex%u@*nXIrTNkWJ+TOS9f+{Tejv7y{#^RaBKFr0Z#I7S4$es4k{B$Q zWZe?2*~-nkiGPF`H?mlXYch!!dD<2bw@i}RhtA5R<~D1Q5|AU6C3X{fmtx5|KK-JM zjeCgAzcYv{o91)N!*8%B=GXDhwA~=OR>u;7)CWSW#*Py&mnEg{0IpBonb=X6LHt?u zlUVgbC{kA5LGTu9bN7{$M1Cpr*_v}ztpAf`PQPwcvg@LrvRduMe0_@q(xd1UyZQb# z)>Tr9i=MB+R_{8`ul7{qSg}pq)=_8fZ{lSl((DueeC;B~R zz2=%V9liICRT9f2BpzGxM<00+XA|Z-#RMg>*BbWnPoLOBoP3UPq{BBt?`9@j@z9ff zbMgl9VO}S3O!flzU`ZAKuIg)Ic!o52M!cSA-kLxj++s%h7Cz<6jlO5yrT?&3SAQfT znt4P|h6#7~QVTob-NBw#*vgeEx)agXo5}AVt`H)8sy6ua-06HpC^7x`K$BDTEpCsw z0(UdIhn?3ljk{)QK{n*Xv#wre*-uA?h&e!vBtA)!HnGczX|fZnOT-+`qN9}EBN0yy zMD!C^O$UjT$mv|-gdzW}i4PezOTdnK!=|97jqFblEYv1+I6ZHMh-yzH3~O#VEe8Zw z{&OMUq^O5AY3}3yeV0o{tIcI!kNxGpOXqW#VGyVIO@mCPP7r3PQ|HLagS~j5kj>rj zniv~h!gctiPW3;&v!AItt~GZr8@25g|M>JI?(p;=)cH z@=fn2(V=Z9$LfT03Tqt5A=fWL*1ekbsc2{A&Ne$~c-&!Ii>Hwfnr+Ajc`rnh_1&WO za6{5$X$05rsY+fcmL;vtx{13PkN6%wf1KtPXAnn@ePhL*%p_wxmvi|K5(#=uvgn$X zIC*ZDIjO{(N&2Ps6EeRONY6xPwkf@kIQUtDtb1?3fBJZWedBk7)#A#Dk9BSAiBtvd zVCg#IMcQl**0ip;fFXOG+pAXtCY31R|bapgu*FDa2V9{fy9E>9s5^JSbddWa>r z6cNv3&JYK0IFLb|AJ_+yJo3H17n!Ny&FZcC%GMHL?6fgya>vbK(ekg`h!d;z*sX&S z+~$alqW{VzSrZG4c>Mk*A@L3;|MI_-nx&hK9(t3Te$dcH9s zg{rSa>!ei3(oM$X_R?|o*}EOAJhULoCcKGFcceMq(Y@R|IX%*`?JS$wL6Eop*7Bc5 ziHoL%Sg`wl>XP@PR&eXqoa6=^_Y=NByI9%oLNX=KkYCw#iksCQN4!b#6UqHUSl{P6 zMCoM#T)Nws=*4_{_Ms`l{rA$9oTqb?sLmjsFVhRzkcQdpcHl*5NnT(RA4Idf*LOu*P2Tb&eNTxVK62-3B4Y@T?&HKK z)`Z($a*d?}7I5WLXD;PyFVU3UO=O*aAbPV%hP^MfnbdiEQe=F3Ggtg=A(@)Il}pG; zViU4m*sJ!Timxpbjg2ahc#AxFIAw&G{xz2G z`yzu&(mX|IzKLNUJkujC1bDE+d~I_66%AG;0OiXc_afz9YH`*(HOZAuGstDYnrnGk z#!hr6kPof1`A=3Av5t2?5)Tv{$(UE4MOnko*=c1xtgc2C`)nS?|1C=3w69x=zV1^d z_xL?wH$Sf8|NM8A&3<%Bgcurf6)r)XM;{F=ZLHayE*~7|_Yz1PB^QR^W>Y@b4C45 zjMFz!hJ89w?{!49=o)JN4={j-~UdH4$#WErc)gxo?*0T=F z>j>S|L7Xw`%oWLLb0eGqcQo_}J3Gjf#eL=w^HzvhB|k{)3s5DIH!4k?x(%#@Xg4c+ z)Q8w^S3vq-K0r7OZ{nwqYLW)~j0nxjgQR4|AZuchOa8C+S<~N6i)l~kPgBqTU4L@4 z{r~Hyj&}cF{S@@S2VKM#c(|(^X$edK=lwy$()B9TV7@k1n=^|1Q2hdDIdsr(mxp2x zUn^ki_BA_N>}W&dl@&4hmGuI_<0|;-h!}S2h={UbcyL3*2T+~aOzTFz76jHTWMrNO zQpO#zSg2hkj6Ly>_Uo8M&wV@#yk41ys(+nFb5Hf5bo(~y-cyvh_@6QM%U~9`o}Gm4 zm{S0)2G4_Qk5>x9Dqp~}b7xUw$}<45Ie=oP1yi5q(X_9<9}+OdzBFf0WEvukreQO% zjp@cTE+wFj9vPwKJ?BF2S?VBc@GI3;(}h;go&mFFe*g}W29%jWFYkuL0|56wN3TrW zq|D`;=wIJP8yBaP3yL*4@ZcFl>hx{`+oe*JcCHMz{E-rUe`%RO#_KrUtksM3*4Ln= z0Xo3m?HKsx@Wo-ZO&T+K^*5bzKh5!~`X0EVd^UQ{IZF^1R0`5=UgGK9@u8kq8lmI1 zDvhcu)-$0~Z1<>AHLziR2AZ(emEPfgg|e2-g(=hZ=zmh1VP3~#(DZW~raF5bCU(8L zF{M`?(+@a?&UrW{`0ZQQmOLyLoXZChQW5!pPOO>N*l4Yss`BHkN-icuO2P7xDS0^ zW@Gzz)38MN91LzKMJ<t1T*ZXd;>f0S`Q?e%Ga3>Sl zY59ky)+}Kpl0xALX&d3`#ZzW{Thftl*WWVzx8(7jl42`eDGcA~ z8q1`_ghB-qSNh(=EOf`UpJ?K~2jKJeSmtc!8@Q=uz3{8gFkDxb2NDf~aBr@TQTh3W zVXt@ynhxN?XBX9I|KBydcY@_GBwL!63_Q$ehnJ(C5w38-UyjyUxEy4;iQ&ADImk-b z%rI^=<1{{lajO@Bw5l??hLFcfBkP&`S7prH_omEUvlQr}+>Gg#tblO^*Wt{E{~*~i zOuIbS63BQX?8PpEbfBPd zyAj<~i_P-5M_V7c&-^@F#9W#E3CbA7LXSsA!U>llI{j!l<$G_IFkJgDGCgCuuyg4? zv{hD87>C)>OSO+Nx2IT|8E-#=g$jLii=u(>R%j;n**q2|CYv+W!Ct)mw-%t!uRLdl zue9@Wg~OPc{0^|T(N&oAP*RvPvrceU=L=Dwn7Pb% zL5jaO6C&>pg`N`dbij1shYuup+cN^L!ai{4&2z9n{3;|wBJ^~c67#`w4Mt}nOmOBe z(5NQ`o_Wg)75836Pv#n9vfZ=5>2WLcV95={{m5SimSh4Anvf4qqPumD%y*i+D-%Qu8DLL9AvyT?a*Cc6|l(|6gzjs1=xJi!OsK< z&^1A!LSH|Bq1?9$#KOo^*i{$BQG9FJnTTmN$~a8!mlDL;5AA_-hZKB;$r3S9y=gmdYT=g2i;aM*^lg zD;yeV_A%k~1a>T{g3cA6Vsq0nc>Jy#u>W{1_3_Xa;izj6ohF@t- zY>ygH8uA>y(b$Vzu|LX0^39=)$|B(*9S&<*^b$1pZpUrXvKXCa2W-tCN@e+L3VRc0 z(or_W;Eqfn9QO~W6PdkCe83U(eTg3SWtTKuQ@Q|9rgHd!9dqH!M-{NJ9%n{k03)?? zis5a1jb0;^!d|5WGP2(fVQc)q!-Pq1T4ekUOA0v)x+AVZ>w6v0YttA#DLhWCQ+R^a zHD^+!@li~ywTt@pZW!x-qzc=OqbRWl7ohHyZ|I)qWxz|24qBpiVV8U_@UluXg@q=P z%;gO($hT*A7|H*{K%>k@`r$o3<}mXCQn8gsUld$LZy!$;)a33GhUu69#~Dh%Xlp0< zIAqCuKJW#;dU%Q{xTXXj8$M=UXnKM@b64OhO`5nuexcxpq$0jiE)f`ciKrPhSFnvw zpU`O|Bh0^=T6llz{;sz6f$ww*7`cHD)MSh=TCO`&n0ZT;x};_!)SW}3Uy8?=Ck~Zh zX-p(DvUv-$vi=hmXP*gYmG=uJcdTYo*1dyfXDk_ml_;9DE(tyQOoEYKg27w7Af`dg z9Nm0oi_l&T6#{!F^bn@S1f3zEzd{nMTwcR8?u-)#?}}wyBE!*7fAfS})_sSheJ8^2 zkYjesy4HB+$b03I%k%n*wS!s*m!f zteKwHt`Hs^Qx&T1F&9c^M4_T}#%SWR`RG)-f^HuzMs=lrz|w2tsOkP6LhT4yR36%+ zHw~Lmeh!VsPn=_pZ5@I!udWJbZrUc?dof%1^_~V8(3BJgnwXlueOTj8;PK8V()4(4f_G5nMKlKJo2CZuq! z6MZ7n1KvH{hE89a%T(Oq(R;t(Op>z`Iy3MR+LkCL+RtWPe;}{XhFk?x!8GJ9ftS~ zG2b6|U@ZypG!Y!bSX(^AuAe#&{ckA?TF! zLf;3<-*BWI?|3pPch;c(|MdXVJxgJjg#ifP(2f1DlZN^AI?P=QjJfPIoe7P64OZHn zqKm|OfX%=CjIMk=aFgkVT~ANa9a9_MYi8|2rB7u+DXJL`OmCv6E&L~Fy?Gg1ChrQ@ zludvq8mFj?w->RSij(w&pF9BXTZJCoph`9$#jRx#sU za|dE`GZ&nemeLrrX3HE?|F~0mLowR>C{0g_ec_E8>R*aSKeXd zFIY2mRsX=F2tznp*2?(Z9ikOJnW4OXMWOX@l0!tn3}JwT2KsYj2V=}028Xg2FegF} zGs%*<*qjrapzlv@;eVBX;l2Y`=^&~D#^qNdmH7=w{BQxYNo^r;J;A5Ff~BC9x3W+m zryzWRoKbVXvB$mC z`~q>IM9(>R-Oq#BvF$XybuyKC-RusIUf9cM$(~|XS#5!cKzsvJHT50FUluVZeqVxq{UZ3^F9bFx zT!E`FY4G7|1{^uIPB`-THX^JkrWfg|!}p%` z$eSm#8QtvHFy!k@VJg3#2{E=8UZv(RYYVn8XSUl3(hc>5c?t?bI&86USLdcFlzO^g z%pjimWb*(l-X)3FtC%oXPDwF($UbIY)m7%9TL+WVp+M<1X$kx9R?yj+iU5#_j6<$7 z+L3*MaVKt~*c2yGyJaoNdvlJi)=Fp2Xmv4Oi+>B|h#q5e+SPF5;o~sFlvYuD58KTTD7;9?o3 z@2-pw1ZIF)qh0u1t!dD?suu1XIU(F>;fvonm51M7b)PEkuEF!2^iiL}UN{(+f!skX zQLlQ44VWVIw5?M)O{N`YA2SOcGo3H|C7uXQ>S*KQGk#-LGrKV-y>XbQ?G36(TV~CD zC;Yvv1ZJ~GAKlZe2aZ*#3X|?sQWvz;!8Nr|Y-ZFx`ah?7N{)HNOl*?F3uhOBIg?gX zd%_dYkBtNCtu6{)zO=<+z%cb_$PoYLwi>e>EN8g(c-pb?H(sI}fOWcL(=W$-@UwH5 zgQ*<^a3=U8_Oz>$-fL(DB>jD%mbC?a@TP*(%6)gIIQ72x#J9JY!J!VkCSDF377=*M znIv%j=W+b9UmR9^44ym1qV$q= zX4)AVY^)dIGke#9W7r6Nwk8YrNOh%qj+fx3pO#bB;f{Fogc);A?7WD!TLZyS8=$jj|DA#!{Ox?P>f)HXA-o8Ww^P0TE*kxs4H)L`8 z5KIU5s-sMVMhH;qPr=nki?Qq8D7O0S8mwS@7bu%1hw(B*R9k-!p7Y=YZNBIv)^90~ zyI?(-OPCjES`~{8+Ag7cz7zPTM_rg^h&6pAj>9kHxqzm>N1U(?kwe{HUjz3ft_52@e8U7r z;`k29b}Y>y3kD8c0^{N;uwB&!Pw|svsK`*D!Fkj75>$YRAp*~fE$h_;{WrI31Z!Iots#b>kOheaan=t}n!#WXI{FacT6w z4KHyyKOC!2KSt-A9l%~I*n!g5VYGQvJs!Weny$b52pybO55>&NXo*#Wc;@EAP{}lV^fi5?^Ys}(e*s%wq@w!vs%cTV`?Bu zJWlXZq>HqDkc6in??%5CK?J@ta5$zif-d-e-SKQk5zlRGDT1Wv@I-qo(A_Ry8}{T! zQQp_}(Z;LU0#oNHZhYG#p4v7PZRt%#m!{4`UoA4H^4mA^9&9e8Z0>JCbrM35(fRYy zE#D7KP3@kg6XjR(DoPB|d(VVO$gM2ihn;5~66^NUx$d74QIs=P;ics`FX}4wT=y<- za@h@s_^w09#SF!U)UM0C+NV#D-uB~Eyoz39fRQ`+n0E=8Sr^_ocD5K@B5Q!i7Aqmw zh3QC(M^B@{#dIF8bDE$lBeo&?%OdchA`3|oD@49FwFu75=s?4Y+UX?6)MkB@{;?eW(I-WJ-G(Do z7k=Q8Wv5^^xt5;s$O4ZtG@%vT-06~nKN#;>1-)S45ccZqGz=s^!!#;q;ryl``q73* zm|u-FUM|^z-Ak8o%G>A;ml{aJXPvV6=CA^6R&G5goF|65OlUZn`bdG2$~0J-ZH<2l z8^S8}r-2T;2w0jY2j?i__@ky!JgB7(q`XVU^UYoG%nTKHzQrDY_HjSH;_Ec0tS(#n zt%Ziue>Y7i<1#8PI*#6FKMcfPiDAf#NN&`R7Br zNSmcU&}~RT=Q0qj?t&A3m#Ie2lQ2$48S7L%Myot`#zqw>8Zq94GdmW;5Kj@z(uMR; z@HPA^I|6pu4AUn+wd03|x6s3eB6Op|5j=QZ1-()h161T6Q1B{;zVaahpL|QxKV+WZ zJCwa~tI!GDIbc7QGbF&Zk`%GrnK}4eK|Eep6p!!C^2d+kttQ#<1hbihnw~RdazN&>2P2xK-v>%`~O<;ErYSNCGRJmeIT2bxt@<5 zh^wWqP3;9SnqBzC&#SQmB?;K0W4)Na*%rEgovPs4Vh7CnsvPzBktKDJ+873SZuBO{WuHQ|d8PcpzF$&28*Yc;yC z^t7P*%QU>qc@cH*;W|2J#|lhZ=MA`A&O>w8ETr7-4Ny*tR%2EEB<8hLpH4F@z=pe= zfnCucb;x}#SamNITlD)I_U(!xB?Z4>Gxo*tW*B`&q8?2kF`IfCKlt*&7-B zFE`|}3!e&VzE6v6l|av|+1ME_8#Vnoz}w#a7;#0tDDgQiRQ{utm~jdQ#6}Q={BxF4 zD&L2gZAQVSExD9t&Rno&<}GUD*K<_wb6ZqN_7OTQxDPl?`Za#lR7N`lsvw_dO{pF` zj{b~4Nu5=6#rpE|kfpBa)Dq8JYR8;D?EUST;M&J(%FaI-^N*cRwQ-o^;45#eMY)th zsN<*+TY@M)ucB1e7h`G9$^_1TE@FneH)5Lxr0}NH31sL*Hx^&12Lv-zvFX8|!DhSf zV75>kyYMlG+8Zy8Ed9h$=J96)_nveLYVY{)3L>*GwK=xf;K+Z}uh?IXJ%M6)*CrM4 zMbD9PdV2|bQ8btOWbzTyXnrF|I+=q;ZMs|UrZFGA7sz1BO<}0j*Ak#M{DCR-a>gEf ze~ljPxW&kp=U-Kb?m+H-wHB5cP0(szld)XqGoY_oMHnIdoY}EPv%$1{Etr7|8Jma( zI%)SD=FqD3OrM%KHhASBntHl~af>_waEBybT=i1SSMrG9q}Ns^I9?0`!A{tV^Acdu zI!kQ-^k4Lrd741(W+tfde}L#r)MKk31~Z~hQp}{(1T(H00N4|9LV0O5;JD0;v6!2P zyw2K+&QUK1J4V)^ckiWubN@Ee`Y%r~U&s(F@C*i@ny0~I+8>a2&#%D|@*cMS);erW zu05l>OaPwwr$ED8A)1$Vl_|n`m@lEm0nZI- z(lei(0|TDY*sr5%jmv&>@Y3CAW)22~IX7Q2wi6cwxjy@up!Fs2->Z7Ww)+Lt*gOE_ zs;+_Fn^sUNF97%_1ORmTCFY}73c_2ILQ8h90~wFvkyWMJu??9#y76B&mhIdL4Q7>r ziwh4hyIVIh0{bp-{){wzd;Ffm^^O&eKhyzYb-}s8V$jS{wsnVN_UmNF_ESEncu@p` zZD^(^1`Z%AF9kS&EO)vp1gEtZDNsx8(~tp8GrC|x9Nmk=JL(7Ap;wNU3ijG*HZIMp zK_|W_HfjXkr*#Ggk=MTGkT)O2k;|{Q@j_&*9bYL_A!%W*Nbu-Uhul~9QNGk_D*1#$ zW7?25G@jD^f)+Z^PjGK)@U8~pWN$I`e%E<<7P5{T%Xd3$GWy^!XjlF&y2vL-ur-B8wb+9dE8b zPiy`*f$3;UaDELpeR|(affjLZ9KfqVIoV*F=Nlp zh70Ca4wDB1Xrq*eg2NFuwAt!%`^mqZ=-c?ah~pR50hKIv95!%6mQDHJDV|(U|9ex= zIAAR2I5^trP|nphc!mt3eh-T%%^L^k@zrzD=_-@xj63p;E}N85CG9qcw2URx&Z|w- zh?*H(Br5@}z7I6;9Zyj|^5!@ml{n?-GPISJ=}@N!x0=vL*ZMp5WxFHSY)>~@Ng1Fn zDlZ&zW7QlRH$g#jT7=`1fhHuhZG&Trx)g0~AL}?%+uPCF+KsllAxH1OGM)C%c!VwZ z)W}F~Oa-g87GkqrKH(jDKaak2S{zTft_Pg#X9`W3chI(B8E)3yhjGunk-ge!P|ad5 z78jBMQ!ZNzbJiQ-Lt0vh)wbKrH^K-Xx$^}sG^(OJmXr&-Pw%C5s1kg0<`d@aM+wF{ zTpG@`k;JatQUi72E@&p##Q0{U!|<*9gc%(duxFPPv4g!yc+|>Q%$D1b+7hfxJ+WLR z)F@a@=SFkjR$L)GGcA{1X?uYQn_Y!!?4OIZ-?xS6`bco-u^}$Eejc>%abqt1*~+YE zoS5QAwwOH8Pk;Gsf?2$~!o>RNU@pc6OnQa{?5WkjW3P(=k56ymYyKBla!vz&e-cW4 zTq1*~6z9PFRyQoZ`Xv<+B8~46`oL$3KGa?QcSs=m0DE?pHm!05KLU?qV%I#8x)+T? z7^=W5IPe(JiO~^yd|M1w5sA?FpAD9c%tRmbD?{V0$>{vh!vc|IvCw1NE%d~qc1Ww5 zV!C{q2}_y9bST|s#J>5%$3<4cmI8{-Xy1ZQR2$)U&b11vyln8@Ruw>E%H4SS$!;wF z&RXa;qA$F6K9xE6d@FWl!2vi_uPS^WUn*^0#wy-r>HBaL2fv7 zuJ(XaA`BMZBZcp}=qw8sHN)W3`^ z6hC1$TzhUQ6<9m~!b<8OA-|OAPpzT*7EA*l?&X6`%}1EnsBox%G7+JL2264MUF^tz z4p`rleOO)F8n{a08dgzfO}DNi!BXXEQ~l#Suw?OOYMeHrP4{5vpL#{~rkg!RM+o8X ze@oHEV-LW(fhekNWCX13oIyYNrOgDji~w0BNqBKxGa}ThMCbmego|z-01wewyrI3u zpggGs7~PBjEAvmlJD-OHIen>u`oeV3xauN?p)8ht^DOmKl!bZh7#HkWyOF9pCqis% zYEY-?(U@iKA#CICLsS60f$EyP$Ji~;hwpuwD3hP->0ZPbD130I_Zhtce@FIERpe|s zTqyvYulGRu$S&YxCy#Zncf-)zC}Zt=0o?I&qy3MmGv<3WsZ;mUFqNNAKs@}6{pq=h zmF{1~dt{de*cG9mU}qL(Q@jZM{Go~N*u=nfs~3QQ+vhRsFn7AVzZdMB52&o!k-*wy zCEB&~GxcT!Fou2ONQj;@N->I9Y5ggrGe8=s_g=;f$uD$}X$k|FBJ6Lc4IFPZX0qKB zskgUf(e8~8nC0s7@bg?HeDTtL;FMz{>`=^Q-W~~|{^q5C4~>S5*{3{EU}=IsqNRn3 zLzQSiF~rifWrewy?}0PQG01(8kK0EqKuzi6!oSPgup5W8v0fQVpw|T9jY@Htas`0X zwgPNr$pN6OwGMZ9;?Hy*{04gz*9n=)``$tiiT_lRTyW#zEV#JoK*f2D67G;BM>Hj8oEH>d@B(#P&gZi9z@4PigePRA;f+Av3F zdq96Q#ycLI13Dgv@JQ)v#&C+^eW_PP=)OJ^YS3xO{Gdk0b9g>jKc@3^kYn{zUg4oQ&XeboEx*#F&%`lN705LR}Z{;<=P+Tz!W+2joO{eI=ND(zJ^Ae?We$e4t>Roti*>s-8Gjn=N z$q%}Byp}doNoh2fT0kG4R>Sk!O(a4nXg{R~vhz{tCLtSIESbov?Ri z2RzNJc2vx{3?~M}dHoBd>21+-9cP9&Iu;E76;OqdyhryH-~#arlsvbMx7;@uA%DsW zS_x0OAl{ia(HN)dTbp_8D~>W4<#=2F<$yx%p>@b*GW-q2%`@+UXLD^I7G*Mrs#XFQ~-<;F2Q zQ;%F2g zg$dr|s+r7%?yuBh-?!k;OByXYIEP6(djlSr6D|nWb)_8|nqY5%IISedfQ5J8!S=1? z$hqlepptHYYm#OHr?_*xi7k9=%uNwVS8-+<22O%U4y`D6^&axb;}m^X_Zd~Hew_Zq zP-w}lxrn=xF@{<7!?v%_Xx&fl%>IBPuwCvBJ=Z9T=Q7j=#yiG%$?8w(SClUbQ?-%L zZckC^--oGNi&SBLQ5=#c<4iAiDS_!bmC#LljOmI$kzgq7Eeeu#p>Dx?G$Fo+{^}J0 zHhEo#7ru_7i$m(Eh|jCxnjaH%@XTg(vD#YH_{Cjh+%t+-Sv{o%cVI}SbtWt@Yn$Tm zR6yRpGUWN}G~Nwz7fP)kr55!qqxWj$Qmd7V=@t7=G+HOeVh>8&P^UkGjl78kpy#e5 zU06Gh=U~}Q5>$R~z_j)@!ys<3@vF5ob22P}Hq0*OHIyHP^D2tagOw9tV00VJ%rl48 zdcG**WdbZx3mu(Dys3pl)3DliIainLHNs}2uGC2EYk;r1L|YyX1#48y!27IAaO=o& zaBde*crBs`yE*OzSM}~^#8pnzYXWbN`i<0PR5rR}sY`R=((Ag|(>Lwt!)60vq{?Y}w#6Xe@Tb7e z#uU6a=|kq^hzl)Mt-%k^1ZGh6KH`%#$lPoVLa#5%K;o-w!A%btxNwm=^US-5{!8s( zt_5}R{-Y!CN%b!9L*3c=f@fi)ZP_rWq`!ReHoUiR?OhyUVyy^zro~sWx+N~4NAH>lst3L5A%PI2)h+Lqh zl}Dw>EMO!m5opY}!49;=z-AJ(R~-RY-K z)}-*nyNUrGR!j9vZ=v&gdSN~YL)Q5l@v0pE(Cnu|+O&HNUA^OYW79hXUb~`(bSZtf zYWRiaS+;C)G#{9%0qn$~SX?x?DshL`V}FhLP?Z6{D?fBpTyaw%>s>-O96OD!?^0sg zs-lsm>S95Pj)y=+aSPJ$_zIKm_Xmxh5epVSKFwTn=a_M4!;y`^_ z6&P*bkJ(q)qva)$$mXXnp?~3X`;U$tg3O*8aFekB;YGT1$I2a`>zElWhJ2!(qsO4p z*|Ux%lYbn-BRUb^P+Slbr^9@iQzwv|76umfofo{aeBHRDFA(XzGBqzV?u=#+`ZME} z`9LqChBj1>fkfwYUb6mHL^42$343cw@5_7%;wzHT^Ebm8?aw^s@Qg!^kBJ;qx%?PB zeYgY-QPITmiZ(O4JFTGK?I++xD9)5$69dZ70Ev5h3e)XuLQJckGM_#RK;xEd>X@Yp z8tYaGrB|rY3_k_V62A*VV+zn)+9p^qt;nqHP=~91(wVK>J3-EC2u;9Fp4!!QSkQmx z5HWFQ$WN?6ZC_tO_}A%`vprTx(`?(JFL(b`GyMo?6}~7zpU0fw?Y@tq^F-r3IYm=u zi{%bvc1i+l-C>NR_J%WNUqaD^68XF*>!rcN8-{d$?<(3(%MYFks)MS6Vh6MA4D7Th z9*r|C6XfNZV8v5CVLCnomGhmN?J>y_@NVj%k}p!Js5mKv=--KL+VGs}XX0sohAtzY z6$foqY=CE=6)2mk)#~;F?6=zsBz{LMqrX3nSuj@-vE~w($fGqhT{g(uIr4yAWMx8%IeT*^c>sJHb;w=8kRO98P&hm|^+xcj!df z5+L#K5il*XWI_{3{RQ)ydA-hO zWelk<8+=UTs=KP}m0;17GaUpYF(9Et)7?L)k~B!l_Be-xAcY9c(8k%q7Q zdx{o3bOF2CPBWEFyWo(ro#lf@|P8N7F zL8*jnc8`JQzSUxSv=1D&e*^lt;wJDb^%GcDzN3!)lc(KPZWXJ##lxFXt&$znZ{V)o z_fc%5msl8)i;m2+WG_Z0g8z*DAUcNdq}qJsKV~Y_x^Wjf4?5Cuy^E=z%Ua<1#wj4e z)RENC+4SAEPbj_Lglaf85#RT;puU`U!bLR z^np}oZ0ae;cJq1Aa>-}*MRztU86$n35xMLJO)anwrQmNqEPGV25L_O-41`YERNQub zW^K>|&h@J^>URjo*MBCVK)v7Kz1aeEf$IX_wO>Oon;-1`wkjNLk$@F<&Z;!>+w4+P+#(yy*9L z;R?6sf>z}Sc3}E!YNm!BmAX#>I60(S@5`waKVE4l)YIw^TRe#6G`XE1&o-F4^4Oj` z_rXCJux5ZwD|uW}q&k6Ptj36Uf6oV7uNH_MJDn+;CS$3r2*7;tdBN%jb3qK0W39}- zh-a(kOQd-!`USgD6m5A#7>A&7M1H zAuLNVl3Z+w6t^a32~Ex3SpRT6OzqltU2wGVj93sHHY?(cHn^=^z>eGVTe7L26iX9S z)Irw*@z1Xw)@^y_tWlq7g#N>;&udCu&r#%~MI?cS~*%+?BlU zuAu^chf%tZ?YM&{W5wSCiUc*^Zg73_PJ+K`@7SRq`veC+xN+O!#t7pT6u7=6>p8AF zlu9n0$A0J1g!|uRNXEPcg4zL7Ve$b5tLG=wOD^|+6b7CjD|mBGjkN+F#Cd;hDSAh~ z@UqWptFI+K;sZIGgnbVJ#Jd?a9eog|Z$rwAj~RF#~(qAt|_aYHiP`&Hn(T~)H{*!z;BcNHiY znr(gd$pf)Pm!c#+K~~Ju2F2d-J;KTDA>v8dQ-vv~?i5G0yc3qy0P&h5GmA$rY7_6w z9VZz26I{|(GeQvNzFW!!Uu$K*ERX$Hsw`<=UTvj0Jer-nMnw?*>xkGhxJ2;sr?&O( zufrwe(+O+U^8A_GA11J;FG#HWvtEju5^@BuwBAY%_p3@)G&D$dSct^;ttYdOcc+)w zRIH-j{~1L+85w_blf5Q2r#C_HuO+*9=aE}NBV$MLv|tt1e!aIuW}lTXa`9$ypwT$C zaDkqf(cf>KX1kDmekN>YX2e?7LuR%0_u;YZ#$7iBlk(0>6#S5+ZDxzG{c5WCYST*c z<4puzy>JudU*m`zmCsQV!{<<)W=7oI9|pkb=@WEuoHd?gtVBDkoriP($pGO-hDzV) z1FSzj;;dUvk|bSK*xp7!{5M-1yuBCPd^Qr#oqAt5`rUPc_ig1;cGd6Hnrd^88 z(gKS*aHiuT-Ip^9C@+4E8%6tpzjS77b*|-}Z(EEV{`L!N2h_lv;Xb5#Z!M^ut_9qh z&eJj5hUtoXF<89pzV+*&TzGs|Ji68)r2gA;3|(z90K=Qq@R3=1aKYofV6?Rbc)a`= zY2lmD{13CivAAYj9}-S!|BmL0CdcB3E3H7t*9p|d1q->PcQZgKIYLgnY^FYits_Gf z&+y9kVZ`3y5_@jr0pj6!7O7V+#n+!Ha(rtrE_ZeYAD6tQetr&x5UvG}J0?>Gi}Jwc zhg$@pDh^~;S}M9SK}c`+kcIKKCyAEkE}^9OE#-T7KAG>=L(OZsOd?|YsCms9T$w!s ziVs+DIhQoaxZIB@mdwEg1sl~%-Em_khoZKY54bx^PEEQJrN6iHab8rJ)!EJ-if zLVa}cz>QDNk*VMAP!F%ah9d&IvA`-1mMyvui`-jq!KhEg!?6&?bzgz8zRS3t@?22Y z+JihJm(a^EDv@`Y;k3))cXUndGb(DyH@qlJiF?)8LaQ7b%@mhcaQ7m=V4puVxYYIn z)>CYP$MejQajrc1SbL2tF|uG9rMV-mkx}?h`Bd7j(1_mjT9Gl@ro*Zn@5L6|_oJ@4 z1wy@h_t8@8yTYx7{&-!R7U9clsb%A3@x)WT?4F}MJMHE#kYJ=tDoq>Ek~`+K(I!RW zrh6MKYBA+@2d_mM&c>ix!ALT}y$&y%;zY_76o^UNWbl~wCk6vL^t;U^!t6ce^xldQ zEV|^4H$62VzFFtkzK7F6Szs}`QJ+dJEl8!-q&qW{XTD{tnoYRlJ^RVJ`XJzXtAu7| zJ0kZx71Z$j>*Q3_T&(>)85_6AlCL}W5*wc>aQWT$G}0IVjeVP-L8cQUd_9`PUdSU4 zUHw4iI3=RL^&2ZQ>H_8NlM1$e+(4U%)1h#M4&&czM-sM};Zu#fVV&wAeeT&g)E?Ob zf7OHodm{pKG;OG0qup>f6Ns0==d@Ag*WR$-50AJp6eA zt@$&Ou3vr}r+uvlpJk=Gmx>y_Q`Lp9TcpfyU7$~U%sWZUR&T)iM=s;g&sn5J?9X2x zv5bUw*uu+N>HJrx_c(IaHqat2z~Wba^pTr`d?jN8=1eOhonu^S`&2D{ky#);=K6U4 z)^~4uE*u3tCp^bu*}vqhe>|qP5We!%6+-Q;mzFnGVg8*pwktnMSGg}B74bjl-ysUNXzR^Se*Yhv5%?^upqLJDqO zB}3LGOpfC^y3=tZ?P33Sn|^cFtm|X?i_<(&i$4On)r@OUaR_eOgNbVkkN% zG=on*(G85>Or-ZFNOL^)&7jJ`hQH)lNS-fO;nUk4XzlxJxsH#<^o>Km!NbgCy65%? zZlTT~O}D(|E5=>~BxxG0lez+RoXDkz*+gciFw$RxV2Aho%-f?&`M)9b)x&}Om-eZ2_@FJ_@lBVvFLEXoucq+HIVa%4C@)el z?kfIw{2^(5I+N~6o=V?S4Z+INeT=9kZPt>ZRsCc(X@WY6CNom+zJUNA*;gd=p=INB)RSXnuc_`1Q zfAa%X*ZztcZ*|iyE2fi(KmpV8(hSZGgra577GXJKF;NYLjBcS4*(S^JHx)lav}&ZN zzhCNA3zrog+)_uL9rA)64Ls33u|XuPN+4TW5mP)h8pdno@H6+W!AZ`6%n0vXCU*E5 zOq|G zhUWa-`R2KQrTP;maxd2v9nyb8i1AqFQcQ{H>V{e#Qa*vxgs&3Oa&o`jNprI530U z&B}$xrmNB6;Z02U+)MPgC-eDZS%yqzOD#;cz5&L}y^TG$#n4V#$|UjR6=vhA^KiH1 z9Fw=DkC?9r#9788dC8J9jQ8%Zgx_ci1yctYz6H`DYY&kr+QzVqIZRJI7tQ3hj-(QI zT_rw#0q|pXiqP)=ndiveRA|^F@~XCuuClufyC0U~#i9ZjY*2z8n6%M$W~2C7reW|x zXCE!wg-L3J7Cn7aBCMa$is(~kXcgHqu)OXeIb}YHfWdc!UZX@`)%izWtXu~jXYt^c z!2rzS76B_~S+bzOh;)rkrq3k@0L2d`qRNIY&hxfD*f)BtD1Wy$J+ba04BOB_qAXLv zfeIz~GNA=IOJ~86mCnqSqn2>t*k1g%K$g#WugHgan=!|)RHBNxTj9U*eCGPZL-61x z0Y7TROg_or3b^-9h0mT~Es*(i8;DYjh>XQYcx=a4ChA={^DW~cIVg7?9&cu_V?2N@ z!kb)_NhArmjZge@VHRl?Gx1mD_zNqQnJvxrRJThb>y^1% z_F)a zPdF!On(*!R1(N1>@7b|?uSsN3EcajMRVw9^9_2dq3NX1O$9+8?C|MsQQ}Xie8E$va z0kK$;D_q=NB3WsiD~@eP>^+kjL9eeh_52r-+!BNe&2~~?quoBqfp_QG?*}v3xqANW zyBr5nC2j+*CG%59v(44k!o1pCag4sXaO{a_YRs|o)=#9F zsqWPj8+zlHH9yvpn|l}tpFK;EoK}A;+@x+VP)wU5$?i-N$R2z?OUt92ySL=M;QQk- z?1dGNg;%}Db2Y;>yV+EhtNXQILOw3w9#qzgAFmGre?QIuldj$=GFvbk%)DPN+?mu| zqRsYD@;lE+lokMP0+qrFmu#bS3d1B}zpOZe!o?DA!%G7FGA}NsCTG_7{PUcmXON(( z#)@;^)gkn0%w_A3cd?r`D1z6Pb&`KJ)o`D_AqnDQ=mqK)@LCe4PM2)tmX1|r2Dd44 zc}D)^z8b(yhfXkwS?i$I^$MzaPAv-1@1d8P)S(w+{mGi&BbX1I27Y)=g`911WAa1I z@yZjL>>vBTq+!-(E~vba$qO+ekpZW%z#|MjSF**iSRFrdK8|ERsgQK80jd9}BHaRt zj881wI$OVl3i2G$TscY?KFifcx zyE-hR{~VajAnRzf;?p25-EB*>J-^^RFFWZ~hbE)_U)RC$ho+G7(;7Hqr5qU%ZiY5k zEMdrUHPpE0IZlfA#f-iaN}Rov{jF=t1m$MnBkvTTpI#$-`M^=wFg^^q-wI}zl}*Q4 zXKx907VJVFHpSvYYboe1Zl+$5k-Yr8ow#C#9&o$4k&Nzof}Y&DjcPm>N|_iJ0dr#k zTGv$zsN1usyyqkMqoz(c>d;y&P70t$QX!;QaWAfvYE{m55ol+L7pWKi$5oEI!i>8* zmWg)WF72W=U<`E%*zgsv*`wm|%-f7qv|esEFpQWW9VRhl3T>_&1MOxPd|SvZZ>m+B5Kg3x`MsMg4WzBwv~JNz*NEy^>6 zR@#2RT3muW=cdx<%cKqJf5xzdx zm+5~u!ck+#1#VBvI@GY^0)5(Co?am{8U`j?qpZ&{bnRkI>ao`wWa_+v1s&S7%_XTn zxAGzz>39Vd9lk;xYlx12ANUI~5e(Kl3i7mgfw0s4?tXaT$TVEU}FH7YBZ z!1YVsF>11j{|8y*Sy-mD1<2NE#wo{wC%<$8=GO%Ms7&;xb5VcP% zq3euQxzHj7?t@bzu1r}@e<=Tnto=f$?lN8B->v;PK2VXXu6x7fZ;YUrphd*7eHlsq zmMeUq{R}sDCzF;hp;Tz)K3Y}^OSw3gqJFIrqOzCHP%dRXoquR5aM}0`jmnV+I#NB3 zQORRl_08zP$Fv zveJ2OV%#y-&_*B`E*nV{w;AE$N4lI;=EdP&G&SYE51zD*$C1nQscy9oIBxk|>VEk; z+{;2(K{2^Ja{pTtAG7cV zk6|2bZHvxd`~ehwp5o5^|4^*?XxN`VKz)rW$4kS;;n+*9_@T#2X}<3a)!6a`-(W^? z%`y+EKOa?baIOK~T_XpVFZzV0HTaUX;n}Q3(kg*Y{x`wuiX7B4v5)%m+X;L$i=*4e zD^Rx|BRub$4Nh`xWPOd+15I5s@+qR54*vRtoatJGZ!KAlPQ5F_hng60C&M4i8tlU} zQx761!+7lYC>Bgwe3txPbdWsAGyz3N?a{GdF)sTRL~6pP;+VOSpl3LQ zgg<@4l}647%8AMNtTo6IJIOBMYl%5r+q@_^G$_zL&|v73ICaWywi!rDq%cc#IO(?#%`hio3}9^!-5B zb0R%-U=&JGjfgS6jZQX1lAp)@$ZESxvUWeB(|_k;i|eMquG$`(J~qY%sm)~9 zLRJ3S5e~QtW67gnWgMk85BwQbh$-W4lsJDFb0@C=>w))}6{c`89UA2GO%HHJ>i5o_ zEe3rRcY$WI3jW20a=$YP*KkrBrwfX}+Vy{N;it{SKdJ?{b-Igo-1gwp>PIqIV~Dx8 zrV7M9X+v{#3q%oR5211FbAC&I9?6?A&PImu6G5HH^os-$IdQ>AB=2lbT%La8>--;x zb~m2Kij#u*+@>d@yp%MuX5V6zntrhKO{*q8+qA+a+ar-5%IzlGMvfqyb`Gv%49 z$tvB&INWDF|7XoUs6V@zaXh!4=~9(5PsrIVG4!^t z4gB)At#IC5YqE6tIcA(sC(ZSg;-qXEsy*?gPVd}aYGxD+odPn6tdyqUee*g$SDN`= zt(?fqxhRnxtzCS{0e3v}`6Qe9+4n`c?{~45;to;C)9s9mf)^V4FHCgVT$9LMZskvC zFnq9%f=K76G4T(2#6O+*1!sj?LaW1Sr4CaTQWK)}N}C5K!3V1z@mIG5Fx6id^Q-5E z@P0}uqE(FtN&fnCFl$#gG&rOOo2#{u&2LYk%ea2_lSvbFQSpVdL-vq&%x64r^eB;v zOCNMn4r6x(4?_ckVCHu~E3gQgN=7%_WxQiLfX|G{=&fZJ^JDgPsJ_ybvj3&PU-qXs zwW%{i21>KZ;psNSxLF-$8fADgQ2a&ioS-UKvKei#f`a zL@y<|&>S4PZo?i>e+1W)sZ5AxA#9($j{7|R9}{3cm*bq(B&MaU?3cD(@QB(dX7%YP zX4SYp#=Ad@nz~Gnx4B|QuFM{$V5cv75b^>xSzSf02C>Y=kawW5>Js-{U5!&}h^I!z zDe|SU84PU6W*p|V%`yLu&zw{S$QPNz|_X-Ws*^5i4+DA(n zB`oEvbzb6B1`?QKAx4aens`1BYo*cDoOL)$A#>vmwJV-(L;G%+^Q3c z$gGEAdhXOgsGm52(HnZmg}cv(|BgRkCf-`dunId$eYG!3HQ}##O7$T=c5)DnUKzrj zc5nDcn@`|;v99Rj0ZS%$(5&>uS;NxBrQvj9vpI293*!@95#Hac9?U72dLh^tI|Gv}B7k=|j z{d2&>Q|)xGvMf{J6@)9_+~&Qn$n(9oHTYzmuk^ZgIigeR_A>X2uQEGSK#2W&bca9yk#c%hHD`!kHd(};EC!OkTlaJm|hi?_#J z%DuR!^duMG(Tx`r{>2V?s}cQgKKC|Wj~wl|i2Ng`gTRvoQa$J~@OT+VMh`nv$85~7 z_F@LClzL}p3Y@^?Xo6M3w}DeGI&{LMY_wsS9cdb9q%u=O$daEv*!>+Lozs)Kn3d+( zdXEdp`{#l+_T_*b_Z@-6N1e`IW)AjDEXMyj6i|YwTeAF|J#k%JPNmda;)1jOIAe4R zB^&Dl?oE}l2AXH1tfO!7#f8^!RmuXOaBnAQ5?PWNuRei~i)F#cn%kgc)po$H-Vf>? zAH!IF2d=aj#xu53z|v>~2{|$X_#MyzJ}Fv2WA`8Gf~FzKdbl4)yPU?`jcvi|ws(#iw)@GTX3?NQ1hf*vtk(saPq?tb*?5HN$6ydA02@Q&f9^F6J+qnJsv>$n=ANd zS%5dG+mPT!XT0(XrZssF{HXaMC=b|6XBz5Iw-&{)M|G9poTX{N!L$l5t387*kII0v zljT50t$-@97~poiJqv~u#vrwO_i=vZ1vop-o{Qb@gje>Z!f?GqXkl=Q*!JfVQvY8( zOLi$S2aR^%`C|)F`n*c+X{k-S(aJ0w%H#VT%OTP98U_~UM2Ceo5?LgDjbxs)TpFld=PI``oy za;6(lu1f$HbF@qRzGxe4TlyKref-F7(fBNxC+Vke_TJ%q2Q$Rj))ytd%LGmDPosAy zFQ6$0WuSq?jhZ}RA(<|n_daw1^OOaI>IToy!<9qS2QypFSTU4qHA@t> zja*MG-2%AmFge`3@fzpg{2Z&8q$0T$zWBq18tzkd1AZ^lz&foegJRjSP)#O7nAH^o zcmJJEw;q2Yd8fMu8oh7lEXJha+>Sx?i7Dd_?9@a%FY~dn zGGU^_Hfhjx;dTDw`9R{iyhB9KTP-?nFH1K`_bcC06hv7?n&fFV;v17vMVqsi#CtD4Z-^xiEShlhimiMlqvBV{M-8JjlC5h;iQ404_)VJ&&wfk-U~QlTf5UR9vJxAS**Y zA;lWLa>!sTH)@l;V}HZm>6xPIYg=&OhITS+BF(ENc9Gf4%iH_j zVBE!5$(Kuhc)^tfQE&+hkB&V=I(LK;XK^$(tiQv(yc#U}6FGt$H)>$S3ER=P{XwFa zmXGk0+K1e@z1}2qUplnAGXhUN&coWP@}ld8-@xai_N61OGD+;p&2(U73Qu}6q29*- zu-R)DW_S7xx+iEGzIMqRM%SrORR8qSReC#M)~GXNzmYvN;)gr`{bwd|(%H+;rJvx> zLpS+ZonO(%gkDkfgJjX26`NQwl`m@cvS5sZ=c427>qSjcX5v`+EPnSpIX=GoEi-cc zAH1JV<|`&jJzgIa;d0A2ywTrtLW|~p-r>7Ebni*yr+TeqWY{RbySm5G3q zCi-DXwF4Tn%a*$kjgkD!PT|4RQ>gBF{b)_%L@uCt9lACtiINZKL+f1@{hxs-Y`!&( z{;yaE^s|66S`&+O5)JW6??F!Hn;Knfr;JaD+_`-wNGSX<8O^xhMoB6{aNf>1$~jSw z{i0n%S;1(OSR%_cd3&Hlvk~;DlmlS=GmOf5b|CNSiKzZZ9g=~Ik;o_(--v5xnP^!~ zuYDh--L{Am%)SH8ZZ4-fUag}0WcRaUA4a3kg|m_E$Rpe(zfiQ%(TTc>Q&6ZvD7x;g zLK&3KLm314oPVY!@`<>JsnQN)%Bi;5QG|!2`E=CQwG|aj(cg-){SfJZ+QUxd-XI?;>Af zI{ZlFLF`1PGd}|V8YMDl)6b}%S0R47Vt&(_D@bBePMe$wkF>xu+3ByEFJiNsQ=A zIFt$;Ze&wuESaSng+tbsaI@(^(bn_{M6w+*FFV(wtIvHz_-7qf4Zg!+MGq1hkqp00 z)WE8S@sO_h%govEMal}EU3$LyD#>9t&~rtwQI-BTHcW#dM{ z^_y&|NvS5KONJa^?akxln1P7V*z3(7pPWuaGj{OGm5un`fqb60THz-Txc>Y zN8JS6ymJ-!SBLTVCMB@;xjyh4my1dUO3_-{6YJf$hq&*@C7I6S!0!2v*uh6*fYXc~ zJoeNrG;{D1b#-(cy8indo)=Kh&G(%RMtnPiddEb8JyG+(D2J8kgOMiADEx%~N>))h z*EVpudYQ;({(I{GXSS<@0(i3;$uZAmlhka0skRR|TjfpOj>$(qH~0fXB~`Lc4^gom zawuVe6UfkK}z18T;nNXqGEsy5{kDfSslRv%0wU%W!mz#c~uv1c37 zHd7)}!WlmJc{Z8Ww1gxEsYui^f`Hs(Kd`e6Q?|GaR9wBp&NOf$2KyJ|NA88xucelf zU0#XAaE%t_!hWHy30#QgZ6Q2Z#1!>}Ouh zq%8VHo=5mYh5nh$-61dVsCOB1_R$ixBt2%~R5#w*)re^NNqd4fR!Mg$SAg21)3i6L zma?8%Z0q30*G@4IogAvh;TL6i`^QT~*P161Z;dE!YQ`Js&c_{Hnp!HlutAl--ms16 zZ#j#1jGF>~xLRP7N3M9oEg9Z(h{gT&g}mPNt4!{$FW|>zEIR3|#&53b#`WrN*xNHA z`SY87P_g$z=}lXgtO@B<}kT|bD}-gCrz#SUVx`IMVY_HoZO zHATA)0`mCAR_1b~EIL^FkEy(S7W)od=AM>KB&T!}sre_apv(Ee_-I%xla2}4uHMJ@ z)-5HU1f%J7VtYP%*%c|gC>O^mL_&A}!*plsEG+z5L=PMo4OYMW!cSAP#blQn8IipQ zPTaVHA2>0as5YzcyK4P$v&~vw^V3sQdfNpS$4Bn<98!1s)>>=v*_d#y{Q7w`2 zs2+r^op`xLMMSt}7UOg)1s{l7%%>@B!RK11<7WrM_?L0LlPYbWxcERw@ zx!ln3Ut&pn5RA<25-|BRY4x_icM6N)sH^`G-`V-tOVgM>W~0JCe>##r&@>9j zZ`EYJ`MQGR2Uqd;PLGAVvUEv75y!4#{K+^!UvRof%8NY{NMCgOM^9U=%`jIo$lTD= zcuK4_Z>sVLMm66gX*EsA?%@zTtO)4eFBX&9f%!lXYCsF#^wL@#|54WWt;qEErljYD z5)PGD;aBBwLUC;udY0{n_do1L&q5F47uSs7kw4A&mhuk#QuaD7@415izBZ$6U#5`s z|EA#jfkNaQaTRrsTmy#o-U1AAB@Rj_p!)O8ICyL-7;#>K|Cj6wBr(3gM6rnW+Fde#bmbXemaEjeh&KO09_AMLrc$0S({ znuTx1|F<`u;ia z*-?(yo|!Lv6LuLadmc;n_34mL!?*GG(v@(mzmS~0?*&h3JO}7F4;<@Hqg(D(P`Du$ zGz9;k8yZ%C^X{kdlh}LM_unIW^V=KvdwwACcD_gN>N*Rv-2CySJ*u=~@CbNczghV6 z@Mkvj2!S^;Uje&;k9fjpgnrM^VuoBVz+4>@YCKwuHi~A#)4x}s&QCJr5d9KPaJ$HT zPQQp>b$3G3;Tvesb1fU?e1_B<)#r`|Y+>4|Yq;3?4@&h{Mi=&8rt!gM@Kxt0=lAv^ zzVmAt$`pvm)d&X|7G6uA+G5Z2#%1E59Ao6)nIXB;Gle*cH8|zXE_9OHb|jHq%T21> zgZI4i1{8cl_qFUn=?g6BJ7Vdzd)3h6A7;1)IpM@gLp){bA9|ccGItbzrt8x}aOj9~ zI`zp1l&#HilR*pQC!7P@Uu2?%FCU{Pqno(r$7I;*o?B4+=z63$O##ZuUt#yGW}(#% zRrKV<7&i8F0dhG01|%ssb7wa_1A)#o+_}n(+ORK}EKTf0`wEk(O?zJ8UMav8E}J9e ziAU1+v%XWhx^>*v!3E&ys1Skk3J>z}-9^wda1({fou}6y7h|sMZnY z{%gD|eTX~1-UigyOeSU)s{~dxX5_V&38*uAjRnPFwDBYt?ENAdFQ1+RbI+VX{C}S~ zk%|I6@lY6R;P1!nythqka&W8Azj!8k?YfR#etH+Z_^c(!*9}LR+;?t{ZGl*;_BPe? zA%Y9CQ{TwC3@uHb!g5VA*i-17fjy!AARytjIioy6N>JcMBASB z0IkzPDBeer8&DRpTJrm;BT|2jO;;7=8X%^peG+p!l!e^f4H&_TdUVZbS+MZtZsGK% zM7sS4}8(BaJnaPjOENn!9RI!SK{`#hSXo?0ccYr8!pZEx(TTDww-W&MJZcPqMSxA4`H zpavJ9sv*OfJItcv!Z(AIu1WNxsBkLbz%hD;Zl7?{najwm*bZ4d8(E|twhi6)c+MvM z`zn}htBf|RX`oCNY^Rx-WdJVS&xOk8Q1iW9Xl>iWl*!@A5{6SnE4NnSozVs_a_FgX=*RPN3bz`o3khQ|S3DXU4J8NC?< z8BM2B`PCAI4@1Daz>iuwBN0XqMzQ^^7pRb`Aa+8YA+!r&uTG=;0rXrtM!3 zT|HU6y^lrvQk9tAsiy2;`em%@+gZcvRu#hhFUl;M@R~iM z|BITieH6a2KnPVOkGa^eTrRHnx^;W-Yhc+W&(0`0#VUE_0QOn}9{>1)ur^(Z`JKL8 zobk#U6wZGEDm8+dAmEcp^WpaEQLGBChFyq=2;DpBCSp|vVe$e#hH|9-+S zE|`3CK1@H+Ji=V=EhD3gBjHb7E06+Liw>wO(tA@Nzwux&GlFi0{*%5+?G3)z!nhFK zC~TltA3MU_|2`cioz@Xurl%3gJR7Gn2K<#5^N1lonZNn+-@qV~ZMsGnN|SM=x62?LL*E2YWgo`w)!`Ot=q zPn-o62jWStZ6DpJ)$M(K?Kz0Ue$;c`zq08!gNA7H`|T2E#z6$S4x{A@VxWA$7W`@O5_9r+1uRq# zW=7xoL3jLaWFmW<>CuOj_y_ML9sGxIjH-piPI zbVI7oja7qxrt!?*HxKE~1|7srloLH>W=V$H$BKRiDWRr5!cZZ5aA%?wb6fi;d`f!Z4z4m~!ZCD0pTlvs??yw39JR7 zcYPr)`b#gobe(QBXHai*CQ$#Q#VOxTh3;>X=^c{;(PQbnoqW%W4zSRtcPM0{;UBg1 znboG;+i$;F$ypUTY@`)k`O_GB>`-F8{S{#F{92$pI*z>~X#_Vq8@ShrS72J%2gz{H zJ8r?W|5%uy!5n>jnVwQLz}nbdf^Ygw(B%yhcIhg4=3k#8S3KwgJTl^dnWrjO;~>xU zg&<^jV-WU@9fsfjTghnUj-XF2>VYTy>cQ@5{%|^41SkI&0>kN7P`D(Doz&k<+r_O% zw{{z`&pw#4`s-yVY6%MuM9+dNCfjhwuKfX7W6hbXLJ1geXDV%gxd_JuaO~c#f8f(g z%Q;#UN5|_PM^z;&z^vUIyjNgJf9-0crTRJHveq!u`YiA`dLqef%@$@TjG$#&Z;{cm z9moddG3z@$U}?KLKles88Ewh39jEMIqWnzatKkUm;%4TWy8?en&I(7^1~c2Iy&~mZ z*{~R8f~cNlB7uqno&D_;-}X0Hnu%Qsz0dU0f+hnp*7+9lNG!v*9D^94-W(X{_LrH( zCy=Nt9xvGd`9CFL%+wND5|r?n`adJOZ$vJbnfn4eXKaAmc2B4G{B>dIJ6lmi|9H}8 zpo^b}7~$2O9VGg#8f^C12H%&3!h4%S;d8HEthTG2wz%AmpJbXc@$Keh)}~-MXY@rn zv;I<N4n3`kgU903f8S3A}w;`;a_cAKrUuM z+k!?E>+~88t7PGp;)TRSZVH>WVWa4@O$dC}vX#rwc)%2Ond4DP5WZb{iG0b3guGaZ=wdjgrf?`7nM%Ubw4I0Xr3T*RI8meSpM zLpb8F8#Ug3Bn#Z_$d=19*a=hKa`TGLQL8^VkPnabNLOZ(@LZ51sYGwdg84!C!*XX5 z#_q(g@9bgwr5!6jrE@IK6M=p8_UzK=!vt09qNiRpwBPM`>`=8;`i}LW6kW_o`F<}v z^OG5T@t+l$6+RhbSwE?nCx@)`e}n5>HA!Qn5wekjL@J~= zf0p(HH0O|%#*IX^E(}fan!wDLvT2XUOeOj|7NL~T1{8BTkji%RgC|<*u;Gvm$&c=( zl8;U!F7<=R-+3CiU=W8#ma2lEa~&}EP@l|OVu!|5x=6Nl*v(uPta6G)+m;CM*_;>bB@mB;tBuG$EnocF@iX+?UyGH*1h0M(j>n7| zK<2L{WWWDz@*%ebo2I4U=Km&e^JT{4i4EnF@KUKJ`{)jOH<7{jrT=j)PP+;9&5d}h zo{CH&^+?;cmuPyREnXn&NBXl3z#sM5 zNp}MM13J_QpDZ@v!&^z;HbpAWI~i>C+(JE2ccj<2ujdZ$ddBYUScNjmi@{fSYif`y zv_8tupkF5G3m<|#Y+Cp+%1t2ksxLnUtUJ$34(Rl=AuCT&o6Tmk+CK)kw-tI+Z8Qzi zlsAL*6*GZ$$|z3apCc?g`iBL9vA}<*krnM7q#|Eb2_LC;axLCblK(Mu9{yN;aU8cR zLPBOCN`&w{_ug}E$|xmit7st_L>ih}_RN-*L=-B;bH_QiWc6zZl}f3UCJiYq()d09 z!t=VX=bZEXem?K_1?w7u`0$2!efXL9af!01Q>KOMFbg8s6gAFa&S{b2%_gqxpCRGA zW1Q&a>PtkSZ30RJQAJ28gZ@_Bf5b{j`BJ4*x~O-@ZU94j2)ZBb6xQ zrwL*+k(k##@PRYm9&I;hCBy$sjbzuXPZeFfQ_TI@YejrB8YJicTTZ$+=yE?M%#`-_ z2FQ|kBZ!B0<}uNWEvO>izxv?{in`+^W>zZ=kQP^tvHwloM1q7uvO0_9JYK~UCjyU> zb0?;9b~lZQq*Gd?MRKqGV2UiWe7J>lvivEQ1`c`4tW=W;@d0U|7s*V&G{r}-RjS7`Lcj7&RI*o&+C##+g4DzqdBfogJS<|lhpLT zw&gGGHe(9T1rwzq``DScwlJS9k8qdG62)KN4ic&kN7$B&PDJ_J-(*qNM0T;V1DCgL zJ$F_?%-O$HAv223G0E3tNzZXP+=}Pz#HQ{4*lig%ncUQOq|)OI@wR;&8+Pym8}s-T zli8;#(d)fKPUsJ1|NYb;wP#gI_UyVr4&5|ntJL)+7oXL!qS-^@n|8sB6jm$tZ*?aP zH%}L-HD>dMw|}$iJkN`Y%LllhA%DeV&Msq{FBB3>=Zz3wjDN-?@AMYutP1$spQM|0~QN}d^P(cP?Nc(AV)h>?mlq?rR zJiMPF8O@iG|H^IIr-pyIo0C^_iT;LU(-jxCTYr$NvQ=Rt$`^_&1FZSUc0qP6P1E_{ zY9Mxd`jZ>CR@$Yl3+865EaqPIWAZvoX47o$;^`$BaDp%e!D$em)jY<2o25;uejk!@ zM?Uc{7bwuKdF|lxEEi#MC6Di9j^kc?-RB<{mE+Kj*ZGyIpP)AUjTNs~QSKXJV5Xgh z;5zv#*sgblz5geYj_caQe&!Af4XGHeU-B2Y-Y^Ht9-l`tCp-D@SZ}H%Zy#*(*aAYP zFQq?ALkt6P&rn-vgb;V=BDB)d!Dl3+$SrR)X!?LP^?6S+iu8y8Oa4eZib$IG^W4wR zZZ*Z}{c%7)&KVT~4dLY|OHdv%5$i~|NXpLg-)d5qLuVAji7b^8YEcwE&1D~N+gE6;uX>&-ek}-IP4O5P zSzZ}mrS6aV$S)jIExxCkKnHuD;HwIa(P7(ORQ{_FUQMV5#3dGL2AhGjQ7zD+#U3w6 z+AQcUG!&ZLPjkzxMhLQdq7Y}(OunqE!3%d1pxmb$zKxfMqJt)Q!+sAi%bbDnU(~^s zWe$9@&v;tx@pZza-k!cFGl35t)eSF69V|Z%?SzqwHp1Z7?ReRe4B&Ng1a{u^0Eax8 z0UU4J!}xPmq)c!LkfbXEuKDH#pt+`V3~(2gp5?hk+hx(@ z&LpH0>%@0#IEpjpT%jH%XrUqbQCJAE181#sV@FX96rltsI=`Y8tuUW#4ePO8B zO8~b2KI5T*SD-c29GBY{^3;tL(7nHzIo$Mf)w7y1o{bMYi>@$g?wUh)S z7d?e}}doU#O%Yk#JG0O?d;ipmxA9GtMe9{QRYxnH~ zZkGblo2ACW$*X$kV`v&Bdt!kwM`4issjyRckbacX8zU0x|1^O1fkf;+T~nBOWeRj6 z;;?Yg4u_r>!SDBO@}5Zox;v20o;p!No<4a5uhK8zK}|8dH|`J!zkL@EM$g30$M&)X z5@m4z=YW)rGzNIfNMNKWA6NOhQ8(_n!OO2s;Qh5*fsch2+0`|TzFq!|+!vxREIYOy zw!FLmtcdH>&pb~lgDst(lzo<3Xg&`z|J0-&R9X6@iVB{fl7!S>Cu1}E=oBX`AXp>1h~K;^e4HTRVNw-{~!&bKmwifk(N z*{Fs{HH^YL%g2FFlXx^*vYgC38IDu$-lY0hHxTWQw*eveIR7?Ti&A)$&5N`CqNF(= z*jt0sX`?eIz_wg(?xsgB%so-Wk9?^BwtRI(vUe)D=(9=GjewDS;Pn{{A8AgvopIxr z)`bCuj}Sdwun$K6I|-^4*TblsR;qsCIk=$6j;bu^!RHp`;BmzkV!QfMta#TPEpr2; z#=k|_rn-yzcc2J@^igpC+^cBA=5LfpD3JaWS5Y;`Wcf?woluq2WPV-v02j6PaMM!@ zU>R~otyx;ID9#YzlKalkw%lL)yO#a;R*53l@-qTFQn z;ujBY@=0TS;jAieAS&UA&+nw!^B=#-p7Rg*-l%QZY1DRjT_=&zPaBP|+lRsICL1&X z?Pg>0Ut%+d5^j%gGt?Qrhb|t>;jNVVxWf~sf;p1|s2(;N%-Z@2@pC))a`FQ9d5}oG z^YZ}KUYFpi?k{MX3O^7FE(cJ&M`$ci?zNWgYb5f@|H};& zuY}1z`U&e%%g|V8hFK#(ZH0uILPP}hzSp+ zQ?mc!#rJ;$r~f{};m10H>=8_A)DEs7P*jk9LHBDy9!%6gFuV1A#HI(lQt=CfOY6Md)_Y$ zC@mXAQTt74BWV{c?BjD_d|4KREm0C|l6pWXNCNGf!=dX)5nqxR&Y)4}vC{qr@J6<@ zQ?F7?cJx_E-%kD@yZJM5%vl3|c3jKF97=+2vGH*8(v`S6kmMPk*L0>n4c~3|=FK$h z=tUP7g2e7zuyr5-&NnIJZ+-kpkrOJZ*mrNZP4ddq*B^K0=N`WeuS{JGH)NiqO^3DN zj1Cjp#~=`d2y3MNkXpV(%UdXt%*Bm2Z*oy%Ug8O7{)!i@tRxHPj}i8`BvSpZuJnuA zLRe-LfC`5dp@&rnJ-^%&toLZ9R)-&=uSWggj29--(UuR0eUpu7vob%jxUm`MKi92SkbA22Db~FBenSJjT}e#}}i@ z3u(k<{U6-AcMJH9lQHG#lt`4%Y^S=_kFl=W(%=8DbVp`hN{BQtqkMBNves#4UY?pl z9o1GM9ji1&p_O06e*^#UmQAH-Q*{N(HMl}-3%Q0=+m;hUV+{%Ien@OC+$tG)opa zmwZ{iJfe-SbKHgMo`sP!_vY~>qOC;XIt{RTQVNlO=NxK!Sj$`ME8`z=Be6L1n8b9w zKH}6m7$M>$5$?2w6Dv6q)wj(+q?ZbL;Clf2dS@;5v26rpX}^(}lAXrN+{>gYLexkv zz57(axiLgT?r0=mbc(A@8%Mr}ZlK_LF`C_yOLdR#V%g)*iG7aY%(Nw&StgOFDGPHK zZ8bOM=8bn|TwUgoKPFBf-sDAc&*$~A`~1>s&gY#I2YKYM-y0?33pdu0hC`0rQKuo% zp&vs;)lFAUoUKLN*o*9QUOpy|7AA^%9P7E`@~Y(ISE~rk?|a1hAquQ%3c)BjEf=r% z`9&P~RV|+J>?E0Of1W*HYR%^Kp5eU3YGhq%inzUA#r~dcBB_4lh^ST>GvgmMis2L_ zI_GkO5I=e-v5s|N&rmnSeo4m|<72Me0>wjO)khh`kB*CkZ@zSwc6=54utiC%d)=K) zQT#|mJ~d-QW9JeV4~-XteIz%&=8YsTNsV~hPZ5do_F|n^Ywi7kDc9_HNql@t09&D~ zD2gjL~w|<1=PsR+g zscjB(c}r;g!^4j~0HQ{$i>#4sa2PfzfZ!YvO_caX2$s64W z`pjrD?9*ZK?%gZMumev;5!Pv3bch3Y#p}MUw&4P9PA5w%1$Sf4Ep;x;u{ak76$_tjZt@-P0sS()apz`U^AvDBzUv+35e?J%H%sHd96^ijd0|e!lIE=1=4#Sw zZKVDImD{wpzbaQeu7Xb3w1AtY+e`KQH;!LBE1%r=yb&&aAIWQRb+9LcB$hf(=Gz}c z!G8&{;G;bcPoMP$)87YhYwnx#S5-^6&>nOCP~I5&`|vB6^|^-Aj{Ql269nUa@4LdV|Qm+l4C)mQDkNx>B+sQOh znG0gBOQ<&{d-)10PrB?yFj#u=I4}QY4So0JbnfK}XK>1O1#Q+Dz{i+eqN*=t0_%Sc ze3ybVy|vaA1hy5>6{CN^rnWNru8$4W+2lq?R;Gcwqy6cc)wZ-c3Z?UJ_|XRHW!&zS zs^UXBh5Q2(bv|&{DeAbb6Br}6gkIGqPqRsiPxW|L!*4zKj5|e8E8S4qvyy=x%G>BCm(Ieb@c_n%qXoH{jd3*b<$5 zO5|8d^}do2ZyOiUvS;Igez#cgzj+m$9FL=5_*) zP3OT7K1#p;T8(SjGr-|}r<5924UbGR!^M*VNbm78Xk8Pra0T~n_~y}v#1 z&vJJdRc(&QqIJT7BO0Je$_0I}Gah_g@RM}8K~ksNtcB)m6WVrQE8l;zmNfQhz|Yc> zsXxzYGA_LVoE{s%ih}Im*vivzwYIjfL#vRRUzARtAG$!zs`lm2JoAO(`kU;*U@>ne z(~A8AkMbT3%P85G>R^uYB1-Z|e)_S8C&2j_6FljOgYd3)fG>S)0?u0JgE^l4RD;7F z`rqEO_^DU25VQygjFd}0Iz39*|JR(F;CGJH*ls5bJyk%;ENsfT=-& zLdyeL_&0k7z0EyHm?8HG`Fp&C=>fW+Su+M6u9l@t7Ua^mYvxPg5z_2wT@(CDKLpct z9#Dn%MhLGAX5km3laOUz3lz`U1d4-o=r8*>3rFWa$DntbaMjY7ZZO>s*H4)R?iKpb zqRS@K=mY~{%9b4d&Cp!ZX;w1q%9BO?ONz1fu>$;YiVc$6V~7>vwgHn`Bdq*z6kaCH z=ba9Y#HXj2!{7P_$Y|_KI8YHM9EvW)ygMGKti3 z6@fI_fzw1P!tZ5}nzTPyh#98|mgH8Dnmup8#DNv)Smtu5xvmat)<5MXDPG*&fD?35 z&~k7g>NB_VhzV`#KMp@h2m}`=y5ZK1w-`D_9jI-IMN2AAv3I-{&{yZI#$jvh=^I@` z80?G20x*Heo*$t|Z6@g6JdKXMI2Am)(vJ7`%L-*rBiZc5i9%iPFBCF5pNu~pg>ya~ zg1;wa)6ClA@b8ZW!r|-JsI=^dkh9wavd;cMduFH5Q(|M-Eze?TA^9pFD)`aO%cbvQ z$9mY&;Yd%`9w%JAszB@Eop=jdkCqJ5lpx6n^bEXklE zGVfz6Wd_T&q!RKXXB0GlKmPqy3&zGDg@>#=@r-44)Xl<7_&do_>ai&$4q!*hbB8Q# zS$Ty@Gn*~MI==!kcm`0cTttq!MI~RnHzAMVmaGL(S!iL4nv*XzXUBZ<P{C?R?* z_9N{TMeJ>r)%d=tJ&Miw1dd#viQ^*G$h6_@U|Op+2s(|)boC6JIe!bvj#EMFzW5^F z(@()eqiLj*p$z#Q_2H>I*OM-%TB++-v~YA^DcZ~K;P+feLhCI=r2AnWGv{OBfUTP92~B zrwd!xG}6b!tAwlvj?mF~HSP5MypZ!F0-9OJk?WQ?OgA^IriQ?%ONSeG({neRgi}tp z1CPm@;Db~j*cCENmie!sv&#(N_^s;Gqicteu9`V?h#Yyz<<>5`QFIDcw#*_QDSx3g z-FPbB_X(xn>@;`-NehQ|e>*m8ednei{J`y~#&l8@0UJkb18c(ZlmB5m%gO>-1JW>`WQ`J4qYf{5%F8dMJ}AL#U?nA4v=IdB1tw(a7T@V%W%?s8J%I7g&3DwX*Xc1&zEGDY-XOFrRYdq(2EXdH`h zzIeoq&5Tm34ySD}Ta32*6IL@4h`zbr#G9W}*jS%CqDF}!`{_JSbiV$@G#Kj>Ta3Pn zF7F!6t&XUci^3j&c#t$pQAk zwjad%a>g-7H=Yu?zEEcJ?02#<4+3g_H#1~wf-Z4y?!B6@{bR{%j2;tn@US>(E6-$g zm`WCqO5&7{5z-tlx;SHJF zA+SdY&e<>u$DCLO(w39JCvOUBT9F0GC*QH>`FuR2@f;PZ6~RYhGuWD}2^`Ngg1fZ| z#Mu-IKQj{XRdTUpv^0OI9RR^v((kMt2T+*K)ErsB{a@% zt)*<8r1h8mX|wnm~a&ZqpdHr5I#@=)l{2M6j93W+}X$OtZakZhK4wU z%z2!WeF{>&`W`W>Jkh}1t#GhLLA>>EFlF|YMN5n-So5;w(EmR(Tx7TwcJEq?Vux?x zy}5<_K`F=L#a>$ij*v6_b8qVB& z3tl*xEOiZDg54#n;j4e=q>j~*RP%0MKKJVw?w8(LwjwzjF;|*dwS}s1-+D}GmRVCH zC+z|Q8s?nqj!;*?`X{0VyS%K87e6W*B1>cG%0+r*XOtA7vcqQ1G zC3JIu!OI%3@8<<@QSKwTIM58Jexf<;pl9I0`U)`O(E=(bay7KKWPsPK)BNMiQQ)q+ z3QRkD5++tWA~&hHLjA6CHr~RPbhjNQCY@X$b+>K?uarexVZJQbK5!Jkic@T(RVI+` zD5+($3PH(MS*VhD1VjvH@~PtxbxF&Fdz>~6ZYHX^1?|byY0-Gn-^>jhwYW^?-nFN8 z>dJ%r#!g&kl08?~SkJ561z@sU6O~@GlpSZ;4Gz-E)GzM{mdh%kE~h?cO9!RQJE?S8 zx7riv`?zu%b2A}c{hs=B+JhTz>H}jNw5Wtd($2@;9H>*gm{Z_NN!zs&?rqX`?rvE+ z{P$Il5<((i;7BF-v#kgQ{geSiyKSKUCIzZsnK^W_4FTDMec;5)9kAr|Y)&+Vr#u#kWoO0!v?*!`#h@z;%)YbO#z!V?JAP2lPU?$6+7%2~#!Ml}ess&)acm zbD0Gbv12d4aL&+%1e%Hom7TS&C<6dSuWoq89ZL+K`N zK+jbhxhZNp#e=I)g5H5OgnSvro1OVfCCo7ZmiIlVFO#D9v6^Gpi*sW^Y3();!+j$= zHXZ^=Ra(IQ-Z%chFMV{QX_)Z%CjrP zXRe6P8}j2u$N8hQZTtCtB7$qs@1lNtyV<`Bxyk4!zu+CFnxoc`B0hATnV6j5z`u8# zR&)Q&dodTVjC>Sq!w4ohykAi#&p2G-TI;qj-}{7Rb zbilSY+z-Bh7cEQhx$ADkG&{)O&=U*K=jAiA&PC#be?3XnHFkLC8hOFsV-p*;eKLNO zb5WRSnt>i_tiyRL+N8Pfu~0~B#;aTR(1%i_{7KsOo+``lXburZkq$A^>i1(8Q$XOgwST5+U7b3C@c90|%tR-HF57$V^W?U~}RX z-jrC(f35Yv>z6%8$Kvz(X8T9@#U_7p^Y}DWW<5-P>$3r73tqrJLQD|H>#=KB6mDIA zjl48Po==JB02OC#;jfw?)DU}IIJvU{kBmg9^2ZE1cI;&QsVEO`R1M{WCxs!o5sh3$ z!cF*J>@Ys9tSdOqUqc3{%MmuqZ}amj`iP)7JG{tQoiyxu#NC_FfOWUWLOZ{1qIAs) z6e(9iwoBbtw0{q_8dO4y14m*-A{|<)8dE+p6u+sc8m-y5iSJ2SDM$|FVc+7B@Y*(oTvdGEh>d;trMU@vK~K!?}4kmNAdse%aev1Z^N9B z4b=FI^>E?x7JMmotnjKUfj?Ke4?j&!<4d}3p_{ffc*Niz@K+PPA_?ZpKFc3 zl^nsf?|%U;|4sO!cN2_l@CJViOr;)JmYni%DwSQCFZNoui0xnUgD?*|O!`k+fFeJS z;)nAWff>V(c&Ev&cKq(;qz**EZ2j$2#3gZ#9`j`K$A`CaA3oI__d5;a`nx1I{4 zj0|o8i}kL2p;HpodBUA2*XH>l^H?@Y<_zzT&3I4c4)({v4gBm$qe#gvGiqM>Bx&#c zHL35D3XI`TX4jR`DCiwTR#NC)UuhPVxFwRE@i&*s+P#}E)tQSNUZ3V0x7)KPSA>I~ zCr^`_&Y`@KPa#j%m2)}E9y59iO~7zP6@OsA8-L(AS@XW?FtNj~Tzot0gv9Q!6F0Fc zlgzLPrz%!V;BVa=1w!s9h`Tp8AP2+6eBZbXan18tY}2_c@}$ja&fmh2_bob2XwQGa z=D++#xajU@R%Cod2W;iIErFvzwLu2&x_2FtEBwtZim~Fq8|sUO->M>LK7-o4@FK_; zy`oaZN5tnUzEX;tji|PaI%eq}8xTX*k!v^ZqF{*}U(nFYhZM^5?KPMAGbs~T{7`BTah zl>HmXPJ2|r>fKok)IPeCjqjqU7qMN;-{?4SsjdgG`m0&J+!K733C~UJwBrXCdV`8u zPtd@S{+wUK~gG z`$94xb2H#$%z#~kE$^Xzhszw=1X{mUkQShYQ`p-}?i_)+u1^=(*WXESWuEjdIcYW+ zRyo4MgE+t%$;gk2Y|vP*8gVC~8Qdu!=SHX`dNcyvRRSJ+Vj7Ef*fNjDAQKIH;F zd6_FPR$9zn^Y|z2UAXeTgExSQ+Bn!W`xARCH32v}JR$8%7O~6!gOrx>I9|G@q#Wn0 z=TRa7PCa=hp>LM~$Ch{O0=pi<bOTf4G!S-G&`w* zPif$)K@O!pVjk5trkU7k^^|Zlcq^V^ohdE$Fn@KmdV{GRx8*0?l+-&OT1e&8~gyy)Ppq?M}YLZ!cT&p0k2@ zzpoGFzhVw!xRhj{QoUr+y@~AL&PQTpsTWqcP*FN7T2Gb-SBTwL_A%N1$C$C3mQnhT z{?*KU%riq@6xg1gSZ3QA9ma1?FR{2Om~m|~AaBUuko;?&K%o~DWBLF{T8*wV9Sin| zw#}MJrdkgYbtx06fz#V13T3fe{^ybGy@0DVPXb@Fap4a{S*fcSCw3zh|E#K}?6MDY zu3x6+)@Yh}b9)>2SoDZEd%>5|2#zF`MOu{ca4%yS&`3T{3TAdI4zf?|`Xu8!6RCnd ziImf6Ehd_)B&`T->D%y)WMotxsn@=Qd>Ma=)cNbh7U}eok=G9}t_}x@CqH&beL90R z&ZZ-{39sfb+S-Fe{hlDn)oY8zbYqWb@5=40o#G)j{qktaA?q>OxnY}h#%P2+WkQhd zduw=BPL7i7*-fsnbEBti*h<{#ogiqxHo+4QDA9Fm_d@3%hE(1W4!M8dLVJCGi7wvt z5e`mzES(kR%hILvi!H=6d^}!1xNiX1nFhL@I$7RKu_KwggNMve%Wq9-&HHhOEm_3 z2#@Ek`3-TR@?x|;?q>SZ~gN1)I{~ z`)oUIwi8LQ$1*&s{2 zCjA!(Lcu&|wpAGajz)~%R&Z_YY{A*HpFG@FA)RG8ky~V2vD{*7xSrgD{61I-nyo9q z*f1WKeRktq`u*8ovvioj!+*tid#3#glL~uxakBkvLPtF4-@+ONA7%E1$g`Q%+iMO@ zsk7g(VjFj0;uOyCcnlZQo5(4jxkc!2l$XTCSF%1g1hzdZm8thMVrvYGxRu=ztlzVd zB+O1>*L@G>Lh6v@_mg~a`NZks#C4mwn|?>Qk6l*Gl|(a6{-He=kDrLAOk2feoiO6s z>MwAPo=fcyxm@Ow`_RR`Yy8<0EhNJ|{mSSy&F21F_fk|T)A8Lpb@xa@_0G4))E=?~)+jGn{eDNA7)p1eaIi$Q`5_ znC+9BiRYF@;?^Z_%T>Cded+TWg}tb;igO9=$&#ni6S7_WdQvgVbvxBA(#R z7%GcC=pE)#Gp~wvA6Dhmbj!r=>ulL)se3r;&TiuP(wWTfh6(7kZv<&HQKq;G#fSG^K-)!wT>ZlrME{LI@Kws3x3!5unzlIvo}r7a+l@Ip@-VeBXAIY) zs>tnNXQNQvt;Epw4eMOyU*)LN;x+=sK`RHj9e?+@Q2 zZ)gtix1PwND4EBMci9u}*z=>{z_wGo`J_@}N$ebcv$rQvocc=4A5WnUZo10dDE`S$ z-+q_LI=K%R%$>*^PHh(-npwiDTOA;-_~r1;cIMQrjaneCbvNN>FXbT4p2UB=Q%AH~ zb)vQ>$wV~m#%Fu~qfACzBEEJ?QFL;y{F~QK;{8RN~H?Pxx^TJv2VX zYb}XG=CX!-@#1VG8@U8MH?jdsBzr*O(|gQfKXXu&6;9|R>N9#Tw885PX?G!S1qyz9 z3@KiIMa{nDEnZGMLjf(LdBHzI5*K*~IYtcD?DoHhwqMo|o2@_2doCNzwM*SVnawBB zsZGBrrJ$E=cfK;M{h|sQ?^K~AXVbC8lV@D6xfQvjdy8?R|fg6{^(^qAhvHPztz)R?Z*8)F*de!al)w~w+SL}1z`J5b8 ztvp6pHav!w3I7Zwt2P6zkBe~h_32pRI{@{54#KDz*@`tF+Iai~ z>;wBU10V@v;L=$caGl&XT<7r(9CLR=3OciCxw%kyv2`rg9rKi`-LMJizI8|3Hv@cz zC8T?_7+&A}4QH5i0e31%5UtpVjsLNv0z8TxZ4ZH1JBj#ThXxE@<%I%JCp>V!3+=2P zM}Axg`Q(z%v=8M5hr$-|ZDVKBqgf7-HNIffIY?Xiy70hj9Ozl2g8o#j%=?aB zZW&9)XCA?!ei3k^`5F46c{)6N?+@l8eSp394%*gfKCnyfM*4l3^a3d>F;2wN8xOSc zIyY9*CRJ%TYdi-_JT}tFUogIrCPSwcG{AG$EAl~jW0bl$j zb!YJ-=#+{p;Nz)EJX%`~?)iR|3(5=v@BR())gH&dPu)4RO?(L|WNuOhIbJa5{1P0q zy&C)o3MJ+rJVx*OH-d~=a|Tb>tb(Jz&V=h~M}V4hNnpiJRTR{C67~k1gZ~wd=l?DX zp~GI$U}r`FviK}unM@g)e7A(wB?ri%ZdZEyj~%2t)ensI9Krr9lDanC624Kd^zeTDw)Xn;0b2{7SsAu!jN zLFH_*!Fj&h(9@eoKnw8#+;&?@xjZ{B%}fFucP#^2T<-$%272s7(S2~}yfW~*yMY@! zbe9^rQ5m(4>4CY{)xf%QE!M0t<#mJ7Y1c#jz|Pr*KOxr!Pp#8IC!YiUPmLx$xFd+q z$iG3EC2AwN;6L2qgamre_B=FRPk|o(@)<6*+e8Onp9K<3E(f&v&pYUWeGxH_DSAF-89@{3;#}X}J+NNvhS!*e%Kju&G==?@a zm?7a0Z#JM!-wtxI$|Vrfpw>>>&~YXbFiN7C9UCRm3zgYjpf;3s831^rlt z#!MFQ@8yvFp1OdVa@9`2<|=4Yw+)@uI0~w+i4<&GhOwmZ5o?uk6FsnN!;}1Uk$QC* z^jFdszJLEf?d`RJx30_s0H6MF}%(cYiuX`1k5?J1Ks@NB+Qt-7FajPNZn~CAvO(#MU*MF_I*yR z++~5StV7`fJ_|?Raf9-$DrjShiO|@Zhn$UMVeeT(IIhtcTnSR3hLvQ6`=&wQtMCwS z{i8;;E$YPv&I-~__Z{-r*(4CGtBFo8S%V`>_E9_15^zyXzBp!U9c{aEDy+-QVmF!} zhPBm(Xv2tMGD{g(U0NA6ydFu)c2>|Y&Ny>sooDdrECnp&T0-;ccwoBe z4Ag3M0I?&o;K*qWIP%#UAv}1M&^_j>c)a;|;h<20TCZtQo`<^e!sbQbyu(|l+He^y zuAYdWq-TTdd@Y#p#F9;*+=va|4d|6)kCUz%4)oae8N6DzEPZk26m(&I7PN}|0hn|H z;mGHBuveiHe%|vMg?=6lmZiy{R~qlxxPmdX)hItmNn2{s)5C(W#Va&m(O>;yO?Ndp&_PlIO6FYs}87W8lb z!cMfWg125SCY-2d_DaYDYHQ7SYFncSmLG`VPu?#=)5aOVmqXb+xA_V9Z}xuDGOUyx ztq}_>S7^fbyMCb5aedspAQ}D|ehX%1j>Wd?4w3SMGr+pn2T(CGLB@NQAj8Z&pxbkT z+B2hwGZiXPr}jLId$o|3N|#t}=L3|a`kV^i>cieVnGN12_3?AuN~i$^Eo>lP2x61! zS?AJw@WM`uW}O{o)Ew%=a8_2 z7=;H$JfX4QwHw{kSasC_i!KCA50Sciwd<3S9CPp`6F9 zOy8HE*f??l8TU#FZvDC%uirBYk5?4BQF_H=h_7uPz}w(6 z(l1gV??;eOsic8N9r-B#yfM!GFdnB(F#FX)^(rktW>NQ76gnpyj-~!x>h^!;GpH zuNH62u0k`1)v1|pD6lbd1{qsqCG?vXNc{~qM1FiHQdv~S-}Wk^nx#wy8%L@4Svtgw zRWb#=KQEEZ+rQx!u{W4`qZHNq7U6U2@8P|dFH<&2Wq8cWMt=YPz2M=$D&YMm8ZP;4 z#@(8Kg8Wpunfu_ONM4%i!4;*~f@#7TN_diptDi@5sfr?KC`Dcvd`Q4cQ%PPp?nhnD z-h^FxMzj3~8?kQX3&#EI9JFI-Bj}Xg>o;~R#b-tyhQ*oc`0=HA@WhI-{GP9mDWmzv zkinRKrg{2YZhd9}>iv6_oht239G^T7{S#-v5oMFfqh}em>0UX&GOB#y_KEz33GY#R z)ih|Icbw?DpMdJc&9M8ECCD~6W=8jw<4NsXxVo>3v}^8TbTaS|_r#`(e;G9kOnEqg zk4e_1b}qY#p3k4kTSO+}PgVOseO(7{fB7R!9rKGb&Yl6u=PY$@zb9sHp5_#rU+^Q` z40+I2!d-4kLP>{{S-3|F3@u;EtIgU^Y0h~K-$|bHs%K2`t}}PJdBf+B`SmJp@(~KS z8b$!UYm=#?MTU5$> zLqEgL@rzHS@Y`mT!*A<+$&e!}xzUaxd|~eowud`~Gv+?0Mm*mN+oT+jzBWhf_~Ac( ztF%8P%d2xf2bZCiyxAz~%^-A$?t?FC)VTvc^x+PTdUjLdT<***7w9p&5A2rd0wZ5u zMC}2`f$7{zF8Dsc>cJnm7Rx05_}Xh|QQi&?j%`P`Of|T`nhG%aXDxs5QZ}bP?mM;b z3=LPk{0Az+tmzx8Ug47B25=O|LP=a8@u@D1H&&WTSFTt9A}>1$6tk_ zxq2yi&q6@#sgp2rOB2#KwMGcuwSmT&8$jAaMM0rqIlaov2)ElQ@srH%NM|?_uQ%?1PscidFLG_b;Q3E%Hm)9JK1dfb3kKjzMF8)3O6alo)r8M$ z{sZ1hE4aApsY11U5g)UAJe<1v9x}Ms%I_%Xz$dz%Q$53n;B(~`Dlh*esFGhsKUNGt z2BYTVkp`>raPU<8$ae>v^gf=~3h{y*e-#I+ZiG@CGoD>;kJy{@=wI;`AaTALZk_T4 z;erKdpSYfTaS_mqpBzK~rp3bv_l@|cmGfxzzwyY(D3kjYGZCw~dH|UuX|DXy6X5x& z7G`au$p@fIi0f9xnVdXj_sd5;W7{Lyr3j>CwPM(e{7h~kS(O2C5F<~O-Y=W+^m@ZHr z@tdn~Q>IhiW+H1iS8(;?@$z#R%56S{vi8~t6K)10pBrbWr;TaCHR=<{ z>G(xL)Z>5P=8bDOZi%9B_wqEl!T16y`pA&R`&Ln#b~rPd4>9v@K#RHg-(^W!)*|Zm z{|udpLk>+G#|z!0l%tdm5+&5LyEF3?N{&KBj))wgoRuT@(WRS8i9+d83LVex%jU;A30B_?llpDEnDsMlg5ggk&f>n+g z&bTF*@>$C-0>n<`!aaM--X#uUKhD`ADQ%t^FWaG*9f=%h z0b2T2GF4t@`L;hjWoPb|@_NvcZ859_oy`&8&#&LISQO&hIj$_UZwr2gObjm!u%>n0nk=wcDKG<}~2>w><$6vd91Z-Hk zg3oX}!k-^?nL8Jg&3&B}#b#VN%kWo=0P1VbEiDOQTMJIgb{!YFzH@R|y@faUDFqd5 zhvQe7XO1dZIrkkGwD=LT>e~=@(&sQ>?^`cP-?R+M=Wn6UwkUzwOP+#;O;?!wd3OYZ z;9U5x=L&bE=q?R^mPLepD#+V#C6v`0vog=Wc(c0=bYH*`ao1}aujoKtx)p}wX6#om zQg6UZkB^fD<`Utr#8+(TQNs}m#(BAA5{-y#C0SE?@Y0>@z)^3?%`Cl-e`xKchZj#G z3vV^VhmKg(q}JNLyF@d$f^j6QalJ-g=;ZGL!z`xiEfd{*>r zLub5X3ol3F>NhJm6Q3KB+3hRD27Wa6XLt&UTe=Q(?m0{Io$5#yJx+I)^&zUMja2P$ zGs9~QMq~b?@aD=myPi$Ap#H1bKzH#LLDMe+esk!>4!(8t$bJjjxb7|py<$sJ3~MR* z)P|o-x-a;w(Gb0qk4Sn~4Hj)4>2OL zObG189%FTBzupkuuk#+86JJiVy()29z-4H(IupEEqj0rOKSs3#E#YjRVs2XfD!S_H zNbp?eKHQLZg`&#+-2LQj@IG5d-GYvR{!VLH@%(&bK0}||%Fhs2+sDKBO-(?u{x8R! zk0$xs%CP^hOWec{o8ai!K3b@v-EAK1 z>xWy(sBTjb_WU#3@(#iA2R*R!@D9?{g@Et!!Q{-od(@^}2?WdA!1~o=;Ih|R@Nifs z*}W%@%ToBk-b5(+?R|&QQ8AZ*MUEfmrdLkmEwxG7$^?a1ISnK$m@_^LbXd)8xpeQ# z9o)fEW6HixXL&569uImr$I+%N92Nlv=w8BG>f-UbzB5SJi4oM!x{1HryB>Z1Rtq|w zE)w=Eu7DG6T*a#c27wQuuSmcFQJ_nfbF%zGoF5lh7Hc*GjWVppA05G7GvcX#^SbH&*%)T&ywlh59rH<9;E$JB-L`9O+qL2UiRX zh6C*Ks8#ne&=4Fbf7QoHdTz&Ys<~4Tef=Hr5cd?obUDlS$xVS|%yH@F`O}bdR;`>p z{zz1N=ZQaApA{duE|yy;7U#^)zS4OWmhyY6zrv(vGSs&$L4L3AaJ2Gt7T&GWEd8Wl zn!LE%B+u6wA^oQ`097784fkJ;hW9#m!ehR7Nb{^Hw0E5~`1!a=`hv`rmp{sdpLXk& zzj~l6oj&4~xLI<6Yi~4>{#fG%9R7LJC3`o+bH*v)WnC}G9lC|P_3D)PYPh1~K36e| z?S4{z`@t#58}y>{iIb$G_WwZYi&oJ&qgz@gTf>lH5wi zhlFHZK<)hwqg3VLV4(SAuuVf(9^p#R&!*4fv{eXnK6xiL8#RJQh1OtOgaItvoW;57 zjup2pwMR+trub5OKGtV6?XUI?MvpYL@b(q4$oWP&{5!@NF0Y6Z`zJ<|!NZ>d$Jx8+ zmM?)q*9Zgq2iz%m^~M$PMoB2qR+%pK`TZXFYkxuJyR6_stE=e!dmVYe)30*JZ~Nuz z+>>#cxt$yzT?+#3SAt}FAU{552n`d}q?=ypfbm*RqJNJv+8IRAjINtt6n_`4{k~92 zKI?L>*+J4nH;sY)jDgZzX)&DG?;J9lu8M+3+R2TTJkXRb>+%HVFp71qp;H_KTw3A%Y=QT8Y(0RG))(hg?l3ua@$}yF}VvB{9bv>`8criz(ZoXbQ&`E=mVoh`J#J1pK+?FE>$;k5DUCwQEKc| z`A*ya2G>UCoAT(yQg=Prb!yb2p-p zNmQP2KLKQ1UMcRH5iH-o{w+nPdgPY^21sun989ZE0C_{7C~0Tue6e@L6kvJPx4fV| zl5JlWB5lcam#c0l6#Y8VY1ijL;$F2=5Oju!_omy)rHVe;;=`8ZgV+=Dk%fjR{Lx8i zo5n8rpXme2#ZTEB-uXqYQ`m;TaM#4&Gn(n@AuO>BFqR*TTLNo#Ultw41c}>7C;Vfx zM(WU8M6Z%F@`mU%`Nd_mqFwb!bnuxG{oFSdjTvx3o_$S_SLt684d`fEe%n*}xDbgQ z&`-3pxFyckbEMoNM_{znLYjYIr+nff#XabJ%XKLak?&SMM|WSe0waUH#5|`$2zP9e zKOAf;uXJcf-xD7L?K<1?P0M4%|DN@ScZ;^lcZH-whYNi~?UEL`iVuJ)F(#y=sD%dI z^#_9Gp7LoUAJUqT^YSy-fjm5Ba``MSLA@WYZXQ23UUH|ggMyk~738IOGm*n;~ zO7IVUEPvoK0{Z12llPsyjsCl#CZD>~S6+IVir+04h-xW6h@1Le?6S5WHtLAs$8)op zK-Vnh(e2;DR7DST>h^K6KoG&KQ7$FNzwahDPON5HwkVPNNyfx1F;B1@^$qVo7)6Zq zr{jz;55|V&$%17jxc%8%N!^UiI92xsGm{w7@q4tGh737Y3{^41whtx6YS~O}ry0@h zQDqbobtb=NF>`m;5%M>Ek7R_sGIcPfICZfm%?YRyOk$mc&F`Kwj!E(Om_{;F*6zhn z&nV`P(srgJ;1`~JDH$sTnhHMLW3nn|0+SwbmdEq{;KM%K?2PwJVxC!QU|wY^4jF1h zqHdYszC-2<_5QCIi>4e>ww_^bxyMNc>P9nlaf-S2brsCd*Bw|R)C2Fo+J#Niq8aU} z_esSQ33J$d9^)EvS#s!z1+&=4pXhE>A(3;YlW)=6n1Vq?%sc-CX1cK_Q`jBHAlJLH zYui6dvUd(-qLom|dUD0*3_08H9ly%in5;dt zhWY*MG^So>an4Kw#Tk?xjkC&S`f^cZ(4KV0cIr{)*(+PJ?0hwj{<(z2))d+e9m^7( z1%D+L$^FUNeG8c@77LjZ6V>sO#;;66>k~Y2Lj)t6tYDjuxxiRYsbb#!9z-6EJ5DmL z>yeUE8l?Kiav|6HlWh2^7kt%v2g!Q-D#>p#Lm=P!$lNna*kgPJGuiPz)=fN)PwR(E z=njqv>VIDNT;s;E53zfvEo4kbj^bLv1M%#VH2%!b!DQIhxBM$B zEz+X)$(BS6;MQ&)&g8AN;tLihG3v8FN#<&Ju_n&xwlz1D@mKi{fsW~xy_wpF6c?B> zXO0-M9mh2Bdm}yez^+=pk8WRVX*@?5_QMUITARV2OTN$iT{)9c8~P3hUnnTH?#g41 zMLuN2^r_5_v1cUz)eXio9ea4L&u8KL-7ty8zBf3?)q=Txpwn)4aUrwSE>vcCdod1a z-G`g+)#BpBjgmb}H*>n7@0sBr`%8{iTxa`^sFQV+%wViChmsPPPTTCEW0_svA!VNu zFH3557jX99Wx}RvEpm5-5-v@S#4c|dn6mYcg;&j!m=|jwv-{srNj;cA+^0++-Qkxc zWeSJus%yjeT`p;oz0GYxY2H<#`SoTTS_0XiXTI1u%bB^_s=>4cj%ChRSKB_@VJAH3 z(PHxKfAibQTI_oEC<`q^P59^DGuXD46hUj;Hym1#i5n&jXTPr17hYT}mE2WHXWGmB zZQtv~mchXbS(_^dC8}wMgtj4`d~TH4!YQIK3^v6?!)C;*$Y>-!uhWg^JLw1j!aKmfaLXs zL9zwCql9wT53+@a9|$#WUzrQL)-peW+S&MGsgQGGkF4a6U8$WK5w_V}EPL88fRTGB z^Mi6b$|9!q6I#@?CGYeOF{f6k@Y9SMBq@8M*!gt@vYTVB@Wt=m@zyuxe8{szW@mp! zw(wXiGq=h}Fdw^&QQsNPr*8C=8Q2H2d1gZ;cO{efGuyZG#h*9H9;f7#MlbhfmmKbr zP32EAGt=3!4L=vMU;5?Cz^bBBrynzTC0U5X>4bmTC)Hp{$>K(4S5>9$_nE`7gIzcu z^TyV0-QK;zugGx8!_XGlhDJBWJG9uY;j5qQ!-D5_GeGDB-PM{nR>MM~djs&lS|>7H z^4Y@AF%i7oT__ak7s?Fuj|ek@SK7iW*I47saQ6B|=aMB>ajdVtCbPufxGZ`h!&c2H zmK`||CfKXK9caiYS2l}jMWgXB(F=LT z7K51V0r~i&1VbKL~dG|)T zvSo&N>}3iX{hvLu@XG)OV!Oh3I*^;u=pd4~GqwiL()nu8p* zTcqb-IKH{23Afx3@xqtx0(xsJ&Ove1SV*-L2EpaPVu+Df_Cg`i?@7##KX0J7A73s}>gNZ-T~{_T25EuOul*@dPI zxqMnwSr~%#={+`j$wE3eTagQl8z|LyrSP-Vo)Am6odcyNk;rOz88FF>C1;xYO7H0J z6c$^mO6RKH66D`9(cC?W^uY`@w6F9!nr`SVI{I!z0nMEfT&5Y~%lHQ)Znk?HJ?V z^Y|6Fe+cp9BCq`AG%kF7j=l1JEL(mzmvhe0!Y9+>`KEOmWhV-w@L1=4GWQ(<)8T%J zf8Wf@JdR%#Ql2+Tq)#TZY5Y|_=vp$f^{W%7y?QtQ0woIDi!KP~wPS_lM;5UqzWsQM z{xjKzsy9Mdo*Dc1y|WOPVaQt=OStLAFC;-fwS?U#8Nr}xJg=9xq|A{u<%$d_zvu1> zc1B_!nYU=beahIu|8w3{W;I$*7;8C&nYLe$we@lg7k!dVs7|n3E^EgL&z*!XpZiIo z4WxL3o-?DpG@Ey>{=yW5c}R3FSn*uhSxMQ3w-Y~?-oh@D9}>5a!NLlam&}ue!|)Mt znlRHq6Azobmp>BgiL)*>$+W`{bGQw1y9VDW33GGhw(9-IjJADIcGjwgE#Dc%d$vu* z--i?kc8!6oviC9Gf7WEI6uOWPT9+ZI?~cID3;Br+y$N`8)?vx5!IQDN`~zd3AP9+j zx`ge=w7IK>kNDa3wP^2=zOXnY4cs(p5w?6W#J9_j;z{1IFu5ZGPle;?8=D^(uNTmR z*P9jm%n>+e?>BgI+%D8>lLS0krQmUF3R>~{I+$FjMK3v@MEMHl$Iy&X*d#2Lc76GX zYdZ9$YU=?FxR?nwH|F7kMJmX&VkZuCdIb+A*;4d;44(AuF!jB03JsIjKB)ntRZIn8tKY9Du5$l!R#Wu^jg;Cy9(6h2! z_^4hT^{xfj)v=pyCHmxr??Pj*Hu5>PedVhfLF*$4c) z_GbMzZUE?uRmO)4M%#LDaHtoT#WgXLlIGhT-gK9{Q*l``enNjCK2MKD@mkEus-fJg zxRHE=Z?fPm4rNtGzT(f~W4LT@HPajajNPfE%C+b{U{!PSgdsEMFll*d!q!K2+@~wM zg-^D}*;TRt#@0C&fBa*^|I%2@mamLs+uI_UO~VW9%$DrL4eti98=B7x>`7P2%e9;F zizQWzuRpf)wOY--icjWSgS41cIfr?F^UuP->rcywi!D&iKE}fFZn8yr37l(2D({@p z&79P+7iNt-Bb!abnc?M1yh=a2(qq3B8B5qC{!xk_Ya2H~_@lCsW15e%jO9YE@_h~S zIW(JFDz#)R_dUk*uO7jtYfWwO`jgmw&IrM`*+$YcaT*>o^e*#qLn?Q&T$wYIih|F9 z*UX5=N4bmjxlH=S@3Psh|8dq$8l`JppK)LEAIoOZqg=&RPRJVBpG#4i!bMpv!=t`i zuzI&Nwq9KPaLDRBz+=O*s#G1qhTtHVY9A7es zhBj-#=K705zamdG{cJ0&?B>J)(d{sB{B{^+_gjoPJO){H$l&&-ZWN?!Bd*+NDDRmy z2+r(ir=x=g0&$oOu8C-cr~V!TcWv^}((^TJzde3p!)pgL>-ShL-^5TFzT6mFY`Q9P z%8TIrL*qGvz*BVEj!{7QSu)PrynnpX?G?^6MZM@FkpUR*8VF4u`oFDdA$skH-pQJV6Z_ zL%@hf%Ax@}i|1~;!G&bSpoQDb;qcmdux02NnlOGEShge#OsmzV6W9Ib##;mVz&;tM zC{ED0%P1FuRYv-F?q}g{6Hn5?5ez#ZLqNr9?sdtoBWEG)n^$oR&lE&Cm#jLB#z^RbH7*f z1J?Dy@p@AvGxyJ8q^qv51I)(=)4MH&?Dnz?b23_l`kFj`QpZWjzgev^HLF(H#Rubs zph`W7{Uw{Sx65A0PJb69Tj%((-kk}uU+;Z|`mF!>8P3_f`JYKl+hq+|z^XvzgY9&o z()SmiZ|cW~uyy>#Qwvz_Usw3{Gv+*_`j0P-nkpOK`03*H=~DKK#zUU`J1Gm=kzE>O z)5CO^9G2;RE}yvXWhVb;-42Ox@ifm5+AGulAZO~$J?t*p55!NKR`XFQ1$Hm1_6t+T zY?17y;p=91{^1B0S-Eb$uqIK-ZiAOhh_fuWyE$cp;OTF~J0$7~+cc&t zI%3Lf<(+O>9Uld5eElpe(%Z#n#;gaUOb5u|=4CS9m>6z?;u_Rkp30s5{)SQBA!q*! z_9F-0t(47d%>j?c8j|ki55OP2E}*{|V*kc!Nm12NP!JsiR&0xAb)tINi_`9dJ}2Ti z%a^C{+O9s_x}?=$Ve1u1hN`{bqVSlM!r5HT!8#CXstPO(k8!KJmv!dS0X-mA=w`B7}j+UEs<5Q92ihhcDbPcO6EqnN*DbQm|k z*uX^3HULxibg+wF&SCpk#|e2C9Qe;Z^98j|EwFFcKlZ{OCAMOp;{3E|Fqz&N!)f&& zD4W)0!TyZVW$b;^_{aT*;k6klxX-I+T<_!Mc1Ek72wB;`IcC>o*|s0MxpNb4@ePen zIFBO_neTr`@G!JnwyE(Bck8PT`{QR4f6!X-8sN+Lk2;QEcBK;D-di0=jo|uo@Z7)h*ZqESKb_sm*;RN8c-&672>Vt-;CG6p$%|LgeA(VB!W7E3(ke&H4 ztYox3ei9-POiD(`_Uw5kn8%G`JtRv&R+=7kVoU|lTOwP~s04%lWN?Wpaz01154;za zB6Ihu1H-px^YO(4!KX>?!Y}i3)=}*yi1u2|%{-jJcq~#T@7xWEY;GLmPCUR&M%obNhVp6#bNzR2f(eNPq;x1@l2yI7w^L#IKze`_~Bw@>ayq{m@`Ee z^Iy-C^}l9wI$w)%_RYzB`~J*>(68H&PggU#83^bt)#L`hGsHp5?{5B$n~;jSt%rl}e89 zj^|$g7sr2S^vAz+Wn3Q*H>|wtsbuC5SG>wPg^5d1V)iaI1=+V_aa8XKA-PtI4~q2% z>iihId8(>RX;~+}W<8yG6F!F2KZ_9FY_Ao}UY=u$;wDh{+|~HTfk#Z#h}WcH_&ni7 zZanTEcn{nE_mDXqV=k1Uqe6MbTISG@Db$6#Dhx|%CwpoQIOe%B9eVc(He7y+1V{7= zqnREu`~7v?oOhpF(RU@6wrdcdn;H%pQf4s+t*m7gcnGkXe*#~e^OwARw1PC`Y)wt@GJ2t?^Y#<5`3J=XRH^m z{Oi=;@}%f#mqv|>t>t543ZYR^JD8dsF4ib|U4KJoQk|g(`Fk4|$logO!^%0ck@(v} zbQ!ytYUNEK?lYsHps5ZXg9sXHzDB%~sY~rk>P4L;nc}tE`oQZ-A)Q(qEN&m~E&mx< zCxm*8l{<}nDuioMVaoku+?1YOvRflfM1xuVfpIu1Dn8V}`5ck^?0E=W@%~7zen}QB z#x15!Un9uQcJ6 z=N*qYck5u7PHaU#kJI8AZFjB$o}$i@x5U~#pIc|2PWSI^;g&6^7i&7t(8xj0;gEX+ zfO27tn9$usO3Y@0^#0{y?$a)&;Ocr(8h&5=$c+ZxKBi>px$rZ~Bxl_bm=DIa(;M2zyeE-pFUCVFX^aNI#2zSCC&h81yK z5k3av9ucy^`;}Odwm=Lxokw3MDZzz_NIv)Q1#;!c2=4UzPvUpQyzni99`V!4%N&}d z@Z0x6+|ob)sM&$X;)5xc;`m*5V1#-O`m3HMuC#e#J0Nw#3A3Tr~)$#uZcf^b>U6YI5tlln-WaT9xRi$ znuejlPd~t(*Z}F3omJu&)l9PUzdE626_j6^YDe-XBtg}?hiJ$5apd-kF!A{JBv5!j z3pEanrS-?%;AlTBsa~H6w6oAv412p(%(ik8A2kd{S9g|^E&nu8QG1ry+^Wc?lr+S| z^Gzh&>koP`HUkVBag}yF_)E?6evqw!6Y%f$Rs@U=Q1vrbXnjbNYY%9$U4kw|IdF^8&d6WXsEI$SO1Z$xe?@7W8k}9VmiGBj2aVfw z!STs2iGSb@@VJX*W(-e|_rFpIRHv5GNfvVW%HXc}?1i%EtywLm=uV)6*%16N=4-WdD+WGy63$v zNR3Joll5P5>r)ds>G=2JDL+4O_lAp@HP(UlSJIa|YU|6F+kE5PB{`z)pONy$;X}mn z@SuEtKX=$3WdzUE6o@-(W{B37p_Gh$$5;d&l{XJLkJDomY{k1P#D@-FX!pKw;dS#O z_`!E4xDl%*7W&*4mkjo#7nVO44^EygFB?(>@FRr>;o3#-wE6}Jv`wP%`)jzn)^ouFyd7G! zj2BmH>B`ZHX70e!bn#!nd|Irh4}{!j6hB9xs8vsHKf^|BU3`RgcFYEwxK^?A`bqL3 zEfGvKF_F(qI0y7o&8fk(+47#;si1a*8jbj}oNkO!0ol&>^4Ou-)Gsws-Z^fM81*+^ zp1e(0JQvt2MvQT%VM~JL@e6yzl3$+kO>Q3Y&09jbZ(d38L0~ZO4;uo|bO7#jRMO0x z(ee|jZ^bhfxne`d0f5KE$bG6Dsr9!TT;AK!a+{oJaNX2NZelqM$UeUm6GxYDCm+3` zYc`n6A7{Q5uY`rrV`oCSFeLyzHumyf+qaW@>(20Y4{!5HD`s*6PDdOzwR)fPgE z9z$u{Ias^3Nf!IO5`);rbyL0~}MMFji`1+kMX5aDfd8dHKBqJejK{bil_!dl>9tqQO1!1d36TH=Tj^Gw92;=$$vg@DZ6Z55N zP$R1aywA_XHLs7$+PD12)h2xBH^>}?&qd=nHzNr(c8TH+C-uOtbS0tZbtGq8o5pQv z(PSq+)}R+E)Zt^jhk&sN=8EsVBDpOC0l#YvH}!Hd@4s*>yu0HbXnUrL?u;Lfs`4f> z8$(QBw;oGBI|;(ygAs7}SVP!7Xd#zm=nBrREP!7!1^~Bt9^mtp#oQmiCqmr`KW?6_erh}jiIE7!OovTCC=)NwL` zl8xf6R4CO+$fWlNEhUk~ugMqbZ$gTjr2ZLJ)PK7x3LGXO-w)kJE<0qPyPu(S+=6a8 zB-@XUU+fQSlBY^dKX$>4qtVhiv-08CQ-#tEz9H<7N$;qgY$KUFGX{-Va)MUQ3MKDV zQ^jqXQZU=08U6DMM3H?Lz-!s&(qG3Q?)fhhExZtcqFqlw9}64w`uas--1gz9P(|T& z*z*ld%ub}grcNe)wN6swKIu?DAfEngcmmyweCQp&FcRZ2QX0Kx3bMO8Q2O+O8%aDH zDFuUOkSk|R$b7>T8Z`6`7`Ng*!dx_Rc$10Zku6D$J1@T7myfes%JGp&>EiPLGT=dH zmKumz(k-g$q@j8m`R6bKdM6~4HN9`RO^Hjv!eDzT&mWPtXI_v7?J*I*MLtEd4!y!} zdaJ~elmz%Zt3X;_Q7irC9z$MiiIxs{83BJtOo>5TJ@Oi~k*=w~Naq|5p-)%!mF{lS zrF?x4nw-3tjPPvYT>gF#-&|cvnr$+usND~o+B-<@@eIScR!L&DLn18MHcfi9?I9dz z5K1Rs4}-s329YnNYV>;geg1du2ln>(aymfv0{30<9(KH^;7HLhap%!kdg}8SVa8im z@S%Dlt>ZkwfEj(zqSenSQBmYeqmII7j&JBC`2{fKv==+L_aMsdXU+j}r8uG^7k<-H zg6IG00F|V4@?85q-WS`=P4GJkvxd(F+eSH{b(3e&uz5F#z1uYLRdu_TtuAZGb};@56l^UXp!VH-JmM6G-#l*VI+vWf{_B4NX3} zL%4GkTpZdCq<_f1$B)2Hk2_G7s*UTnXX6o3W01AX5(FI?OouIP z5mJ42qqZ$csBL1cu+jSf8Cz%t*X>Lv^T9*VQXGvUo-ctN8&jA%B0&2Ad8ITfGG$%DVdT%rg;RmAjyp0cViFmm{;yES>rMG4wt^60ZnT5q0NBfsuPem7^Jq2`FHL_9loWGc!{&PeuHFkR8U>-s-Y_(4^;_^^L4lC&{}oMGr z-xjiyt6@>+Ivl*R7bNut2^kkDx~12qEG3Vf^RqDcp569x9Jh zM#DVz1ARpf?0!%UJv*C)eawWD5eXj4sOu8D=7~_UdT%U)_KX+h769=xIr-q6nq6H-YIT>w2T+LCW{C62VHX;bksWgD}xGt(WeG}wbM4*@^ zJ5(6F5`k+z$S3BI;2~+i*J(Q5-lBx7-sa(L54C{qNoRCr<2dwWOamu57tU!f%10YM zq=Clqx>zIn01^am>>Rrit$yx?tyLPJN#H_!<0g{K&+ zfM?iy-T+iT>LW?)ZscN()9?WWt0MN{NnvW>Uvkt=Rk*z<994RZZ z(c?aoo-O~tsiB6z+_RoFzB7l`{z^oe&n48{`V89fpdYxjaxnVy?g`K@84NUz)-iV{ zLd5i62z_>H0Ok5{crhS^6xXN2D|?h_x$ap~`zs3lUT{r#WmZamDfXwS9SYCbj!X3P z*|S3AWjA8yIgCD1oq)a#`U{U*ycK$DB4M&y9PL!hvFjgvPI5K>faTL33xBt`Q1EvK zJT_blSz9i^TK!{D&E7vkkf#M+azBQ>k^Y+;$W-*xKkSF{W)ZZ6Y6A?_%(By4Z z5Ag6S29uAM316!Fp!?ra;KH~0C^Y{jTJ^cFV0Yyj)US-BHp;Vb{gYM8FX!&9%wxtMP3FO2?>>xaY#=F*I?;~H?=PYmfG8io`)e?_q>kmxe>)Z?K0&` zCwzd_@@(#<>MfMC*j>D0Jr*i{(xKNeU*WmgTU;HlgC6d(B5IQrezx)yVwVw!TDU*-uKxh4{a>;;&HfM?{1=nnHAAE`x=h9X zS9H)>?OvhU5Q}#ze_?y;H_-oM2FbmZgVj5G>Dy#ycB?`foj65SdK~9eq8D+6WAn())C4$VTQOZRZ5>=ZCWeNFB#@foF!Xh(5=|*BqNkMB z;HUX<*kIfd{J|y|?FqR`9S6rk<-!Pj`$#cb>C{Y~?Hq_V6o$~*V-E1le=Im$E)!Oq z7>f){tl8`Po{O3*ofPZQm9zSz$e&hp;o2TGy3R8X)xUJ(e5=e!(1Q!aPdx!Ix~U;I z8*z(tOo{;=Q5R70*SB!c?EQ33un8TH?~@HFXAM9jPkcWL?b<;aP6d5=<#-h zdt1lj>gH7_@XBN1T5?|T)99m=}hJ-e|K^<+j{6g zFJF=u_YUrF3lZE_HH!ZVN<__0GcI(Qj0CLML-{j0aB{(WkoV!H*yvbC-&iQ2&fmAh zf=X2o6O+S@4IPI16|4huX1dEqd2q0@tB`_C>)12(+TyEkPNb0y6n*;D!)udMfGJc( zp&5nZ@r$~2RK_s5V`c^@ZvQ2Qi&9Q44Wb#94`|5$`FNa)^FH^WpU0 zk>F%_mAIg(7VH%V!)um_c-$KSobhVn91^yPt(hmdi$OhfP+0~S+0`U^@4XI&4L9W$ zdi%okrF+P$YCW;M@(LXv?=R}Uapc^Ou0k&s6yTJmfow#RKeE?$r2l?IgRvgE@|#43 z-8Re}tZDrWBz=3i5^RSi&p%0Chn0xtxz%E6$QwmAX9J&n)ewIv_!8SJT#?xBP1y5# z@(+DY<(Id8;J(*A5yd&$^y#8~oN|Sen3K>(LRUN|!wni?RY^L9<0qW$B~q#BV|bWtvNny;dYeKh6N< zLl5AuzPE(y+TqxxdK?nUe{uJ}B+}FF0@lbmh$6PEL&0T-gnmO)$1 zBjis;4j%I19r=C@^ceFlAjN-1zl87#=xLNUInP$L|_R zc4Q2M@yq?-$zfgaP0L-ff!Ts9uIZtIl4pvZ$0hPg%M$p2>Eub(KD;bh35C3M0#VC) zq3cHm4^3Er*4D)fe;%4)pM&d3RM$Q3iSIqAr|bdOtx17Lm#gBKQdKb^d>Dxp?g+;; z4w3K~OF-JSa5C{o1meBoggrOb;BVPpVBUB?e77lw4&vgu0U8t03C}rbwMjJcUvr-L ztSEze3kBgO(WCu`#lnC?*~oeJNi<7Giu309AkQfwAa3<2yeYj3{_)PmE}wI_Re{Rf zl#lJO`s-%0pj;Vk*p)35I;(Ii$L3O%aw!fTy&7xIe89%7yQ#>!@ma2>GmJ%Nae-jVrQL^G;?MNoum3dL34&6(U! z+}ZhycsY$!%o`JQ@c2yezn%u7cgO}ePfJAYGv497LEN7cC@vKr#K| z7mOY{p5->(Jt~h}t}PB2)y>8FMTpsJRbXz`I(pFk6pc=u2DH`>AiI1Pk#pzcBrYS1 z<@wGtqIpt382nXB?)2pz-MO_$1U}1z0dEG$ZJtNN%a&SFOYeDzpLAR>idB`~ z)l7nscP3$WM=`SOsvzb&Wa7+)tqP9$1CkN2p3dyoEPnEy!e&Np;>HcvkgvOQhPxyk zDz|;;3-o_Ci=Ve{h0|45i!+q_h)v6_k;_X>(eOTt?%(jH#HT;d{dWRx%8cT(FPh>_ z-tS;^x4>0pV(QuGLe4KTLQ4<6gu8-s`H#Osgv~mZFzezYL0fUAQ1Iv>bX3`cS85y4 z>@a2YsAVgOZP~q6ZP z&ACnXi{XlmG^JX>d6E+v3$88vosR7qI6=Kf0t)xDstc9x489PDcEg7 zHk`68l}R|Y8Ov|)=XQU^!p`7+V&AU;+~pzyai2_BaxfaM45Os)p<=MSJB#;xmOvjW z^1o7X8EWjcKrvfi@Pq%nhxT{ogUu1;g2Cz(Xy&aq^`;IH7E zU!f3~*@w$o7)hr*O%!4*-Dv8|JM77=59l(@gJ6;Re7arhD5%Q31yvFdc>bdZ1tip> z+WjfGw z0^O)CP5EOeeo1{zf1b8Sp>y}5gU2Lj_s|LKbG^UlQF}H1??fatNzsAJUKrB5XO5De zChns9@lLvGohq$X84co}-?T03kfIgolWBhSX7TIz4QRc~e`w0%AZh!Ut#EH`CfZUx zko;|YOMiAOCca0Vg%K8)!L$1N(uTQv5QZp7uNYl%g12GAX12FT7+V z8h%`e4rJv)<9XAto6Q`w_FE43;z1ZbRZT%yg&AG?#YBphH7Y!IQ^33v8pQZmGI}`A znBH@CAlq3lsPKx?D+=aec87zs0o=oXh?=k@JBsev9)-tW>LaZfSxui_TqoW3E}Xj| z)I+b!U%1gL+|eTQM(&usnN-(V6FR<~Cv~(BkyhSG#@D9BiPkR(4VzhwJ=`)l`vwQp zzEC2~9FPo@$2U`pDi*5ybf7;gFW@1U*3%8GH_*nEb>!^ED#Wywlh8%#Qf-&1VrjMm zTH(=zA{-5n>W&L2`g*E#!SlWJ;

L+=fWyV!_{*D?~W=^-sVs0z;x&ZnF5lu2;I zIO+7k`=qZIh2a~sE9q^gGicz2DP-0*8B&%^knVOVfH!Y!r{i|tM!VWR(M_A1vCrx) z=zHiaaw#cPdi?xsa%a&z=(D^H|2Ex-`jN|^?}w-8$<%a0j*X&g@2R2J_w=Q0;r-A& z`_WR5dk-yd)9HdDN#4wA>wUg&`295wTgB&M2f;@3MINT2=$U5xz&D`!uI z)BIe~#)VpVs`wav8h!#+esYJu7f(b7!j>smY`0-+*+4X5??9>J!>hD8^#QQ^^AN2Y zejc9Kkw>4D=D_fR1vH5JpR4l@$Ljz8xDg_=tVDLkeV_3jw|k(XP?UBFB`JzZN=2VC zviFQ4v!R3v_mU!`C^V>u6iw}fruzE*`#aZl{y6`g>pIst=ly;?pU=m0l~BJ`nRnDa zotyGz4i5w{g{QyF=iT}hYc+q!P^ftFve0GVEql7-bRHwro$F&SA^gvCp^!Y7AWk{K z5YBec6xJUs67AWY%}HX4g;gFNJokGXVe{@}VOERy-(<3HZDI=c7Sf#2{s&V!XOGp$z;yV%L0*`-@=a|=?G#TUU^Sl|{;g)P%aR|j z%B-0|)YX1iRAZ%4wwP6=^<|0!xuYgR{imQ}L8`!Crvz0$Z-E9^9`L{4y=+Ck)e=bB zTL=}UHVUSv57)lt?PZ@ly|Y&GPoCg)@U~jB^&4uYJu0i6{#l)EqF*fB`R|}0;#g}< z_?a(Ow(5Ie@AH#2T6!D#Nju1zqJUI^`M&#taN*IZUISTdxhzR2rBj0y#D4feYgTP# z|Fv3e#{L>Z=dh{o!!s;d#;V|{j>^Y)w6p;EZ8yroi#R{*=%|9xLTD@3bkF%3G7n^C01Mf9IUKP zKCW5)>IkcLO{Sn9RtTEzn%8FKlLAUjLD(602oZPXSxNFHwHq_C1efwG1YalK2nsK% zSnXIM&khdf2@D-nxSj=Up~HzrD`jKpLldYkhR#DlX3on;HLzK&FL-Ye2MiI#1>o^Hpn$`5~s3lOk20wn~S%L zl4e}w_wJ&(vvjTtM@zZ{)^4W+n=}&HY1XT(IvYFKFX9wLKjLl+Hd*8=?NwOY9|mr>!;~DPgbt8^QX!`U-pc=mp`bv$6Pn z<^U(g^vG04T98nO+ACz=>=a}_;`2wsb2(SU}gmG=R8I0neQe=^$QbtZdM1lKPtO< zEysH~p~Gjmr;}ua?b~B`%?Z9-xs0ja`t6UoN_(?J`4u#;Ci5Nl{00RvT=XCBO7d~` z^=mv0t4fmau{30cfNc51fOk*hB2gOm5@#8gVO{?8n$Xkr7+b!{hZB*q zO?WW4lK1MU6mQLLKVI;mQ@o;!Z+J;vN!$n7#=M6$iozH6iM+%&a=bemguE0VBWvTJ z9aeosfjqV5bn)81$Auw6XYR`F)!cE>UT%?v7T2ZpChxL`4o8P?$=gtLMR1zy!Ztsc z#__QDF1(Ow$n$>_H3d&z&pSiEMAtudssA$4ffpOax)dhbnAV#&oP>7 zS;gb0Y4rS~u5ubBw4gmo50dNvf`X{Rx5E6bh*%DMUQ`c#)`c;ES-__YCJy zX*m0N&`DwAvhSjS8)@1rN)v{7RB%jXt3(CSQ}fujNg|_{RcwiqwcKAF<($hpYecV0;zcAGC5%oh64+0q za;xXQXWR6hM7=|6H`J z?vz5U$m(Ju|FEfoSlZ+gd+UgV)z5eN+~$*ZR*}!K@a{1^&PmN!eo&fTU0DU>RE7m{ zsTK8{-xr7ZDpm5rBZP z!0f&sH~*Yft@D__xDE)||LV7KmE@H~ns*CC!JJ^>BMpi@x95U*DuN)Gy}C!NcleCe z@G>yPxH`b;SR*HnTz*AFJ3Qw;-{&mqZ7C6loof+Gy#K`tBRJd;mj)}fj@g2q+zD=2 z+(ORTNbROy?vDG)(3IwQpO@g0p^}{%feZLD=U1ei7QE>(;Oe+ zjP6|VrNAyW=jUnR1VM{Wy1!)q>Zuj&UCI(QhOQDPJ5`9CYAnRrx>npTuXl@PwJhVj z8&t0Q`Avmuzl0QT{&8BEw7Y=QH@%0g@vci$G_UT$V6kY{RnxkM0h`61(agHr zXLZC2-|Ez@Q|ES6IMs z7r2zAbBdaO3R>0(IR`VRdhUbb1l+`KzPDo-yFY}_ulPrDwk<6Y=&4+{s>$+Y&#J$~ zDY{!z6YpEf+1|$H7=PQy-C;V7-*9;WXZgk%g3jtTwgp+v-=&~BweHFj3c9cG6XR_; z{kB*563Cc8ZGk&yc>6)zilHY8n3#lBr`&In^ z2KTZ(Zd7nItF{Qn9M1D^OqTP9`=9fF1U%-i*lWglY?sMd9oWk;GP%zm-&w@jXm^IS z`gbv3?duY&s3phvOMkR*R%Tvc5B}YZd&Xo0lM!>-t$ok={<`0$nDd$fduUgyqr9H2 z{aA^c#Fi3V)YccY_TJIvhK{1zat;P26*}Kloqz{5bvw*Z5g+0)CRzO155WiC}c63g_|ZMz-G-S&mbZ z5kFz(YYv+93^HE1Pd!Y*xyu2`HytHg_lB%_|?w2!n^C{b7&yu1Z!ln zP;)W7BA3}|uf6-Qar z^$jA42i+W3ZEewktBb{6!&f;-+QRCo>eT-H)hy9_vp~_3sTq>}RIjmfRG2{BYA)A6 zR4p2flM^jd$P%p3FyU-^Immi)`rnf(rf(RD#e^RSN;2>jeLDa4Kgqv5aq1V5=sC&Z2taes!ZoIhRuB>oEYmQZh3J~w45MOCvkC62(Nu={Hg5?`1D?D~* z8oT(0A1nRy7O}UuTyU;;zIdi{B9m*2ZBzzC-+T}%4+q{FlDGVL$B_!k}9pH;Q1n3P3BDcIg zPFsAAXB_TRWu`1k1`Z2HN$$LjAn_lh4s~||$7}++I7Bf1CX7+pHy?vLLkp-*iypAe zs0Ms9z_bpxo{l>4kDi@QQniZN%+)5|@Wi5xL}H;W>^OOx4%|>i3rCGe6^krz{_bY_ ziDn$2!iK0sA%_avJ`1iprw*e^v;gbu1h6+*36zVQV93}1$k5rR!O`F?%w+p}v?pT+ zSu!y}^ekUVjmxJJ@~_6}O*-NVPUYZ8{yn;)f}me!MNx$X zt)zjz4R{gU0c@ww0v?sKjpxQdLQQZkIF<3FOswxF=ob^#6#GBhrZgr3SJjZhc?xnur>cBsXHea zgwqn_f=z|MyhItyrw>BMwVjY@ox)^{HUPWo%T)WVSjI@%YT6q_Q;{dU!Q=CxG`IgM zxa%xIn_3#fqNBH%hvp|y^FCPv%aAzc>#vC*^HMw!W>P~x*=a?$E&oN`NL~R3dK-Y; z^ikTSgu)x!4bg?Cy7Vr+AJDlefrwt4LCO%v(csKSbk(ZGNWyRyXpIt~k!m*Hpt6@J zjdF&j_a39no&`X;?jBm_S%@Bb8^QKf4`Jrl8mQ7`4L%RqlX9QK@Kqx<%H@&)UK(-xxjaAaLzdUqN9nY!7>&xBf zoSm1EixVa{bgH7<#|OdmoTYT{-$79NdmnYc>k*Xg;-ZgUO7!ioOyr&#Ne@?W(7ohK zsA^vw6!*BoQP0hwoQOmeS@8b+2Uzsr8*n{+o(jBm zpU84bg%R;bkitj~(kL$?(wiLdCG92j91{<6EertR(2IT66vwrI{#$GNVjj z!(Icp^~VDApzIbZ>uiSe<*e|xnE#OEqMh{e{v7zXyO7v-G?cUv>_LGnb>N{Ai8Ab- z(H)4dFePG`X;Y>EzAuL6AvVv?K} zgfDE3rw*=k!;|eR;8TM%I8l;E`8GA6Z51i-Voxa2@>mErRWra8SrI#YS%E#-^AXvm zj;;3DBl$%)@o+*O{a{-)y0>tYU}RyWr!_$vMUPWP!dY-zOBE$;{upZJ?ng(UJFQj{ zhPvD*iGg3%sKmApojCFuwnyv2lHd|>KV>>t!<}Li)u>`ee-GqnyPRGYu8;OeYzH11 z40Pi#AEXRVQj5V5;T4k$qhkwEeQFe%vFsYrXMGG8Y@A1%AGkt%p7a96kIvG=``b~4 z{w4HQc`g!eFe1PHT8MRTdV~IPHmPVTi#7)DG#Hj zt$iR}HJZ@fa1t&mngDCd-I3O`3i#`t9QN9%4(~-!IAR%#($2~Ua$WNg+pdJfnS0Q_ z`9&0nFhaXkZQ#~S7JQkt8p)JAK#UFFV9bA~aQ)>SX!=xrus7zS!WmbI>Ia>qtf&vI zzokSC{n(AHc2&~vwN>yyeiY8S+)TtxJ%8!QS$MngRltuVaf^I1Dvde;u5RL@Ae|*B z_R(&j(RhRWp3s6V?-x+k(ueTP>wMTTrypj&pFuPFXCu88-zcYua+J{j09KB7gX3{V zxTnz_?=Q#(+)RYOEtYU z=*_{ku=cSFHKLS^eo8#2cW(AW&YjW7uG|hTN*xEiLzh71+37&)cp=(fD2d^-*P!rd z8o1Y!iIRu9fWgrZ;HT{`V5(|Ey~wd9!yG?Bh3^-T-rxkvlbR&9U-iLW>ndpL+ndSN z9uI*O(MhCI3V81v52R7?7&5bukbVcZ;+6m|_&5+uu6*l-PCL${7k>HLoZJ&JfF*s3 zdUO>sJGC7K&&mdVUKm%)Ipf*OS;*+HHg^5G6O}I_is7)snm>fbTY^Y|5xN{`+U0MjRSddZz*10H3`3@?!-s768P#*N!Gg6x!|yD zG@4{7(J|}V&`|9*^f@#Qe-TNrBwNbKOz{{>eRBusPtPOzF6P2XorfSGIvhQpdWRWd zKTyDSEqKGm3l}f>PR^Aoo%-*1q2+hZktSQuAckErwQ!me@`!MQE%X>dy?1=1mB3C5is!u?(zD&^OMXJJLq+%Ac5P+g2!?niOR{*}bT zbP)tQcHxNJZ2HjUMCkD_5?5! z(54G@e~l3{{WoA|h8-H*CxZq>%gEBQxs(Z=09kj_aO*V*{Q9Ri9-mk@lDTMptka(k5S&(LR}PsOz^J(3oN|-ASHH3@6BJ8J$ z2sZ^}snd%-&J9Dk3VLLRydulA`z7&QHJn&~<1&#pe;qhnavI&pU4)~fs*#mR4HyX`F6|DgED+ zCe^5=KOZlu_(ivf2H@?lBZU3cM{s4A9&DS6OT~5~)`!iDNlQl`{GVeglpVWDoQzUH z>+|H{>vj_qptgbf=^l$&qo+WL%?BvQQ6%ep*Fk4P4f@21b~5qtG|1CiLiZ*dffYv6 z(EVv?bQx}fO_s~C^)wN5?KH%_^@=F`$$Z-M)&QJ&bPqB7JBHk;8H=KguhNR6mT2u0 z37~Z4EK;0mq3N+%O;|so;5C^>H2XCM64&@hH6#_4NhrZoPciImYlCh*MnK*bk~?fS z<9(VB$bBm{u;YKeaCco6JZ$)u8hCveotwjik4-kAJQFuKn;?nc?2e5E~To`NGMN_f=icgLdzTCkcW2~@u`WzYo=Myytswr;wLLWn(ej|>^}&Hz79^#H{3Y2+* zs!NXs9fw^B^(ser*|8bak5FiD^n19wiH|0>UkA@V&Bb?~eWLi=oWajA3uJivAUQ9^ z8$CVmO}%6d!lqIcIBT0C9Cu)#m2WE0-;qnO2VX>sB`!gKsZI1I`x(f5l1scyf5McI z%0TP>1%uz)6JbXA9$KIzM)F%}Y_KkxX@2`6%$7334ckjWdE_e?o;9VP&D{m1y``Z+ z(ovvirb*>*K2Kh&u0ntQl~H@#7vk`rdw`N{H0&+J^hNU-SS|hwJk$OTmJMb=)Xk+& zaaN)*=!4g+EkyZsxyYi{2SkY#@Jy91NHl8U5Nhk97n>$&(J5Y2ad|kCInfdR7F@flx}3>SC_?T z&xJgC{yZljOyI(-->JyanS^mxkoJ4Gj!+JefX;<`&;yxe=q|UAFj}96dnrh%Zd4|> zz-l^li!9)8iG;d}FHn4}87dXeCAtL8lTGpv$!ve<#s6yFmw zM0e>$zbol`rNsnmMLQZiupYIppO48Cyz^*ASIq9y62lc zwU1bemE^9HA7p=_uMrf40g6P+Gd(yxG!pzv`UhH)p1^IlIM}`N4Sjqx2DR5j(>so; zK$jp4FQ%H1-?EaS@eVb*Cp8rA)Vm5ZkK56r+l~-#euAE7?xd6)Raw){Y2uIL^TE^l zBoyPhj|^c&Qt@|8aFcQo<^ISHUr|+pS6bZh`0U?UcIi>_)VL5*v+Z$~{tP%K*N*q= zenfId9>U*88qxEkG3ZM%3qDs~M@g3lusRA@bboj=MiB>)gWfSz*YKClO0GnXztgDm zPh9b%MNG6}<96s+B+05edlB1I7J<<|ghgW*pZ|HDHG8!r5FR{(%OXvvcdH?ixYz(r z_7u>Xj1-vSRYHca8&TuU4AlSn67|#T13E;61LrC2+GUL!&hb8mYUnt4^@A%s!ruyb zioUpKn=4kkB?|}T)M1L-4D8yz6*fwp1{mIl;w?E8pItUJN3cWK+73tT^2eJFx{_WR zPw?Ll*5JCnJtbf60Zr%HljQznTw5{KS*y^1@=j_~kC|pHo6JC%8LLjsvgt>>Lk1u$ zHxdROKE&!-vVjrm2aba zEsAhcay$AmQ-dYjpU(<@vX8QHf_V9?bb5LrL0Y!Fgw+Rx(EXMxURBhFZYDcm@7bqd zrpa8^miF)TifCJ47GaAken(Plr!Z_7wvhU8w+n63$8cr44m#9@utQ85HrDGxzXfk` zgYs3>ar7A-loXG0{#lU)FIW_Jg$_Qcw2)dsDq;PxJ|KI$AFcZ?!d~r|{JdQSmUj)K z)%|gFn^G9 zop0z}s}275eUdnkABlB%Kj;_s8kF2e6*zCD3TZoQ0}il_MfRN%=!4%&a$wqYR$&nr z3gaG--e1CyQ~xVkUE2{70f=>SgCWI=Y@|(G09d?vlyqC~z{&$*pv6mubpwfT+}k47 z{++Gh;y8^vdSd97&91m~YzwNMe*v3^EoIfse@ljVOrSM>>nPI)&4gJ;Bhb|S0|MX7 z#UsI&kd4nI;)le;*28~s$NFout>0T}_WKWrQf5-;uP?=c$DWV@cjqA88^u6H&l-N} zQ^ZDvhB!O!B=TL-PFXr%C2cIm8RmvO^0v9IMTx4E<=b8r%6Ek-!y*1PDerrM`NqqI z%FSw|9Bq^=?#VnS^5^fOewaUCK6&Czaj(B1e;U$JsuM&0nU` zW)Jw58>td%{;nBh#Xlo*j{6D5QbrB=PGuAGe%o&{rTPuAB3_AD5}!|%J-k3of!T=7 z$M#YtjrHUK({=PB<59-F6Ff>~;rW=fZ6Kk~ z3Cojm?POEi8HRRsGwE74i%P6BCA0SE6LUTOF$-JunEJ#FYWv|;)LonDWN`U;=KTGQ zq}2F7W=BdD!Rz)Vwq0My(9hgw!K|82P6SI(LqWz=Wd^b+T62|RzH4SQ@V;7tRu{jyeDxnfNL~fVb!5E!bLgg^3NS56P z%6x$b{nlQ}a<#2Gr5aFg`Ekt*izPo^5PlY$hzjp_B(e=6UAyN|Wu3mn!zK09I~N-U zCs~oH{9=%l+iPKIc~G6IS3hMTt(Qcy3Z65KH=ibsp1VVCUhhaXt85{?UL0nvjm}28 z{}oXsg};&gEsDHSVnXx3<>M{0T&OdfG!f>v15TVAE`4wZKVREK9&<29gNt%8eG4Je z-$|^S?zQwHX*)XEp&mb-;>PK;*uwaoh|V$k#JU!*0eW{u!JPWb$cbByI`Sr|4fb+i zxxra#^=c=4ZnY*>*tG!Z&Dw-nWxwzT=M3u9S63X)sld078d@=R49Mo;99CedGW9fh zEmY4s0FoaZq#yQ$p)IK^shX-jv~Gz?@o?F))M!V=3&V847cbyM;S$l0@zI^|DMTP(K2&(pu4 zn_Dedz2Y4t@!ka9=(dKJo$gY-F$d9oUp1;A`vK1T5)P*a0pwjAMQ!aG!HIh!!Rf3M zR7v^|?3c2Y98K7R>`r~frEdeMpYLwaG2IoQj`N$W|Kr1wt&|6@cV4ot4~F3elOL=< zi)W(wt{3qK&3j<(i&d5$E^Nh^RZg$Tel8tn#3Hc?b{0EyjO*4c_oWp zJ^zTkpGVa; z@z>C?k7a;>lAcP4KPlPCD7_2*p-9$?V>yfv;7s zA@t-Gz@9~#a4J0sWNj=-w@=rolK*muY_~*c_*ojVhvxu7`zBllZow}fV+pmvHK0SL z3r6{v;=M{7<}0%_WSGq)Hq3ZV`>(%4o3B%)PTk9;V-i?IMMMV}IDDK`esrH%{pT>< ze<_pRm0~H(4@(mtUUb6d zrTVm2{z_u2Y$maRyBr0rlcvjGr4YHNuR~nv#1#G734ClNQK@r2F)jNG<)52GIi}Ai z<`14j-Ip-=ZEyhHG`#`W4nn+JTtr)zNTORu#;ATTQ#7)CB_s;{kQ8|U5ex(3;V~7^ z8xTn-nXY9TZO^Cvb*T}1-KwDFsv2l`@GRK<@gDP-`Y_u3U^Xon@n(Mg@CBa#ewpab zutaaZ)DcF8fIhY67-{rnCiP*>AdI5c!_j{=VCP6G{xejF?szBDT`vQXZ~S!fv`sB} zOI{U+wQL2wy5~{OLo0A_LI<& zhjW`C6}=Rc?ctE0ownhe*w19&`f?1Xt%UihQfS}0opjgCxmY={8xrkZ=p(^{@uVkR zu-F6N-FX4ePEJO>_#aYJ)ki&gQY_71uj!@(J#g0e1yUNEM6F@cFl^~P+Wl2HsIK`; z2@V4E@^_SE1{5gK*3&3O?2NA^Ekh%pp2Ch_67c5pDB3ROD(XCZ2v0sa zgDe@Y)YuD4WO>IF*2#pSHmy(?=f9YKGFzKW6tu&#`JYgtS~HRl(IyRi`>|W;FcELW zC;hd|>2dF`^fq!Fv9;y#pCxH%(;Ihk`-OwJf`1#B3T#Nm-2>E+M>5oC@}TVv3|Qfu zDzd}4fZn)J0es@8k#OsE+;ztp$px*z^JWF&E=@bu`p(0k<$e;Hv*iKNvnUQNA8v#Z zC=zG1P%MeGQu6s27hf4RfajcQiJjq&&}y+CG+7L$VfI-9Uab8JHA|-Wy$c}vd}SNuuH``NJZ8>J zSL|X|zP@4}$2)KSa4%+6G=;up*{P>v3yS;+^t0_U{uUTMzV?h|fSi6C6JHMHk zvQ(Lj^~odCe@r9Q`fAN30``-iixygPjINqjPqU?de>h>Gb0L^I_Njz$NnA)0-Lsgj z72ag-+Z*Pu$N!O!0tT5`S7(@`pMI3%z7+CQ%yNr}{I6tgPChYo*^g@boWziAFd#Oy zX<5VvUm-pnjy5m)Z>xD=-z*C!wKrzDb8?Aoqv@npkrYEM;~aU$hTynf{eC&6AC8QljfGEPh#(n9X~kU`ABuS+M9>>X_Yg z#@a7=@O5d45*SDxy_~dqw`kQ3TpGO)oRh#A#EJJ;2xAJL<*P3dPyz~!Qte0*+ zbM|!e!oEu4Ltisx=#>rGH1?eF<4z-~U;4;wi)6Q1UC~p*O$98~{N624FTOPAyY!r3an zDRXTv)LJb<8TU`nFFbFe*5^_nWNt0G{oDdq=`zr5+g^CW<{dEjy%3D6y+i*^24Roz zBGeUk3AjmDAh-1-)ZKCjxgOsHkMgI+pC{bN8K%0(`i?YiJ2MyOsG5=LJMLoN@Av7% z*)Paidr8<}`Gu~WW{F=E$Y6m{CerggNe=4paqRqOV6f>F`Dt}5+K=O)${h`u_*#S2 zI@(9x4XvXs2epCaie&QPPdS#aZ} zNO^NFzPW7?tK-o>Qg6Z&q0Gc(Vi3ps`)+V%{MhE{?E?+s9PN=ryzy7QD2?PS3rm+3}|E+y^Q0 z$iqi)(3=H_k2Gy~D}nyvYC)BRM?hkg7Bc*BouYU?Fhw$oT-Yg(WCtQqim(Wt+rfex z=Nf?Yz+=>yWfAOq(u*W+Jc9KaQ$gH6H^ChD^I&}HyZB^v8<0H6A%9<7N`(7PhrxDk z=!v8W3cJ3ZD7SH$LZOA5sL6^|4Msr~F zcrzhxZ>J(PrX!TJ73;13LYUr4L$OUEfX=_cbXWgMzqZYxGD(zgAktSBX5g=OAnpI#FNJ2I-#*HQ}whx5rQEcV~x^9gfQjvQ^yrf4+n`JN2=nYeFZ`}!$#@!CW4OMZr zUn*`^uP2%g=RmVZ<~Ytc6*w<6#9QnBpyyeKVWpY{S|-UvmohWJ{53h`QlAza`f|!? zaxNMxp$-^l{uf&Gy3&iH2GIejlhEb*btE$tjaQi01VpFS;yDsgxWCHPv9wh>^X0{Y5v4BL{gQVFIONZU6Rr9RtEKi!&v4!>%r zz0}jtNr4WZO)R}}~uQ~}0gB2;mlh3A~!jm|n92IU8jAo-gTQ0F-tS(e$t zJ?66XSFtha>hK0$)NMu2B;TR4nm-9er&CzGEuT(mC?^|7Z-Oed8v66+?^A5uHq_$k zj-)pGldo0NaDPV=@V>B{3|i-m_-B{FSrbn|+>Lj*te}QmIvhlcCZ5yvUfan5#v|Nc zt%@oH$8kol4eqKoXBkVp1jWS#DCx8TZ5N=353z$#N=F_x-K55HO&5@5?aKI6-g_|i z^$KCqp{sOcr;WO?RzN#E#Z;$Ljw&| zclXkEXA6nVkBy1gg5z{e-ZaL?gnmYNl><>L^M{!CvI|K24N&*(&oP>}D9|-4#>m5q zzZ2@7nHEc?E5M{RDvVt(uFz|LxX_v(da0X6Q5KJm&Z7^Nm@&VUaDdOkRLVEvVOgVA(3&?a&^=O#&`wI zux_uV1K;$L%9O}*iC-Dhju~l**H}s&i z3x~6opUTy#(kd0k&zm-&9yrn`--a?pKTk6bO1uGwCXO=O{!3?k+&d4XFOOkl@oAy} zp9Pm%Z!j#bby$r37+_Lfu?+S8EMRMD&YXND0y9?nfa}||;GuOK#=Z6aK$5qBikP{F zKE*O3JcDR(zvUxv;RiE(C*$ZZiPsp#OA;)!CPx@EEO-pK*8yCeUdM0=NeTH;XI-@uw4*b-ih{#|YT1)vD zGzge-69uOen~O*3gtbD3$A22k9n5YZdZ$RGT?_!%Zrf11pGm_pwGbHo={&>6B9L~L zoD18G45*C7GH|r>DR?@#h(0QHlWzX@iB7xiMNK@xf ziKlmnRj?IkUXP=>1sPKsd^ZK(Z=~KC>cO>}HbKcH5WH#8hJDBVK?48I9Fcdt!aGZQOZy8uv^cZ~m zHb_4!_NA)=&Qq?{*U3222ke!a122uQ1a1p#scqt=AS9!n`fh3jPG>%%EOKgy&sTMs zTYlHmDof6SLl#}&n(s%(ilPKa>{&(1h(!!Fb_PX0Eg;3^pFm9hMPO=ijb_eS#q?3! z1YiG1q?RVFVJa>>M~6c|FZdcjIeR~ZMmg!sq_1Cyja6mjq_-o}CMOr>SxnHc6k}oN zPF;9!tvnK3eL+&58Gv6pgCrAggF?pzz$dI2^0XDvi~Hx9#g$_Kn731{EBFjvk}u6n zsif>(l7Ww14t;R9Bs91=lm5`N5xyE`6Tq^Vnv`(@EkoCtH*89PM`9%rWB7&U;mx$C z>31sEAqb2mz6S0-x*#q+8ynwAM!f1Nn?PN94W#X zaRSPuIuAcq^nlyCf50n=&h$C16i(Nyg%4Azk-At6Vd0CZdtHjR>KEa1jX-o~$N}FC zu|ePUXR@k3w$M7E^{DH=VlpK*9(jBo279;m)3a;Wz<0kMQnR-+(9EDRl<+#5ZhLhR ztv~&deB^r)%}CY3yfSmND60-$_v!>!=9+`s-gQXwi5qt4NkSTTqQI|z$!Ps?4X9%2 zhE(8sNN=#DLl?lQ66SBPf5y|P?3EN&FqlOe(tNDcs6bb=c9NGj-v(Xo_vrnu(%ALk z2$KJP6n&bzoea6|jjexGfLRLyNLgboRIj`j>X}Y}Q{fV<_%adsG^T_;SUt6F?eZd( zYwlpztyB8WfgHSZ#WHOB(~R}d_cyravf@!-W-QaPP6LNF>MoxL@ zQOJq6)befqQ(lqd@bUCa=(%hY`tK6J*SF6?m8uld8j1!cPF0k7>ql_vUKG=%(VK~? zm%;~!BuJspY*;qaif&RQU}V%xRIqs-bHSql`tNQIyj_@2k(Z3%s|hYV;<67ocf6td zzD+r(%H+uL+s#b90)SM+PK187Jo2`20;Zm_P``K+wQ}uDIA=`*b7X3do0~TunC#?} zF{@RPW~n3^9{Ec?JRT0yQ%?Y|2VrPio``gL+zI+NikUjYy`VIF6`f<*Kwk9vPFRz$$RU6gLcMUuD2kr?H%P&LDwdi3WC^fzXqh#L|(aN-O3X^9U^o{EvRp4kkx z7d{5Xm*2vuivN(;Ve6@xZ3+DLx{+D5tbt*DH5y z=+LA2RAHD7si9UzXALM2Gg{w(yO9E7YvK%g%T`w^I(CRDEl35PeI_wF_o= zUIxbMl9bFq8hExwhH3vFO&oKipq$k~DsDz0c+hZ@3=Q*w8{XfCgI-e1&DY=1+OkLB zp1@yJRh%z8`-%fCetXfvtPpUaA_XWO>!%icS0E(Cf8dd-XN09f2UPgoM;C5X0M9K< z$n@o!P~P`7UHS6?@XS&GD)KXF;m+l-%jzb~yM6*3PYZ*eg^l39(A7xd@GtUSpc7m- z_Kq3*FAsb^qDb3~%TaFcW9jaLGf2(kAdqBv3Vb+SP6pA>K*l{)igENZSYT)bjdMn5 zkDYJnuNyv7m;QNBwiiEwpndT$UZEV=tZJmDGjD^}-3w@Yb}YEr&Z6xqSCR894m11Q zAjnv+4Ch{iaI(sd3B#YkBj;a{^chKlcSM!Wc9EsMaNpAwvtV9BtMsEZ=?mmN7KC9s; zhgFE9X-LbcT>=JWVPxC)Wso`b?@6P_;p(OCQytK<#2*JIC^iE0<%Ai`&+DZD-#(Jw zQ1lWoqfY?mo)#AG%wFSt$@;kN3bvrLExCp$&Ki>3{@*QFM9wSvYIXS;BL1CAmpD7tLHTPOp>SjqE-^(6jVC zl22cU4_%v@bvEvXsd>MV!?p-85dR*zZEHsRUfaXC%|q}cTM5ON`+zyZOXT%}C_D*| zP`eG+;TQ8$;ioHnn0mpGo;6;MVodhHv;QTc)>T{>^)wA!L58@^+yVc&u7^r4OvCn1 zozcf5y}0{HB)z_GN>?88Cr5(kprd=c>5r~bwDIEiAh{xgqCNh=!^U1{%Em1F`^u>V%eBB(;@3LYrRHcmk z_q+hr8kLk*_dmk%W(ic^6Nfba6rumtHWAkfgR!sCF4|>51nH!c0M_*+(xr#4p~3D# z#G5;{Y`zJ|rBR;v*u7k^vK^9fn$n1NGl1?n;h<=L9o`ofPrg5;LG9FurI$1VvS>*O z-W%`~l8L^U6QqG#q{i_Qozq}dcn}&fmY_WsHlsKt1`1dgf}5tj#&`Hdq~6gUbf!}P z-s_|hft}&ddaDd%sqIHk-HPG5)&G!Uq%_pOvkh_8dJIa?tVRXg zmTq8I{#8jK+W8spAok>Ho47L13~x1557*ncKe- zTFaH0bgB*|&mXZA?6U??yT8~+9BTjo#(TchZgHv@^O#u2bP zA(Ou5{y&D!!yn2&fa8d4%8Dqm?(SLN^*mIBk|sq%NsH2;LZzaT$V`Y5l9HW-l-*C1 zA|#d4&`=uMyOjFfKXCWDd%f=Ye(y8hA33~2G6%2kD5Y<{N{53h7O-P(snaP=vaok{ z1jw%Igs1$*!z-R2;p4A?z{mM03ir)ps#a`Z*Ew8)@_Wsgi@(a?;VdnBZDAOkX0FA~ zZhQbPC|-wmzRy9oKW>3$>)O}=ha+sO_ePPS(tXLBiBm*4V9+vV=K*SW@-Xo|8&9@S z6h!OZ@1SabSFsxtj)^jdPnR6YYob1GS|slM63>QNU1Fy6ZlE7=@yv2fZF=Fi3C!uW zhb{H$47uAAXmR|U6xNJ;PtSW>LH}q{ryqh+CTE(hq<@z@Yq`r^;+eNle0AhIcKzEf z+Tc+Ib?8V9MJCN;A?L^K`_Lr`Wfa*7W?3Tnf+YI%*~KTjb%yVfizn>^T&S@v-&V`XVz28@!M(Um8}VzUlGRKRhVIE+OUBgE#oA5dH$f~ z&!d1E7)TPeGeztMoz=|DX}=`jAC44Ho-vIBv-9a=w;M%%HL=u_jaTXCMjORC9s%6k zFf}pjyF*k~v`zHe>X+!r4u39Mqfj!iSHc|#%w!eR{JGt>Nn+(L74{+cZJ9s9kd@gt zhU$5Fg-ylz+&(!q@srL^jH|;@vGd0nmaX5GOWyvRLp9!B$ZqI(EYVx?lK!q7&aA6W zWyf9?Nzp>-l1AADY*p_xvDY|7)~$K6sAEkTb30aB()QvfEuOki`ns8nsJ5A1Gu+XU*9r673t^J?-A_entxqi%I87BRBz0QMO|zFg($A9o`n1PV5}7MG`{R#g z&e)TZ3n5s!t zpLrr#@4i>ExFgaW>19z(p53CkhLPs=rE>HD%##!4 zJ=tsSr}~L{SUpa%ET)Ls_Q##t6KPMYefTP>bSsktFP>;AGkX*jxHC)A=zWfQ^vHq^ z-~ZTr>X)(9Sc73=3EyV6g>4q^m@rp7ZCr(9iA|t{oU@|z7utyL9zISr$ZWUFKHDPF zSbkbk_4lWF?%O`eT}hwCqDMXwJ}f~TW}6~@|GGrt;0&n`Gk`>I@GHL7kPG!*BvU=g zaZqn;6|FVv2>otWH`lyMf$`k80S(*h0T)=MvR`VuQO+&EZ0fRMu3s-=#q0dIoMV0X zitRzrrx(WFpPvBN+r)yOTjIbGtWB5cyOAxXY0NQOGxYoXL)3Px4Zi3L=K6aY0K>O2 z-$Ngv7M&pYYXCjhPpKOVMK{Y*;1pVXFn1HN^<-tvkr9ns*At zRxM|ZCKa*IWumZ3N(VJ zcHG}{7HF@11h4%3%pR8BkEfO{#9;>$m=vP~cNl>>(P7%=RnSUdzL@S_#^}tIBaP8*w8gp_X3YNOjNeVfgeZ99iI(8qP-9<{(ba6=$JGZV9(*=2y1qYZQrmB?s`0D)cmG z4Sbo|3O{BYWRlmNK^Z3)wrK7;bj|V_3Ozmu#Wh1{QHwT-?rnet^&_$1@(-y6y&=z5 zKVvV%E0SXiRk>gH1$1g-CR`Hh1u~P?Ab!DbW^{=<9)0RJx2Zaw8BB;o&G|BLjIS~N zt#AY_R~}-lO`gF;@w1pkn@i{`74r}?=NG;<_c7QOsf|vpG{aGEA<`(?&z3K_32nR7 z*@kgVjIq)rmE2_b|4NBNbCkzB` zb77a%_@RHn{*0Z$BKE0i5)QMKW6D3xL;5on$g1nh*&&@TfD;^`@kmc5Z=)M|ag~Ah zWD-d`V~)+h1=3P+8@8-^567Cdv3Ivw5IngWt9{-_vM1CN8RrpP;jjm&^Z;geBqTC& z&u#*LY81%beGT;_<>L!ZQ?b5X92`~WOMF9af~(_dxcicsxXJA-8*SZ8p6IkBL-;ocn-OD-$oyMJCeE1`a|HA2SBk;x<^~5PS9cj(2g{BRiMBTC%Np94# zJAS^yPv<6bY4;0wc{f+?>eV^;E&qo-p16=~oG}9|)9u8^G_^U06|bN}b2BnUaFb;c+-v=Y>;Ap~*A-g;Wv2#qitZEmUsn<96Lv|1egBGBaWdptl|YTq!&F8J$mJZR?UkgKNkKa+N)wv=9S^#NzPR= zYkdORe)a@x`Ede9_7!qYKCjq>PXkyuP)rtN?&i#2PoKy6f-5;yVz1d{PU0T%uLOnObT~B-Y?ZcOGTaI64 zzgy=)qN~6S6zlQrZ5=o`Hh>SDpGM9H&*Z;`3?OxK9Xl= zaNqft^=xk@n@tWugVu-aiSSSO#oHp>_sNumFaHD09~LA#A9~pBygUjEvmM@azr8u+|HD?K?;YoP>Re50+Y{A=&Lxt9^U&0f2GvH)Dod0jyK_Pokjhw5B7gYR~ z3hhz%NporvFE=%VZyGU#vs{P4YYDW~7h|ap74cH&Q^Wkx#ASTWtaGS9Z;H^Bpuh({ z7YRFKP55)OB!pd8BXo`L7b?$}^D{;y3tfF5dA-@eRuiX=#EXplh3#Yhg7SgOykI3F zZ`_rz-0CAF@4OjO*_*=e+Vhj2S9e9~A;}0D_W+Itzxd`Y8-yu`ck%7@s=Sd{pM1O- zj4#BQ2nxzsLZVwIKmO+vJh}ZbZ{4|q==+@DM}s^vZ?P{D9ZUv_S7-8??&-WP+6u-q_m= zp2iE-Q&PxI@fTss!t?0kA0vYOh6``j+QS*!kg#zVKx9@4zir+la^Ou55m(3yvG!5I z*JUw$UtB7$cWyVayYPWKFm*n;b)}kJD5+%^Uy$(QBoDcdb3KWQqA@tM*P35WpXSZ4 zUtsTl$-%0zOZW>@vQec}N4(~|o(%rWgDnakGTROCBf9^jAq7NgVo0w1_0k-YjY z7HoYs!L}HEzWsA8H*`RWBvh#ddCeXrkRP@M*}8cu~{%8mE&ePTGI&2#Fw83q<(+H4o&z^(D$Z zHwMfyo5GEas~uam+uhMzRboD*dC^7Y$#;esRu&V9Wy{$ccyyg`{w8_amjAx*X`9Jr1i?JmtUj9On|pG{THTbF`9}bCQHYUQ+)Q z&7N4mKl4!Jr)*LeriVR1#r+;+(zYN7Z1njDlG9|^*)IN`0TH}b+~NA=vdF)dX3pDM zj(fSt2+OHkBi*;rBz{IbIThVcRMK2=sO(W*11CVgS(oAbzx&C9&Trgg=l$f<<|ka} z_HVd%(Icer;5fSGdXkJkro?MwOA`M4JChc5k3R85OR~f+m%e-6+R}lYDLQ;=CewQ$ zK{Ccfo{2WRDk)Ij%@}<9!8}SawOl$;f!^S8keR-C1hvB|o|(3N2^0UThf4NJq>)}a zUApj(#OgnZsN8^J^PA+v_x|)V_h&$QZ`lfZifx7X-wFq2Nu@k3Q!Qe)|1hV2x{Il! zf1sUecCa9Pgd}?1CPpRok0rIMnb!MZO3CaPD=C%Bp!#f0 z#rLg~=}Yb3>4onui#N;4Fk9Lsk^}ZX=*;iFOhao3J!_OQEvy_xE!?_IqW097$-bV+ z#4hTf#p54KTK7Mqv+S2q^$)Y?Jh>d|eC0Z^*PdicJ&WnI8<8;IwdXLSnwD737b~(y zeHA1DB|4(ECl(a#Zzvh3>&Z+^U>OCYI$G&)yQRyRpG>m3gi`Wsx74Ce)7OK`skjvm zRJNWoJGoa&bgu8Ec*o7jl9#x}a!uR>cGi&)TJ@2^P+@9cY;+O5i7&69r8&^+@4>h&Vq~MvFGT!ugGpanyzzWX((;;5cv* zA1rf__KsDgnbQau@GBPFANK=}ovzMS&|i?w25Eoz#RSgdy#s#NdI;o{O~vufN!Z=u zB-(dE9zD$tg#MCp@cdUK9+&+9kNtN9$tCdcsDXfsgoDtna5`#KkU{gm)^NM8d}4Hu z9Y!@JQTW}xQ+VdSGA4V`1hRSGVi2j}&qkMrL+2x*Ow8SLc*^lvcsKfu&P7t}(9~&U z!GS3Fq1cT5;--SB`TIZ@a}*vA$tSM|wz2j}GeO0N6CmB%jHR!plMgmFD5_x|F+Z+E zqRrlrOJfeh^pi`lqt`QT;>kLERCg*aUAvZOUFqirUM)XW2w-4!o@$%_XEodQ5IhMulYKg~IC_tS-xP8w-??dkNv63|ORZTMGaoKocun_7Ji$V#x8wO=Dib(Z z1~$3sv6Cy~!7^_-xTd$23m@^9lkq#v{uyq}&RB8=xP0-4OLrduV~?F>cQ4-q_!E$e zaSi|-QXJZ_N-Jhn+%(E@GzG-J6rs`2aWH4hIBMCEOAy_@&zQ>Gq0TNDVC_|VnY8pV zP{#i+aBVy)^`ZAslOuHDTG``_`;rK%pWOqvvaOu5NQ1LD^8-%0dW8CMYZzN-%d#^^ z%%ZMM$$^VyZ9&i5Vz_N9gpMiZ$adT)F574}aQx}cj5}-s2OO_~$c?QqLT5bk8vTJX zw?=TApv#3$d@32Zd7c|-xu5g!I|6P_I}ZGBO@XC_^SOrD9O&3y#~dI3k^OPz2ypNF zM@4r=g3;TDGb=A01nVxI=3Kq9Ip31g;1oRp7G{V5zW){OSn>rryWilz@)JOR(pzfZ zg%)N9yB2M!bYl)y1aa_M8hzuV3;s7a3#DLyLqmS;xc&S-y3zR}7~Xvr>DeTL zw)YrR>@R=|l)rL@vxaEJf@5&lD$JA(F2#<+o-oeeesE9YvS_2kUr1BY0~#SmVD(Xf z&GwlIax3<;OHFHWbJtDSNL28wJ~iN_aTU!|I>YK#Eo7~1XnIw_DU`TY6_SAm%+b6K zu2XmcE#TGfVb`S;N~PDe9C2b;Lq1(Ug@kByN+ z|6Y8l;VybKR7~&ds)6?kUxSOk98q1O5xX(O9SlppM;WZMWB(XXC~rb6s;PZJFHOzH zw@=70(K3Mj5cG+P+-5~7?v;mr!{zYAVR@*t%YfREY06suZKQYW^-*`nGwhWpFV0dS z4rIE<;9;j#=&=#^s4!U_ratrOR*Wq+po*~nBW0*&xF^uK*JZx}g9Q3dbKsu`tt6bNDXSJA+?v7+yE5s48-&D!o z`=#K>xAACHcQ3yE{Vr6iZRff*9-)MQldQXr9t(cHK=R?T+|cFm+|ht)FgC;$*L79m#ak|*>4UM%aHT@%Qzzy+ zo8y?_F)rZZ>Un5Etv)adTS9!+^f9(^o4}f5F<^K7S|&I&8y9ZW!Giq~{1Z&Z8nQNI z@fr<~_OAjySW?Pp=rkeAKY_?G-jFyS$tQI&R;0l83vn9VqTlNAfHF0;L;VU zXq%oC6mmz7{MhUaZMTbXS*-$)gj|C&lbqS~Zw_qmh#atWYa@ruIw3ZULQ^h9bNQV{ zC}_ngeD~H_xMmw|6*pT?_+2&|dyRg@k5LW<8{fsljs5Y$?7Ay>b-I<{QLjw0#+3@S zPiZUfn3bSs(Re<(s8v{%G?UCuY!cL)jtH~X=<(~VuJSHlZt+#!EIHG#5rzhBuyP2t zLN3n6Rxw6Fe3DNlkIa6e?vs&%Ta7gjM83k78Eg5qP3y>Qvwy)+%PRHx}^90$K9EAPKg09h8qR4pTsHSdmy>=zKAJE3P4N=0UR3#i@i-aca zEm*Xk7AB;h6ktaQUwhPnAF;`e#4Df1MxjdujZyc7?Ef?byNiY-@{@t!Jd{p)J09}7 zNzcgUsoBWGsSOw^?C0;!_Y?BgCJNmrj{vaT#wusWM6B-S3=^|_h~_PKEZcWPXnN@{ zgu2TKvpUovxkOw2H`lfd%Y%GWd@d8X}#M7OLi3t zaXSx?Een@`CTc#ffI7+5$@apb%AdS?bEDu{dyUkTh^=Oa4x*xai^#l3VyGe;JAZKFMWx+D@XIUm29DZ{RqTOdC!&~wjjp4GvICOHs*JREl9pJ z8xFM?;+k5TUv%#a)J@4CZ|u{7*Rd!vuiTq2p0<}HXkW#t&sL+N2pZMxm_weF81fsP zZ;^}JrQN{S7qP}H8T@$4dGhN>2>v>MDmQLQ2)kW13}24jBdsL#;8)(M?6&kqe(wFJ zEJ(}aTC2aaCPz0T-%=44nXr6eQ9RMNT+YV6*XG@uwQ%c=bf)2_9{5_QK|G{Kr{?)8 zUi=Yq@{`^(E6*q}k48Fk4o8;pv{f=$knBcO`$zGeL8^j6O%p5$^&@h>FS90aEBfAj z8dKnXO*Xz3Cn=*SszY3DDXTB?OKC zh?frJfR?TuC3oDhrM5}W1Mo_5|D}*drO7gnxz|IzJe!|8D zaZbb1^oJ&$q(?TBJ@eHKH;rJo}~;S$(%8SryLCL!%v>v&o1FT``Z z7g4=^guixcr!dLYmtU>@7hPGU2G*^A#OC;AfDg~BsDXd3bnv_+*gsd9&N*Mp=vato zk0L1x4&%DTP<$P0;eCa>*K`bRV>x=V zG+Pz`4@PD_}bx_jA#s;g|v$5_}o)CY4tM>07#CNPs$Y9Uno zm&FqWy2_}U$=kYzmg~)>|4HxF=?#xT&)&E2RE-OL@JB4tG}}p^j5DQ2SGuut4!ois zZZ|`1#g~EG$|?{lno1|D1u@odt!RBkciMYN5jT68BW3(^1)DO1#ajoG=;urHnWbB| zGxlW>^aOh`eEa1o`^B>j@sst@aHr?UUR#eVFt>$_cN7iMr1#hGaJWRr7Aq$2!PX~T z82|g%;PSKCbVtE7`srVLc=u}#_k3SC^eoc^j_zGB$T6E*D)B(2e*5V?;vPzEWD@t| zKP9HmxEr*eb)&CWsen7dm2|;~AGEKo2V?^s&>vwwm{(bhMm6O?)80N7+ZjpEu3_|% zIXcYf=pGobP|O*KTOo7t2P8#DVZ!nmTA&#{qRDt znJk0t#1}?Z)N)$-X3V&Wa=2t&AJhLV8;v}r0PlGsXmc=z)zy+m_q|(ydbbP;vUmix zeUSm7!BX!gC>Q0<4}v1-fxdg!!nyefpZLY>ob#bs=o?OScNr`<8V?Qya%|2%H~RCb-(Y3d4VW#>W^8iQrthm>K)E)z z*qLGN^!6{mx#`Jo*z3V#P{$}GB)OUd3oMiAGu{`GSS$<1d8E=OlOtj2@<{Ohp*r|9 zRvUMHAD|=O#4_!7wy_UnlIg$tsyOfYTI4@>b$+ZcfuAk? z-?P=zKuBiq5t{}@VfNWRGJmT&q2?SCmY0_aGi8!^r*|8Ku#cDd6=$beZ8-K8HSe4v zWWMVF?wN_a^Zfa^>RAxF!)_v(cNI`e)h2%Vv}=5a@=0_jq>Cq6Bk&*oJg+#-Uiec# zn;(oUAcvHH;Q4oF<1Ll4!e19JVU=q(KZmZuDlgCT-(q#i+8N>e`jPX9{?KHky}%co zTW`)!KRv{!#TW^>x(xWD&?ETj_adcBZ-HHjB9Z+xgsy2I!K_79c=#%vUm^WY_Y7|n zj;~N5mnY=`>$L~?46}n|rlk={^0ctJng14aH#~y(e+*W{a1)$rPCJVJ2>-kq>o(aJV=333S)P#$h9fZlhEJ>rmKW=L1 zJK}=2lIwq;@`ruH`G0Sh345skvZP3%dyk*=+Cy-;vy89LvWAaxCV|S)k<66ap`bvT4Y*a^Noed!g@V;z=6CtTzrHynh!MiFM|rqMvN%mRXQp4^;gUaSz;%AuR@nL-P5 zig&&NXuSgJ>VkC0jMZWPQVY40HWQfCyZTVI>H}w(_?5dDxtF_{JixS%iv%N^8=zTy zHVD>Mf=zvnJj3i&ILi4 zCz$H)3gD^6)6b5_fZXxgaNzDU4tjmy&XgrEcUrzMnfK-ci)k4!(DfXs$@)ZhyzJ$S zUpRBw8{$DLn8I!SwuUjda#zyz?(?fS*oFg1nht{3zVey zJ7a3#-Z;29T;MFmoRh3-Ud*j17Pu?Qs+`Vdsb`tA88$g*urt5B15wsnn6sM7oPn_# zo7;AiY8I}uqwq*3?Bggfa%3xK5~a*(Ew{dPIV( zM?N{{zm#ur_vK$IUBo?k!{GNja#rEeKGrw0GT}_NB7b8l%WH742z6)+7ss}dBd27A zdQ%yGSB?yE(L5m3R+I{Zd^E3>u~Jy!UCp2Hv9sEH;~_ecZ7ob)-3a)MG@jO%A(A_T zXy2v{By0Omc+$*^KVf)*Pf|L9f_`1%udP$Wd9fGx@OC1!aSr^-h211KEAvn zn!N1RCJ%obT5Wj$1T-9}Lg_7fxN>_s_;^Cy%3s!j&$hoJ?4B1UxEHUqdYGq9RR7)J zcZ^(#J0IjR67C+MC|Ep~M`rO6yozNJSw5IcG?Ux-Q6FXt z;r?^^3L`TdE<}U)7=0?$=P;Nv*g-kjG*Nx>ZNR4F7+u~az=fCHz^gH&I0|Fx4BEvxeU`Bg-`z&WHnDfHfQ5U zXzKhG+&U1%TAvPM`pxZ`QyKlRf4T*1Tp`b4(Q)Kg?+t5iuVx&#t%C|o42qI6gI)cX zQENX+v(L{JnA|zaY}ls#^i?Aft-j?Q7#&nepUOW9OWry$A3G<}O)F-B?JLKC(&?)3 zi<$;F_cDV%dnlDYSDDZFY<*3cocjd>E=&VwGBKLgT zbY?{28M@lQpUb?w6l{|Md9nvSOM*U(;mSKrfM3Hf`hD+xus%PY?)@ns|MrheO}7d& z?vFg9k;LNkYDIv}RG1m^F=(@bH9hf23)|j%0CmOvp?xgYGVcq%us^)|=yz-Nuzzp~ zJ$P*b?tQ-oc{_#S-T_5$De^V?SfmKPe+)$J>xZGIsU_(9#!?g-`HDGpUYao{y38x@ zLh4sX1JfOlO6Q?!6#qaEx^$H@KL05*c4OyYO8dQ}SrO8jg^fsYT`fJ-LE&kI5wz<0 zCZPJDo!+=NoI99z1r^&hgE8sl(5ucwsL)d2_vVjBSGEG3R-%t(hWwHhQ~5!yP_kh`3$9GD!EP5~(8%LXywS59DO*f|oRn9? z?~ZEn*}1`Z@}YiQ>vjd-Dmw#qkN=O`%&a4Fm*?`YvZHwur&z98O-1NRwnW+?B?zB&kO2?)9~~#njhF#3L6{`@~y7=yr0qp z!FO?iuw~B_Aa3;MzezhKpu&xNJH>{SE{Vq@ceA|nuGi%Lwe@^rNfqu-GZ4<7dIBF6 zry%({5&zF85ZsSk#vhim0Bvi}lgq*G_;%=f9PreVpVb!6KY3V8u9h?rrAP}Bue%L= zvpR{)!>rliY0BV+PCov7PKsAGR3+h39#Goj)5N*v4Vk3Lv*ICLeDkUgk=^eAlker@ zwEZl3H^v=Zwg{2Fw>BBw?uzsmhO;?K=ab+kcAV=rQ~r(3Agp;3hC-RiV9V%(c!c~g z5M${>@|D#{_sZYOEgEW@DQnojTUYQ=pbZHF=4ZRLGe;$pz=8WX5j!k17K0}=ABqF(^uHmlk zo@k$F<#5IiK1D00sXy;Y7+QFKb_PfG^fwNePHZ5#?$_u+ae1p$)Dx$u{ z#pKAJ7fAiT>r&RW1zW2A86LP(i3aQ=I1Sn9_!DM0t4sHB^3GGpX7_xoXHkeB+^rp zy|pFKm5R+OW&YdLsH_q8xQYcr2!q zAR4TLZLu0$;h0P$+dLmeNqY*F#__N%I0|@3d3=KN1RUI}fikq-pjMly$WXZz9}HW= z)gHKn=G>jhFk8)0!_#DN=voTr%lrgsqr=&+Q$IqVA5Mt>Wz0>R=7QqRWpVeNW}=hq z1=P5s6;9Z+0lwZ52yX1@;Ew(cLq8*Aq~H?~a;O~-X74~~VpKKQ$jG7%j}+nP##*-H z<2yRhD-Ygu*pEtTiqMSaGFroP3BIebf-AeSg;_4Y4_vk1&gu7+BhmXf6h3M!dZb{< ze3JI>cC3y9&GlwXEI6a8EChMk{Phm1GOKsGbIFnD+!EANVD9HLqgNX`L0*}Lcs z4Z$$pa}b37T8f(G^%2nRLwVQVfr^yr*l?r?x6ybf&>-$8kV<3xnFFZwZaiz3qlPl> z5a^hX;qQ76H16gd1P1RxM#`kTDrFk!=qA$Fj{ae%XFR8xQuazr_WkBsP3@S|6|doy z9-8UQ-G$=%wjpGqLo3JGv$A(H(0@}>n1+~HK(r_fR$Cf_%f7eSE2U#$Q|fA{xzC0E z8IT5Knr1Ru{m)QHdlFd{Wa`0pT+E^92dB0WgC5~aye>O*N4?A2HXV2Wz6Df z6VTt$CzxqNW+0io;F6> z#SEaw=KO$$Gk{xwU7&VVMAwwPZDyu6Yxg&6|r%B(hkemdED@e^BS- zz970_8FP476no*tdA!$JAB8C$L#w+aOo-`dVlos#npk7nv+V*J{IQF;QvaBMvpFE) zNj!NPSB~CIKg4whUI*ow_gQ6oOLkAzVz~SGQFc>L0U2>di@V&@#ORLQ&fL6|Kqh`X zgexC!1a1MN8bsAWX%mBB>xFOYAnuwkOSWsJm7m7RS=Rwo)yv?gfPop`Wt!0ZZ_IlI2 zI1U&jKS8HAC6Q5yGl<8<$IM;3Hkj6LfPQ~7Cc1?up;<^C$P; zW1CLcV|VH&yRtNe6x=LhLRw3}GmBWxPTCy}l=4<&+umVeQ6Ks$Dnh}V!-?3n9bT#e zpi}D`v*u9&8u3KhYqHA3?o~(0;p0D;l|Q}60h3<6;g}hMtMUsLWaK(Y+Bm>Hkj{Ycqn&KEZ zL%OqZ;-E6;x#JGz3INhmrJ(7h0yH)ff{$%kSjlrZQLXI;iQ`p?Ww$jvE;V=6A5n}Wyo*mQ$#V~F`nQ58K&EQ#kDpruJ!i{X)LoMEQ#7Ow$*H|vDj7Lw^C9t@DBiXUmmV}qK;%z^A*@^Os ze1mk}9;f%RF>CAa@X?Lvv7H+VNngg_@G|E7ZGV9mQ|H09hFCmI9a8i&3zUh%$oLvr;+Z*$U!k#|S1p>ztyYa9S3Q>_ok*IsJ7K>E=IfE-kr(m2o+HF^cNSWAY#5(v@E@3CFF`lpNV2qK4p*t_K=PDrfn9nHj{N%` zEh~G8t_Nw74JAp$mPx@LdW{HP^nvdlhO;4d3*g_2LsZ?dF6u+t894HS6}Nm;67=|% z#aVn?1b?_U5>)6PubJYq3Cb_;>m$2{2C)9UHC zOcm_xQp4=IHv`Rg(t!b6M?-tXM7CqaZKx^V3H-fPkdO9PP^O>HbzKcdn&mUmF5k^C zs7VpF=v;xtsscXvcR$k`G9Q)ZcF-f<%Ro_b2se~6ik)j}3Wja@!Z@B3!#~$b;pX+e zY$_-M5#waJ4U0)-I=vS`@4d>LB!`X6dm zAI3ar8-iP(h(Y2qgJ_jn1Lcb+YDfAuQ9I%L; zdi^k$;+#b8n76}I9?B$MFB+DopCuK$jrmOLCG7cwHaPG^8+mZj1&vyDnRxadAiD;y zqOk63_*Tyo{O2b|b_1SV)0yRb^?V+jJ88iCeVvE5x+LMGb?3mPyQ|4AB^$i__hgbP zT7!p`Z$#?j&ytOw4fto=FMM@mCz1VSN+K?m@S!(nLHDFQa_+AoCu{fz8|ek0{Z;E= zQ(_NdZ>^b5> zivPPwPCZm6J>Dj$G|G(V_#H)Z*Y4t~Q#ok$`%|Fbu#;6uj>k?bSCHW|4w7ECR8}R7 z;x~dx@Zo<8I1k=&ehgP2y^c!U(&k~jx%dN|v{#)ASNMt}f4)Pe zm!i=#>kwY&Rumk5LPG;0^OZAj@1|(r=9+;t74;So-kmkUyV~?O!M02DsGw;hKWOiXU zIk|l_niNTq0j(tb=-NbJrI~`c8HbRQiW`{zREFEl=aYKpmz@8tPdFonM)e*k=$m{p z<2xb^AMd&hg>ML>?h#lvU<7I$J_^5@nnGqNUq@puKfy-%%W-O!0)OSe4{o!K1IZ~| z$#xrU!FQaeA*XFK;rDmYT z;*Vjs2NELl=qXd>;Y7Oj8^CYz=NP4zuBd#(9VTXNhm`xZ2uEj`Aj7#%taN1r>ttp# zDhn60=O1xHVguGYAe&Zk0E*0Pta&7AGjdMhZ}63!9FvKp&koH?B1Fp(bj+qVukK{_O*@zE&FB*d-$(49icbC zF1hQ&jgd(ejasmcd3Jv|*KHV0Gh#We@831n%V;L^!bO2?J)zF}GwWy^a$GFyn#Fzg z-6|RQuz<7I&SkFL=whZ{wV?K0Jj;ID7sM?8p2_Z=c$AsA>nOcAhT=wVTfo&unX!AC z6gl^iE7-J&FF1qEk<>Q&5v$y|Uff+Xp53|cC{6E3qu#vJVE#j?k}jgeY8+cF?Oj_@ zV_$Dz;|g-AwGKXP)~b7KpZhE3;_SVQ+spm5Ptgl%!u%9==ceR0yS!6eDi;N~iDa zPNY7G+t?X1POvW;IhH;(NxUuAha2$9q!W+YiVGb~*c?T3W^vnDspM79)eJ?88D<3~ zs;Z=hCr=Rj;9_p8_!YA**Ppw=8gf|=6~PkkVtV|UUF@|WMJhDq9;>gik~MeP%SGG1 z;|#lwi&b{^vsqdf=zF~fMH7}CV0>Fun99&Stfz^H{Szn4ojdJn78bJ~y2iws;#GlK7o%ZX0AC7YA@x7S3m{d`O@s znwYY$51bXfzS%6k zQR0~1+pPPT`HXUdD(lpx!>;?im9Fv67jOBI$C0`{lEfd3^TD4sEYj-xorR31-O$f&suHfb#q}kmO8r-~w^{m#g&s@){c*&Wzu5d42Cx}1qUqfwk|Bu@GWQw@m{u~#1^9z%^Xcw2+Y|33K z)Byc$6?A3IKGwllgR1-WoW-5%+0y1{Zi3w}&Y`eC91`%6z0`Px&h$$c-5hp^p&Ldr zi+4w{9lu%DMkM8#i!>OM6B{^io}>089-*&4-pig6*NBgwE@lfK6iTjO5qmwtojEw* z#&o_5W6f{La4+dx*yIc zV6-AXbZ$4VxaB14e{mmHGak)HyK*RSuRNdD^q5%MEyp2Y@QWRy}UB~&ufP&7oTtTbs)k)M9&PdMj2pZ7e^_j}*hwe}>j z86Aq-OU|OCH&du!nlHVpN{PPVcpCjLfNa^*Pj|gO3>&9DB5#(3^Mz|2NK9S%V(ZP5a9QEvr8UOr^Wo;F0znUWfN3mmrZGq^iEhJVv@5BFA_BfNyKxo~?AS2H4p zRDpU1mcF1+ZWitQt0n|{UOP!vara!*)aXRa2vD=>6 z^m)Y@RFgN8CcRank*8B}J(^8o%T$S-s2tH1S9$AAeRRdQbwH*oibf{>z~{dklBxNd z;fZ<$nt%E-4&M8L+^v0q`+DD^Wo5hRW6NwB;E8U>{5GAmY0EPw~z8qv=l z$9daX2gyL;8+3AaH*8+yfnBR#g6)51k{OqZ$hC)oFy%@-xpwsjobDv?$_1Oz2gNKg za<9Q|IW0(LSv`E<+e^%)Jn1*vM3S@V7@9PFBe8DL!9VLfN&1GB_~ki0xaH+63FG-W z?iKfv7DE*psH4gY>nka^a2`5(-{DPSJCWwER#M(W~(br1QFS-J33+-Ov39nZTh9HxH85$Xu>9c@bfobTNefp1_n!Ypmd1Spvt^>mO}As%Z|!01 ze(pN4zDeozInzmrY!xY9ehROA(G5DqyYS-p(OkIuI9?%o9GSmiDGVKV7Z=Vt2G1X# zPL%Iek?Jdd*fY=Xp}WB=$S~IdkDc%!Z>Lz0OCwLA6TzN%=dAVESGE?G7)v}yQ)Otm z=N-OaxP<8ZP{5IrW5G$?gJ8jov1F0@J><1hiWq+!LN?c>ko2oKVzaS?Xtze;0+BbF zyQLi4F0!F+|Jo%x3`?@kp_WT`NyVcA24U^vAE2kyAE`L~;g7xc!WPf3VRHQ_P%3uWhmQf@X9*?j7uVFcnTX`4dYC0?9pk9JAjFq3WzcyfR#fHdt@P zPWM94I3)~D+Ie%E59#0svC^dQp#gFAx8Nps-6wtljo{;nR~#(=4@NhA0-w%VkZm{Q z$iCHyxcX2g*Va%){w$Y9#%`J1?wb+V^Y#H`CE;u3nd?)X+HS7Is}z8I4fxb5jl&<5 z>BcHsyu17sk$SL~+@0i2@pxr)uHhj*8|VdgFQ?@5`^z|IPb*0qo=F=|%klv?r;>Zy z^^s=WH}*1mkHV5yqx81NSnb9E>d#Qyrx9;|GluUm8A1H2 zzSXRmgpDbqdJPZy zs6o|v;n;gsGw5`dC9`|N$jsba_T795KkSVKdD*%PJ}glnhYmf(m3j`yTSEps$DnsjEr2t=tTHI_H#qGE<31`+Hg12)If~kWVC`I-xUt~TO z6ZufQvv)R_czQoJty&0z|L(vt69;hO%?{*tZ7F(qA|2L!`vw-;7Gs|$9En=I0Pn>f zus3uS)?HWuWvnOQ@XkMQVYMXxpR2(=`Cf$-n$F?!Igju)+b?YX#{_ce!$fd-Vlvlg zk_+D^<^Yd>ukmK44nI6N3t!c9;l{t@$;4;#;i@$&xozQ6I9ErEEZ>yC$+KF>gwMyh zU&l;A_osMJWB|DAzhz`^l02>+7ftfZbjZK{k@R(1B}5|@VRN?>zGPq|ITGiIPcKU( zFh-v4ufEI;3VU&haSN1MQq0zPCZMP)J(LhV4}TmSjn@Ymkx$y{Xv>5(Bx86Skafv` zlO(R6m-;Q-fn`gvrR7Qf9i52REq6wvZ!AUWTjpXJ=dtACg->Xs%RhSm?L*@3qlSjd zRuD~RD}GIu004mot@vRN9^`4!xwHjsRSTqwEACSHxfA)M)B#-4;!dw>DPo(!WGZdZ zMEV00vFDScWYzp5#N=%c^8Bd-N~TN_J81m|=VC9={Ns~Jkopf1-noBweC3DK5?BF)4GC7t?!=GUqxmc2qsaZ4lgXubB5-xXKa!R?2~GXlO>{%msF|H3(MvmqHl5MOLoc+@ z29>e2I?;xvq^F_%3hz*nV2Eru@Du%2T!I>hBk&S$8!+QxHa}TPO5%MRByUpPsNKZ5 zyjaqmcJdgBxP}B?Xu{$j3t4_4zmm?yl*%0=9lEsay;VjtXAsJ%;L!x=eIbm8s^7 zF#Nq&THJW&3M^)o;SHTpH2JV2Pzjqv3v`e2%}v|LT?oSS;}tjGaR}qEiXb zTZ7}9eXz&nQYPT~B{&dl#y%BBGajvecwOl@KHk?12X;H~a~))``tu|_eOVo|TX8DC z%)J$pty@7b>w-*Y8{*9`M{=>z<9NfaNN{fPWiI_6<%2%HM(MX?!Nwc*_|rRC=(M9B zRB!QMfrmamFXzb4_kWJ8U%lm*FTTi}HeH4z7J1>5ae8P~h!cu>osYD~&LwMtC~)S| zVb_Se%!qk6p|PY)ap8w|77e-sFnVYf8nu$A-i~p=}!o_c;xD|p=Y^zTe zzE+*gX^cC=R(*;BiB1RE9c>n@-Y9eO{rp6(W`;4>_h|#8Q|`#_NV-$v!4?kFFqwXr0ruZDy5k1&kGqTi!vr&T|;E8 zG1uaAuM^k(Okc2Y;z;h)(gjRoM-(H{Y!U30S;L-DFkm!t9odRovzgEv_M&pD=j@E1 zBe>l4j~J(hB3ApK3ad0FnLCpr5_a!OU>`5H8d2iE zK+a`=v)F$^O;~5=FWeRO$y~Z@DQB8+gz-_<<@9deVsE`K;%3KticAVjSo_c-!4|1l zHc3T|y|#A($JD2CgJsSZt(wW~>6@EHFM}j}D0eZVUwT1gNXD}|OP(^-=TEZ64~j%X z5{}U>>*s>@EGv<_ydgVps<%bn)p_i$!nuMqXYVol3}hMq=zpRKqYYWI{W$w`!wH6) zD`AYk`G{59Y`KEHQwftC%(d|IxYtp2#I?f|JeT;nAMJYsFOFYK3>|c6U-Dlr@A)oV zyXPNSn=%8tZaYE8$J(Rqv3;D+pJzniY>L?hub{=C9atTwCH_Si*wq$=HS*u%w>hQQ zHgcq77j+fQ*;mCY8ikS5W5J(cikx2joD}#wi+A1V;nThp zQneJs-x*Fsj{*+C|L*MshH{eJ$&$T%Y0)@hGqeZTf0p9s4?M@RH^Wf=?q9g`ye)PL zQRPP#pM;-2o#5?`Zvifzm^{@@BDZSQ;5S1n+%VRSY{_v)+CNmF?D!f;7ro=HlHGV~ zTNUi>WlsVoxKlPbjeC{<0w45TfFdT`7_#=m@yM*n#P@B0?;mm1Wm zO~PS#i7V%)jZ>uRo#S~Ymn7`=Zze?_vUua|Pr+AQ3$>F3yvgSjda*GCWxN_Co>6d= z9IX_JTPiHD$HrUao9_pxSQJQW)4xmZ-B+kpb3NUoF$t_~i9maTiumozkZjYJ&%iKi>L^IXXv>Ul5{KH1m9U%WVm27Kw`r#CQkezTZgP=5ql7ro$< zPp2V~x+?8e%anMl&SC34|LEChMEABYMk(xSoO(@%Pc4rHU;E#YPg$Q~R-P2~dOsB@ zOYNcGL$m1jn{K>>^h{)uF46#LHT>~H5gk>hOD_&}pk$kBBKJo?lMlG!`8$8`vvk$P z8cCgCr(OrOTPs8EC=cVRsoz1ZPC0pLq=mv%f07+5f1v-SCg7XL4${aAhw08eKXFq+ z4P9ubO~bm6iuGd;qO-;a=$EuQexs}`vDx(n>RG2jr5bY__eldR2&*8y3ngdNQA;5| zbroG(nU1CuP9%#w9ufRl2_Kh=LKa*o-tzb~%6XRL-{VPPcW;m zfUj_M7FT3SlZHPt#TvRB>9kZTp86pYa~8uAf64(E6K0I8+IhF>au|S>DwqS7g z5~PNToA@X8ugKEsHYC3Wl7K4{sPIV?)y{iMe80b@?IZppU$Yg#*^qBUUXJJ6rS<@A z>vZ}s@&US*-%1=8y@&fPj?sBWI^s%&$-G6X0;$Y9Pxs6_kCLyY)5@KzDW@KY@v?mK zb?OwNsXZ5qYWMOx&T5LA?=s-qn+E!%`X}zWaT4d%T7$UUDb!Ge$b*UlpMhQatxyW$MU!47fZGTQ9Qym>~tII*?S7Af5bUJ9~ z_2;B%-4MDM@rcNc%fY`iE|O*c1!K>x7>v|P;BBHNNZ8y<=soo?x-E1+A235*d`0aH zZ0ec^1}|Aj`pL`C@yuvykhho~zy6t=iSOoz(v#@O6)#}x7zHqYFoTTg@5M9TZ^oYH zGsLU1RKR}+$Dq-5NvLXk0-q@>5ZioDBEwD=V&ims`s3#=F}HpVPI2rY`dV|KP%`&f zG4z7$f1x3M=nyaVxPOta{JfpIl^@3M=GgLn0nzw{%@geT)}Ho1dqBF4OQ`tsPCWDX zH#%$IFl_f(j$L&1X?^r|FfU|0^-c+aO{2e)yOKL=bgvdUsG&wjg%#6G#Tqi&6w~~{ zfAIO{7#L<&jO$;0Vdq{y$SqEEA#K_b+|(thaFb0Z$ole-Hya-`agP+{Wi@Y^}k{$+u}k)MjGcJ?18jsbaO__QbeFX;%qHTo}~l!nQIS0?;AqbLqsjleZi9pI0P z=kfT|G308lCb^U&h0_Po=(XkC9k8C) z30EiUKiU(s1P7QhX8^A<$wke?2AoNaL|+{!JMD`s8zCQqYUeEF9(`5852lQPcWz!l z2i_jXIi@P?oqMO@q)0X7XfzL~|5%SZipo)&d?WmNwG;+P_${gR*ZKKdSF!%vD8cJx zx$~nV@QaAuXi3gdeyT!)A}PN9bcMQ2jWbf4KpH%DpOV>gXLPCTJTPTno5=2EpjY zrwDNT`ETUtr-sv;V$k2_e_+NJd#F>Z477aCqD8x(qT9c|1147rEIlGd_ieuccgc*w zMWX}KnV5q&g4xu$128n{DFR^+kfB*Q<9cO3*1!FRw;8Hq?04Vcr%&%;95+wETN0owTtPxFzq8U-;yqL1M!HTT zyN_+B3bAcyz}ZOzG$a7Z}wX(aNa8}X?;wUD#OW)k^AYK z8cAN|*;^dELmQ5f*R{MV`xTb_%oKZUHKpG75zPz9M>h`S(th?KUS_Ez*0WcqG2A#Z zPd-(wly*`)U&83_jomADzW0na_%FAdUoDSEY+5S*Z}tsv{+}1UVqA|S!XXOCi6bEj z-5}dLgnkWPM{5`L!d!=LdUu`~_Ry-KbJwYhPfB{qr7bf_|DRFht_#8a_r{3N&2 zIw}X{H))Z^j9bw2%Pete^ApMlg=;j-giD+qn1yDk96VwO}9w7=VzMHH&?7Ryn}A8y3N+T z&1TD=wF|VucQCGN7Mt^}nikzFHnW>t0)#myo-z69$-*s-+qk?E!0j55Zq7a`WyZpW?Tl&w4p>@_4xBk3kD_$!K-U=Ab$w7*_9>_9Z zhSCI}Mv*Ojaa9x$FvtXT4T!GQT@#t|5$t-;=^S<0#dw~V=Aybv810t#++2Agd^5+C z9dY!fx!&hQW&)8GIfTjz-&rjd&6iOUT+wu6JX4C9f$lWHq(^hOJf0JJ@43c2xe>>j zrXwc9;l4=O?5QyF)nwta=n-69!!uUt&|&7p(L&+CqGRkNO%qYLt`D>EN}wotm670L z_EB@i_A!jcnpjq_yqI;;A7Noiqqw4H&jj*e_s!ehA@*&2r{IokE1URt2m5bp9BVL3 z#v-fcJZowFLwKNYpT*14U}n;;oubIoqeNY6vbm-u(=3v2-4;ahM#6`iW6ZCNa_9Ev zTCs+wsyI}+iM@Q*ncID39IJJyj+v{tMPPikkUPV zloB+@V&3Wwkwu|0d#)gq4fb+p%H9pJ`_8+Gve#v@tN$Jmm|cD&9G^9X9cg4K`2M$_ zG4fCpB(m$d_Pi_+I3n2>uD`(etxM(lu2(WSbB4&L@9T)_zp0?l(3GsR3gcWhec;U> zUnTx&$!_=htmYCUb)v=zixojuTEn=c~&l_oye_ufFrd_)ZoXlQ|mC4NxHM zxw81pg=}Niq;_JdYczN(x{N?8< zq`dqjY3?zn(%dR?HT^j5%@Yun#yWa(#X|Tf*N+T`Me{Y6>hTxpP;|NP8CYIW2=%`= zfpN;xWU$wtT)sC4nhj`>TMnr(+`)lN9($Wydl7_3sHWo$qB_)W)(C3GCKG?jTr4AE zD!Fqb32kwZ@P$=Ov7OQc@+R>KYWS7OFWr&AZ5a;2M@ouGe$-u}I5(L~T0Nis605;+ z&u{W0Y@*Qnf_C_bx5I>XC{EofT`B^rru^Wj*)`(x;hs!^no38aZCv&p!Jx9J5Eh`eUkW0SB*Zcl3k`R`3C zUh@Z2jgESnFDJuKlT9J_cWdDjTb6LHwGUwjM{&o2g~UfwmvrJ0^yl55=#Z@@6_0d+ z-fgWY?&o)0yY~ivBJ&w;kNOF4ni-)?3O0N1h1+fA$f8xFX|Bw85)DJ}+hem(?>|lc zzzr#s^PhyH+<1mv{5BcQliv%*Fme4NOh40o0AEL+3NX!P>K0 zcut29t$Jh%f4v@w!ioantVKy+i(Ucy&+-EPtrgBK)={$4O&x>O^z%Wd!GFBb0}a@ItB#G4QDfcyI72t*P&8Ss z6fJ7ZWxjlyh`mfg_Y>ZhB5Z=#Z{IzePREei$(A^L{y5q^}o!W@CGmnEZdv|v1 zV^g$a&PrbIZ#js4@Eo7IB;hyvt>gpJtN4Di&5~JG1$LPw4W9`P<2U{jaIV}q;{5e8 z*x^-z3Rnprc2zgx$}CaRMjNb@@CrM>s%8gwhoc|EwVV*{W}a=81(y`eAyTYEtKJFF z_r?h-8a=Y|uUb%^+;j92nLXk0|(v zdgtk&Hm^r`eZw>)ef|na?t71T6^7jvlEdAvU5!2WN3;9&{E*4Gn>=$M2hVaDOH%#h z*xM_{p@g6~{KoP*zvbaI1V=fd&5!e;uK8-v=_-S2HU$D@j~e!QNh>xucZ3uB*I;IF zI=t$;8g;I=1|vfH;l~|Pd~ZxCVq@HpsL#%?Fn&gk&-NUBgtxh+0@9lNxabKd#|(2f-KN({115WMeNMopYUWo1*G`z z8s?|Y!hUM0$7J? z$KZ>M&v0L;0@CV-=<2NNcxvBf{#tbguCECI(U(pE&#n@%BWVeDJrW`K(3JC&yN34o zpNDG3x1jum8(?8^Gu~731^gFjKwn$gk~zBv;b-NO=v) zsaw$Q{`Gjo-ZNCM@Cba)k0NDyHhflFGuHknLipcbKCR^-_71tk%|Ba-iCrnqwJQOi zPQ4-Z1v1>x^%roD(J9iXl_hb9{N^@Ec7ic{hX%-%(HoYI{zpDy> z4_QLS{+S6^Ro8Rpf65S__0ibI-<*&GrTEt2nY3`#H-5+ED55f>fX^WcC_ecr z?`JAY!l7o14S!FvKS(`e#^3qy0@|GnMJ?;XM2*I=;PNFA>hOx>RDW2*#h;YX*j18l z{)bd=T<4sQ>;@tYEoPgeKU{SA5Z|@hk6UrU zh@b8Ln7xRVV7_k&eE44!r|*>wziw1z9j*4jt|NL#wi&{dIF3A zW0`1bd@NHU*@5UDddfK}l)_z-zT23t1@L^12{Ry=g{p2{=4bC8&Ahh8OoQ7lkYqlU zi+lGKjsH~02-o~(_ZX{kT?0!P|KcK)F%3c{O%sLxutv;rWqhp9ksq~b9XxkBO?0j( z6lOWN11xYy-djdsqnja2Q=cBnc2@!S48ugjb2Gv9H>x1Hd<1MzIK$u9$H;D(7^r^f zgdb%**pIIF`6sWd`39XLW|r?Ds8D#tY95e<8EWCcUTy?fQ(Onme3F;EPe#FCo~kHI z*#!)K&t{HYI0-s!$BK5jv&>FzHdMTq&xMCn@z?#eMUM`gg9^6V=!MB|q1DU9K)t36 z-eM8Ipi=;?Pi}$5Rgt_+YZ*_jr-Kh&=G+`RPo~0rF5G5r$49vy{Cn&IFTo zl!#VND*?Deoj=(>LeqOfu#LY6tk)hF#s2!s z^8Qw$;g4rUj(=8wTc4yrj%+u#eUT&D8oRR1zK_Qb&rU~^5HPvvIb03YlTxZ zSHLZ1ZpifQK0fkL6xi0BC%U%K5PnXSfgk=EqWwqrqoeNYnb;qGP_6PfZywr*|1Pk4R^FW>&zFE0Wp0%iVa9{V#s!`RUA&kiWe9+yM4z#y)_p zWx(Ah;e1VCI>?MGfnC^wm%es|w_BFWo;=sZY&)-3)eFy`d*fAHfsuNAyatY&7kju5)588U*7d|{ALpWyGp(ISH_#)A4q z`po3GdN%kiCpf5eliy={Qs8mLj;Tv!_yx~yiKxp8ksaK|&HnO>QJb-eQ&=>}*kz1o z+9xFoSB@*^H%zM&`dIuEty-ic+V-GXP`JxWu%xq7R26%G*=ehO)e7d^L}FSN=lzgdhnC&$s6Fhr)V)sS^Zp` zxL^45$6wYm@svR17$pogUBuA-Ho=zNE4Y{lAP{K?+1HNKMK!CeMc1$gv;3nTPZrDZ z?EW5l8Dmn!R!K-FN643{`h3#5Xnv3CBKpC`1Po-KA}Y$?(Og{>db+=fwp>-_<@S5x z&#R}?%`gXz-nNfQe~KZu=2c?PxH!^tCkq=swnAr-6MyjVc=3n|ZQvd5O;4S%BBdVt zNU7>;=ze)VK^M~bpN%|4?@h_D#B*gPpGu##6w#J44tZ~FCfCdBiF)8taediV?%}{Z zDmpj7Yb|jk%GSjw-pBlH9JzZ-IrKyy2a(f^Z2&41Bx&GNFG0xqsN0J z9kx}o@fmjmWU^yB|G4@KDQXL%T6^Ch6+L;JZ8Mvs-CTe*CIBR@auw%xOM~Ml_VZ&> zV{vrHX>zT>fvO$W;13HoQnSoaDE#pU&dfmtE2pXPOF|9k)r`3k-ry3fH==~E9B!k7 zi|lc++ZlcxbBxRxC65Abv3Oykfq16T2mXEEH@N%9Vs!808-A3glGyIjN;Gy_H4I`Hp@V)_%QSZ49vgVH}2rG1^f1m4vfK#_IpFRO! zv0aU-A|Dcg+F1HwsU|s}JQHkoQDVZ4#IiM%E&@=^xQGdBs&*I02@Cc8w6h5)oB+~;0EhC= zBKf{-$=R`mJ0&qW=;0%RS&q$oV)j8nVFlv57HhIgE}FB|YkzZc3ZDgo_6l6>Q<6of z+?Jk7cA47?QQsXI_8z}h0Hh`gWu7^*!7(yyLQ^sSDbP*OTUE%p|2Ag`q#U|g6{|BMFTF~hX;0?=`rIh;Pqmz7zuPd}a)28t$vCSMuBrgb4g z!JfTrMuVlmDM-lqW>g7+_CI8TTlGXXdp3#s6!-BKk&SFhR-VXron$WAb`8vKZsfe* zr%L?vsUo|N4@9p*P0(l0C`P?vJMatt&iQ|oNB4U+qcz_@hz{J5f=n` z?YeUf+HkKbni^9^O(4+SYnFK#!x zvMq!&3>yzEpJ<@ewkob_ktO(?QwI;No(YuZ<}g*#T42w)45nW$iJ3Lm1T^LNz{81~ z(9kV;=J(hyT|9LCnnI3FQediDqJSSA2vr;C}eUlypo=Q;O&ay6s> zO9@>bpDG%uv>U9{K8BwDxX8p$oWwU5nDCyhYnXz8vuN_547X@V9-p(9Mb^D8xVbDcME$>Rp#DLULG7XQWTL$j={-R3i#?iP@*j7x_L3g(P570P z-7CnGfpGFU`X$`DeIb3ZRgVM)+SBkIHsq)AY+S7Kj!La~0{7fnqE=N_L zjp&rFc)Hr;IB}Z|NSMP+{N`LCjK8vkx-~zh!u5B^ENNx@Z}JNgv?U39#^jKLFB-98 zq#d{?e}Ol8Y(*@;FQP8t@$_qbG@s~iB1V1YXkmmExbkuV2Cg&E%d-b)!hJW1pQD*5 zXeoe}dwOE`6n8w?bOex2dqTA2I`OdEdVKvun7Cfc669@>My~3?XvPK^Fi+qswmlk6 zeD*Qo(lHOI){<*t!=+YuZ0#f}kTBsjFsSqd8m{MPnY8R!P;Wa{4O}Ua5_G|hoMK^cYtoKZS;8TGFUmH zp1ieFC#9BhBsYemuD-?8yr7JD5O>lZgSaw7(SmD zLb4Yk^jVxt(!!=u9gxfUUAM+JI&(?mDjuzQp+e6W*@59qZm-jgkxe z_;|^G+tXHnO>Z~h8T-}{jg@ZRPz+>HG5!`bcM$5&M+lOwG)&!P_rR-2o&?vI2 zB^PZ{Rwm90Qn*bu6?Alc><)aCJ@iJ4*X}?)%5D(V~8uZ=8HpA$&iaFc9cp+;)aW~ds_nEHe3waG~(fO z^*Ow&^f{^+-GuA5ZKFyR<7hyInz&}?8niMzg-8WR!+GMHj?OEdIZ@#_c3vHJqZ)*KajK`1?1&+mgwi$(0TI~62*ig_{i1&PY zIQio@pmMPcAG%|~J+5BNfBZ9_tb(mj!Qn8D-I@&@wz`qs_vC45pnxYtY$8%2 zGmucZ6ZgCgBV&FL{KTXI9exsy)@|*TI9|N?A;U8A@Y@U^HR25kIg^j}or}gtTARVR z#!%Ap%>j?zrc25`FU3c2E{vGqM{<^rmT)trN$VOzvd#71rjzAIzk#}iQFxx`L4NqKI_U~bC$3=^@m$6Q z|2(S;^MjXzn5(~Wq|y^2T{eou5DWO_?p_H8zXaLpwc=ssD|$J!5Af4gaR%S7AnQOy zQYaonWGBqxZeG!(y{%qAC|b@}7mPy2lDUwwI2AWvTtb@o&)6ne^qf=H4lhvUK;NG;7ksg&n80K8*o zI(Ga~Pqwv2!i2DRvP1qKs4fXaU#o=pr1Buw#9YChBn(`tHpB+{6kl9CA4P7Rf#=XT z;$y0a)_mSUDsmTLd)=u(ZCME#=Uc<>oFBw`cS`&Z(H)%9v>dEUV_?DWdr*1?u&oqL~y>)EEq*5|}IEAaPkt6a7 zA5rl4L1eDK1FRpfg-03aa6=^>IHeY&4!RCL2nr%?ONOv{ej<3ApM+=4KY>%sh6uOH z5C|N*aEWXrC;XX#W?Z%4y3NzMPwj2IcIGqoWScrp(0PfJVjZ}1Pp_cjd%wU4@8$S_ z!Z948EQ?E*%!a4joqNqWV9E{YBb;l^V8T*XiW7&Gahd4UzcR@n* ze)91BQsS}QlrBxb09H-8g}48vV928auN1#TlQUM3)xx*r#M?az?kqhywy&N)&_andB?D>0#eZXjgWmqr&BzI)^7M^-Ah0UGu z1llxhg6cyd;Gu6UR_{N7=gypqSNC1QeA;SAyw8Jd#r-hNI)!3TD3FiDpZ9XHIp0P-tcaI<9pL9x!*Ookm_L$yV&tj!JUdk%Xn*~Re=S$%Tz*Hg zhdV~`VD&LJXhRCt{t966(FEKZV2?-t)Fg_f@-TAVd({2cfLr7^5yixYqQN(hai5$# zfv0S_tY1wieC$px)V`dN-RO_{&|#<+S&mK_ynvnZ;pqO>F+7a$!6zR8?pW1nK4hE^ znsD|An|x6YM{C|-MoC!Foio(H4%J!Edt@HciI>NZkBQMc3j=Y!mkM=l*F~pmd&sZ9 z9(?ZhgJ90BgVf);4*6%Q)AkLUkk`wzw6NAlY~bt6UwKN%yWjQn$PPPP;8a2XGfJSH z>5cetM;%GfY$dM_2=SYol^{NLj@VxZ!hC04iMZ8<%yVB!GECY*aP4|}HinQd8DctJ z&xr)i^1((mSLyIhO>tK1XY$+q7R?wipq&Q!;w+mPhzw;>TPFgZ)b$g|Q^mpGm!tnG zAK~eyo^aiZYs70%f$nvYM^6Y0q)C!R*3XJ*lJ z_a4#{7v$;A3LU)HPM>BOAH!f?3(@k*#6R!lLM3>eZygm)CK;`wGwNgLA?0Kq@8iW9 z5=K$OZF^vovJ%TA&POJXkI>V{R?y+VVe-sG7ObBmEq>+KgxnMq!Skp-ax3>0PDtH{ z-~HJkwowN_`=TjocZ@`9FL&^^&)vnK4W$ z^u&9v|As#s7vN7Rl-?V;3s_8dq5mXjir2f|6aS5xq-v`=>4_$^BJdLJ`E;H$CqSQTR0TQ+x6h7yonW_m!%+c=if?HPEOjU9}6Yy^(+okUh=BwTjO7Dth zeVcOx3ASUvg^SZ!U*)xIV%{9q;YX#QX|^X5sk9ncOwi%q+*ASZ&=DqCbsOI>T*dxS zxXW6Mt2Y-rJmZ({R$&dB^ceYPJJ|9ne~Yk%pSV;>A3ixa*5W)I4W?VU307@QVtST* z;KonW6pf5LEYu0UB`^rG6ZAJ$h;FwEfp32fZ>GLVgr3H5$CU>J{clTnJ3B|=WW!Mw zJ{m_X777$u<45j%hTA^=+*GdZ(EZ)j#U615%r@Aq{ z|DCXi8JoluG?@#FN3>haTJf1x?0&_l9�G|IGkqQctkLJvezfBotlibSr-@o>NYoH?s{Oc{Uabp*E1@AAMtO0 zstOZ+-w|9ov7Pg1{mR-F37DRWf6TKmWpKyoHxnc*Vjp?R3+~EJ;FhiaBU;!$Mfl6l zfhm|BVR5i2lFNN|fK$~77uwF#W@k)0$Dg-079}57!@fiRVASi0{Bz@TFz?KKCh_%7 z_O-7UdNj9`kAJ3vMqc~P$InhdqkoRXW>0OHr~M|-x92jtpFa^~|0_Vhs-sZ8+6d^d z`Xa2}TLteA=ztF`%h(QkN4({*8Mj8lH9;*)VS!vCd>Yxwt;pJl#+aGGjf3te+tmTi z&Y1_g7Pca}&kA@WXoD3d70Ag?6Lk$GVlOw$XND)C(+i6k)74*K?spgP@~$nfJN6o= zN}0{Q@y&)FkM+=>zVBS%R6`UIw4T3kSPr=zOhRXFWWY4Vv2f3^DL}70lMf%XmN14( z(ZX^m6ws~&L^l+;R)O)qhdzUJ`k!dnT$3?Z$h$+v!no9|2 z_4#pV!H_u~+m?i_Pc2|4*e0XE&pW}2b^kMT-v3nnaU3Thn`{YR>)w0D=X}Pw(hw!2 zlAjBCP1v;U*(b=Ek?l zIAOLiTliNV8>TqJPt6f<-Lr>mSd%x}h>ai%rb(O$`cR#l%Vj*gk8Vpi!-5s9FksVZ z)RCi%vTh~dYa$j@{ftFxc1ts1KDS}SX7CPC|CQ7Gg}^vc_9< zkngT3z*y%G3>&u}?S7O71*2bbf1`Qs+rku}G|dYAw#Y-LroM&7vND{PzbraE*Od$0 zRRtftN#*w3jAl(X7Sp{^0dRslhw8^KL#CR+^jUR%{P*2BU|G&EPqw*oQ@kdE@h&@% z+G;0s_xD3+xBea7|40)bVrOw?ANy$Ut<7+{>qAcU<}xn$*IIme9K{Uhu zw{*VP9WN_LhpUqH@SC)oC}Cj%_BC9<9h_%^PS~Ge{dHrINKFozX_@0|D-Ph7D_s~F zulBvf{HGhI=Ah?s`S7XYByp41WPYjH9<;4AjvW0O1G;{! z=K4P`;zy5t1cSZ>@iC_$Hs0LEI~>y$SM2r%4eKV6%8(BJYE&BvdzH*z(e>ml)qmlm zVXyJR`>MRnVQuX6_aiv5e3sZGZ60^3SK`^)6GxWbKT85OnxWVaTD-0IXr!?|j!#_i z6+dR~!3gW|;?Z8C#O^n`@V#DjahJCluV-B%mQmh@@bwwIl>J@63$Bn#lTpb0dmb#L zd(q;|_uz&k=ac-PkSy5i2t!l@_{`2jXj8vB-?=b`-yM01U~7F`;242z-&UYh){S2+ z$mCxKn3BE;PoZ+1F0b*rANBid5{+xM*sO09yrtR(rbow+$gdv!;p?8f+=^_lb)SWJ z*gXUG{x}crPO?NciF3g6+XcKh*o-%rRZJ4&R5^0rT|8bV1D}=s4Ay9T!iBaHCY9#| zr1|%dxBvum)3egK#~tcu+%pr-;CrHY<_t|@Go&ZJ->oPxKLtdW0B3Z*k+Dn_|ZSGp=RKKHf=sJ(Ts{3mnF6BBiTOo zlGu(-$ab-=SZ{qR$+5V@{~@agyF?uy@b?u@opC~(TM@_KCA-BkEv9^TkG@ss%Dd>n z0}b9~>LpHVwj`5OG@6tsw<5EFO#H~N4{j)&$J?&0<(;l(px@s*Bs_6b_-)K(ez2a1 zbu}G$Tfax7WnvdjN}Pf)&wPvwdXQ!7p6?Q%ipHMk%yK z(o0;L_>q$U@{n>8|9xP}H|K8i3y=m+- zvyj(sT7 znW?xgyF$nsZmM5JdEDtrb?YlB(Vtbw(n0%E#q`{O9v)@dbx| z?$Ogipq8nGtc5E$qjEW`-Ahe*xz1zagl)WdSEQvCDUl-iuWR_p@n%T8^gr?LS0cWy zIz-%RFJtv|=s34}c`v^__#cjeso-F17Ev5v$c?`9{M3f#(=!8^T*18WLv=-?B> zRK%MtqC=l13NFJ>g1lv~=uHDr0*5#SVR!mj!LEEA;2e5_z0|W#Q1kmd^LLvAd+FeN zD&*h?W@FSr_FW{TFFsTjt}B!VbMpRC?wRWZK3K?;hSg_x(l6f}jDBYbIBl<431?t121@HWqP?3FUjCfnV z;B)v6!S*Nhl+&hh^m*GZCc|zllUQ<8^xS8bP<2HwTb;rP>Kfk)R^2`=h;<(=Y;<6S zzL&$8hyLH`uod z5SXZv#Ma8|0*X2(+8N%@czJsY5;~7D*L|)rl?!`-!(T0~@zX1T(!?yb`r$aC!^BR( zQlTOHq4x{@-}{AZevO9cq@<4U8s#qV*0*Q17fcd76-Ep88tTw-W8;PA^+Fl>C6@$a z&zdsQp+e!`=Z3;(veIl*P6K;XK7&b}u?mteu2o_{oghOLGZta6WxD&w~ncautQn z@1lcjjo1MFN7Ooz5PbU~V2&uIgG-&9P%R^k*6i~YcCHzw8ZJkOk~e1xCrLMmbgM23 z&MEMW+Px?A@=-qoKDFb)g{MKnU5>hRcCjp5GBJz#Z!JxYkBVcy+Rdcm%A?qqfwlCr z(|@S7rn5zYhEd?@%~+Aak2-4YrxwwQx)|Xa?L0w1%W2x^Y$`1u%`ocW>VoK*V}M)w zEa7px{g&SQ7l{&erwRXyl6VmOd|7Fg5A0WAiokT24wEzzC~7){1bg})Q?J`QL<0^% zB6jl;(5l#Cx##B&Ve|ZTLhA$S!dz-OW4q}Seazz!2tFCdTs-%i9Zp*%s-%B0!VH1% zQehJPGhCNm_%H!T#}|W(E0u-e4}UPFY^dnRrj>#@lOQc}v|tVdwX(nEd#SNC`fT#b zOCn3-AZG0wUTEJiQ}m?gJ2Ufmig0N5cc%Mvyl?e4+8V*q%3jt~z#MbScg_t0o$6^cjMEd!#wJoRS$@LJ(>AaJU<;#rW|ZZ> zk~aKO=8s_u7FGyP$90PeW%H?n#-4(Iec$N&Pok)~#tqbxZTH#xThav~ z(NUDVgA}dcDo2IeCX2Kzi-gU^)iiNFN8Q-%N^h@8qPP`1gacDTn3%GcLh&1#(qBl6 zF6GY_bbH(p#5LWd$8N5tdcZhFKf_RGCY>rQ|m=-N5q!$%JVuG2ah<=84J zv1X7u`gD#Z){3P0(bd8tM#VDVloeH^IZfpDw?%kXngZT!9n`f&+XdZ@7X<61Uf!A|;_!ERW!5#E$@pbq#;2e9C{3aehkAYh6S1vh5~pu}>f7yt~X49;C6(PED9n6pKB-y5OS=6JYU`FVLq@8YPPLfTLCk-aKk4 zu`N8unZ0O(ibebJV1PV&{mYI!?@1qbsd!pTHVz z4;UezjPA0vbTs!)e>^mKv4&l?|2fgv;sdvQ`a(kA=@J>nnopCt376Biuys~6mwV5d z^dGCkr_Q`3@y}-QEq5NW)3vg&+Vc)pf4eL@_wRjp^JO%Q4A3ElEqPea*Rt{oXaULmLglb^uXkwIwVIgnl(t)#z*z9LGSOn=-erJ@~mHlOj{6*?I;!2 z<j8lko=-Fs?=;LK10qt(2Y z3JB#b-Bz&l<=m6he=bH0bGVsy`FoVft}LczJP zlNwljc@6?2k6B8g8^=XU>gJd^%$~d=sUr@mv&+id`wH1=x;Rt+wXBRW^xn%#LG!RNxXmh9X_dv(MyUg>N za-=)=4>x>l4yZqW3D2o}$NlR*k8~D?pbeml(@fe6jl*_IxGd`Mxb19IwXO^sNSSfE z(z)Cja~cos*bBYojkwt_ouHs!jV;$OW!-rn8n2AJ`P=TMkuOyeh$8#~ESJ1-J8{mb920q^tkIU~I zB^M^WAmd&nv&-}SaJj7&YiXRy=vG&vB_*q&=d&i{ykY_-`C@EnD320?9LQ7M5-xc5 z0p?=VHe^<_iH(&hK}t7fu=18S;82(HE&QFgq1A{_v(7JRuRQp#-*e46o!D$8vb9UrgF{^JIibP~qs@%shIaV4zP z`PbC8h4F%eQGv|TwoSCzA{qLGry}^C)gU;I3Pq($7#523A*~L}b>~}Y z*Pz*S!@4Ra>e)7CWc*Z?n&3nq`dq|jksYF<_WM-A@{7#BW+`E1;YTL3XFzyp_gV%! z9i->_9H3uIU1Y8`@NArpHS^A94BsC_kw;b@tO3uGvY#v2bKavl>pOkKXUjxTZ(oFY zi>s{VNqN5Y+e-d}U^n~h*EjqEZ|0lkq@eva^`um7G8tS@1fB0868LojK5m+io_Jhl zc}~P925kUk8&&z^Z}Q>6rH3I3xy>5CKtyGnH!`|@9krL*<2hSYu*NJia{bc={>~nC z{LcO@d1aG=Z+^eeuaKGq<<4i3Q(om@{jTSD_QJF1R^TWYFh2;-FYRRqXT89BihJ;= zrE6HLd$&p3DFe3u6d^UTA!JL+3zmP1k0UVdWrsU-6t>dEJeF+Nljc$9@1exAvid8OiKY zxf5izY&NkE$Rg!C&42+Fi`KP$Wu<;Og65x!WO>OC?!?rwSZ+@upE}|IRKqf0zJ~zm zx&*S{ot*enG9U0L>3zKHr2wKaJ)e)h3Gu$G5{BZeW9rxMZ;}on-4lXX~g?TixDKVF&G~B!v(3e+_E|{8knEXWS%Fv;Tk8jP+qc z?bxq^RBFGd1w~t?pV6n5SUFJpb{GrN!(FJHqHuxaLrKw-uTi(oH;R%xR*UXxY!d`b443wUZ763 zHd80n+suCruBAt|xC?wA#aQ$-z7j6C-zj)|^8vMYMdBaJPWLg~+vZhejS$)8KO-hg`MfHnt z{<>w<`?{$*>ai%|+W>rg`WEM3@>?`@JmALVM^hTVPqOM>W^mq&yY$ofm$^MT z>*;r&uc6FW`;o=HCsgT!J#g@FE^1D5=EA;Tm+UJla|bLexH~WG;g5IY;o68a?!uD{ zX2H}+=;qN^tj}2+R39^+{e62iP}iP9|Jf+XC{B%G>3zFdtHv_Ub!IO2{Guh8^1Kbb zz81w!?yiDXKE2@R;AlJ`{hayNc^DRyM9>pj~-Uf}^+pd3$+E2)R~Iv=yAvUhNN-)R*1?+V2n z@MN~O|6`pT7En)%QqcSIP#E#^8I^p8O{fg&!}2bN6mV z-8Ng0-}5hw6Wt1;m%IS6s^jU=aS4pRWikvOvm3gkXG68ZJ7_rTFnvVl6D$nWW=Wb1 zxKeuvYL{AO+IbbGERls@oQ?64QX6jb(Gwhz)F-#9F4I3% zWx-9RL6}L7i7Yw>z?^f_MXU@4ksC%crf*z1<>oZbP^C?{&+{vLuF;XJc&Nx$I5~5- zvt7WXj~AFIH3G6M$AeVO9A@v-QPjQT4>-!bhbo@6h~xiz$zCjZ!n%BjrTL->tchQg zD9tPq7^usEDyKT8uIU$uJyybPu-h$KR20VjvD*Z;9Y=8ZXt-!Y0nK^FvZD1Kqrtf1 zR-pv^CE9=d2s?K9EYVU2O|V$TlKoROEUL2$2j%T~v|4dA*i;=0yskR21IarnuRopC z<889ko|yZf_o$fDv1F;SYyZ(dK01JZ1(nQ#h94rc@*-wIa+~OU)f&+|&z)>nu@IEn z{sBd`Mxs_lC(demJslXRB-$M;&Cc|b7V)puxovk^n^=Jtl{K9^fGg8h46o_~p)=PAlgkJ9Rj%3S$Ue zOj!s2t6-yL3Ef@h&h6x$f|&`;+*~_dIQ7zqNb_hsD109)`hHGcw7w&PoxS!rGjnzy zNa}Y3c3(e&Pu6}SJLO`okMlJp_%NVZ3H#|I9l~Ibgyx||Wre`wF zKBGmdbbm7;{$tRmOBuK$TpFpr${@BYFT*?kVxWcpVXXP#4BEIM9L53}pwh3(C#!V> z&7+R^@QjZrEBi5u@Yuq^owe|FeF|$3zaLLK+l5p^4bj0786sRIODvLt*{PQ&;g9B5 zaB;N_AMt7*yY_7?k;&!Q1tAmRg!VA@u~9s0I%PKU{o>6we*J?)+m6A@)9)}wcWY6P z$t)&;t?lhr!dW{Q80qtDgUof@9a|0TI}mDg*hjuTJjRYqkOB5jLL}4$AJ(V( z22sf?1Z$NfyuIRn{CpAO%?4h>y#}wbPQ@W^^^dirQST5A8kH!?pjVPhWX2O;CzT(iR4cH@88_Q2P%2^+MMZV@=1DUVsJs zYcil?g7z7tkuSbJ$ZfGQU-Bl7f7MgQ(&A*S7h%q??_7YUHtF#%XMH0oahvhoeq-`& zof+wTw;##Km4n3>uJQ8=<2d3L#@lMvV~4aSc&>ywR(GP4>?lveN`q&}ub?yd=fNuE zdc}o5^L7`nAmu=g{5Ix&QzFQvN?GyZPkHcRnKWM%p8#fjT1wh7tB_yVIan27ihqWe zb8*j%Nap=Gq9;8U7EDVfI*%G)BaSE8N;15akuo8}IoP$c1lgqhg_(=bk$gkQ?~d^! z5gL1t!Iw=W^vVxptcZz@hBba%Bn_3P>w}KdPq0|Ry0>1~OP(zM$QI{k@_xCQ@LXpe z=>KvNSq+y$vlRnGJFAxDn!Ay!D}6xuu6TaItE=c^*b?yI>m<^h{ggTW3v&`o)$<7 ztkd{2XB5O;`>H^sNP(~a)Q$FXC)n}Q1^B$a5P#;<$-y5^WV@ds4@%7N@R>-yVPrO( z`s_54(n=?1I$FW&${I3eO${gibqZ0a4915SZNdf{DAc(wiIsCmKNBy>ADZOMLlP+)4gMMJJG|Wbxi*(Ok**6!se#f%80@QLWxtQoS^l zWX7x`27BYs=G*1GRe2$d3q8d(AE_aR1Fb;m1#X=O~K=Hv*YgYcv?`zb^J2Zqb)_4qWdfq>(O56Z;Eh>g$M4J>a*ra$K z*7G!g#nK|wzT`Ld-FllH!<_>YlC7D(IRaP{p3D7?*TwPDI;1sW0kdjGJzkz@iM$qN z(64L$z*3cL&hB|Eb7biZxa5-o5u2Rn%s=dbiIRDqU9=3^9Z|sCj(o=abID{K(VBwnnZ!#Zxbj`xSm<|oA0Augngw8bd%bG0<_%Jmv#!|k19e_A#Q zTJ{QTGWm~RcK8;jtbCZK|Gk9A#1rv6{m*QD?_*-(eifgb$dH>#8rb>MM>NUlKhjf~ z$nPo&CW@El@nL$Oanks);;&Viui18401 za^~%K;G0KAU|oa*U!8-#%FYQ|{#7b;NSle*7{c3!iqdB8{7D_)W#-xaPhS=2Ru;l$jeqouqym zwJU>;oRiOt5f&i$_BCi%@Idv||8Y?{cTj=Y8CwNM(FfB!;l|wq=!mI5mu%F7R^BK> zH+nf((f9`PXMVtqwsX11MzM_J?l^37&W#;=eiA;lCJDOjJrCc7Yk-uZ93+nNfE|xw zP>yUAy!ASko4rOGXMUQ9Hx{U(=OKgW&;Ds>nr1Uz^DO`*dDNhA0~aRjgAux+63%h{ zA)wdeCpS?{$N8wP7B#y&j9EtSd(ALeJ4h z9G2h;{Y7BVbt_X?8pD0<+XV#2&!I8aiO5(<7hM{(V2n39$%$VPb$jn9^ zzB`b^ebOw(W43N!6z5t2m$%uVWUVP9GS0+R6I-D98F$<}Qy#BN7{m=EgX`PwjiQ6! zv%mjVBe`X^h@Z3q8}_u~>sI@jA#nrRDJbk5#uj!lT*Ofg^lD%?b9;v$zL|dwt8A^NrImle zXP*1<17#^Fy?*vL$Il(F4y3foSoPoVJTw~34cHqDjgezaT z5vng7%lKq!;0bevVWTh*J@jIr%cNnh_-q(TxNrr}h$uv<_4{xEXMludVlw$rBZ#Xn zLRA-DGDk%Fkok;9oVcJ37`=;umt-}7&v_@5p?V0_-Mk94-3E|av4C!W8j4h@Uuf0Q zXecLD4f7-2xGDZV-1)U9kl*7-ytCqhBu~Dci{9Lh6i;fyY}-T>^ZNj2HYyC{2Lv$q z5{0hjyhqC_b#cul2j)%SGhA4&0mheXWV!CDJvj7R0ILO`@r3&v`E=1~=wAl9Q4^Vl#0niIcK*m>VVVn68 z_;E%ca=qY-V*`8Po$?YqZ6|}++!%VC#D#svCyHKbIFELdWSbs7KhHR5&V(v559ry| zv(Wl^dboF#E;IX409+!_#fQzaVO9B4Ty3(Mt>Ml-B|EW4~rj+LM2ftKb@KyhWo(0T77G)2t@A71>MaWT$C zCl{#UmJ{*hu)90E!}}}V-Dt;beG>)ZzDu#+bl)?x!@A*L{v0EY0;tYHGQ-?HooW1j z1s)kZ$$ioP1>dfI&V@aHK{vjaxE{n?*@(_W`i`77x?z0)P5g0|c@bO&7w4Tt+tKzLjy7h~M9;K#Gd_uxj;e+`Zii-}k9to+zcDjporz zlxh+EpJq08Ec*n%KCVM2RSbdV-2aG+VFJmJcBOp^FC+bq1EgSLKcji(7${l1#vc;djiLT{m#(%@=S=+j%bK zpDC1jvxA%ZB^=G0Z%lk$Rbl>=Cpcr|5p5kh51%kxM*fU8#jV$6aFd}s-SOO)d)!%s z)}KxwU}zF?ERkmKs@{iP%OQGKqe~)NFTnrO&v3>k9@ACRR-^7KE%@V55T5f*i5)(y z&d<~zVKlCG(x>;;FtsM}aJK0rR9d-`M68IwobzbLWRB!ox@5SX;?s2honvgy3}fun zHi;cGubLDVH8E4v)`RqevfN9j?UFO{H|&J_u!`(yGzLhV><$OXbq_D@UeH!3zSGC} ztX_hgW9PufV;^Djp&P_wqbi$}vxFGtR-l;HSxniYaP+sd7(P6g2i&+q;OSjT%GY>6 z^PP`ih{UDkq+SG*?+=5KQcDub zUp~a1JvM;Cv{X64$SNGMEeDldZGwkB<>IZo9mwf_7huyWH&Qz)0n>NK@!Kyv;8Ir@ zkW(2#wnn2KRis)$|Ewp#MP!9WKAN(s`^Vzl!s*azBXkcZb=eB_F!zd-BF4e_Gv z9I$Kp7`XNH4cH$2jO+Qb1+O}GU&6!w2S3lwgFD#cIHYqPd>Q-&cC7ouExP-Gg+C{; zo0KH=voHr|F8PGjYyL1DdT!+N=&nM{hwuO;N)gqd6op9u}QdE%U&xR%_ zk!f+J+wq)p-Zl?FNBd{~c$}wtPHm@hy=E&ugNcl08#a zs|)XIY9K=~neZ)fz&(R=xgJlN%)VNH_e8Xju+t`drA93qTbYS1PxyjBy~oT3=j&+E z*?y?ZpTXBmC*xNssrcvb1~~LHp3M8cl`AzZ<|5N;abD(Y_UX4Gyx+x>&6l{0P~u0< zYGMf5vg{0=IsGYK{a^zA_46?CiU`DV(&^kY-S0@1FJc;FdYH`o7kH))11++3aKX}G zu&I(GmDMpMWl1q}bVe~6wwOkatgD3DRZ8S;nhH6v)dacg7~vM#E%^KjIcRHqkG)v6 ziOgy!0X{d56Kg3Y-HPk@OCAgp%xed?uOF?T^v& zO%nFfa=hf0q#tmih6_9X3C|meWX-NRVsBOtDl9YQPHLE;QCC`k!r*`ST>J(sx)RDI zY;3~VB$Au`LmRjF-@s0Fv4~nT4Rx+7hda{DV2FbyPWjFgn`gW6bh$)m{PQq&xfBnB z4Cdi5iI?P`t}GYLIkVd=pQFy_HTdxoN%nGuF6*}F7?Jfl%K3eJ$fS?D2ParJai`Ku-}KHq;vi+EU)mB^xN3NGv1Q3fY^>ZynYm^nV5q8o<1NiX^JmcdYerz zQY0>CB=e21F6QuxtH^wBAe?$@4jxj_$MqMCB>9C&=+In=Pv_7~V7BiTj2dyq^Hz7U zJs}v6D{BUJKH13RY9M;~r5~RB9*ar!I8ydm6>pD-$6wr*p}GFaU|hdGGW?fCzcy-P zO04^kisaQ+FwYPrzP`uY!YrnK#NdX=9rUT#qtIjgWQ;QGxSiqq(b&nO@iU<|47rfP z?F!h8!V(s6ts|$I$G5K_!;D3&?TJ)8MtuM%YU#t**8TL2*AG$u&J$2?k0$D#n#JiS z*MkQe_8}zk%AWT0MZ3Pv!(BD?@Y<|Tc&GIx;L~{<4tN(bf$7djW!C|&|MhXOyCsK9 za<65lebPZ*!%I-8TPW~nOHr-16fNV4(ZcXrByX|}{?18)i+u~ZN%>D;uN&;v<($D?9=YW**vN>H51g#$|8Pm7TQ0wqXq-Agsl^s@MQeWlb8}mEp z0GUE2qc9!pTT=rxZFe@9Re@~H7SD%hAbr>OOb1yun@-6CFa~{jd`g3XTdH=;azwBasPI-(%<4L;hey6@J5<8(l1npTha`1_rn+5;=(c5 zGb$PA4 zAY_z&k(9K4CC-1hVY}21DCLngd34tUNr&G9@1$1q6Pk~4BSAs@kZCrynN@^cx4XgB zqQ_*1>R}umb%0#7e}c;9?S%PzCh$*{XYrS3x{}0mI{a~gh@|em&#U{E!l#ygWcjPf zKq{IcR~lo`hkyCdLy}jy@uZTw&PkDsrAZ{pVcIn&71xd80x4CXUW)uSXu z5twsL4TI!)ct#F_{KC8Z?6@;vnWG4vKV}Y-{q4ZV+n4#DW@E|au@3y!=R&?*c9ht& z+y{->oJwX4E(0xH#Ux?rN9<>?mUof;%(uAS0`+gC_&B|f$b5c0`ye47?~?ReELORb z%(6jA-J!&H$_ue@K#zBwW5Wf*v&gdH8!q{J2E1gV$#I`%Zc)5B8Hrnh?}YPM+Jhob zjDL{W>FQ(`qVUx51}HGb3&hse!Z{Wp^qa0Y=2T!Rl5T4U(Kl(-yT1%557#5xYY2C2 zpGoJr&wy?3yV2iG-@p^C-4cIl0ScXM2IU$K!f?CK@N)ZqTu^p9JzLV-k=nF``BgyU z^!t~&P6Z!m=h4FsdnX}<$xbl(IgdcWInGgTGiRvRhB8`NESxNZ?x(*%yA&(nl%Qhl zx4;wh`$?YhC@W@~wmfPNu;kv})&(mLS8yI0fo#vZI;g(U8ioH>2TxB=Lldhd7OQSk zq?saN-40xYItwUh-RR5JrCk8xs+nj}dk@+aq>qBtM*!i>k>j{jF6HbX^w?g@wY;rm zuWf9h+jhi3D~;92*(e1KY%ZZ+G&3_Z$f9TR z(#)%