From 898ebee28e69414f42b630057f5e0c9ab2c46e32 Mon Sep 17 00:00:00 2001 From: fan-ziqi Date: Mon, 15 Jul 2024 19:31:56 +0800 Subject: [PATCH] devel: isaaclab --- README.md | 4 +- README_CN.md | 4 +- src/rl_sar/config.yaml | 140 +++++++++++++++++++- src/rl_sar/launch/gazebo_a1_isaaclab.launch | 54 ++++++++ src/rl_sar/library/rl_sdk/rl_sdk.cpp | 69 ++++++++-- src/rl_sar/library/rl_sdk/rl_sdk.hpp | 3 +- src/rl_sar/models/a1_isaaclab/policy.pt | Bin 0 -> 172902 bytes src/rl_sar/scripts/rl_sdk.py | 42 ++++-- src/rl_sar/scripts/rl_sim.py | 18 ++- src/rl_sar/src/rl_real_a1.cpp | 36 +++-- src/rl_sar/src/rl_sim.cpp | 22 ++- 11 files changed, 338 insertions(+), 54 deletions(-) create mode 100644 src/rl_sar/launch/gazebo_a1_isaaclab.launch create mode 100644 src/rl_sar/models/a1_isaaclab/policy.pt diff --git a/README.md b/README.md index fc9bb57..2298ead 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,8 @@ Simulation verification and physical deployment of robot reinforcement learning algorithms, suitable for quadruped robots, wheeled robots, and humanoid robots. "sar" stands for "simulation and real" +This framework supports legged_gym based on IaacGym and IsaacLab based on IsaacSim. Use `framework` to distinguish them when using them. + [Click to discuss on Discord](https://discord.gg/vmVjkhVugU) ## Preparation @@ -90,7 +92,7 @@ source devel/setup.bash (for python version) rosrun rl_sar rl_sim.py ``` -Where \ can be `a1` or `gr1t1` or `gr1t2`. +Where \ can be `a1` or `a1_isaaclab` or `gr1t1` or `gr1t2`. Control: * Press **\** to toggle simulation start/stop. diff --git a/README_CN.md b/README_CN.md index 73667b9..cd105d3 100644 --- a/README_CN.md +++ b/README_CN.md @@ -4,6 +4,8 @@ 机器人强化学习算法的仿真验证与实物部署,适配四足机器人、轮足机器人、人形机器人。"sar"代表"simulation and real" +本框架支持基于IaacGym的legged_gym,也支持基于IsaacSim的IsaacLab,使用时用`framework`加以区分。 + [点击在Discord上讨论](https://discord.gg/MC9KguQHtt) ## 准备 @@ -90,7 +92,7 @@ source devel/setup.bash (for python version) rosrun rl_sar rl_sim.py ``` -其中 \ 可以是 `a1` 或 `gr1t1` 或 `gr1t2`. +其中 \ 可以是 `a1` 或 `a1_isaaclab` 或 `gr1t1` 或 `gr1t2`. 控制: diff --git a/src/rl_sar/config.yaml b/src/rl_sar/config.yaml index c723aa8..5eaff85 100644 --- a/src/rl_sar/config.yaml +++ b/src/rl_sar/config.yaml @@ -1,5 +1,8 @@ a1: model_name: "model_0702.pt" + framework: "isaacgym" + rows: 4 + cols: 3 dt: 0.005 decimation: 4 num_observations: 45 @@ -52,6 +55,9 @@ a1: gr1t1: model_name: "model_4000_jit.pt" + framework: "isaacgym" + rows: 2 + cols: 5 dt: 0.001 decimation: 20 num_observations: 39 @@ -86,6 +92,9 @@ gr1t1: gr1t2: model_name: "model_4000_jit.pt" + framework: "isaacgym" + rows: 2 + cols: 5 dt: 0.001 decimation: 20 num_observations: 39 @@ -116,4 +125,133 @@ gr1t2: default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618, 0.0, 0.0, -0.2618, 0.5236, -0.2618] joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller", - "r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"] \ No newline at end of file + "r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"] + +a1_isaaclab: + model_name: "policy.pt" + framework: "isaacsim" + rows: 4 + cols: 3 + dt: 0.005 + decimation: 4 + num_observations: 45 + clip_obs: 100.0 + clip_actions_lower: [-100, -100, -100, + -100, -100, -100, + -100, -100, -100, + -100, -100, -100] + clip_actions_upper: [100, 100, 100, + 100, 100, 100, + 100, 100, 100, + 100, 100, 100] + rl_kp: [20, 20, 20, + 20, 20, 20, + 20, 20, 20, + 20, 20, 20] + rl_kd: [0.5, 0.5, 0.5, + 0.5, 0.5, 0.5, + 0.5, 0.5, 0.5, + 0.5, 0.5, 0.5] + fixed_kp: [80, 80, 80, + 80, 80, 80, + 80, 80, 80, + 80, 80, 80] + fixed_kd: [3, 3, 3, + 3, 3, 3, + 3, 3, 3, + 3, 3, 3] + hip_scale_reduction: 1.0 + hip_scale_reduction_indices: [] + num_of_dofs: 12 + action_scale: 0.25 + lin_vel_scale: 2.0 + ang_vel_scale: 0.25 + dof_pos_scale: 1.0 + dof_vel_scale: 0.05 + commands_scale: [1.0, 1.0, 1.0] + torque_limits: [33.5, 33.5, 33.5, + 33.5, 33.5, 33.5, + 33.5, 33.5, 33.5, + 33.5, 33.5, 33.5] + default_dof_pos: [ 0.1000, 0.8000, -1.5000, + -0.1000, 0.8000, -1.5000, + 0.1000, 1.0000, -1.5000, + -0.1000, 1.0000, -1.5000] + joint_controller_names: ["FL_hip_controller", "FL_thigh_controller", "FL_calf_controller", + "FR_hip_controller", "FR_thigh_controller", "FR_calf_controller", + "RL_hip_controller", "RL_thigh_controller", "RL_calf_controller", + "RR_hip_controller", "RR_thigh_controller", "RR_calf_controller"] + +gr1t1_isaaclab: + model_name: "policy.pt" + framework: "isaacsim" + rows: 2 + cols: 5 + dt: 0.001 + decimation: 20 + num_observations: 39 + clip_obs: 100.0 + clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991, + -1.1391, -1.0491, -2.0991, -0.4391, -1.3991] + clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691, + 0.4391, 1.0491, 1.0491, 2.2691, 0.8691] + rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3, + 57.0, 43.0, 114.0, 114.0, 15.3] + rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5, + 5.7, 4.3, 11.4, 11.4, 1.5] + fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3, + 57.0, 43.0, 114.0, 114.0, 15.3] + fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5, + 5.7, 4.3, 11.4, 11.4, 1.5] + hip_scale_reduction: 1.0 + hip_scale_reduction_indices: [] + num_of_dofs: 10 + action_scale: 1.0 + lin_vel_scale: 1.0 + ang_vel_scale: 1.0 + dof_pos_scale: 1.0 + dof_vel_scale: 1.0 + commands_scale: [1.0, 1.0, 1.0] + torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0, + 60.0, 45.0, 130.0, 130.0, 16.0] + default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618, + 0.0, 0.0, -0.2618, 0.5236, -0.2618] + joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller", + "r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"] + +gr1t2_isaaclab: + model_name: "policy.pt" + framework: "isaacsim" + rows: 2 + cols: 5 + dt: 0.001 + decimation: 20 + num_observations: 39 + clip_obs: 100.0 + clip_actions_lower: [-0.4391, -1.0491, -2.0991, -0.4391, -1.3991, + -1.1391, -1.0491, -2.0991, -0.4391, -1.3991] + clip_actions_upper: [1.1391, 1.0491, 1.0491, 2.2691, 0.8691, + 0.4391, 1.0491, 1.0491, 2.2691, 0.8691] + rl_kp: [57.0, 43.0, 114.0, 114.0, 15.3, + 57.0, 43.0, 114.0, 114.0, 15.3] + rl_kd: [5.7, 4.3, 11.4, 11.4, 1.5, + 5.7, 4.3, 11.4, 11.4, 1.5] + fixed_kp: [57.0, 43.0, 114.0, 114.0, 15.3, + 57.0, 43.0, 114.0, 114.0, 15.3] + fixed_kd: [5.7, 4.3, 11.4, 11.4, 1.5, + 5.7, 4.3, 11.4, 11.4, 1.5] + hip_scale_reduction: 1.0 + hip_scale_reduction_indices: [] + num_of_dofs: 10 + action_scale: 1.0 + lin_vel_scale: 1.0 + ang_vel_scale: 1.0 + dof_pos_scale: 1.0 + dof_vel_scale: 1.0 + commands_scale: [1.0, 1.0, 1.0] + torque_limits: [60.0, 45.0, 130.0, 130.0, 16.0, + 60.0, 45.0, 130.0, 130.0, 16.0] + default_dof_pos: [0.0, 0.0, -0.2618, 0.5236, -0.2618, + 0.0, 0.0, -0.2618, 0.5236, -0.2618] + joint_controller_names: ["l_hip_roll_controller", "l_hip_yaw_controller", "l_hip_pitch_controller", "l_knee_pitch_controller", "l_ankle_pitch_controller", + "r_hip_roll_controller", "r_hip_yaw_controller", "r_hip_pitch_controller", "r_knee_pitch_controller", "r_ankle_pitch_controller"] diff --git a/src/rl_sar/launch/gazebo_a1_isaaclab.launch b/src/rl_sar/launch/gazebo_a1_isaaclab.launch new file mode 100644 index 0000000..964b226 --- /dev/null +++ b/src/rl_sar/launch/gazebo_a1_isaaclab.launch @@ -0,0 +1,54 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/rl_sar/library/rl_sdk/rl_sdk.cpp b/src/rl_sar/library/rl_sdk/rl_sdk.cpp index 54f4489..68c6a08 100644 --- a/src/rl_sar/library/rl_sdk/rl_sdk.cpp +++ b/src/rl_sar/library/rl_sdk/rl_sdk.cpp @@ -4,8 +4,8 @@ torch::Tensor RL_XXX::ComputeObservation() { torch::Tensor obs = torch::cat({ - this->QuatRotateInverse(this->obs.base_quat, this->obs.ang_vel) * this->params.ang_vel_scale, - this->QuatRotateInverse(this->obs.base_quat, this->obs.gravity_vec), + this->QuatRotateInverse(this->obs.base_quat, this->obs.ang_vel, this->params.framework) * this->params.ang_vel_scale, + this->QuatRotateInverse(this->obs.base_quat, this->obs.gravity_vec, this->params.framework), this->obs.commands * this->params.commands_scale, (this->obs.dof_pos - this->params.default_dof_pos) * this->params.dof_pos_scale, this->obs.dof_vel * this->params.dof_vel_scale, @@ -66,11 +66,22 @@ torch::Tensor RL::ComputePosition(torch::Tensor actions) return actions_scaled + this->params.default_dof_pos; } -torch::Tensor RL::QuatRotateInverse(torch::Tensor q, torch::Tensor v) +torch::Tensor RL::QuatRotateInverse(torch::Tensor q, torch::Tensor v, const std::string& framework) { + torch::Tensor q_w; + torch::Tensor q_vec; + if(framework == "isaacsim") + { + q_w = q.index({torch::indexing::Slice(), 0}); + q_vec = q.index({torch::indexing::Slice(), torch::indexing::Slice(1, 4)}); + } + else if(framework == "isaacgym") + { + q_w = q.index({torch::indexing::Slice(), 3}); + q_vec = q.index({torch::indexing::Slice(), torch::indexing::Slice(0, 3)}); + } c10::IntArrayRef shape = q.sizes(); - torch::Tensor q_w = q.index({torch::indexing::Slice(), -1}); - torch::Tensor q_vec = q.index({torch::indexing::Slice(), torch::indexing::Slice(0, 3)}); + torch::Tensor a = v * (2.0 * torch::pow(q_w, 2) - 1.0).unsqueeze(-1); torch::Tensor b = torch::cross(q_vec, v, -1) * q_w.unsqueeze(-1) * 2.0; torch::Tensor c = q_vec * torch::bmm(q_vec.view({shape[0], 1, 3}), v.view({shape[0], 3, 1})).squeeze(-1) * 2.0; @@ -304,6 +315,33 @@ std::vector ReadVectorFromYaml(const YAML::Node& node) return values; } +template +std::vector ReadVectorFromYaml(const YAML::Node& node, const std::string& framework, const int& rows, const int& cols) +{ + std::vector values; + for(const auto& val : node) + { + values.push_back(val.as()); + } + + if(framework == "isaacsim") + { + std::vector transposed_values(cols * rows); + for(int r = 0; r < rows; ++r) + { + for(int c = 0; c < cols; ++c) + { + transposed_values[c * rows + r] = values[r * cols + c]; + } + } + return transposed_values; + } + else if(framework == "isaacgym") + { + return values; + } +} + void RL::ReadYaml(std::string robot_name) { YAML::Node config; @@ -318,12 +356,15 @@ void RL::ReadYaml(std::string robot_name) } this->params.model_name = config["model_name"].as(); + this->params.framework = config["framework"].as(); + int rows = config["rows"].as(); + int cols = config["cols"].as(); this->params.dt = config["dt"].as(); this->params.decimation = config["decimation"].as(); this->params.num_observations = config["num_observations"].as(); this->params.clip_obs = config["clip_obs"].as(); - this->params.clip_actions_upper = torch::tensor(ReadVectorFromYaml(config["clip_actions_upper"])).view({1, -1}); - this->params.clip_actions_lower = torch::tensor(ReadVectorFromYaml(config["clip_actions_lower"])).view({1, -1}); + this->params.clip_actions_upper = torch::tensor(ReadVectorFromYaml(config["clip_actions_upper"], this->params.framework, rows, cols)).view({1, -1}); + this->params.clip_actions_lower = torch::tensor(ReadVectorFromYaml(config["clip_actions_lower"], this->params.framework, rows, cols)).view({1, -1}); this->params.action_scale = config["action_scale"].as(); this->params.hip_scale_reduction = config["hip_scale_reduction"].as(); this->params.hip_scale_reduction_indices = ReadVectorFromYaml(config["hip_scale_reduction_indices"]); @@ -334,13 +375,13 @@ void RL::ReadYaml(std::string robot_name) this->params.dof_vel_scale = config["dof_vel_scale"].as(); // this->params.commands_scale = torch::tensor(ReadVectorFromYaml(config["commands_scale"])).view({1, -1}); this->params.commands_scale = torch::tensor({this->params.lin_vel_scale, this->params.lin_vel_scale, this->params.ang_vel_scale}); - this->params.rl_kp = torch::tensor(ReadVectorFromYaml(config["rl_kp"])).view({1, -1}); - this->params.rl_kd = torch::tensor(ReadVectorFromYaml(config["rl_kd"])).view({1, -1}); - this->params.fixed_kp = torch::tensor(ReadVectorFromYaml(config["fixed_kp"])).view({1, -1}); - this->params.fixed_kd = torch::tensor(ReadVectorFromYaml(config["fixed_kd"])).view({1, -1}); - this->params.torque_limits = torch::tensor(ReadVectorFromYaml(config["torque_limits"])).view({1, -1}); - this->params.default_dof_pos = torch::tensor(ReadVectorFromYaml(config["default_dof_pos"])).view({1, -1}); - this->params.joint_controller_names = ReadVectorFromYaml(config["joint_controller_names"]); + this->params.rl_kp = torch::tensor(ReadVectorFromYaml(config["rl_kp"], this->params.framework, rows, cols)).view({1, -1}); + this->params.rl_kd = torch::tensor(ReadVectorFromYaml(config["rl_kd"], this->params.framework, rows, cols)).view({1, -1}); + this->params.fixed_kp = torch::tensor(ReadVectorFromYaml(config["fixed_kp"], this->params.framework, rows, cols)).view({1, -1}); + this->params.fixed_kd = torch::tensor(ReadVectorFromYaml(config["fixed_kd"], this->params.framework, rows, cols)).view({1, -1}); + this->params.torque_limits = torch::tensor(ReadVectorFromYaml(config["torque_limits"], this->params.framework, rows, cols)).view({1, -1}); + this->params.default_dof_pos = torch::tensor(ReadVectorFromYaml(config["default_dof_pos"], this->params.framework, rows, cols)).view({1, -1}); + this->params.joint_controller_names = ReadVectorFromYaml(config["joint_controller_names"], this->params.framework, rows, cols); } void RL::CSVInit(std::string robot_name) diff --git a/src/rl_sar/library/rl_sdk/rl_sdk.hpp b/src/rl_sar/library/rl_sdk/rl_sdk.hpp index 37761a2..51ab6c8 100644 --- a/src/rl_sar/library/rl_sdk/rl_sdk.hpp +++ b/src/rl_sar/library/rl_sdk/rl_sdk.hpp @@ -70,6 +70,7 @@ struct Control struct ModelParams { std::string model_name; + std::string framework; double dt; int decimation; int num_observations; @@ -133,7 +134,7 @@ public: void StateController(const RobotState *state, RobotCommand *command); torch::Tensor ComputeTorques(torch::Tensor actions); torch::Tensor ComputePosition(torch::Tensor actions); - torch::Tensor QuatRotateInverse(torch::Tensor q, torch::Tensor v); + torch::Tensor QuatRotateInverse(torch::Tensor q, torch::Tensor v, const std::string& framework); // yaml params void ReadYaml(std::string robot_name); diff --git a/src/rl_sar/models/a1_isaaclab/policy.pt b/src/rl_sar/models/a1_isaaclab/policy.pt new file mode 100644 index 0000000000000000000000000000000000000000..8dfe1ebdef48b631e1c9aba6aad42ae928948d21 GIT binary patch literal 172902 zcmZUaXFQf~*vBO#AuBYHlq7|OxUb{5X-K7Lpn-;_(V``a>@8$gh*Tt_6z=OhZYo0R zZ?vbDwgxS!9?#q7Ip1EduIqCi9r6eR|WhMUKQIHrRv3;A*7SDag>(~0P zH8!!EsVuSb|DJ@OlC-U^2KjP(^6ZaBvv5sev(0i`RoummT{wehqGzYncpJ8iA`Ak{WO>kUC1unA3i~RDH>Ur)kqfTWrG3B z&O&vdJI-*lpr_}~kiGjFbiDe8Pqr=<+?$>O#)li3TU0bXGO)w`&lOwYs^Eg&Ko#)j&^?9SD8_=5@MQ03?*}AupD53fu=DJS@y!S~kea-|tVtW|_uAM@q z*g{kj*RW;zURb$104KgajaL+&^QR#Iz3dm#_wXrf@3%_09eYPGe^4|_)Uts8wsnx^ z)M+ehqc&XWtb)Lmk(}+=lWcb4S1zsG7u;SwV>1IM!RFv@NPe`3X>J&Ts>A2eqvEBc zAz_X!FaFTqr13a$Q-{btwhIomOH)(MWXP^=$Ga`Fm{RU)w!?&~VxpaLLg%NySWMnATBTt^iV1`k^{&`_E1ErapGPmu-9dZcxtifg@|2%O zdpgF@ik^GqW}mSPe(byvUxtO(LpKL+}X4b+(SoxqS{VyX7W3 z@xcXeY&(t0yE{R-$&$K$++w;5F7U@IT@=byEZ zHEn#tcORSx(znKgXTlU{y4lDjZkHk7(VBwPVV}tCN+`Llzt2zYjH53h-ehbu3b~vx zw)ST-&aTr$`Rz;Lzymqq4dpsW$dus5I4z_XC7bvkPZHU&NtL2C-E!g`V@~tQ1;?@J zPBhAYe8ySjE`oBMBs}9{iSh4@kRNGp{a^TPwr9>vto^S6lU!Q4N`pGKZMY>gzA}J@ zwG-(?@@B}%6M*v#Bhk^~ySzfnANV~y3#xCeW|FBw`0wftw#McPEt63Y&y8xK+g2tt z%-tM=_ym?|HV6whf8~FjJH!4lcN!TQ1&a=wqi=m4w*M%mSsfVz_3OsA*BR09#yIpl z)``D#k73ZIbtrj5l3XJ1fsM2#jZIaej2kkn$h?$2c^ZX)>zZ{2acES zLH)b&lxHqM`-jb8+J)b^GxvHnf#1saBw-mp)KyDhET4XT!l9 z8$8*qEG*QPAzLkJ@}J~FTYeOBANH(5mtSpkE++}3=j7qofZgC(XT=KM?Zt7%M<{M| zARcxtr+8S6`H~`*>UfRHtJmPf_DD26(TMj26Vc56FeZ#ZRLZ_UYNO79dCxg2kE>!c z{7R6)SmvHoj{kj$XA70W_?<@#xxbeg?>euV-CMpBf@U7!Z8p1d5ktp7mCFWJDmfbl z&kbP-U$4OVgc$Ts@fN>taT310JC;_>)rV>KW0>5tC9HUyKfXOYp3QuJk+QZ2as3Kn zj9q*H?GJtc|I=T&yCXx1>E|%Z&{~L4v;*B+?r3a16hGdtg!ng=ID2P3`&@Pghc&fv zvPA|c-)fJ47InZ%YX?+F{e@P`Hi+6C6xpRYk%HSpGT~Zhv8ZOnA+}Vsi*>x~w=xpv z!y1WD{!M{V4Zkdc6{{q$9doqkxpoKB(1@kfo|W`IaI7%=ZxR=_R~-j^+zIj;B0SJ$ z0~yV6U?Szg#^kC~&s9zOv$_QSjlRQ%HOym#(manMp4oNhZe<4O( z%D{acNtipW7v0|e;_M~za0isbxy1))Px%PZDq$fgo^@tV|GUfHL`LJ8D^}c(@=I*@ z?v)~iBvUN<B%}Do{|^%gho72_`{C;?(Rw-b%0LyJ%?qf}QwN89b;Ri#({a`C60)x-(mPSg1*6|zkwiHW&yKz*)i*Nv*GgANSM%7B-kU;V>y8n zSo6H2f<(`9R9d)f@+qfdCX)J|DE{Ztk?qdv{I2P`BXOL);DLsfOWg%w0*sS1* zk|w5thrddAa+J~PUBeT0M#_leq^a7pJn+9-O+X4#zs1?zk|H#8j``3ZQC zUx>^9Z@r%1V zT^^ey)39u4Gk#7yhfZT;F){lQJurL-Js}_2s0FjwRgKfIQJ_g8iEh?7Vgx^2j^`HX zoo6yb-S~frce!|Q0GngK;bzbhk#*5S_AJy;{LgcZFz3q=RyloO21qW%;Mck^_O}X= z%p=aj+MMj1i`l9{=b+%=Z%#LQJH81RN>@}P>7-;D4gPTr_wK4j)Q}P$KW2#!*L;Ee z!*@Bi2n$;3{s=tQ9D}%f$#m1ZkVP5#audDn(Z?_kISkUc7|+z(jDF* z@iMp|+_tRPOOrM)*^h zpPh=y%~}jh)>)T%-=!gP$Dwy$1iv_4n^|p(Ma#rCzUJE{W)>;HV^X=~-dh5@W*>!z zZ%)t>eNQ^y_6j@)t)iBDx)friDBO2^8{MDv79)Za*{(ZBaIeJ(?DSZJMjO{)$|DCH zH1#|#R}RABnf=heuolSi1wYn&Jruatu#XeQ!zuM9PPf|(&b3E@Zc`(7uWLC}$u45Y zHOtsr-xGYQ={#Zl^lv!kz#8QIeW2Snktv?oLV72=>84YuXr#+h+~0SRb(*|lrp+ce z{&YV6S$`7?)e1>9?J~|>G@dN|fAXRCwCQWcUXz-8(M6M-U)VQnHo&BYk={#qv^(*k@TQzIJYK}XaB~jQ=8gMu5wEb zKjfSV+zLpAarGZqV)b{pSzIGJRbPP;ujkT+eQOI|Q}MAHsa)WW0O7 zneN&};C{m?0?U%W+=<0gsln+HWgl~72BS(*#kK%4qMcd9vNZ5+&%(V10k};n9`-vL zvm@OBu=~L+Y}UvTh?eEyRTxJ8wIhkQ@W76XlPT=pVhmaJ8Dj5GU?axWf?8}ipKY;_ z>xnuGHGc6-{)8hR)qj;+cWwl}a9PZ5<>--h-5ioBJWW||&rsN-7?dqp4=_6cqZ9uDS$#g$#Bk`XFaJ0aH_No!r(_q0?<%cjk zg+a9XRup#$-4Q%MIM_^PN1^ZYnw<<1%Ywo?k5}v9+OUD(6 zkw|7wCvT@y+COpUv>2!nsR-TYzQ7&vDLCT0F^0XELbBV}qn+Lcdb=?Mt_G^n$1@jk zxqmc`eP~Ug&-BnSa|~Q@{D@QQqA{jej&!Y#V%EBw^r3{o$YVdj*xZ)l=lq2~x(cXi zzk=RP6~OoW12}u~F~EX5UO3kpgUV}j_+H%6BUKyohOl^!3=zNI~a6U)S;Zl zR!U5;rInZ8K}CltHMQS^)8esYHe)!xI&uUR+Ko_XKbTs+bhDlQ5!|Jf#e$FPzj2x; zW;5;eQ*d}#DDxKXf{2|vnbG#k?7Vk7U-m2s{fpMttkL+%+m*IrV5On8aXn@bWiFf9kE`0+fqf2PDJemA@ zpHuPzF|PJ1Wo91+4{)3pB5tQM+h@28mAj(g-N#<$ar-_j7XD+Qp3=gc>t6&JWjzqR zP#Sx@L*dh4MJA9u$V}_cLto$+R$UnhyE2TJlQ@vFx{F|2jS@<&+zAcNIaGLZHu>Mz z79Tl(9||=~xl0R=Q+H+z1xHll+UXNXE84gA~x;WfL7 zbTVi%cDyT~-RoN^c)@Fwn{-B`I5G~SFodiQe4*gh=e*g=FZArfW@z>Eg=Je);iXax z+`e^_ZR_)5sYfpG5+5(ILAyIdhduhZGvDnX@{c6^$ezda-@SyH&m&lHo+|J4QwF_b zzTlVo!D7REv2@|$VEkizwPw!IKHgquDveDey!_-VyxKb-hmFi)-tE>DG47^lrlT_J z?n=aea+<<2)d(Etl=ymJ>eN?zi zBMzR#W1a`lS>6>+S*^gy>t^8D?^SSpk1nMSy8vbCd!b`OB(GU{pL2e(ms4MGnb%Q0 z!#)no!&#s8x%G95cQHZ2Vu*qA*_9uJnvTh8kYG#7fdjeVe?}@ z!IK-_Y}n6sE;2#Lb;TayYAZYW6CMssB6TuJunuTCbd*i{u^5G|HhAe)4zzq7gDTp0 zY2S^LAZ5ciXTRaJL>(b?UM34S^Tl_s|8fQO0!*4d0%hhDLwWI4T(C!yqGx$w%S}&e z$-hjaQzDqa&VuXNu70Pup3196x3Fgd8yMbhz&x^c(&0OpR znw;82YPZwbD#uMsq~c6UG9S_2Et`Du|8VrAi23NgX1}>B%r$QTYUP-6mW3n4*Nn4h zGA^(A2b7n9%C53aVAP_l%ejMTG%?D=T6)>MsG$~;@COS_#H4{F#5$u+J-Ryi#*#X8^8r+=EL}fZLsQzD)w*LO#z2g*{ytr z54>jxe}9`xN`|4>cy<|Fwb!Au+vVWUdJWVXyqj()H-LeXCB99|z*4G2_brY1Th#7I7(KH7FWIEKBx7=!nqkJo|r@qLl={_#0mVMA5DK%N70Ab z2^6CIp7y`^1tBrHjLcV3uJbv5$iVWj?$it1x^^6`wG6~(RT{Wp&Ovt2M@slMRg*%D zUqSDNT~H|?nRa| zM~(^iPZizs+0D61PrwO*r|7W6Mf@XWE;hP$NObAlCswAm5(i}tBRLO8TBTA#4i`P) z;b~oQuR{v;bR1x(mW(3l?Gh+bQpV4JHE3cthk>uAvceAw>Cn1*);N7DA9PXz7nTjM zlckpQ-m#7z#W#~x)_{I@(#AdoDSFgzO4IH~fvv@6tFAaz&a1DE8?#MbB>7?zJGn2C z-~2fg9OQ?yxhvnZ(3m0I!T+rJnX$+{rb)D8oG*r}_d`QSB7VbMYPdTRTR+SN|H9cA zJ5PeMxYWpO!&@O&O9Pp67~6VdV872z!M&@SXiZ2wTk+#G8q~BxetQJ&$sLXd<|b2a z^F`Xda|vbrI)e{lzT&4BCGbaf6t8*c0d{pAr@+yz^z&FbT#?()%FT%_@lwIROZISe zgE;P~MG>p1ki>YUO#(QO!u|ZN%`MOBg+bCuOj~g&x8U>wW;0qw_<3zF`&BzpxV_{u z`TWRZ)0al0^x0*c!7gWPAGH;qsH`UW1DDyZL#q79xMN^!dK&lsQX-SKP3S7Cjc2cJ zz{mA*sB_7Kek5(A`OkXLJ@*|8zA_qXb(84OP&r!DnMz&rud}uhm+@FsDz4t?gb!X; z;t%_1RzAY0Cc?rABInGdT^=Q@vHU2Xer^a#dniK6pM$V?Ql2QR_aA#Y^${=As6zb7 zFuH$jDHayK#Z^B_*q@P0aonNd;wxxLP9arHd)--V{W6XYjDJ&)cmnpkJN}LbHpv z;hcs%9rJw!k6Tr+aCan2jorm=y_v`g?XtKhhvK+561s5ob+eWJ$Ysp;(s!mU)5$$N zqYC!B?{b!RP3f3H1aCI{Hha{jO&nK7u?6qoN7Wh}lw^-TPKI-7xQ$Ngh)J*C3tIFP zNU?b(7g})|=MK3AO0xZ2@B1V{xl#g(*PF06ftl!0?1Xcif3s=DXRu|@aoXSdUi5rl zJdp1fu|&ku*n zJ!km(4Q2eKuxmJ>rHcBK*1@txI_&FGDf;7k0_~32ampW06Pq=LxWYoZmfZ!y_ZQg6 zz3I?2)^MPS60Mzm9H#!Zp%(KM6xL!zYpz8>+Tn?G-AtOQGKP@feH~g=u1|7?)%=rq z6F&aD8f+e<#y@qEBcDc7(3$<5Df@ikdQx)W^QGOeV$f?|!_x_M^qaYNce6=Dc_?nY zQ%r?t)Nuoi;NP>eRAKy?J^kv#Lx~N(-~O9@oT@@oHoc&`I(3+Do`vNTUh|K?zQKSE z3GA3}80zi61fpT5=;U0+g^Ztz+12ZqbHE_-oHD?q$FD2_r{8sG{j!q&>>tYlqW*B^B2~I6Z_FwlJJF_b z=I~#5Dmx$l3W7Xsac6KRXf`dueLF)~ntcPOU9}kJTiJ?iH9v^d=I&&lK3`+c=g4B= zzzkZe(98OFC1CXFslr)DH{cQvca(bamg)3(2rjDcgYGD0Y%qRC+L3#(_vFA=clARj zqgn_xIYFw$E?}G`WMOYs^UYs&GOhK^xFWa!l=_db;nRKT+3iF+c{>jeum|w=h$(H` z^%nbnE~j3XVA5KhO<&gfV|2xBmU~2&vID}ogx!aDmk)VNSfR#J507Fw@|N`Y!W~XM zY`wtc{Z1Gb#{F`3|uSR&XufrmlV%B0b3mQTJ zMsniw<;aRZ@Ywo9mpz*E1&YGnK-}p11SLRXp-I;`MzfWX4_YJ4}?)K>Q zJpk{;ctfFcAlIQ14IyE>dHp%UO#7 zKen4oIh4d=N^kLjg{d%YQ$4FGzswI$91GFWCz!0o64?9O2Bc36u;ti3y5nC4Z|2@5 z_mOY;vjIQY)on9D`?^%}D9Q^TmYzxk{HceeJtHQk%3MLR_*)H)>v7hZD0 zedY})=kNq4EX~IiZTr}@s$*zfbl$r3T@vO=++(R@_F|dtc6{0_Dc;eqOj9-2LhbA! zc-zsASN3scUP~%OqqY~Z*SiaN_r>zecl<@>n0!@~!DsRT&Re+5Qy&C%hC`|A>~3;_ z7}~qv4V2d%XZ^-+*`+(*SzMh37kyh2qLFEuBH21fs`Uer*T-O|uew)U+f6jo;fEG%L&S6`YTw}YThULB(OQWxz6r^Wu z!2I9EETjLz)>rPhGj}F;|E&OfV)Mx1i3dIL z-+|ui_VLd5i=kv|GTL9w8DM6m=pNGxSw^$)rSCoPe_)5N`pa2++kCk8<|W8fc;bWS zM&cz>=a_b159&7}R%W!p4gVb0X1=F%)$NzRd8t#F*V9u>;qg__JXS*9L)<7vY(kG0MTu6lUgyhib+P*m z=RjW}l2xQ?GS#^=Q0YHY^q=5KgS8$|&*OmSMLBc9FQBRp8@VfX9E$7fzO!#KURcuqr?i zK1--k&01f`z3oEdJ|4ugrjG9*z+a@@`F-)Etd-Cnn;xEg#9ba*(*q z+=P2A{hXaT{EJ3(d|e*mf|esD!xSe4fz4_ua`65SZl2R*Pn(ahiw}6_?QyZD^Yl0Vyu)GkI&CPLp0yBZ zSC0ZKxnz2C`!3p_+9;khHj4CaOecf&nT+jRga<#JgtY<#dfa&t)2_T`;hXQ`>c&$v zF>MVyc=-rFu5ULz7@Ue;hHGf)m-k%TJyis6qC=mxV4VMOdRSaTLVrhkl0(!q^!Bk4RDE~uRQ-wPi%5w2E9yCCe2_a$gKJRUt$fwZQBWYnLQYu zx<^yM(S6+H)Ca6}p|9Y$z9}tEFs3z+zu^<(Mobublqra+aE3w#s8)Io?i4btRbs~@#^K185ooCE7~Ez_DMB^;5cDONmj3Z}Il#|I85zTBZkr;iS&MH^)? zS7jNA7mtSbpU%>XGl@7hT9?+^Ib+TpGe{}W#<4~NtW$e4JZeZqb1oh4L@q;bi+OBa zsuRS-O9=nX48wP0)$z}l$!H?e2W~0XM186wF{IuS%jPB^4wqm@Z8j+!kyu%IEiul$|LfqSRn#?vVW&$sy^qtA%^E;QVH^>IrL$PQODj47>o56jb8f`DX z!J7rfGo$a)aKrou=h3bJUkd}d!AiHe^rc$t^lt;UZ~GH|(Pe3Bn5M>-sz_7k+ys*J zTZP?L{+O&%I- z^TuM@=lT?ug&ag%rbitO*C*{&FNp278YE~Wg9#G zpiKW%oSoW>@2BU`jjS~Ko>k38Cw}0sh|A$;-Fkl0-Y+<2@=)9 zlk(ohVyg0f8lNlVWjlV-i4(uE^4K8keq;tEKR&Qpc_X%`u>ud|Y=kA4O7E`4La9L^ zpU}Dp!`jfLAsrA3Pl>0&*!iQwi+EqDd5N*ry z#7}rHiM{Z!VK*$)<6uGfCir%}p4*x{jV$gT1Ic4uY<^l9XVNhY)^uglw5huhZ{?$1 z-)H7*E;Xh0@$qQ)>ob2S zt&xsiy+jv-T*$0xB>#Gj8+iZxK?<_L=#pN{Lb(vKH15D5iJkDpYa!^P7KDJ^;HQTysDK}=J94H9>a0{kLz*Mt)>{HZVF5q-6yEC^Jv~*%%RctD2_`DwC zC9*MZu_Er6agttAEe?n!vE{WD=xnx~&1)2r`QUoo0*vopwg|nmO+e|}Q>>dhkAe|! z=(97}qqPA)1l9Ai#x~MmenJTQ^xs_W7l3egJG25P_0u?TD z=wn{MM#(ma#(asut+69v${I25eWFUgMr(+zmfK?ayrZ1V%caQT-0|+SN!+3i2A10$ za8kd#u%>4>*YzkLwiJd?(CJ{lAgC4#Uw>lMYQ;X?ILz{on&a7%BN1~C^DnzLqYBB< zHKR(L6mg7S@t~K5cpagMN(*qqq{sYYTML@3KN=H{)Pv@l7Fb%8#SOOyc-39aMnwGJ z^3KiXM~_}Ju~Y#1?rjA2HPjkAIQ>l@VOc5V8;Uo_ykLJ0_i;w2htS7| zuDHm2uuyXGNVYptN|>@##6tg(;9Ri|dET-`{evaw@n;WzHE$t)l*-^FGrhrSp9}?! zeJdCloyD}A3?Y0sN?yR{wah z?AH6>)-sny57D3%i{hZ=rZgs%Ao&`XKwLsSHmy;hp@*2X=LNpr~^ zc-n5wZsy3+Ye`FN+Np~<+Rdc9svN7Wb7>z9#@l=2>C0RN%Goav*BEZbSMh4XO$)z+ zdCgGzW@>{$7A5SsXQ(Q10@p%eZyjyc4|8O&6o^rL$dj2 z!D;MK&St){?Fr{}%?3KUtYPfOLvYDToB0QPXYw-}$#87}=Up`r_#2`~y?s9X#s7BT z>QheS_oA5pGBTMGQz~#l%@KU#oWt9%loCHG4`z>_SJ9HR|IL>!A=O_7tgC$iF1?e? ziY3CydD36jf7*u0-;2l8doOvtx0|SG_hoVnX~3c*@px;1?cEnR(!cxuXz)vlh4l}n zpu7K=t$s3K-2?7Tq8kLnIYQ^%jnLaLo!txcgzTx>Y|7`)f=^pJ8Ml5m>Z{gag5nc0 zvs^)TyCkXDaRpM{RNB-NQax{TD&=;)<`id0(45zvxZgpJHJLYI#zzl)dCMD~aSOGAAru&kA#_z`Jr z%b!)0sT0jM1++60|3yT$nQWBuC^peFj_E3`WpmmT@ZH6WA}jw*%zUF9a-U3D-Goc5 zzU2YCSv8*0{_2QLeDs9=n_TH+#Slu)n9KiuydP(rxyItkQ}APn962hUV~M0plPvyY zKi_8X!DUvs{lG6?ulXNPu_PUt(~NRg3MhI;3&1Hk@gtR&I4toh>kBZWdM`Dx(hPUZ zdzpciQ>AIo9wYS7xd|5|qj>+EHEj6sG#E+0nUu8zygF0KDKrV#p<72;e`!41mysa& zzBQ1=n+;)|zoqa?vL5LNsS4lA=F#!)jciZraricWJ6vK=hjG6?&fEAYx)4f?#=fjgc0o%y*Mi2sT&gWg4sLQ;Z>(>(?5 zPm{RsHH9B=xUWB|G4 zHXzYo3JKZiOl89uKG(jLFDxDn_HjpG*Uyo7{OAF2;6Kn$gQWw^UChG%$?!M(x8eQo zZnV}-R~S^hmHqwwp2c6AL#LO!BG-M9{`ARWSlx2!+FgK~4qjqVw1*Z+*b3a9ouUPf zZ#ctWQMkrZjt;g2<2nUx%HEeoV`5M80UBF5<<*Rzu-cj)wv7~jb+|@KerM?1{#R_m zz9-z!Oef|qlLUU6;W9;->K?|`j5`3S^^x3rIZ2GR ze@8)-MK}7&Siy{&*j_XbmS0F_M=M>~)YeYk_2w_uEKH)x;vD96U6~oGr(^HZ5J>HL z#2yXggiGS*(AS))RA)Rj}eF9%9=j@+_cb2PZMSga51emb1^7qA9;B1#4C_n9`{Pdm;@e za&UJgCOXpyUFb3q@weaPE1~}1WfD^9l0=GV**a5}{>%Z}yvj@XMpGG{G zHJL8Wi{%1mXkdtB3=6tk&;5qGpiu7$N#cVv%YQi5Ot++KmFD<9{WSWj%)^9J=P++( zIED{?Ly*@4bdHY+HB*WPTze6(J&#HYlJ*X;tEXVxVx+n>_%t@7~ut}6UxVivMuAZw^M3@`Q^K%?3Wynd<*_huT=Cik~|@1qU){EHu6 z|1=6h_GHoNtqSa|VkYhW8_L|+U9NMRh`qB?rZVku;xT`$=!sSsQ&kONn+Ea=bq;s9 ziC1+1{xow=34QG0Y6X?shUMYxeqj|JBZIXD@ z9!v38pVNGGuQSU?{sG}~(U9@b2Ss1wz`!ORzp9*OCmh3ZuT~%JJ(GiFFiLC-E8x_j z(F5K_1{&Rw5#E?G46|lW#{L04;xTSEEzKMvd{z05R3DqrxmDvSCvrL|-nofOM{1z8 zff6c>%Y{JiJ-jI3KI^{|2P@_m@Jl{S=c-Mwa!ENyxoNiHaMgO?otCTeZfh3R7`*pq z0UBZO7~ z3xk(uJsX z;}U5+H$sa*B}%v+iBA#-39n~eq!{To>fSdL{>nFSWs^D9u{RMn44zEgD<9CW>)&zE z@iNxea~JxJi!&N1Vh&A761A1)p5hRxF?#UCCF#eO9ffCYKX$}|;LLMpGTG#2J+ zRWXSRi&;ueAM1O|3;d>dfXku3aPgHI+W+gI!_Ds?r9)EO=Tb%~XLadmT`Tje^2N%K zQFOqzA9@b_VZB2V@vvDI(-sb83u9i;$pta=x+k24@vdmmw}LjRKVaijWrUe^WiZ{- z1!wDsS*u$no6?{zwmtNLWDF{3O1nGs+#g2C7oO9(l&g#zYC*D7TVd#S1|1ndl3)AS z$A`1|r{Xk_PQJm~TG~17=NH)T1dPzu$%QyY!VgXW=hbuUSMO2%{*Y4Nq$rli#TkezfZWxfe} zX!nh9HthEYHhokFPC4#DP50F)YuPilIH~}f-q}*hhdY$BSW>uP&;_iPPr*I!idfit zd2!g3WDJzK$8OY)=R@6fL?a~In9`8(@Wf~VRO}f73b9L|>&SF=BWVj;c3=ee@2omr zKO%yC3-_?nS%;`y(~?T{{;}er!4x@xBgqO5QzTR9$lNiI(w2{w7m%v5_S55IcDQ3m zF6~l$i}#)-@!i?Au<>mU`8OP(=RZTZmA{Yk!f$DuPF5m)4|~gPUh#&{?rev;4H4Ki z!ls3%2<~4%#)d1^*Q`@#h+9X z%)u`{jgH5Cfcqmg@y*wtw5ppyyw4r@ql zPjf2r-$*NO{ba>YyixSffsEx(viWi+QAaC=;y$Qhz)MBs(=QD4xoP5}@+vr5X24F$ ztb&&ARCw_IFnd=OL^DrrWhy08$xd2PkhzIxfhiT#K0;Gursa;+$vd%ea{$}0Uye5> zS=34>=4VMIvm2f-xZn4BIa{*|mh;WQTK4pLnDZ%#u?x~5bn{^w-%E&h-znsG`>5gh zmle1%b{byvpGGs1!m;yBAR9VKTAY}ri(77$;MSpwajMK z+j)T0sbtaCJ$K0PkR>x+Fa$MDIgpy%UW(03BE1>m;5KCw#dz>=b-4@^lzwJ;-%n!5 zA9Z?awvgS~GJ&q`Q5KN57tCkV*w-b0xb(!qurKQ=`!C3klgaPl>V8|m?mzoD#jOmN z%pZ@^ccsM^SBO&XwUWx&Yn<$o2ofs}7f6>L!p^hFq^6&ZLgV|iL2@u@2z5v%zye24 zGNGb>a>DqoT+}{Si%rc&bR=DsIrK!ZH=n{#AoBpzUWemR*_9MGB@Ijro0&q=GkRf> zgh4G+>EC5vs{PsvgGJI1KRuTV+8qss&KJS#V;Cp9UxRg=NaaHs+xSHR29(h76t3lt z;YvdzA+#$CW_(hjkgF&xEl$Nk+KG9qt+D^G6Vn~=56rj8?}@p`aox+4#UTL^RWSMF)FzOGv~YEvwQ_QR(6lck1=QRu6C?Fc%sln ze<{uBye=@U^~K{qPI3}U*Q2)QXuKl;OY2Uw)=VwGtQpQ|9YIoHVI#Hn+{E2 z3sjDaP{N9)Dzy?swj5ew1XcVAwjpj{t42uOxUTVi(s;sB+e@+ zz@4)SXoN5nv|sq)LsKu}^MA1Pz+n6llOS5%*^a^+uR$341ojW?C8EvGSOzGI-vu1N zROcl0J^-vxC!XfS@G@NeC z<(n(Rc`cjUP(S}H6ME?|-Hw4Q<3fu8PtHQ1W#%HzxLk%i@)PKq-wV*Qy~3LR4%9`o z9bS6j3?~L{!lNCh(RJHwq1Nb3?7tsF6H@JIl3xxP1jyqyxkEViXeg^M+0QR88SsH5 zBiQs8``O(1e9YBQrChUljhPDPA{L;5*)LwHAQH$$ z2Bj8XWXoom@SDC|f^?Oy@a|A2JUl-~;3xTrPq5p}8eSB#{GN13u5MzZzecjrjzaOO zB~s!gP5taOhH|Cy-vyRYkyNIWO_k0cScX;t_uBF^ZTFEQSh0ID@{m%b) z?|;u||4RpBG(Z0d!cg`RNZjIsD} zg_zrJe}fDDWG6Q8HfG(blVFzjRNgUhr|4l`E?KlmK&1lqZ=}Ueg>Yx(E_TvON6D*v z?;ZTPv6m?xmIF1NqwLY!Tj1@S!U_%IsU+b)TBRGnv>w#L2&)I|rnGkT>(|w&SCI@) zEc{SoSS|FK_i*wPlKDevf8miw4XA5u2FbJ*?n>klG8KHAi-#=vzsaiHHOX8$IoAQy zg5BVfd^@i?qYiD$W@2c?e3tIJgk=mphF=t-FcKr#(n1+dt-YLLEJw3{nmSbUb}Qy? zm=90RD5!iOJ2%@4&Nqj#%us2YnYxGQ;3X534n-z?e*rY5Uu2x< zJ$Z~9h&W*j{_rr*1gw4BWAE|w+DX@);c#UP5 z6n0#_dcCz2{yILOI$kb?xnB7LCqHPz&;(01wmBM$(#}9@@mpFO{ux6Q^f0Yg5{?}c zVYJs1_UmChlhToADiRD7Wwo#<&xVcrVkv%-rhpDVbn*F^a)>b4$*)S4gg!M9zo<4( zym^5m{hs)WD;i?OD-DVl)fwF9HEaHoMQ{hMYl*b!NRqT^2yDUL9|MHwVF{@QeWg)6 zW1AX|a=(Sgdij@Nbh<6YBC}sWwp1eZq>C{!DFyx;SAfNnr9r091>{X)`CX5vz|Z{q z?6*>aLF-zHWO+2DLmkz`f!n5)YZ0@q8 z^sIeM$>J)1biO^x7QAH(bt6$DVk2zsoWorop}Vd1Chvt>Nu!~P-dj+O~c%P6B z{`DTs=Fep*H*DGb`FgnCFQ07>n2Ix2?Sc2f`P{@?dvL0kU>2AY~JKV8E=z4syUWgOAA5$8CPMmMP4u|wFflqS9OeAzVH)Pkdk8x3$ zQ=-Y{Yh~ixv$9O}j4yR>OM^tSNbvB{r&Z?<^3smCVAhGD^eVcB+rO%S|J|(0$UsrN z*d-I4yo79169<7UMmB*bBv|`$L;R#)4-ZpQ#8)GN*szhq*r0G5Hr})hEwB1wg-#Z} z9e|!t4u&7l$W4tzeBF69c&f?#e46#`?XE5{JH3iqkZ4vy&RFsI226Hb7*s)>fB3%N0nphT44&Vj>tz@C%`=`$D;Oy<=kUSMJjmNPLq<_IN390P&i!ZZ>PGm z&=gm4RyRP;s{wHFu`@}_+1f+}NTT~TcUJHsp27G=ayIzN`Mz#di_KZ;edDKxVE1j&zoNcHKHG1$TfT+eKvyqHk_){9%5 zQ|~#@>bVWuL#iq7wGTL}908Z2w{%3h8s0@SIC6BjO~m)daB{6=_2FfXSjjEJd--|H zUv!rDGB#%k+c&e^_0O1n{T|+LUlM;eQxi?JRBfV11=GgXAiTYEDcvdTw0ikwEDQNM z7=F&02En@+W?SdMH{)I6{Dg&k+<|3ybcYv;KeS-##3FX9X)ynF>@PNdVG)E#yK(A` zS9#aQEZAf52sRa)(OiQz8h-aCul!>QX>2?Poi2N;Mg@K3KJ$ku+35$&oO++tz59bz zV=6K1#Cm-CCXea1CxN(G0%e{{@(-fw*vrIP7WyEL6vI^UPP!%ADIX2$N@+MU^&hn^ zTme#34m0hGt*rU34tY9Bq2G)YY~NAB8k~KsEjSTvi`!0F*8Sw`Rmfe7a$pY>CHRcp zpP{EWm6tmATU;$w38hPvp{v}D?|qZb?T)wscb|FCx6)$BzG)1GRuSU*jZN_O^gd?v zdn!0*#L?E5L;22pZJUCNwY=Y^m)z~8%Iw#;TrTdBV)goBF&-W0$YO&_82{rS+aVXu zWl4R2EItY%2n4ncG4e%K&>$U4@0f?DZCykg~tsqh2Jb5o(%U7nnNYOuN~(G)!Y zJXYMeEavt}R%>lNOnJlZq49DZwrgo7+nCeBnG{*l;b#lr>M($J1};#b+QnT>*Mr=H zhq;bvQZ(?~c0SU-0j9;~qt^2!G&_-WFnPe^u+eNI= z_8vZMlVr=T1+gE(8gMUrgtfncru!x_?}jv9eVLSvaaA#(EB_BZPB;$HOpf_} zNW?(z9&k$d0qqyPan*>SI6~h6<^1=fzGO95yxAA8YQ*EY59Q>1_AeiXwX{QJ0o`~w zn;+cfLRk_4^qKS^_P{-UepCau>(B%~$Ik#VHP7&$)N)v<)?ut{{yZ|up;m!926gW~AH@fbpo7I`%^OmC%Ki!#*=qCN~oWm_oKFjPr z88i2vEnqwIoLFJYF;-J_4VyiFa~91hP->vWYKH!z52KEP#;pz*+E)qoet|6D^!;fy z3h5LZ-a$_!`nW!m5wO7QD`)X)8ok^p%l<3)0`~^z(z2b#&@@yY9`*psU)xK@ey>1h zNgA323}YjM-B@1u9fpDjjhtPk2 z4>K-2%+76%qych~+?UxwEdNXosQT41iP=wKZb=}6b%RlT{4-4RUV=l`c5$uEkHB(? zl+B|c1<;$bjlcEh1gB9vj8WNac0Twp4c_vKOVb?8q)%#crn&uK^7=WQxjPQ#ot#hc zR}O-a_h|NWbu^pnmOyoLsvk+^rg3ft7X1{)73U8PKxoath~gX_4^K?0B=vWR`oWiuiDFQD&*3?6-QA<^ob7Y4&ncE-wy+Qs)Zg+ z181_;7`8q=$a!zp6Tf%+AZlG~!goHE#hOhe)a+CYdsf}0);*HdpIVzRPPL4(7qnBa zXD=`QubnO3Qo|y*-GT?5HL&uN0=qd|hFqLFMPFVV6b(*$2~8!t=!;l`O}rt&k{2vt z=clSxD;@nw<3lUitc3^h(D+8Ac%g$IegN4Xd%C4LqFTGRnRb6P#+t3?@s{#?xF4_! z%iL_}n(#f|BxOp2^FwJ^#}n?w%fB>lQzRshde5cK(E&+`gV3FKlruMK<#(e9waq(W z`gpO;%F7*G=Itth71l%Q2OasdO{Y;OPPuyBsbCz{rizCax6tWg1IkFB&29_t-IE(* zaY)(#4Bk72S>?pT-Hhwxbvgz%9^XOFUz%XythKoL-3sz^IR~r9jzpiUG2)bh&oIa* z1?{7YDv!5?V`#Dp?w)iD;&T4MJ(~w4n>!2w^&}u^+Y7NIzg=WM8!}S^>&?tBVdz(_oO8GwY6nF`23RjkE?2fJL z6|no{aoB2F26-KEARj-OtxLHGi#P1!_Wj+%7Tz($V%t&-c^1yj*N(7pP%RN9q5~Gb z;V?Zl0p2I=;AW&3FssFT*wrN`m}%J^{>02HR9)1?$IRQ#X8aSO^eAQS+Jy+{eWphy z|0ZHvaSjBxFi`VYOa7g?G~MAOIV9<^(Q*g4HDjO9*ILEuw48tRbwd@|j4Q-O+c{MZ zhxEC187^>pTp3i@o*?rD`fQoK50icG$foMn1;4OZ{Kd)SF$xLXNqSlSmVbxShz?7^Wh{6_btKD zZxS{Oh9zL4xe3h~WzQuoFT!Wr_lvc+=CHM^!}#*DgZTAW1nb!%gA-iEggJMywnhe@ zFQ|pFyNe*WsU0>?TSjr^kKl;bJKp21GF9)m0@EZzNsiW#Q~5~JwNr-A{;zr6L#A|k z{}o0}xh!w%C`{u^XzvzGYp2uP4 z#u#wS5c(c(&T>QD$FQE*@nrV*0sq%}IeD~dpyKJ1FhTGMJEAVpiN_H%NIaA|Joq9W zR&x|n8l{Ae<5_m)K?AC*hOqmQJH+>@cjKyWL3nTb0O3BofTZeL*64qO!sjK3ZmN5+ z0SDEfz(0%I7rzr_Lfmoh*-Tb7#gbpY*9@kmM6edmLd>m+#4#09nXQyFs?R&X{@7ih z!0ksNVnh`8=-(ygGPoJqS{9Iangxyv6g2UzlhLx~B3#b>Y1OwkovJL(Q2aD?(orp; zoD)gl@$w^VD2j#w*50TeIDxs2aAH#)k7K^#pDft$E(8j`*}m>gWLSBTciWRh0WB%4 ze_|b5kn|JIkG_KoRy||avmUeEU#_C2$1Zl2{!q}f7jTIm#nuXIRIBVW42Q#Dt#Xnq zw>L8FX_8!*nFop&t;1=}7g%)AUEv+Mg6%spv$|GI60*eeAWdT+X5W*{<%wMEF8F8S_+eIUgHNWsplG1t#QS}6<|KfqB^*(isE0q1)YC#q7B0PC#5i$ zapiurtx&#t;`0>T(W1i&?`jKU&&titg~5JLz-==aucm9q(2{ znZil5boOMkX7u9Iw{jp#bwZm{gK+5ZdMv3vhvuX1vD}Ule!$`4s&&@0pkT8nJZRi1 zu8>rtFVhD@o@xbs3T&m1#>>F%dn%lA^#T*a3{h(LLzuBFLX=jw5#v3jZNB|3Kp!uu z>YHi?xOCZBW+*PBn6ve4ymcIEYzVk>@n;R*K8ht#b{J$Rk9E6(&>+^< zX7fljwnTn3J$YlqG@gwuJ_y{9{>I~SR213<+WPGw+J0?#c60iqrrOg!2w3Jg zp^9B^tfTb(A~tnQJ$3nWtfA!?nLZvu9wkhXo>z_PBxhN?-Vsq1eDxgbEgTCb5JNHJj*2=1H9=;K14+G56#>?Wr|ulBf{38OO7WPcl%v*$smflG(QLMc@`>jCnB+c*j+*g}g>J z4L7?7QzhDAmr*#|mRu@|oR(@G^HLXUCpLhU(E)a}PnjK?bsioBuY|6_vE0cQ9fU)a zs#Wq|G3i}{QR-O|FB!ZBY9sw{gKjix{B>d{hD~54rwiC4%X4gnLj_&#c}`XV`Q&k5 zg>7HFAND<22#?CQlKaL_q@|2$BW(?rALlNaqE=zTSm-3mQnmm@w2oA!&2j z{24OSlUQr}ovrGY;8i1%=s}tsn{@Wl=BNCT$TFQAeNecT$_s zA|Z>mkRRw4#IyE&Qt+*J1`P4POowFJNXg~}H7}S5#_ePH%1sBUK&ymzo+@N>-|B#= zl?%5t@Gtl3??;-kzyS{q|3$Zx8_+v#Fa)y+G-F>3cUwo9T{JCbKdN$Y>eaOn-SVA9 z=c?lP;V0PS?b_8*@k-SnmUWTFt0l<$+Y8LW4hmc(2g+X~;mZ6`TVC%M% zn9%)x{OvX8y#oeicLL+- zL~|nYAIP33(;jT+)TGvI+$u)t0`$-daO5cXc z51!POX+xVlC15uhu=8v^)c#ASWzB!dHp7`l=So1(9xZUyIZFw1wLyN*SD1WCgO$BZ z<7%d_V!L{Z`7=f$l+m3HH$&FI8tXS!FBHNdtWeC4kUd8CWXAFivlN(Xl1b&Hkz*+5 z-#&`+Z{Z%4RYCa@Tj4oA#Hac>afe2o5e>_j#|#w>S=mxC=QOtgahH4_+Gpt z@1c2yK01~1j~^bUt#kz3R^EYOuZ(ESI#-sSp1~)syv1?m4y?L75>|gtBL0;En;ZX^ zOpbI=N7`|kD(LjfLtJQM&|_|kkqPeDHJENJSjLU-+56P?U zn6*+JOJ%=vd$K#AOwrr=(tsP#mGzkKn-l`C){Uo9yF((Su6uA&eGd2V;#?*>U?Oeo z-pT(msHg35r8H@%8`IaX67>cvQ0AP)P&&>L#>xip?oPSft^0;p)HVi_!H%ibrSetV zB5A6j9Qh?Zp|#Ej{&)SDROl^`kP_C9aQ*+UAM^iRKNCNuaeLIi^P;OqSW*1DiU;At zx$(nIuvC;qkq1;^7WWlWHHNVllY2#H57yCs$NgO4LKKNAUaFWAc zkyhz33e zDOdjR8KIXfeMntRR{JM2wbrMksILs)x9wsvM=!%QJxSdCEsNi1`3rJ0UUGtPN#;BK z@$D%e*k;xXJH3;5t^2WfK;{q39r=-0wGBi|kK@1{&Y<&><>c^Ap1i7_z?Q}#e73-6 zw>Nx2=|wtV;;clIJOb&z-@8yqs)0&Iy;YNt@tU78h@IZMQ0zawn3i@PgMeKlS$^tO zSZS38rKZcF!XXe=9=^bbLOEhCc6Yd!1Qypg zY|@X1^X`#2JHQ3)I%h(|e_f#4zMJY4N5H0+|Hw($gDokFp)He2Ku-TLe5tE}DoY8> zx|c~ccZPC)Gq$p*xnZ29>Q3(8pWAd`?tLnWd_vWp`5?7L89rq##w>|KfuTAG@6R;? zr5D$^UtRO*gm^KnyqeDcANKNzB?hzrOF>FvGn+nWHk&2cAmrtVGnHd3pg!}S)T8?$=)d^H-HUR_M73t{bnO2rh_JEN_g`nYT^5w7R zf}P(r2oBA8))g+7}*!@87KnsGRg zRh*3Fx41v#N-oN??VZ!u78Afiy>YPb+74>9P@}>%`#HypNwjZ8rP&0eK6dw~yHnQOB3J`!;Ag&IlP7tkFyXHku<2Te8^faA6+;^Hlr z@!kbJ_E0CD`j(C(w==>u^%z}hUPC#$qrr7XE}1-a#j`6lFnQ1nXtZ&{pncYC*YZ=M zQMd9Tq3bL!uc65te0l5r|BYagE%k78#b~(K!ALfLChPO-1EbLY^V>SK! zxqt=Y(r_s@KvEyp*^a{UxLPvFafZm+BjRYg0$SHKlEuhn5i8E%q;J0F#x{1soRfoC z@%3q9*PdF?nJUSaY|5bN5eZ&UnvNj%s38eS8vd3!8OkKIJ{@)dMdF2{jx0Gneb^2sif+1qPd+e<+{1j?ae+}@6f~C49pwjK z<&M))kuPm}J(-=|qt3jZ__Oh|w3)Nl92)4nhR$0ylI)^q?8w8z{P-OqqOZ*>X{Mmn zJzaZ|weF4L|Ft{uvDMo6;mty*_>;@IW=-X!Kema@1+Ba9P9DvAC57V-T!L5Xfmr|R z0p^vR012;RSaokUT~2gDN0(-JG37ZtQE{NQ-SXfV?FoHWYw*W!A>;CPB%ioP7b-Ok zu&ZB_GT$bG|3P8{-F@hyMF7Ug3;eh3iQMI;;VjJU7v$Uigst~(kl$oYc45aO3JZ0F z2qDwqHmMN;4Gu!+)_u(4%6zO%Gr$8TLY~a41{N(dB}cF8u)t1&?)_B4qqpC13945} zsrNY41#iaJ^53asXEeXw-kL3xnFtf|FH?3=B$_9v(~A29-5*|1e4zqsQ~t?^U9G_0 z;@cF|6T>SP`+y2BhL9(%qRmR@dBX?ZaHDT5U8p@k+Rq|ksW?{PPTr)aJJZ>b_5;u; zZ_cK_bA$zFAM>9MEyk2KO^k`X#Me%>r*Svj;r9p&wxw}A8GRAq&n+o9{ly9PrQsL^ zmHdF@j7uzQ(RI>mHiQL_hk;#q0)E#T#yWczz<}V9WDmIz^J<4^cq0QlA7#$t*fDwr z=1l+VQ$FCBDSJEiPu0IE_h8a@F%6vHL`ThfxD_Uk_#Mrl z9!|p8wZ5#ny++_*gwrC=97r{71&Kl03~yY9MIXZ`VWhxSY_cLI=(0n&6PSBFj)k_# z!`W(S6uH`9BN*e__meRrYC2^Uu7veNRx|a$wairLKUzHuK>IVD^!ngy+9xXy*%g^! z;+xJ{UlLQyjb5;G%%ljtv(O|}N*iYJw9$4fviqCpTeBOz8u3cdFk;AHsu3&N@)Rzq zhC_7qW1Ksto?rUz5q@9aNzX>t!>JjG&=KvEjczy;z2fpZcTC)4eS8j5>Ty{*8s5`{9{hD9$A_+%O;t*LUoO z=y~#N;rMu{RBEI7A@2kl3=cMg^FZ->8aCPOq3b`C8M=7EHy?Q6B3JiQ;Z z?x;h}tr0j&$mY#XyadxCI{2obDQuia7B};kum{Q8!+RE50fw!@2f{l{``|$sZ?~AQ zc#*_z)XQSIttV6a${@J22zqh`*<8-K!`8A9zTMTZz4!5F737372fxF9ok=pkqIPanq4cZ>a%9M1`Uf&71L;CR6bPOI9`ZDX@ z3o}++y?FafcPg+|z?8{PNg_6cpjVH2w@rnzqY?b%WNqdja*$>WRAsBRW!bE$g6`y% z!hDz3S-b6U1MZ{=t($d@mmBp5CJdLwvg#4=rMi)OWT^$~r7E~_9|j8! zQ#AV#yOV`;C!pKTi#3lw4fUICVX>YBzGzn^@yQh0E~CWMI+gfAi$0R?iC%tOb0JAC zIm!LC&?42lPRwS0B38zl@aYex&}*Mu@sk6uzzxE{ci1s*!6R9w{;(DHkE-J<#a}=^ z^fv4(l7fzpz@pv0^4IuLxFxlW3hf(U#MdOs8LPv_=%&Dz>lXZv^a*Tey$3syXNg|p zG+0NuC0D7lkInLz5jaiO@KTuDbHd|4y0l6Kf1MY2wrAB~RrMFrKNHWNw}_(MJx4f2 zN#43FTn%N%o6wc(cKo3c1M%UhADrspp}blC2tJ^o0F*~8<~FUVCfn5xqVEZpAt5Q4 z^}rt*USdk$SDfa1N@Xa96LN{?S5x%(My`M8Tz-z-e!8V#!)fpe{2T3l(Vt==j}Wk1 zw5lPSEgn7wqgOnHV1x1Oulg%c3p7Vf%V;j9FotZ8yru*1I$>L>2k49##gcuL(SG|7 z(WF*M{>cq#ys|3}t|za>{}hjkPFY=`K}#QU?We7nvf^^=d}7Mn-;HJ=4vOsbszBz=70gdH|Vz;Q>jxd-Py z%_JieUFvuD<%jm`<0k(WI3%zjcc+PY&oha1_?HFz`MZf5W>^YYmN~3Jb0GEBJJV4M zW%1keZ=m1P%nkm0hBVH7CGnU|G}CPpDz})j>n)?1OqK;Lv6>9Ysyld(?aR?I>oYC< zw-OeoNiaTeJ*Za{)1|KYT&>+vSo^e{`pR5kontpYboyChoS5&M`JQ40edOvLIaa!5 zBAcSOkocpX+>IzPDa_agO`6IqA@%?mJzBuxPd+2IZ7*qtju*|iuf?9=F+4VTjKIIk z;T$)vqSiZ}xWB4^)bdoB%Z~!|e=>>NDxS#32|2H}+fO0WDTy?_v~kk6GXD5GNp`U~ zg_H^ofsN8OPBPpF`Ar0EpWShAe>1*)7l$+E*V1U%$GdOP#S1#hlv;3+`*dw1?)Nkj zeORl8SLb)bkoUKl))`AkcTvU|)&QJi+RhCv z+KH-#D=5BlHQjH&4B6vCaAtuTs-OSD_vGZj>Xkx?#!v(0e_o;u>3!VGNn;T|R)F6C zd+blrU_%>c3jA>ytlIt`XL75PQ+>V-!oTX^nq!L0BqkZHI;LXNtTni^IF_FG_)}Qz zY|e4QHQe>P4Xz$L2LmpdvMtjj*o)Z)^kV-qjB=5~`6io4wbqm`|E2@e>u0jLT2i9v z4|@2ms|w&RI}X$O#z4vR``p?w^C`UJF!p+WBAr1FaM>WAZQfDFg*9E_O8u{stLhiA z*~mohTFrEt=B)^>W=5>C@G|^T9|?U$!y)=y3nT}IQ_`3LP}kA{0iT-4cJ51vb&n0rT-yS9~i_;w+Df$z9~uE^`&H~ z0_s>8!cANGm|Hoekp}vl;dCxeW85qu$5W)nTCaZ~KT~sU<<3qQxc%oZ3mu;uaDMIpcHBY>4|bN*!@GAyRne7vlE6FKC-ivr21Zgp zXv6v|mmpi>FASc$3UaBG_dj97zCB;ga@y9A>p^XF8Wvl1a=#oL$X3Fzczb#kG_`8T zwLLWd?+_rFWIT4=0gg6aWKY)&L#-n-S$UKiTkHCbt_a*`uXG_F;npJ_zsZSZhsV*d zX-D~+2Mh%EtT5wf@+!71{yDk6oedp3e$mpx+3fe}7P>Gjfc*ST$aC-sl1-S1YeUEK z*_-wuSEEPb6B_h4&ljzu$MJTbM$o_?$<~(FLcrsw469DPO`XeRSd@o4Ha=8k88!PD zxA+{4<-tA2s#D{>~X8pBAa#p(LTpr;$Wi)Sn)la zUmn;^lKBs*-G4l6_CE=6iW~XL>K0J=yk4ySypNw^riYP@919Bd!FlUb;IViGlab~qHX%)xH7pjmc+G|4=h`k%chiZ< zdCQZksVwuG;mUT&hSOO6O0bm%)_Kf=`L8Yq)taXiQI>)2)mNxLOpEz!6K0^rT!f0Y zEx5GuH0dAjr|9iB!TzWuRpv^t2j{m?!kQ@9Hc*e<|J4j@ie+Jl(2;QON#Vy@reZn=izxtGs*)6sL__?ii9j{6o+>ozAv z(>4l}7xwmFIS5&Nfge)P&GoN-PG@gh!_QBu;Ib$luNC-Ge}Ds}T-L`SUcN$)fMa#} zaya_y0Z6mkMfI1);Gy(a{C&51nAs#`Wt1*Zw@(W;W*g-pG z$AC_}0zz^FypT`FQ;RN=zQ=N=T*Uwc&vo|v9h7z>mDFcWW&nnyBf58{G-9AhMTOFw4mT(R;(h%luU53iT+4w@pGG}kl=U&4(@-uF%^8cC0uGj8E z(>bb0=p-WS<;KM*qK3C26K&SOi+Ypr(|<2%XWl^ceK3v<`XdswXdb5A`bGwku5fqK zY^Yd#0v`RAfe$XG7+>N@pZC`BPd;{Y6Gx~}%bqx@IonJp<>bjS=`tVQtH*ju{BX;( z#c=+w3`zAzve$DY8vA>S?4}56WH`awti$4v1K6V*@?3sm0_Z5JjoPQ!^WY- z!aRbboX)2u(Df>Y%?db0lYU47%I?S4cP@$Kk4VD13!SK2`+%A@@8IN%lUUhn5k3>R zb;WtF_z2Al;tvmpv2V47a6Qz8G9%J4u*H)G9*W?ZOe|y={H41gj$rZE5RE>#QtR3s zWZSNf=3_ouonnuu%bp|OvU4;oLCBV-W#ZP_HtZ6*S{nt8?f0E0G%_QPJ-g-vlIjAt zQsC36NjbB|`yDu7cr>o~($8t0aYj8YdGVjW#i(&H3VkMR#hIFFa6K~zzegLzrUV4a+vz~IWJ9~lE|GIxHX2kW%ih6^*$ z`r#|M@9!mkRQe6|orUyD@ko^WnU1CwOIiMxHeQ>{LA965IqT3Wky7PimVCt=eN-Ev zrc{p&o07)cENJ9%@^fj=r&YMue*mss_mA$!Bw_Vub8fDRHOmfKNTn;PXx#5-^l=~Y zt`9Bns#F{puFONddT$)ND4Hbh-xEzaJ__sY3)q(ZGHlhXQ&e*IJJ*zBFX){jcD45; zXDag@UfEmViUl#`;rJO6)-_P$yJj-Dc!X~GFxIzMo8@J6&`r5mF1B(ESM_EV|ESi3 z^^TQbmY4%(RTgwWxu2R3pQGT#)%01)95d>VlV^$(J~}@S##S8Umlyqk>1I*fl{bmP zS^hI$6IYJ`g_UsaZwWn5PlelGrg4vpgzvB+$N!h4j1%;;K`#0OAK7sq^!0`bys$`` z^l%Z+7YxCV;!xD9DWdCVOW=0CDmVZ6M^foO$GtxCgO)}jTg}(dLax`22i5-~XFqN?swnnALH<^HSm4 zy%;*XT^HRX>uAZ?GHyU*Gt_64@Cu=0Sn@qj_TP|SaHGN&yT2nXHPr>TA_GXf`G)dy zbl6gM1pjLo$a>nXaZunbN|Y03H*FNyiV0!-6xrLbdc{!sBdx;xlyBp(KcC4>T@#Id z>yhRlM~JkaN$Unmv7O3~Ng`k|RyX{!3aE`n<0W%hQPX8=iSWQ4YZcsjMj1yq2>lz$ zy>z;?kk4Cp7d(32!;W<|EcCq-OWUr6t14Y+tK@I0_D!bTmq$QVNrU}3kxJo{m*Jmb z1~4w*Hs5t+5Ep%1ntgX(MHczjAndr{+iUHj7MF4GN<0tUPY+^%N$O9bo+Ig97Q6=}egWo*&9*ZkaNGJI_48Tfd6810n%Ml**7QJeWl7&vej zIN2Rxx2Gqtm7k~L`E+IGHSHSJ2J2GUhb?eg;tZ=-x=+g|8^X1w)i|*5C{A;dz9@kWQh&*(iVf zG#K{n1aJM-SlJf`E9I5o(Q^@ZTF_M79;UO^@1ij3;cR^U@fEzk;0>!%+-Uyi(QLza zZ8R@;!Nd9vSIwxXQje!6;eH(WTojXtR= zKo)7U$;T!!!%IGpr=ACIogMILb`14;Jp*g`)zIrX0spRh54MY?xS)PBmX!A&=Em7D z>+u)ib)-79s;5)gk!+}ry+R*k=P}RjREQNaJHCbnSUX<@7A`%(Hx2FKyeBK5yDzf5 z6T{iDdjgNGU?is9Fvd5UzqwiIRiBN|??!ZSv*=u+v5b$NY+cK}sV?Dbo@9UL-QryTW-le<7PUG!`O8 zi=#6&>z3qjK`A{t#pqXng$4-iVBb4*$t6 zz>DcixO(S7-1P-(`1%WnIO*~N`t;WT=N#+gH`!P-C8PHwJwrq*?k**Z+gnlZ%}6$9 zN&>t!nnNE%(#&+XJM+nm7l25Pv|{3H=FxeT%lmeY`(CGy=Y^c|^iBr(=@*3_bR_Qc z5_%ae7s&K-E?iOcL2nH|u=_P1wY}OP*{_`5U#^2U&1(2};VpjHvNX;!b1cp6b)k!v zMl{2ugxnVCu^WX4u)Kc=HX1r3cRPkAHXY^vg}Aa)!vCY!tuK0bxsq)1HQBIt3;EyI z1KH}Bp}g+MBXHedB~2E$((wEm_?}@;R$Y%lrKAoXg}tWLG?J}JP-mx_1culw8=5PX zMvErxBBL>t-1DIitli9?aud_K$ys6xmQbET zT)>TXAB}rHtr698&P;yiYB)0302}OuT*a7h_AYP_-ni?`FBL~{;a8hD!l``0H^E-hbNq*ea?p}HN?as!l)97r_$*gDY<@7Ay?Qc} z=}*rT56Y;4*;a-q86b}~0}|nC+D&MHl0n}X^oGBSwG>QW10Plx8!}|g!qc1 z2wx}4Aatr z6Bjty1UorWd^hGLx&J5RfJHJaJ1m60O_u=$sO0Y%?xcV#+bLGZ6w(** zqOEqisHCij|K)9F`a%wI?92-kDtNG=XJasP@lE>Ay^m(SOr{}wMpO1xU7=TEhzGqD z@WRF)^g~t&-{D1(PDBWG479-C?_%I^P&F9#FTzVQ0eIN5hO4|?#YZZhVrrgqnX1s|RW^WNbnon9`?TA8aX&gFWzAEB3k>Bex~+j~H-J_Xk-H^I3IpQ-I_ zIW0-PARak;Gy7w9o7#;!p{QdjJEnDr61}q_acn*4pIM1^^oE}9dCMs$zvky@u0{7F z!yqhw2J?7zheip0`{MN>aP(*;6*=dzpGLXxE%!Pm`U|?5`Aus&QO~8B4q-9VLz!nm z5^w&ggj9rCBEz?7aMtPCEa=XBQR}@3e)^d@3cQ!aviuT7BdmnEK?dsRu;45F-g8Uf zK&dd%&sQ+{^KxEx+)z0FkHA*H71HId(X*IQ_%Yv>MFse7Buf=aW!)OnzfT-SS}$LM2K_SIIPp6^8u2g{*bZYmWX{R@h73`jHeFxH3v zpp~C3arBk*ux%NGZih*DYV=tA&%zwTE}CHQtvPrfRWK)Y8@3P17Up#iLf3iQDKE4O zQqCHqq(e6MDRwxQD`a4T4_yTF=--@Z={b-OGhrLdB6&8fpFsGnioe^y$@Li>`)Nt~ zLjG{#%3w-uzX5wXQs_XpCLcfFkTs-_!jmo;qR46+CVvE3k>C|yn!vHJag$(4V-Qmb z*Tvi$v)I-=3AW_7z&2Yjn*H)U1mACN#LcSzth`cE`Cni6LRk54Zi2@JTJ`oD=TRla z<}DtDMfJPcWjR}{du+yvw)*3!dVwv!yo|k<+sn2V>apSE!m^jD;j)p_*t)7uqGg4F z{GHtn^tM4HZgeh$j43l=as3#y%xMryxhRm{ZWTBjRtU|1^qA)(D}kq_E#A~|R`4X_ z;C#J2+dSqUWPVPeaUsTFtegO2Gc~xdJ41!e^hbJlSqXoH3-czX`O}ks4tQwhA?OaA z1M@y6gHve|O^VUQAeAoIxgm_dyVZ^RuAB=V=jy5)cjbcjma{OaQ^aoiE3yvP6mjUX zZYYVbVX3WyafZOmfX=<7{ACIIGjbo!(UM>)>)QAr=?L~ z3d;4WqvYD>G`jMcz-)a>Hr4gwLuZWe)!6^o`9bNVwm$@Va28uUDj2@1B(TBr-@=E< zmGE}&FdA@fc@icD=HY-|Bsl#wDdf{XZcq+prOTc~yY? zzE}J_cU{o3FdlF#uSrwN0-vZ?uWB5Ne7g6%KyIktd zy|m`C1G~1l29h`5fw&FNVd6g*R<4?WVWUqnr~jeoyu)(*zc@~%p`rOrgNlYqg(7yU_O%hXd2A{UhlGxi3bj>}4nH&(f zBg3twC0*koIpj8-Up9<}{xf9~%Pzn&=}uUGc`Uo-Pw;zx1}*MSp!tKtm~4GKsE*IU z?sRW@K4lXvzI>Cq6nr7^z(5w}R7!vCTEOU=So~s^DLX%00%eoixSydljC7_n-j09Rv9h)*1ArUkwAFj|Gvk6IsDGs%yOr^?L&BBG=fixLJ=U;SE&D|J!uy;CN`^Ovq zn0mpJ!TV|cfqF_x^<$DZhQgW%1-M)h2-n(+VRwuTQ?$7XasSTI?glY&>wm)s=UTg4 zc7)T9sA83IBKJvBnXUHn<6}CByWe2X)@@7Xo#F=Knk#2P#WNDbijpuOCxq7B(uF$4aq>%6dHa zUXg8IHJzO~Z_WCCkHS>7-`q=q#rbmjBjksL;LL9~$*yZO6nOu|)SD`}%cF)=M#j>O zL+|OX>2ra;*)TOA3rf&3IV3 z;{sR>{YO=GnVk79c~&vSjLAG7%}kd`qU&8f>a%;#xh&~sH6u7Mn7oP4d^wV(WJscCWgkWTilDX~au^VA zCO8Pb^Pf~-aB9bF*dy%}DxX@yMSlCqt%^%$@3!V~Pdx5IMM{;h7f=ITw?N!sV8nLa zQv+x7Ih^RpaeUt}i2bfoW4+B<7_&Z)cTX9|t$1k&VU03uRsM}K)9q^k4LSDY&rxoj zgCXo2UQZfBq*%}M)k2@k5BM=&3eC43gSp>#LZ4{~%IsgsUU%*$okM3R<>)|E_xes_ zmmHx14}Z}10duJ*K$UGT4aO4T*u=C2o+DnxD^7Q;qDEN3w`aLNS26y zKMo*=$q7`VzlmA*7BbVE<7~n0dtAJNuvg| z{j86^&Gu!ho~-9irJLa5;!04Po(nS)_Ry8k;cWlqB-+{jADv5AWcMeVv!(Y9S(tEh zitd)cCeUXq>pjHRugfqP?F=Rx)63GY48kev^;x>1vG|VHUXUx^3#m!p#iC&bq?dJs zdcI~*{@+4&YL2SV1upOk`?EP^`xJVv?ZH>;m2iuX=#Zi1F;L+L!SS30>}6y>)XGaU zalIQUIV)nCa|9f-{6=toq;QwD#h9=<{;+%pl)g`f@yWi_Y~+M%BMg}G?G`>i@*wf` zvbfIfDdd(4J)MeX#6Roi&)l%b-am=t=ko>fP6~I@*)M?-*1|b`CybkG%{iw(gtP-~ z5cT^Z_0~7TS)1_~E)JVRy%CI*(opPgpP{Usf z8j^E|n|^E&C^X%rPsK4JL83(LYdCz_7X!~ni0Pi+EAV|5CN}!{i(hm|4r6bO!?=bW z@JDVdU)OY#pJQ|ueB`3}!P06N?&U^7qJFy_GxzZgxhiO7IuODphS80*$&8!U#oaqS z0gh;`#>La)#A@7VamS@mY;B$omwPh={?i)+FXvW*-0VzP^1gs;mmNdtZ__x|ww+3i zI8kx$5_;?u2z!3oplhuaS$`V=#brhCWJ5l^FzJHuQ5g_>U2w-eH+{izgh=<|Bg~x=@0(=#yXmrpU3^#GXv!1FYtS{ zTS<9&5d0h!N}IMPVM=)`SF=kGGlZS|il+DcRXu6!xMl`pPt}SaSso_UUoRlLu9!;x zy20__q3m_bMegf}Vd9E4FQ~?ADsENR1kKJoyyLwB2IV*L!+)%0c)}KrUYkT}`qDV* z*+_O$CS4pB8b#JEU3|NRC1-zKa9RFc1nK{Nk;{oxzHxXqb#f0y+QYVyYV$hQd02uX zzBa(P&WGTN5^!MuB0EDF1XmwLOfFbQy&@exaH=KDj);Y+16RX<$KFgWx&%yxo65^_ zb9j1P4GuIZ(ly6S@ESK0c8)(lYYd#Q!6XGj#*uiV>m;_cAsSX_Z^XQtBJSbf3wA4Z z2)X9HuAF~W6KTwO3hIaCSk=JM?2__x`dt_=j;`@%Q)1uHQ^7y`JKY)XnH9kXq3cV@ zR*u=O9>5~_85o-SfQGFZ3y&*>Y{b3;^lIM@IH>NGtnQ<@axPeY!4rj~uSct8FzRhcWn2@_dy&99IAl>e@AnkpuI z&V@eia9uM$EdCVlXg8WEeH41r0%BoL`53sqUK%NV zn<69RxO|Jr@r5gha^CY#zgy#iJWY13RDszo=>t>wwU{O3u)4=8iv$RrHpI^p*rHfw zwnRzbCy&A3_HXUyLAIai>vCP@ ze7p`G8S1g2ZJO-u@Fp(lRy&br?|yRAb%kEGR9Sjl(Z*ZXjA11P>P&xh3XXLaJe%!t+`G1P zb})Sx>vXz=qaFr>49&tsYUd2z%%h4g4dUCvv+ak33Y!q~nBDjk%!UiQ{~HT**vr|f zSeTYf@9j5}Os21x%8VdveFR@6(E-I(*I;qkX7YcO%4$lhXhT^p-44-XCT`wPWST@{ zo6!# zVi&oZ{-OE9(Ayj|NwEl4R}?Jl&+u#wtFgvSM}MxBMmhhH&h5jRN&~-{8|O zTj;Z}Bzt*X%FMbCuWU9j^LJBW{)F%Nt2l@@571-uQTThf#Bz0w1L&RLQuhln6Eda3 z-khr8xpfx*_0JdRm9C}?yD01(xee+oX5h)JQfSxE$Eb<`?#JtCB)9(%eEIJvy1T`| zU0D^pV6>dAYCOb_9K0d2eIQR8pJ_vypETRM>8{<)*Y`vZ|7MdFHxBD(orEVRZ_q0P zWj3)}o0DJl1MZ4W!n^V&h_?zB&0IB}-R;^){nN}qa|O@M3Qpy39ST9?6KN3hOK>#R zJK>gMID!p( z!T4sG;dpq8F1a|bp+npH$!6&ow!*^&v#&a^M#&@Gl@5Wmx;qK4ZrA1C=3W5B7gOoX zUw!oIGNB<6GoX8@0r15W*cjOn@I3h=w0Ta$K*OV;AN~YhXg`OXv}*Bx87tUE|F`^d z?+zOM?y&g!;M1hCyN+M9-HiLQ>pj2r%Nja2MTG>F2<08m<~yIoP`i5*@dnBKRMtWY zs$04FTGzQ1?eTc>urCbA&808J(#&k}0H$17MY(1R`68|X&fM2#MLMfR$4jzE^MSzb zjL>82BFCd#gobFAbQJYu6~Uq-V;E|g;f0oDs+WppANF4+zZ^$?=(u|{`<@~D>6Zyh zw~b;(i30nvP7kX)-G#Y$4u3DqoONuDV;w0c=}_fzJmZzbu%z&uKX&waHj{Y&@{uXQ9rWqURK+&3KGeZEUO z$~^eLu>xx}*d9I>m5KjM(`Bc^>v-AoMy$`a0`7w&THX(#2a7aF@t6$FP*q^uoyn|V zV=Vh_F(0C2PccVTH>T(Rj$isi438(>5ITSr;l(E&j=dTMX>&ucY(PJ+AvlO+LSxYI zz7ozGmrHw8|M9bU3o87ijkgQl^8a?+6grKSv0}{;406$DA#2Wp_{##$amqv-Y~YSV z3Z}9fE?w|?$#DK+F0j0-5|dT4imCH*8SAq9&8;|=19J^!aW}8a^m^9tx}X2?$qG7l zckD&%VDKOa(EY%5h1SFFDRuC4x&rA%J%Y}jV!Geo#hf3#quNpWH0feC_jR2ihz~3U zqhtOQxXlA+x&47&Z#QmN(;lwUub8Rz45WF(Y+3#9Wl*QThxv3#a^Dvgpv~F{Hk)NJ z!)H-Ah2)_zv1ih3Y%H!0osP=_j8Wp70)E-#fWseisAC>RC6cCWyx}^yoOK+bbQ10! z?h8SBozxN+#58=PNY?r>J$amo7d9RN$?S#9;E)L&QWJ6|nh|)K`^qi;d=~@uJBqcm zc4B_!JdpXm0mJ)#a0Q>%3q2|`v7|^7iM3!+Y>Ezc4rs#EuUAk#a9WBY=2gmp)>xbiOB}=hI`T!c(;YLqiCvdh! z=PB)u3x8aGCshQiP)GF>+7-6~^CJ@I=p$Dw;CA6D&H$zDSBV0ac|hy%Qs|!|_({56 z^O4SJu*z}_oBZ`UnWSjrvw-vXXx3ZNNbHA;Y#LK9^8@3!ZrIni80^kC;<%e@aY{*~ z*wXqN4Q{s*+;8t`sGTPNX~kc1(UxJZR!H6UX~T^4SoIb(}hi%AI#Pk5a-`=_!B9%zr?QWjLvmQy~Q&#F_j z@r^TXA1TMC-!`D$dGg?WY$D7sz6oa576feUxy?omVV_{q^+ z@35cThoYmnbodrFIbWYUJL3YGTo2}6stV2!`RVv;qbmEfte2*jh0|ZdHg1orJA1os z6w@4Jii(1t!hBu^4A%+d;>TO!)p3Q~(X1D|#sVn{TEDUEi_nQ+ymJ$GwtW~Eqgx62 z-dpJEsB2=w);xaxL}lLa&NSR&oI(p9)iUj*9{Bdx9n}vMvtNFvMOG?vG@H*M>=PxBh#X|*%6 zm==tK-Gw4Plhv?YW-nX~?_eQ5PI$ml9!uQxz!KM>ndlOYo_ByhDe$@>ialJWqXzyq z4@UJKEw*{sCu(lV5%m~mQ=d{h{nCy@GcQkg)Kdk;Zg=^4#mC8Vw!kZd{73nJv@p+W zrpQL!5dR+z2z$E_SG{G0`7lx}A2Xb@TM&aVu#t?Su zB0ibEjG0(h^T&otv$n5@k=>Fk&$E$=F8IL~Q5gjJ<-o>~VKn1Y3j|&ZLQR3|cz)Ll z!!kCredVjseEwrPzQ&a~dCy@@9Y^?!o#8mTYb2|6H5AwOq`^V|8W^{;16*eg75|%A z$0|f_Fu_xnd(~)zQbxVF^n5iRGyf{5ou|q!*((cPFf~*Qtl<tNe|K(CSmqf#pAx~84sNAiW&#sAyh-TcxGtW$yM)i*_?-Xex=`@! z?q)G955TQJ2ScZ*po;lCHuTX7inIEUcbMlXbXj)7wXMNWc&dg~Exp2))|Rq28^ZXG zU`hHmDG@7MUAV`oYP^188CJAL(#@|U*rNMOXz@lPYMhkAyWLY`OI%{nWy?7>rFNtE zHs?--^W)jp`z6f&>0Y$B0?hb#1+Sl}$JEc}iaMoZN#0P3m7Iu1iGdf$-{Ld-7q5xa zqR-K|uZx)F@{t(l82}HYyy5P+f3$L^0<;%>rR&Uzh5b%qi}y}Mx$smneYpx;DvwgI zZ#ceo7)bwi_P_>fd)9VwKQjn1VwoX(aptY_@YC_MNc!;(44<{R^v#3k{5@ zz;S&WCtW|2G_EHL-fdIz(^6u_Gfi1=+epygp2|O8wS?PqLJ}p)ifO(eItunn=I+nf zMhlO?UeZ6BiLpf0)H=m=G9%6lYM41c76T@B|f2;meNd4@~^?K zLU3*TIm&h}8z?w5m$6CnG{IKkBy>cND&26Y1YG>q(>j~iqGxwzv-c?zp!2ROSx+&g z7LR`Vs%XP*9Wx@cU`598~QaenU7xF4x7~ew+Z)=QobmO023+&B$|p$*VvIFp`lctW{_ z+ML;We>kd>3G&IV7_&25oLZX>QYkBG-j-J0enkpQp7w!^;Uo9=^hMH}mBsuNZg5!3 z(??@F7En5r%^w&_2ax}h*(^&g1V%HZeE{s=pq`)T#+;n>&k zRje(4ii|I3k>zV&ObPZS^Jng~`NSghhz(^nw>;_i_$9Cw8lEtOB)7faB zf0PWjxLspUif*>^aC+Da?s}Xocfoug`{3>rQITl_P?w>JG!T;2^lB zH_@&d1GaE^4%9ok(SxXBm^4w3UABqix+*i+_Vc&PB-MvaYWx=gx8s~(rfn3MKb%Ff zEn3iGDKBt}O?1WWgfL@`6ki!F#Vxzm!3&09@%;&h%(`T{?q2gAFQd3N2C+UZQDHo7f# zqDebmbGmOsx$p~Pnf--3f?NJNS3PSa+mQ5-p0*EXNw!_Q!^8=A!*@C>byVPN1wJxs zeKWUU=~B8gU<+C(8PX{aCw3{~6s>t!27(Y==m6Tt%-Touu}h?Jtp5w~J8vg6wT;Du zZD0878FKVdaV>7xEOg^F`_M0z4l!5yX!F2hd~ba@6e(@xALc5dk)!M#yEy}TvdvJ_UjaO(IEw$?kYkl{vE0GH6mI5PE4KIU0308BoV11gVEvX2%=*O; z*dnkFwZS5`=)**Oy>L3jvjKd~w{a{(Du7q1ZKJ1>PvO9h%OIr_45mLW;jKHVyisu? zt@IJzg}pa{eW5?MuQ3&*=M+s0xH5#j?vY|S+fT!9v!QHJXDVI2uSj;CETav{=?OM#bEk$60ck)jX4i8LDn&b%+CCTyiEzT z_uL5FV8z3*5sq|lXf7PyvK!tt{(l!|%`)zm@)Ohyd9^}Y2s%9&FWP3(%c1jG=wdni zW__Jh9_Zny${RF$;v_CTzMfQ1&w^>=B{1sZG%7qX7oPOJfxW+GpnT+Y7_ysavf3_I zF3iOr!<6VwdJsh`zM-HA5^!c^Jy~juqHobh!Nt*?iD#!!US=4%4Qb}SDXpb-jRCmL zFQ0NJnS-~K9r#QLWbLXYG;6drZ#U{ZxS7b8?P*=bI_DJudKz+4^F&NbL7J<#se!}w z3t^S+Z=usl=t#=Ur+ixtST7j$ex0$yt)CVE>?o%G@8;OEv2t(Ty2BN$lv}9eL=^Aws-2&e&EZ0MSCZK^4MQx{$*g<)E zza*H(xZ&J_^}>vwSP8>r??UeHEp)O;1Ff>uK;`^r$a>|1yG9HbtEO(^myH>M%N&*cS@TrEsrU;KWR z4s{K{wvI70B~xBpFhY-;ru~+mX;A=0-b!qI#}|m5p@m0XzHtw?4P(_=k14$28qNRx zlotCaaQv|4=%zo6J^F1)ZI;I{^Y=p7vZIUs3cLGrax$e7&n1|{HebxHQDh!#EeUG& zvFY~;Ay@4wG}cw|VyLABp(zk4O$l1+~DPjA;cn1#>j>Q4^Ww?4i-Qqe01XFFEU~lFe#@ zm?@)h+-D8&$df>i-_I%Rizd5i5QK_GVPMjb2|3L_NW!Cl8*CQE zy&WaVGBh63o7!mjVY?ojgn8;2Re3qEL`@BbqEv9*u7W<| zRNTKXmOGWS7tQutp~i1dDpnmN{2#8T+Y1(>j${dSO*z2Am)sFazq>`X&6=2Ud;%2P zYT+;a8t&DYW>VJ)11;$ZILkDI?F4NoEXSdN(gG#-;%ck=o_UXbex zCx~>sz$Yj!#m^hV`G;eZP$&I8Y=rwPvO~|+f09+S5K-g z-NLqNmBGctAS#~ml=f&P!7qWsSTgSxgyc%n-E2KvCNq@1nXZH@H^<`c7v8KFWvFe7 z2c=x-;9NJDvjLyZP+Vj`dB3iQlpV8ir~4Qh^Z5h3I^G5ankRs@7lF#%m(;xRTWRGc zC2nxpL9QjCl)uDfVE*P`{G9#ca883At5ONZ)enNjS3f2)vB?#%dpL{z)3;&02E}mG z<{bB|6R4=`G%W9Kg}HKnI0u*EY~p`Xm}CDE3|~Emtmh-RGp{&WFF!!w%WlAbO=(c+ zmn+)-Qw#ggYB0%L*T9}K(ERp)D7L5;f^*W`oo+RBFNza4hApD-3s!7x)Mq%fXDM5v zQ$}5D%tY>?4frf`KEGt0H#2#f%uHHD$oUV)uM-lvwC|s|vpd^Fn^iW0_kkgtjMsb0 zYxg3l!Ji=LKmr)AtfnS|yJB+%0H?=?AT-7WG?GNr;26OSW3_N>>>W}NTeIXkb*R=` z#x%^H@QeMgz{;E5&|Ex&D=$!IW1O?;%;s!LnGy~k2fpFt#)+6*gBAXLrO9nmJRvso zD1z|srh?0D24>Z3!mIb5=yk7$tN6mBrfz|le>n<+H(f6K*?Wwt)2Ea2qt|faqy+13 zvZGfO@fh{PfK77GqD@D00eiJ@$*VH@c@&w&6dyLxSdIIadY)vLRf1R15%}tG0s@0p z(x0<>tgORPbmH@P^v?WD>$Adzd*3&Z-hC0vri}yN$6?eo^BYNgI7;#BGfDSD6R)jQ zCpse+MrXF#veeIKIiC<2X1~c2q`ynCnAb0;$0Y^QEHyBGP9nc(iHMS&+}Q~Kp=@{X z1bUfagT_ibAxp{y&y1F2OWTC+;XHxQ)nNm(m*TX2x4Feax76}?$<$dT2Z`VNd6<8l z){pxOb+N{*IxUYDoOfcoJH{eiItfi7y?c1uro-C`SX)hFDoxeKU zGuRd_oi6ceMviPuW2dOaPJ_8UIW8_fbsR=kD}(2!GuS6z&c~}Kk!4y8w0d|7SwuZH zEisTfU(dsozCl}Zq<2qT62PULxgIZEB{ zq`p2*~mM`7G+8U!!ReTRN{Rjl}8QEC&s}&+seuJ%619lx!MTJJ; z9e&F`IFw~i31gh_&9&+D%uxX?wmhP_%WuKkJb_o|b3b@h5ZP(e2+FpaGV#+VL8+na89OjFc?#kg=ZXMe_DUR*T$!B*Jb5LT|ZE=${ zvWSCbJU?kC7OgN~Yv(X7WPbr3j<95KrW%G_is2LIPXozU`}vnagR%YBCb3H4Rcc-s zhJyx1umu~3vI*QBdM6peONVK*RLNAB5*S4997m(&Mi&Y;wt~6;1Sj;4PkgmsC@y$1 z7ItyrtY0OP>zHTE&bs(eP}m$Y7H+z?Wd;#Gn+~0O!&$zA7L#x5;u9jiQA6b_%vyN> z8@9V(%x6Q~|6K>;ALy{M^`+b=vq)A@Zi?}$viMo{HkVjx&4%Ut#~Rv`%EG@LVrex` z=#%^n{((*&>`sy7p6cb}#BqsG{hP!e=8xk>znIJ>)rJ5U`X?{UE`k|$|=|2IgRlt(8P zJ*K>mBk{752ebaPop#L4v3ue4h`2qKWKeXGq+e&iwRM|ChmwCo_Ob-_K(n zL)u94R~1zyZ$e9h*)Zl+fhgVk1sr)<1S6)_)0gZrbWGQ0HUpx#@VzeVeN{63JmJq` zemw(I&t$C1=j?t;#Zcg+yZoakJ@C)f7ayuWq}G8as6g-vt>3y3HrO6vKKIn{a?1~B z5nMrw?bgvFIVHBS`2v3_@((x|TBEM?1@<@mvB2>Dg=7bN>~3!+-8GH0Ed3nq=ihQx zV{5qV6fGv_y8@nVQ^Sit1wU2566X7I7(1zdh8o2~XkYv@`eLWW;-`OwfW(dD>^F?Q zuD3vElVjdcu+0KYND{58uX{EUELZhX^4%+e{~J-+0 z9_>%$?eiRV2i&Hj^Yd7DjXJ%)wU-}ZKb4!K*~O_?on(HW>@n5-FimVS0<+P1BHe-= z?1HWoS|9gB%gevGiOEJV^+y=_?$SZW)OXaCdKJQ+J|>s2K>B)hG0ibsgjWY{;kRrG z;1b^~WAU#PQFHGgR`;g{ZpX^8`8W3Q^+sc;SW_RG{tjiohPi=f;ShE!z5qY2N0JxW z(T9!yAoACJ+FbaZYCVSH)WlYP87lMLZ4zj5b1Oax?B`xB9!Ok#KBpYaQ-#4tPGg0g z__6*Vkh{sjudq0-Ag72An5D?B-HhO7>b`;>{rVWTddgPKzcrbk`@6Rywj{TlV3t&E;VHb|&s~sum?VbW{8J1MIDzJ4w4gYI%7`!KK&M{uei;9dOQ+UKb|5Z$L%mO12ExjGV2^*!p$lc^I>f^*buWA8?K$ef@fE` zfRV4D&t*HG5haPi)#^C>mZ`w5EW(s3Gg_eHOw(2+@`(;}>CL@slu%p2zcMa{etn@A z$+Md}$LI2ws!~BEEEVjZ?tvjAuEF`NC>Wg?j@$pOq}vV#^lKmB>cLO=W%}#c(@z(` zx4DQbQ0@VNHi4s+k$m>w3i6mXN_dvZV)&~O(0@doJRWP{xx4$>q9#8myEvM4o(SY~ zD?W0Ig?Z!erUcIQ=UVp6;S)IDc@EVo?r2*xh^@J7OIJ6KX5Xg=VMyH&{O~LeuYM__ z@Qo=bJARAkdP6YXdb$8QE5b=*(Khs*sKsKI+yUK9HMHkV6b1Af3qrF?0(&cg(^t%4 z(V@8@6?KQT%`JlmYTIyu!C@$Dn8Z3(_(5!>KL4}l28{Da!?!7^p#3(Gv1m2SUQtTl zmi!fOQ;lYuy@-9%6+F=aPIx6-xJ~J3;B4+U?>tNr{STgpBTi;qt{uT8DWMNkwnEr_ z2)DgJ6?R~SJ2jgMK1|zDn6gt6w;z_q&e$K^$|=fZVxa>*nMWyNc|JGi^-yMeEf*H7 zpUS=Xc#%Zs{v*vXF>oaKG)#-WB$8EK44%`IxaZYIOy5ZtK8D)R^cj!neUb;3lqo`a z;dne0xq>PGh{XrfL$S*09yb%BxC!Rg@U-%tCq89%^0}!I*3mBJb)K2hhd%jMebx-H1{aF2aF}%nXnk*W(KWf zFW)Cpl+rSKH&~G?99l@HuB`^^Q=MQFT1BJYnBqCF$?OrPbBm@DWaehWlQb*reob_t zIUNk-=P-UtB7N6z!Q2zWaKl?6cYfwK*1ay|K79z|#z%y(?q#i@@_HA;rIPvcpg zPcoa3mnZxTFOC~*gmbRmBEPE>08*-$%!q4cIqSE=1Z_pu{`UlB&2)mr7tYal!^tc! z?-YG6eNNp``e-M0h1UN`<~pQw_@Rg5INvW-tYy3gdeVDXyPy)DIwWA!nNmoK{za=_ z2%O(JO$hUor)}eJlEboDJU?_1dls3``}VnGxT^)MIVbdeu1v+xd(F9=Ju_KzmlKMG zyLv&*JMp@y@l%2ScRyZ&ktbxKD#n}oEO)@DvCaIsgFnSzzun-K zPn{!+uk!2^`NGhGBGR(27kS^-z)OXx_^EI>++J;iKcCHIM_gi=o6TTmapeN_-4pW> zSFhkWtsGo7vkneU7>AM9d${}y!`aK7Lm0}NVehvqe3PXon9PU<+nsTgG~Jdpn#t0b z|E98&x&>Uv`b+pmDI8`uX7J?>i@60as;OR>S4~Q_uO|u~&zTRdQ^C(4)cMz&sq<&) ze!vI(5HtW24D2zX-5v)GDZ;q*f|F)P7uPl;0-g$cz%d68;GHQ+RMp$T4>s3_kJ=^> z@81gIxmKlRgSK*1x?5nY^Y~?VTIqP-EAi(!#?14lkR?wvWbTTB(`;F_=wrGKDRoYR z_5aPnyb}&&7;sW#*>W86>d(R011m^xpoldmkL8kAny|_%a_s7J2O9HUnQ9*h`NgAe z$->VIK1T#nil>l~ohCw;mXmN}eK?mRp@}ySb&+T7D~J!B#**xg;M*s8^ljsQwnuQp z6ew(Cr)@Sv*vKtVv9Or`{%<%H{JsvC=RYE&#%r8NW-{C5%fr*v<=}VY1HDsE5V-qD zte$MeEHd-#Tti&hbv;u&Jgbl#`mLEqSsy(-F&MA!&Sv|z-h))bGdTR<8M5(|p&?u1 z*~F<)?AH)gsCWMlXU{q%Fd1&*4RJ5Q=dv~HeJ#mCmG`m$-?O~W9z`Y_x`>&q)4_Rb z9hvyU1o{bU>6k$X43bMH7O)T3&CwF>zL%iqk0h)676zwxhSQ}F*Er?7S={w(Q?_A% zKD(i04AIxj_zY_;vi&FA?|-aeQ&0YbvlBLuV}d5Wk*=i+mf_-!DPpnFo)XGAkV3ou zi@@h=ow5A%MXq(mB7FUP4L!3M$+nfQXVY3&uv^3Q*ypiU?8curOuIFmEEdIKfY&3s za#@ne__Tn_M0alL<2{i02>Je)e7NcHk?Q{t7B209-P;!9ydrlNt{;HqF&^wu!5@C( z_PMmMLI!6Q>)>WrTk89=l|0K*@X|^b#;gzEPcLt*KX4hP_NF3Rs0&6#C#h~r5+0oD zhZ^>3^v++GM&0V?a+SKs{@)7BGJZf)CymEF10Ry{DFbp9JnX7#BKb$x;#o`R5ZFKB z2wc6_J7cQC29cX+);)9X!!+$v*Q(6sI1&(C+(|T~#+({ib-ht=N z<6fheDC|wIJ_s!w1thW^Uo`}SzXl)2&z8mjtWdM_C# zK2T+1wUt=V`U$j3I^ocif$ZP8lMrce9Mfht1NZ)rz!xNw##vPyu|zx$I!BGr`gnI12UYc199EO@cwEn2A@>N%`#mSJ1~e#QBUNgjz%yIWfN@W z6Hrfed)YR>ldx~t5i#v=C544q^xwF_@LzNj4!W?MX)9`yCR$9N!nE&)9 zfzD+)@q-sxvz8TaK)l*yZQxI* zUIZ^;eqFWv49<0x6&-Y00e&7U*m-hKs4prh#t|tz|bJ zMo@UCJ*4~8Q1y<{w0zhW`2N-nzlvm$>aUaRiN~^>SqBKM3;|Tow7&oTfGN9`JL+{*{)7#d90t2C;$H(zzU8OZG$W6x@*g1&0QU zY2i3av~dXI+YN@ki~27TwJqqh-| z_a!Sn$>KCuKew5ZqMCVG&X5^YTi^mqD>!p*3GKJ6CwcA}v;+OE)mnePi+N^@(uVPn)mGxj=Uv{?O>!xisxs5Uc2F7ClRk;NqOasBiEk zsC*p{QszskTK*dM{JI|5y_tpT)3VUrP6BPUd~k@85iHI-!c7#s)6R*-qOK_qh1}qH z`Xk*=?P^14a-uUzy;ElMG)B|GjH}{>-fDcI&Pi52{sqYk{Vs2SRU$z)@5LSz+EFSEgd60v?O1>DM3lgK{JI8c+AVay#}HCvf1I;FD9Yz-cscD znTvXb%;wuAC{Iwse1}u$fDs8Of_ghr`K@L)eGU%Q64mJxK9(#z`-F zMP<4I=Un&{e$GSo*ykM2_sKHXSJHTV&nMB{?b2vhZ9yjrECjF01(JPR$T#~g#-O^f zEF;pHxxPLGcW1bvqgo#X*l}E3O(GT_Rl}4IcV7HD0{7GMfZ}yxOm+jw&eo7yxu%MPs z$eiOZh(Cy>bcf-a#Jyv9CmLp6&Qtas7mr|^cTiQNw~1d z!n^6ccq^gz%7^9d-^SK0aALpjegf5nk0F0VI!$*E!lP4$^L6Uo+&krUC~;VxbQ0gf zn(e2l@r57j>n{;Kx%ZSis5KI5m#6X5G6&J1%$fYwo2x0JaWOphKMb+29*a${NV43E zzHGYnN}5ujj03|3FAyg|TSrOZiS-#U?AS4~Kjy>s-Hbz+ zVTbwi>@L3K=DZ9MSVl8^Q*@19sn`qeTi(!f;yGznnc)>hPYM_2>{W7dIAVhmo;z%U zk$quU^!^O<`nQQqjR*sq9q+hTlQ&_Ndk*%TKE@6Sv#5T94$HUd=ce{MV8u(pk5&AX z4qQ^?PQ*PU$#qdMBWoF(zb1t*_IyvW8}{Oo8dIEo;yf;HuV>9i-*EeTrgCc9<5{nT zH2SWX0=hO}oO3vbM0ZKa5d%tr{NBlem7VQ zBjOiSB-5lWU_qCx;pQiEc4O{v{KcJO+ina%^8ilAcuF>;P!bIf3dxtyqeN6!6Fz3o=Bq1EABM(xCJTQ zssTE5h_VER<@1Z9y#0?)Ww}0;@an6B-S>s3Y1$l?$Onc2gz#o1@KDPLHj1<@ryU7awBg1q0|67K0bRcjn+L(S3VWe97T>P z@g1~K$WdRBzl9}XYUq=EoCZZ)1^1di)NPZ>f6zC;=s(Ud!)-Ao8ietiA8YV|>#nf< z2m81+LiYdvyud((d-PZ6291rCz~1X&xODa~JbG{k)eMqj$_ZCt*N}RC(vb$PYqt?3 zL>?0->&AIO)#Bz4P)EI``aahP# z+F#;73NE;NHO;hJO9eabU8e`?3i#ac3`IOL$B7CrxvIyvA*in!r1mC5mHT8|JJl4E zIy7*o=SuWHdXZM0jr$)(=i!gl`^Is5%O*s!BO^1ObKOK%D3yjpLrJBfQs1cTO^BjW zMxscG%6QIoS4xRe6zw4`rAaDEzw`SCyzqLSbME`PKA-m+GvA1joJApM)~N9aXGu`pF33(mv{QbD^b*i`iqZjU(80WO0^j%ibysk>qBXeTf4 z*h{20ikR6#?YK#J4LBTDpuDzS%%?#Cm~M2KUfIsjbB!FzSKX0X4|OnFH&tP)>{K!* zQkA(gQy*LtWyq?w8u)c_H@)GBY@FLo#_r5!-qVq{V4VMvX-rQ?qexk*Yi@uZ(H7KY z@EI@X|9gL90O#9{5EkP}6z&%h-CRL(szQr?zTgB7lFszbcVlw0#TF%Qe`N;dT0l?8 z5;!2A3Atp~1suQirTnUPHtxxQc6gMN51beE~|u0|D{K6s;9m} zukHZ)Qc01{Y&%YOW|+ajU$r>xf+>$fv!kZLQu;(t1z%WBf}hU-!;z&AArrM9Eeu&ytO_$AGy7F&%_<*FQ=Ct1TQnC$@(E~mhE zs1Ev_65#Z^P8<|HiUISvE-9GNDjvdyO2D~!fo$9!EAnC6W;hdg(9xD-Oii^s2i`Nz z;X97k^+hEY+hUUNb@Fybfk7?)`qQf1E)>uTG+7scN)vtv2OvDxxuZ zYv3Zspx*ZM6Ry&@1YKXb-H^^Ih?%<*?~W8x{}adA*ZPPa3ajDn_64NS=N^6d+mQxw zOw5f%cI-1}3EJ$gOT;S+(SYMF@K31F9a2T)kf9^FaKi|$-dax{+pJ|XZ*Ir07Y;#j z%5Nx0O@PVic_3lX$9*5usqXbqs&bsW&ySQ4N0T0S+o?|eMjdU=@V~?R@5dQdX9u?{ zKkm={jt^khpf-J@`yA~8rD*MiSnA+gOjK=B(52CVlur4EyE5y*Rq_XIoqLPb3GIZb zC&HmnV)T9NAEhsC5+Sa zu#jeT&Zd!ZYSgxK1}$6`OFrvIfb;!*tny(mBK|-IOt-4AK4oRi-KJXf%C`u5Wr-=d zFWiQIR)2wGm;ONU-7L(WpUnO@E`uS`@^B$Vm{zPb#bfnvn4#|DC=hgj_Jyax+NCEz z#4epBcO|Inq!OM-ya3FQY+x?FF{PnNhncDivvBTmj?M8coEE98($F2FXls_qJ-@~w zBQuc3=PV#wzUjd^2Ui-+arj-tx!hu)9gJ<4Arq^VNYSqQxIo4Pi`qCp0ZAigE!AL8 zwkl5Fa|#qp4RA{!OU@m$psId-aJ$8e%T4pae_;!indweizdO=XQb*VV7b7C8p^njA z&CIvWN9YQNQoPo+8C=u!h_yi?72EQV@tl7L_PyH!%U-OZEkACs`AV)-(nFI-t8uJx z+bViZtp<+mea!|2NpW+@cTB&AAPqmN*ra2ag5vr!=umVz2-KzH#2*VtL!~0saF|0g z3Ts)nBSA!Vb{agZaHncJtf^zVApOHVmnyf1viqBBn6C?m@%FhI)-+>;kre*}ds;V; zuLJj)??>zCxT7___%4_v-%uf6l}EvUx;||TbB8zf&mr#1JhJF{4L3&#r33axG->YSfIQAwBHj4~ibi+-b1iX{<~yT|OkcOPzWo@m2AX0*vVoSYnrAxkZgJ7cNx z-8J%vDd$tPZ`=Z3r#JD|pH3z9r_|_iZm;py>K!aNv=1IGRv>(KGnu)49;x*Hjr#rH zaLjNC6)Vbt_4Bz*$(bC^zt;tyYS!SFRS7tFt`{9=L@+5PhIHKyJLcA{G3571fgef6 z@2ARf>Dy@PGcW)mA8uo4w=X?DKM?aLl|YTT06pin2)9g9z(L9HtYeTI4fgGZti&bs zi3WETe{~RwJN@A`*pMj?rN}ptDtvV@6GhX)utn4hMH^d~x!pHmVtywR)$yG@y6Z4C z6U&Aq$o+iIAC=u}r0-Dh*5NM^VM2 zxWo4h>yv(vZAwaTTo;#u?{$*ku7N35fBDHa()pltJ)ZrtLWs1l1^WIXT0Bf5G$^@@jG3%k$r+MV4Krb4)pDQ;z+I{}G|okC8oHlwjo zRZw-Z0R9>nqDk~s=#I)~Khz#&wT)T${^TKxdulM|@(lP}WTM_Vr`)99KHT>di|&E6enS4YVa{_pJ&`a%u=au`GRnGR@|t;EW#e2<6w zy=j)`LlEsXg!lC-R6$OYP99gs1IkDF)JKLqyJv!@JQxbQpMj*IGTqv?lRS<|0B)i8JS0NmyLA$LYq^K8?13ni zQ)^>#N;Ki(fnfN&Rft%Mc$33o6tym>5_cO(8npKw8=l|{qV7T9efAxu&anacEFl^* zDW08qCl4;mS;5{-EH#mN#((Rb2?EXs*qd6lOwL9}I&VfXd*#pzG##L@T&fu7Ypas< z04W-L!Ur>g=fH6E4El4Y49|796)l_ff$13>K+Wb-R8@G4JvW`1@sEe_X60pAHh&iR z$<4zaYR2=*Mx@bZ?ng*lu1!s|EkVWlCJ4+8ga@#b6iS%W!h#NV)+cc?tKlePI;jzM zav8alrLlw=*+Ig5&oWU8wXiGK11D&$hEaYfy|?8B^jU<%-z@`-pT!`G&TK#!<$+Jz zW*iz&AUEXHNSm%N{b9O?cR;xYR_(Xv7*Fpx{@^y)>ivTqPq1c$lzqvF!bx1Y_ALKa zz9$^KRtR3nXV|B!IpJd-9T%DS{C(2yI+v}U&+MoMs*#04MV!#9rGeBA;QUru1B zEI-WHBy}-m)km1*A91|N2U6I|@~Mo+qvce2`bv0iISXXOmBF~I20uM~j$VOb$e4xE z3*{PAp)CbA*9nr-%u|lf*-K}?K99{&0W^D$5&OzjimIJh#C}=x9%r0n;g;?$a-|_1 zfAkvBcZPyQw%r@<&u-*C|MsB!O@Vvv6ynvpNAUXEA~rmF4*B-I5LT|5&fTrv@{!l^<27QzYu*>SdJA}wJFJZ$vD==(-XX1aN_tcV86b=s(fxv z-Yv`Q9e#_#0@C!vzBHC3e#F#6sl;W$S$O&N1bS~0!`h@gTo?TYB!1gt-``qLc<4sg zajX~-=Y#aa1}A#nb{mrxv4)PGwxh|#@#MAB1(>^X09Raer~h;X+2xg|d0vxJsrC~! zD&kf_D{ri#0m>E3{iCtGD={@-emsZVJ*COY|1l=3ulwQ2yi4rwerq}{?*rb+NXM3~ zK2&_OGMzRh0&;XKm^Uw^XyW0ye67pN=^vU0#HJ1^ST)QzSc8G7YQ)Lw9n*F$55<-! z5+tXni{TUIweVMbI8TuN<^Hd|@%iwm)f`o;ed+XP60|sK53-;3)4?NI^ovsqE5Wh& zb9%e^fA&NYfn!-T>(6=irT<=@U|0@)EX-x}cg=vX{qiWQzMK}}RkV8_!>EY#vc}7} zyK?Xf{O@ZwIJch${l}Z|XN*4G_Mo1L`u&peYLTW}I(pFmgE+Ct9>Sl#wM?kzCzLen zVYSnZVd4R6nkVrH^X;a>k@Za&bZ;gp|NR6%3%o{u*GY6|#Q}KpDh=)$Y0y)`#pDS4 z5~R%3G4Hl5v58KkKR;`e`7e#>&YHXIfmmZionnlWa6_4Mc4T7iLyr0NfCk9^VIIH8 zfOQJb*!9mDI&?>qJwD?(kl!iT_j5XCff+utuEm#PC)vewRGDRxV<_X1!%8+az+1b2 zIB)JH+?_4rxFX;QtUT>aWe4U!;|eKWB{c@`)06Rv?HXL2p+VJ*GO1IpIF%hOV5T#l zL9}@}>ysr(F9i?6&NUn8X-yHr)C&>sL{T^dw0#!GXB{U{!~X#4%?V@6TkP1p%4-m~>kNPVwiIpX_=)A8w!sS{9{C_~ z5%s;FKz(c;SvggLK2Fep$Dh)$q5U4-^4-Cc-*F$kPs@-s+uTW>ku|JOy~n;D@gWYi zCvk})LsPqJ*|}nO@MPp#?wyebqZzJ{7r%^JXoyg~?lShjry*oUfCd=dD#kBQxjyv^ zZfCyX7SmGfNtUdvKn;a2tYUB~5xwpJqgzzy^2|71kGnWLXSG|cybpzo~VNmUt12XN;@c7b7a@Tt~36ZQO za|26J=dK()F?NCzZ?oZq+GN({_7oDE+=biR4&uu_@=)ko$-h0SM@uYr;vBC&F!eJc zBW*r(dNCjCkFFq#PL#6A`UOyB6h}+~Ynd-6+==*&-x$8YfyR90J}bg^nQQzbki%sc zsA(D-as4OrAf*fRKZk%D=g3>NFN6%A^Q6ZQaC1ywd#u$kCouc{E?E2n|yjRI=w2}kve;-07PShgLZcHP&0S7qV^I}?8<;`6FCQ0_m%^~Po3Nas& z*=aJZr0%RQIrAUKw5?LY?4UwSxlm56?2i#^JI)auB22a1UP8UsS>7|97&7u_D%rlH zocwTn%sAT$(#i)sqQP}L_uBfwoL7x(@Py5D)SvTf?K_V1rz_DYE`xB5V_qy+_yk@( zxX5~a_yiue)bVkE7B1CHf||giv|aQQM2xD#d4GKx(qBWZ&nQCV2Se&H?=iF9ca+`t zV=4@qNJ02!9ipIe2WNfpA+@b5z##7;c*u{lV$zf7k&@?dCiW^@C&7I#7i5sgS5??% zpNZchhS`S^Q^-usGfcU&J=kh>K#BEvY?67w+K#>B-Fp~J#A^b87nZ@~q{$%T^pSa^ zeTu(RIv%IQRl%-lob$jufnHB4Ms-a+Yz+#>sO783L>*~5U~vQQvq^MLL_B>~HIM$j zdy3<$l#`6oGkk-qvJ{aaQ%`QEr8~^Y-A)aHdmB^A7W-2aTbpc#1)iYhuTd~`iVLzUK%=?xvO{KFq552dO+#f9h-vUKboj@0 zehlwJ+9Iy&))_**v`0WzZj5=ptpgI}PeSj91diAG3ghx@J%_ddkA zt{dsiDoql0Q<)JNyNr96%i?CsEI?Kf6TW%D=|@R87+QpMaTACL&L`Swg&;IqfQEx= zRB=^1u3F?vbvvuk^?NNuhV|o!&Ub#&kw}O+ehGb!Rl=_iw(t* zQ`7auOMk3b>&`&hy|9X%&*QRm$A;LtFm*Cv?;J?k_=%ANF?iYX9%D2#=-)Y4nTw}2 z`75lZP_al)zFhQlR>1r{iW$0tP^}s!EzCrTlDF7U^#H@?YrvBy;#9tut%b`mkWKA&HOu%GCCnQsp0q z;nML`I(ODm>{xIJ(>O-K6ceCapHGttR4`A6wv{`nAl0syOcu2RCDOBB2{p+*~u8h-@>N<4zdYrd%#mc z6TAESu|4WBM)}E*$ltd>^KLhaYfyHj?jcZui~R2#$N6W$OXx6s!@rVdhb9iQac_(+ zP3xRV%L-1z^lwgV?WhvF=kW*p7d)Mg7jd)Gu>rg4^ z$t0>+ngNmW$4LKTF<{I@DbN22ewVn#{)rZ)liC~E&NM#!oNtMVk+a!rOE)pWWvU!w z*OKyF5~9@9M33tkZAuIRKHW7b~X;MS(km;WXDceeR(te=zk1HwY{lJVFr6|;{zZ; z$zi zFGUOojL55}iEw*)07MEYL87-iaoFw#vkcnd+=g)a@`n~k4ra1bW<10f5?18Z1`Qgt z-vHBph>_VA{m^-TCK;c#8@~Qh#*4zmypbPPw0~U=nIt)kXBS*Xi^@Zc_J=GY+^kCl z?^F?m5H4p>`5qny{$Q;Rs=?F`ahS1Clr8yhy+gx|RH!cf4}-NOSW%1rxcyxwJ+vZ% zEzsSLZ&KXg?ej8N-MXAa54XX=x2q@@n1s&)d--S2q=G29$^RAJ#82JQ1=l1V!Zv+H z+?&0Jifb;1VBK?g%-ov(d$1TEbWFe)PigA5Z6&g*s$@p-MJVOEW0o&JXX~XY!JD-l3@AT5wuyPc?}c{mZ$k@xbvcKeRA3xj%K_Qx75`+bGkrSu;)7pQ{jv1e>k;Yn~*7b0FFH=(K04`)sN1r2Mm z=%UYGfgV`|L64?!e2Y~OSyF>8q3-yhVH#3T36j%y6nds!gq@}7jL0cTl;*FbYi69l z5~nAO#6K@m?H0@5KG?}d`e~668B_Yq<^`2LBSr754aaVgI%@4QndAsLIi8Q6M%!Z^ zvl3ZTVK4tTY+V>a1>IWN!-j5bU~VqE{LxE#^x?ixXk`b4_BnZ!#o) zpGk!8{K0$KqIBO+5jruT8#YK?!W`;AH)aaZ!z*O*DdjT29J5h4(3vU*Tf@$l9_$L$ zr%Q^sjJ1jtJ!zE<4vn2SE~`%LhO-!(=-GHC)Q<{;IZ}s02A7mq!TqCl#G~mL$A&Nm z|2LO0VYND|^)Zl~4Lb<~(^e3vx12}aGn)}RpU1lDw%>1RVaLw&3 zYPFewIC=!L2%i>iZ_)GfZ6+gG?#v%SlxtEDQjgQ@71 zR|N^Jf0>kK1tND!jPwg?P_vI0>CNqb*x%;Yarlf3EZdU1VFluf=mczwp>*14=g5F@Z^A+#I5So$ZrELZ{ooQHPcAX8Jn_9jjwRv`)f~6<=Xy zlp0MmRE1gl%V2nR9UM_mCF6QYIKQ|Z*F@i8X+=BS^x^zf<&SY?oHA=O#ejHaCScNS z4QR7#=DRMGXCK_H;}tk4z*y9DNY0TUA8rMa_{MsoLZod!=dd*%3CXTo@O)OVKsS-#NK*4F;|5!rFoZe2?^MB2H3> z;N5ggy|I9-YPk(KsTl7mx)Q-uKcccZlq{}sr7c~}V6^i&D0gOpv*!YOzN-}@t_IUB zGZKhL+aP-|XdRXt8Ikz{|9~EFr5nAt+{hL!h7UH}6GMUYY_+Cly*2pVG>`mb9|KIg z&+(~`LW#F5h@|ghOp;Q-jdOoapBIm5f(5XyKARco)q)XaSvYWNGj0i*3SJf(B$q0Y z?IxShF}NDy)rQ#na{1u-D2D{}7ehzoCm5hld6&+|!QOa3BGzq6nK1{Zo=t!g*DT3{ z-aW9zGXj>SIMc%m+nJ1~-N1YJ5ySuNgQRP=L_;-=G_+pC=x}X(Z&QV}t`?vYQ@|8w zWuaw266Q@Rf`{ueNra6CEsAPGuP1)QLDrqA$R6U{&$@KQJZ_&BsLKTGQeb}`-vkzC z!eO@9G$Nr~j)q*0_(Y#A*||QIZQ{7P6{qfCRv|Kb0~j(U3%I|>gRXIZ2#>~J@*Rit zi0NiM)ac0}VTib~SSD;t zh1LXO#Vr%EO1m0Tn?>MimpQrEDM947Ja1<01*p?}9kTR-20Z)q8iKYjg{^r3DEBmv z%y$~ceLG$0{`Pg~=vxh!3k`VJ-uUo$p4fx^4mYsdc@m2zz0t+kRx2j=bDr#;ub5r)5~|n9P}$3?sHmD5oj)N9b6R&X zhd!(U@$d7=obhfDTDXKA(@bX@IsW~W+^3Fl$Azhw)hS--wqtzn&lkw%ze`E&5016- zLzdJ`6rg8*H-blzKfSzf7#c1KBhN^OCIs$de;x9}t8P}*?$B|p_F&;ps~-8IBuwjn zXArh14I*Es;rhNhTxn1Y6(e%QW5Wz|KKu`NKDmRk&w_|=Vk>(;(~77YFw9qdgtTZu zwm3YG`FvTKioTH{wx^Ql#~TMwdgfi?7MuuisTFYli7}ZsJr?TPEZ}i=6nSz$AFJln zfZ*SI&|@tHlk9=Y{kw|u4BVIoq0`tc9#3@xkD{|+FMO?ygX+G^Y!bKE_W3vlkN3k61zEfD;{&R-{Rsi)^>!UT)d-6{^=%lGA14U>l!H1=^xWrnnaod$j?T zj5ZRpQ?sei-*)_$6+<=$nu4h2V*IA}lD+!dfe}wCgHy9qY5G)EIv(Q%6VzwXO9D+~ z{;>);(L9U;b4OrhACmvN2=mZff%L!mMBMU|;49ya9n6y^kGIdp>h5e>*PjLl@6MqD zuFXV*yK6jKvkZE^B=P2bb0Qa=KcSPu5>#k^4aLiULiiL>BC~c9?P~78FJE*>Ov)nC z?4D0gSvu03nn&RIWeH<4ozQ?=PcT;dFMRv$MNbq|fa*qfl=qgPr~k`gy{C4w?aUa& zn?GSj`Hr}L@dudTtp-?qY!?e|8v+EvQ z(n(41=}FA|=F`luZ5B>XvOr6&AJl8jG5wi&v^*jJwjKP+5CcDYHd2}lcZd_>5%}yEBDjwTFt+`^gvRl#d-vcl-X} zF6|PkV!0huCjUg6K~bp8`~n8EQsDHHDll4C!ZEE4_zByR;AD*(9$Wf@J(tsrFRlxM z%q1sseNcclPn-iiraq~|6Q+N<7+c8v?*-Qx$0c%LLy z=X3LRr#d!g)B&HECo=Dpq;O8ndRmi}$M-kpT*ik@i1e>@k7bRwEx@F?>*)R!2XM`Xb|z=a5RRNUi&9OMC>oA% zQCb_y3j)b+2`{SoaRaUuDu6GO6`9BYMcTTz3PX|=p*m5APRmH(CFSJf;JX&Kr*IFK zPhLegDfPjv5J944T*qkCF!WD?46Q4WAv#4yr15ellX0_v_6J?$<%zlB@3TeCUzg0H zFNNYTymt`^89#zTK^)U~nLG{bbiqoM3=*a`owwU+4VopdB6S^`V9|VT7L>!~Beelb^lQa>D@$T z)&`K;{nI(dU?}eh=SD4DU4l7hG>CL{KCGq|SKhj$*!Y;_3#GL4uh1XQRqTA^ZRC(VB zzcM+H&~5?1r^`v`x_clWm4f94iMZ|N7`!Z2g^LnD8NZ%JhH|q7ql#;=QeraPitJ;i zPR=9Br%myn8$z%k$Nk|ck*G(Lh|2ftKy`v>JK^?;{EcY$F`m(VWlUChzJd9YaZGre zCS#u-fw?6oh_8zhhNZ-@4$_EId@RYS)nd?+I)kj)s7hUD-h`#OvLst&H~am)0=25& zL6f2xN53|pst;bGaBn3HDNbZIckLz)0h4KB?tJ2v*MtVs%b4?xbC}QNj$r&Nfx8C@ zg5A~;)^Z*9o>ik5I-pLE{?&qS=dzfU#2G?r{mF&3^{mRd^Ni>QKA5#NVqS<7bZOt` zdtCkvl8gLRocE0Q0W=#jY3~a#T5lSM;w8l*Z?v<$x;W*B@pZ4-R5s zjU#SX=G=M*huM~{Q<$u1&6HVgMBP$H^l(%Hcjg;ou6-IdRC{4s9Oe5S--n|Q+VPm3 zHXCGA1Ow`xwBf=(_EEkDyUA!R^e4uF+38qhs#Uv?$zk-k zN@VvgKB4175LqukhP^YH*Br+o>~sbwymn@4!$m;)at6He7J>qscrrP#9L{v?W44Am zk=R)sY+->Y{@`*lO8Kw&Up-FYvDP6B5c9(D^Qs)LAdQi@z_Fs;mg147Da@h|0_3or z0?byM&Hc?Ll+ks9s-MDS-M-T^w#u}?lvM{nA(wk+VFu?6-@$BV)=~>AC+3xo5?QQn zg{(TqsSQ3e9FVGnVpcdJ()yAFMvPx>)>ko9nj{x;+@Z$ ztY*VFI9GTGaWV(@T}nhRayMGkYq43G>CAln(`=b{6|9xH47VygQJwP@ zxZ5s(T{F3}`Zpo^YDqTfX>}&s1xwL`J3ma}Sbog;G-7%94m0KWJve)ThwZ?z6^jwV zG;_xXX<2tt!|NTdLFh8^l-FS=RKnq5oDzx{_u zsBJp4rk2Y;pRY&nvvK%zZU!{2PJ^TF(r6ZVoR<(kmD;h}QEyo=iX}QLes?pq^Q=1rfrMD>$fJ7 z@7V{z@xwR%vtyZfwV&&p1q+dXpHf)SeKmNg%M^$7fiav7%a4+r?&{;YR-wLrteMsg_B?~(1jG+b6vkl$FXje5Sf2zklpn$g6?qt z!3r-d1>VAZP-#pCyR#}7zT^S4?i*tt21PMBiVm2sor<3$JD@u(lW8-4$i8}h2mgMZ zOs+d5!6AA9-&)>8_egGjFsTq4Tr$`wfz`Oyem!}Pk6`1ugP8G8kQn$&(#b^@%)AGQ zSZW!^{E{$&;G1P_jrngFZSVgyBCXke#X0 z&_1vmBj3JewI@GC@rn20#5p~()b9)GXm(@bXMbAH69MDe=e)29*O(<&nz@YMd-k`> zTxRFeo9v6d_wlu#1+tIlG2!8@5K{IS{M&xOntwY z5+VX0MfozmwU|3|9?_nCn9&Se$>b;fU`sA2kP(#$DDqR2GK<#Xu?M2CGWHcSPuQAn zs+J&EO(lpb$FSP=^g9#2v;ptD`Ny78xQT0q4cPWyH_*4W7%Y@0k@}efI9%Y2{J}PK zSAT?y^JGZ5uOu~o_!xDLPoQu3@gTiq7F^xh%<8OLjDFOazFV@5>yEbI%!vDN)12$j zO;#jVLViJaS21JdXo2Uf)7c_+8ns9~MPD6#!u->hCHt0)@|5RHA_GEZWXg+pYIRDQ z6pdbo_do1OtiUt^Pk>Z^&L_&OCU3`?eEi{-4Vj7!tWBjg@d*8ZqaTA=v5As&Xrm`R zCVU=x^5^3NiG2L@z6X{CU4Yga7Sn~Evp|gq36n1-aj_)Mb;qQ57 zWaaueu#!CsX~o&tfsp6S%T#T9>jlZLG`WETYm-IaX-Ig`DF7z;(w07ajsgvma#6EQO)`#=HiM)c>ljy@~*HPf(5=KUAA=7Q1 z#Sco*A}t{&a4nmG4f4v=c1a6cvhg=)JddDecl+53p0kO^-wfWC@^UtFQvoaz+|4<3 zVnNB@g^EPivohJM*jY2PY4`=MXC0Ia<@Jr&`|CdM&i*K7hn+0Vzmmus|Ef&4)kM-y zGDk?Xy)-?&XEpn!l;c*Ge1gkVo_c?E$KEy1n8oSGS+(3q+_)i`x?Ey0GiENF%U?vd zrz(=+5N_wVRRsR46ok@o6VPfACh3n?u#f*O1G%nati<9}P&yp|^=ciQH(Qj(k6mG3 zjJx18g(MJ<+Cv{%rZe&n+~_bX2FjejYO(1{yfW`4J_t_0|7_LZpsFWrly4#H-uj`I z<3GO8`d@SjL9?Y<_4e@wZ# zjzSHZZj+`TMGo>y>W3lq3xf1B72?@ihKdWd>FhpX2xZ=}!bc{8y`dbHvsJ|JLC5g< zvV&kNwG$%47jrY;7Em?gzK0_R+1M+e*}4=%NO@HW{NYXXhu|va!FB_bJ$V4M*DWHm zFIq7I)5e(3Uw^=|dp9uaO$0gjr-+@=FUf1`noL#G?t=NWt)$vGoq3~hfvmHM#QGKe zyx5T(RK}sc=jE`hQHI=!Ql-Bx)WR38TbLf|Lz7=W zhm5)pjLLTl;`&evLrm6^uDGSdU84*8{ra&&QJzo@LGoNA8qYI-sQ>#KZsz9?rH`$N zsMH)fVa7xD!nSPOy+4d3nyb=}1>;P2{u%tyZ;p4j@;Sd^AndO)K_8bu{)VAB)MADW zK48|v{>hT$PhSzZ#pscdo;rBAXBTc>vXE3-XF|`cIQF}+IOFc-L9=X{5R`hEEvMeX zbJIf5H4!0V3Dbz%0ZnR^6hO57N*GOjOJa7Z#PROJ6<8iV6>?wvgy-VH)al-I`mSL$ zu3jLE%iiWf>Cq8Lf83AW;kxuudnSDlRYf3w0OOt+(Bxnv;uCSq(fYztJgujQ!~VAD ze69zUK0X3t+=$ek_YDG;`opHSaALGgi}V`$frz~qghdB}!yq5*G#O^zY)Ps)F%|yR zCXzai0qe!NTnD5c@CtmNfY9O(*yeNvROTIUe4lGhth9NggWCgZ`j()EvnUZwRHf~m z-qg71AaV@8n#(c!CiK9S1;SXlEuX{) zh?1Z!Q|Y~&dzd}&29CTv$Ot)yV9>1=5bk?|LK+W|cS!`SP1e&DKFP3g*#z+K-a*#? zF$D?J1VT6E(-mUs#O-$oZ=2y({`bNS;7`6f8fRLPP186gop?2wR~-sLpZjn*O`^vY ztLUe@@jUUq2O#y;kLpYffH+4lzP_a&M2f719}?GwZnhujm;b+q`UxN7 z^ytit03z^q8JXC9gv^iU5uMmToWbWD1&ega_H}XOw7)H_R2af~b`8n*b6~vcj7e?U zI+z&y8O!=dV9i}mM#0t!;|1S9k(v>`ndwH&PxOGsC3!Nl&KR8JUf}2b2Uywb6>Qjo zrx1Hjk*wUEM|IsoVOxO~T$|;^pH^}hzE)1A#j$)_yaR=SMU@8%+T!v9y#q8W`&+*6QbLjW03p6=S=~)3AMzwnv-I&{g5=M>aQgj9% z^%R2RBOX(BHJY5MkRgY>GT_sB1;SWx{tT|W`N2$yWX-juqJ?_Y`|2qg@ZVER*m#G@ zG0^I6Yd8ekjU-J5vow+s(OPTsWDea-PFx ztuW4MF`r%uaw0bt?q$DdPXfc=mALeLA;b)Lkq_&v>GQQ-ut89gj-K34J+u|by!LW_ za?dGv_c|B1mM1EymoCiB1be;MCC9(< ze|bxjv2Gi>XKpy0l~f|u5jN;zJ{SJXHijp`$Dp?UWAo+fLij|e7nb*n(U4LFq96T( z?HC+qX8)JVQ=61S$L`$1$-Ppvx9t=dURVc0D{t|m?u60Fj5h9Y+W<}PgP2!&Ti6%k zmc;e)C)_nj4DvdQ2*O( zc5tMKE%P|Y?Y&YlHO~m^rcS4FCf8tZWpS?>^PD^ z^bU)W2=S}nSD{P16{_IbzEWIi9|wP`^0@9z2a5YVflm{-`{cbkrtr=b@+G1l-@eR8 z9rFy7w^@`XH;k-1N zyZZ~@J1H0#+Z4joU$Pzb%&)J7`wNQ_v%-j4}pH=B)v73j-YL)!EG7Q^kdE@DqlKC5^AHK*(AkC&&;*{#6hLoF2php=VPD0(0j~c~ zBZMz7?ODy}!sWyaqqNAo`ZQR#+K~7x=h!Cm?J24Bq>I1y@xLv~MaLjBn&f>8cJquJ zew{pmAL$#+`}vvg$<5?XEc3y*Gf&y8xnJ?`L6-MRq>lA9Jj4|In~e?Y<47;>9hg~8 zWvH;FpfO6Is&HxCgG-w)|ihRD?$4;`*3~;8`Aw0i+hi7 z673_r%TH5aceVwUl6=A*@Ry;kN3}>G$CedZu^+|`7vsh&gKU6FFkIgC8zWC2VTFD^ z!hbz+B-FbWw;R4dw;Qo!L%tg?z4k6f^$Sy_IaO@W^nBKIL>K}$U4`nEhGYi!TzfXX z1a8{#*)Pxt_f0szd8i1@v;Tn~%%@Y6I(2esRuFMAY(}@JZFJ$QJa#DL9+q!vz!|$1 zkm;|B7$c(zM0{x{z_WvRbx;gjW^5&qKK8W2tlRk13_y@ z9V^~Bk%3WBYQ9yQm~8om0zxa{jFccbuzUu6VE!6riB2FcHxYDIEb&oh6|@C4GzfHJ@=5iaC!^ zyT_at&bIu~y|>W66k1gb84ojG{_m)u%ui4gsAbrbAf;X%%f+7a1#Nyz)Rjjk5gAP?<4 ziHxEpTGYCLYgs55elCM()f&hCoqK6}>t8~iazATre_#gm5=+s>Enc{>9o(b7S_gfQ}+JJX1_~!;E1OX z722AFAxaCV*w5v>af`!LMY|Ca6iYF+-j7WFD?{@|doZzJ4z1mgO15gt)1x!QsfKka z)HiVMa!tWY^EU>u_m;|oA8##9a1x=VuNF}gU7!;di_nLsme8A16Y-)?815;lAg^w4 zEbOLz{2qZzxTos{Rq|BEl*_F!R$xq8-OpoKc0B}guG^cbPOv3*DfNl)CsAjesmYif z9W*Fm?^(TolLxOt+@s@2q6}2{Q{V>%JtwDL$C+yA7k3enJ23kE!9xYm{(DgtV z@P#FzW12FZx-*39EFUI^1JapEnWAKv5h97sf7naQ<8X0b720)F;}ehl5I4f{!$rnf zgKhHEwJi&RKee$s!DV3cy&leO6C;}^*bz08Us$6O4;z;zq1t9Ma{UJ({$Gu#?ERO_ z%Q68hU$vBRl79=opFL+~*PX+$3@?;kd<8}(m!RDWXS8&G3M=*Qz|&){|D))<(ASw@-Yi4_W3DK)BhK|&EQejtxr&9Y!AsuJHm>FM6=GD z%TRI61$D_BE>F0Oud*}-@;m%ZYW!77~yN%1>te;6*-MNbMpM95Mf>Z0!OhJmy=tzKb*WRL^K^0V; zJV{zJ#^Jq@0ktmg1Ex-q4y#Sl7$y1~uJrl^rv!~gHJ=@W7P@D;fR)EFA`7p=SkKSC=04HRu$Zd&rz-s2(h7$=eMJ=7^)Eg&AG{cOTJvbcwwCwTk)M-^lHs-LYN$C*F(5Bv1A% z;?p^wnYsF3AQO{N);$A0j(Njpv35AX9bO%{bAsxlMIbtrTuYo`&%ebFhGido!QSjQ z<0O;FI7=O+C9dJ@&1^|}G-(zI`f5w6)I2GFxeUF0ZYtqDG{Vydt+{T+bb5d3ZOkbW zr;?86*|Dl#xK*jek_Y)XyrLX)C#jPgt~{D?&kE*OPNk0j6~lbqDR|`Az>XgD1*xLd zkaDn{36D69a6^>sczXsXX6z(q3|_;;= zvp01?n<+PEsoqNOHLbzG7h}-*d>;L_Gm2UH*@s4bddpPpuLaAgeVj{t66*icrz*eQ zu-9`w_C<-H2A7@8?(W2yzf{R~sVlgc!7jbsw)g|=Pw`{2RV#rLp|PRa;Z%D}fQFmQ;0c^v4)-Q<*{9|w*phJ- z2GVBZ#?~xYIfrw;%cL;xzpo)x|8gPw>>~2%VH50-9OdR7T*gi{iW;ty!G8IBFd(N% z>cV@j-MbP**4QoueRoZM2&kjKyBV!}mcVLnv7&L(DL5v%j%Ea{V(#Eaa8bO33s!PW z7^MUBqv|W1&?H6mloa@vY7EIL4&=M#**DNwr9g_<8BE-^i}0;F8oT3n@*d_c=0B41 zgv;WpG$^Ww3DX>blxt0}NpXPLX&McZ))GwY+jz|Fc)@O}5Tps;lVM!y7Tju?N&AfT zX!FY$+IsskroWXT_J=1^1y`;kFy$;Py+510xhnzB9Vdfd4A;d-k_FWx=Xu&~Pk8e# zD)1C`{AEt()q?r#8aUl$gYO44;8`O#2h0sr4{oRjPs!iXR3leVFK;_>H z(y*0lnCy>|xIXp{+B|llyz|y<^Qmm~jWHyT%a_8fKOB4dI@jYD7Q`Og8$8)emOa0= zg}E%vaXbuCnGWa4)ckBaMvc3mLh*XKc4#{|Eauo3#&d}Je`oM5ca46DSxNr*Yq15^ z+Vp)+BU~&$3D3JvF`8=5V6_hDBJDs}KW_rLG?qW>sN*+0`zwHbb^Jaw%n!gvVTWku zUJK&#G8bjj%*fNb=4@>6bMPPL`jPi3+@C(1?YM9XOsx8FYKk_wy6HKQmvaWuY0YTs zxES|rd5GJ09f9TbhnXEA$C#Q2x8MWE88oV?pvMyL;8NkI_@dPpC58a_T>m5C5)Tip zR^w({{=6L3uS|K8B-xhZ%G+b3k2~5G34hT|Xx^kr7qC3$reGch%f5gGW6$uA&_%Sa zV3_*K)2#eBcMZMNB@P<$c*w{F3q`D8C`^M^xaOl=sSz3MTStF$>5uXU=}cus3$5CYu<9I=FkZWi)!$~jOhUH3L)|AO3Jgpg6=Zv zpt>iA(Oky$V|!CzpzsSX?L#9SJeUo)TDiT?12tN`Ns06u{DtEG*0Ya-gQ@+?wd9_@ zE4+I!!1FfG;_#JoNy4eF|aQ*71ifW=M|kk$5a<^9vZjz_+6?3l_R`i=A*An zuUic&Y>_-aXqW}>RT%^8d}fpBxleG3uN&NRNh9t_b7^h!94bBT43j4Q$KL2= znH${$D55va8V2}ctjjR}v0fm`j5=^k=oJuk{WMyJv@+68{!Cf*LaJ9%fKHi40L^8X z=NE;%7Zn^!PlVbz_w%xPPvM;IBgFEH96V^#B_iXTW6jfsGNWE}oqZdMzNo>Y6SA4H z7Cr`bq~o`DJoxcVj4tVjA`iX^(wBNSFgs=%wg2ITdOJ^Glld^r&NIZ~@;v7Lw>&u2 z?+6_VBIJtIEb?_coE!vy=HIX!9a*&$bR?}wNlyau_3m-pd@ld8e1t8Z#61TVj0W>Vdwh+1a~TmG^hjy{^h#I$OH!JByE z5jg@u8|R{R=oaqU$zxZxZNQK1gXp1kn`wR)$C#$SV&nrhz#n-&YoYH8*P@Kj@yR@l zIx0Z!JZQlZ6NbI^F@u+zSOIr4Ij*gEDRPlP+^YHs+J~C4%W)RE&Q8HEd*f-{oqU*G zaGNf%b0Z-o&TwhYFz#8T##Xp0(67O9>^rwQyrXjt!jCjDYdl1-aSz8v1Y=*iA+f|rhWz;D85h!qv}4fY2QzST+?mX|9uei8g%IJXI=KLsT#XqRfO(R zX~rkglodDYXa0;?6Sr03P!<->_pw|@Grw?dGtXGip>ZG*bBVE?JQ|>)$~0qk}NHCeD&lww`4z?}mF@9RJ z1GoM#B$HOyQQmwbR9^jvK3I@LUu=zmf7TD^7JNP-( z7MpkOhNdN=92Y`lcN^o)FdbPZ_{5` zK0AUe30;IMjo0FlI1^BrD?t}?bHPsA45*LQAmXj7L9^o!?A^Txf1f!_R%Tygk8jr^ zJw97#M?bem_q~m4H>v?D&Se}Lt!U&;XVT}<$!_T2+{Ftfy>bz*s(*L%NocN)A+xv*v$cSm-dCq@>cfe z+Zte9r_hYxg`7(+4l*yY@Ygkqe|+U?{LD*0pUN7PEy!{dwoI7Rddy|(fY{UKqqa?7?$e9jW)P8ECe61*z)!i%HXuv!(aeaqRPMT&KL8*0i>RPMvt0D~hh1xgOJUE%1X; zAFGq6NbF)Q*w8Frh{}7ydRsa(&&o@-;B^+iS;oNF!Eo%F@PtwHZiBp} zWjJwUHfh+FfK##-kn66t#LU@(OzK?6?o`#H5+~&8yc88Wb?;o>yvGi7{z_E}UsdSa zn0&G-M3{V#m`j{?b>h_K?{M+_cleLQkQmo2l2bUVcC5+@Q|--(U#$U&x#&tlrJ696 zIFW|=XJB~w94hPmlpavepraFO;GRGN;hWl0(Lf2(tvi=U7|o<9;6)DG8PNppyHkZYDomIhE|c?MT1uIgd#J!f>!-A(`(T z&6GX*jS7EVXw(gLOn;?Adta!kStceLX`aA{C7{K6*z`k6T@3P3cK1>sjBlJR(aL1ZR-rEMzI96Tss9XHg6<{ z{EX<9jaH=csu=BjUk!@+mS7Wg9c+@;kr^q;a86K@ye>LOO3ZWEbY~+vG&P!iQ5iH-5_HszR_?9Ebq8~)ywU-1 z&{OBYAaW$R$AsK1YhnzPK0=DmV>~T2gLA^nph=BiF*SHQwOT1e-Q%T6vw#e(I(`ps zM((DEU&fQxSLe9>bP~HMtB#kV*~QLNszJ%swam%dA~bEbC+j1A*>@`Ik&+rq`k!3@ zOxv^*&u5?H*(vGMOSYL1a@>fF1oG&N&%x|UM-P1TA)4}TM*?5ngSvdagaZ!BH1$Lz zo;-7vByoIj&+H^>qE$*o`i>LpZGAYJtqdm@o`w$xQ>jMIFD7?Pfd?slU7 zZ*M^BVO6+LG7;^$-NC)rOR&gZjW#s(*$rRbRq#H(TT34;zr;DMt*PoZF*@;1Cv$W{H(0FJ zge%vzG3>iC{b8`3I9mT;mpWNc;joiTn$#YcR(lWJWn4hNH-Ig!xPT8rr0J1eTWNFq zHtM*g7=wF+apZG!UBiik@TN)+hP8pro#?>Wy^6=PS7OM-{wB2jZ!HO2oXz-4PbA|( zTpoC@2fbypfErd3>cpQ<3o6u!=*3VlD`eP>f8)sI=V?&iFHVjR+K}mbc{Jor0?xU< z3Fhodrqwqlk;PfJanN-i+|O->hN-*Q(3TXU+@8ZbbNV>m7crqkT7B#W zZd6=cxRnNR@9FImZRt&~?c`DI84x&cN5x}OA^4g-u72svn{z*kjQuktZhJfF)gP+p zdCQb0h68IORYcdFZGwKTb8}~(33cp^ClWcHq-h|Bx#lgyx$C)mzbqWH60*pItGUQ@ zr@;FqKhefdmvkqmQGdOs^itAi9ObVP!p_#!ecqeH@*f=P33IuS1#L!H}w zxHbPU_4=tq&ug!Qzib=(LiIdcA$u<1U-C@Gy{=1bPni&u`5O|{$%OoZc8aR2Xu-)797FMRxWKN4CFXi%@RJ21_y zjNIBfin<>i=o0hqyx9GRaLoM()1Q~h^(u#$PZv+}BqyI_lA|N=!-9SknY@hpPPU^z z9x72=o*4a*kq%!!)>G;IQ@PxmBvptKgfi(~o}_aSyt0`?512i`(}8m2~He`*Ig zd02@qOcR6(`Df6@bz~ISC=W3E^=p{;5lGUhM zsz~1-|BmJ3*YJUzCM_7TBU_RV(Z=uH?Ed}>5GWHtm#22o+#Zg>$gvbG!+(=yV{dSU z{X*u{mn&#hZU)8{aYW|%Zaf{N2Csh(!ArIXHS{z=VL8Vhfsce)twd>>f$X0Xcr%j1a{8ERU^3|jzMTV@y?>Km7>PA+$ zsFDLtGbk04Cr`h6Go4lOOi+;(e%UjVHs%D;QqN_~h3-^bn{P^=k5{n&eypMivA4)S zrvh-}I6Fr^%%g6lwVXEi9AhI+$3)kYi;bp6J3NE`-wbubVFloT=cWIsx2yaw}Mn((Kk z4qY0w*uBn;Y~jCn`1aTh4Sgq*^v~j8`LxpBzr-73KdmMK&qQHa)K#|IK9g*jxR0L5 z&jYg-1(NWs1CpIaK<-aHRqKeR)BLO8gS;?3QzAnyhqx2bW9mf2?jN3bYfO)njX_$^ z8e*wyPfMP}(a4LMa4Xe^Jd-kp4JVi5JFo5Z`j0wrKeG_Z^sF(zG==Dth+@_BH~68c z5T$ZgC-rD5By zz<(vX$){d7idX!>o13YLNz_2h$<5^V;2yd$*M_vcI7wvOj)N!1uXDFiBzk9n`7GB3 zbEp5nOR)(=O{5#^MtSr8>NRCNmR`3E} zxc0DhKgzMmWfQD+m<$3NPm%LaAF_d$CE(f(7xMSCBK;B~LUJ}{vz3jzaPBWc+Ok{m z;k!5N#>nq5B};;C?Q*4EQI%-;UK3knY%sg&2(`G9#q~Pd>A?x@u=A%KZZqe0;!e+q z7^8+3HL~Po)jSBSoj1C4E}-Nd_tDVOsB#^ONsFWMZ$YGkJPWfO7V*cc|}s#`KhBg`|>1`K39{d z-*^I1PXag>Hjg|#q{40tk|E0?dvW4U6Tlsu>aA$Jy3wj9M9 z1K%-0XBS>*)x$^0x}Y_7h6X+oCRLWA)LHHg_B6kNf4fsbtHK<1_bjGc4`tHWc3lXM z;JTphw;?!t2fpiC&#&Okfx8=Rp~l&WkpC7k)<-Ckv#Ly^$YOXo)()+0$tZA41_wUt z6Aa{bch{bAJymzwSLi@ieZ2~sg(uL;Q4NS4KM%2ef+%bx0&-oVu+MNd{iY#B!pF6# zbjL>8us4DiG~J7OoKMC}qbESt{Vay>bjHez4bUg0&D)VKjb~Jk@wfY*X7iUUfhNx! zOj;9x*2lMlW+jh3ox7N(N&3@8Cmraud%y9Ubw2y?V-Q>p*@QZ0_rnhH9Q;amFt@m8 z8Mx~by9-=>++GkjCrrW%kLSW_JsYa%Ai%tQCr0K=E`wby@+8=HlnLu-f|lt;pI7k{#V%bV=sIx<p>UT)H3=+p4hJHgx^DLSj=^7o?R-1y!r8XLS!}^R}mz* z$CLdh+=g8dS3&t}Bl;@O2Kls1vfIlFij(HiN{`p9zP2Fw`T8rihU?P)yUC!pS&HVi z%YaxxB06z9|8b=g_*0yRG;sj;&P}5(?+;K#o+o`~Elw8OAed`E$Njf@@Z;g%SXz@x zj=CeAwrK__aulPwepck#_ynS+d<3tCOol4%_n&ZqM`Mq2>_V= zlgmeD%fmdHshmxn+_u7{RC&76&lJ6Edmuv38&97!rAiM2s1w6B?)GQvBBbY&OPjY6;luzk z>TU}93DNlZUO0_Y9AqaxtOP^1X~fjR9@Pxr!_6adR9|-iOpJNVep`K<`YFvrnH3wT zTSgaHaLukYigZ1wqr;(A1`)u{&rTGvVktYW^yS>@9O- zbtavlA(0D7>kxOH2}lyd3r}F!{TNv?S(GTD6a?Ba5ZITAR&&om3CdE#t=#!Ys}!ZC zY^DK4d>ovtMTGiXX!?s9)=Vc88cj!`v8#?Q?E1BV@-_?2AtO=Y4V}N`D7crzYa+LZHb$69!~u={mg?)IZ6c2xVk4gkquN;&Rt z;~b``>Jt)gGZML_o|!Rk5yzy8AuIOHA`fQB8Bg(iClvioelHpMKX)9Zn1RqKW>LK^)GxJ zNrGPs*3z*(8PIRjg(ZzOXCo3jqucpA--3O$U_B3QV@R-dwaFH#DB{r0^1{~Ro?;QAqB@1#ezcWvOI`YHpE}K7`xXi! zu3>h8DhWCB68@>3qkeM)N%|wKW}B2@^T!*4;j+kwo$y9v#u~!qq^|- zg9wdZ}Hh^M~|?R{p#`LbhR%H?a!iA*Wj zt)qZHR~C?#Yme7m;QAa#?fkKFV>-MxmYeFz$N>xP-VtM5`s$O|Y&D zQWJm!@nxXw?1!(4!%4xfAMBV|E!S%rgdex(kk8j;*`a}nQ2*}`q~|PPG4V2#uvoz}1j~k+y{?=_E z(ffkSk!Vn3m18I{H=fIbJm)(tNTvC$bEvAP7)ct6M8$?axHNnlCW+jKmfsg(U+-Ri zcGo!+Pxy;P30-)7Y6&h6_hi<#s^jN^$@uuX6IBUlhUcs6Fuds>I;x}sPfvi(jEct) z#ZxGJGK(0fDv&sjTyT_Gf-j%m#;bv*B+IdfX(((4ZDCU|lnLcsUwMkP?R&t;<{yQ* zEyWnBFGa%CdRbwa*UYZN=b6{iH|z_pXprCf!r0lVOw#&lU^u{#jI8*MX7d8+pxrET zGh2|PReyq6sYalz8iMk15m0_<3`7iy!FW`Ms_E@vAD`I=x)zhEg6hQVs`^SNGXm&gU|+ zpp0)Hyu%(RIri{M_LI7OfMgZE_N-mwAwxkrA|I@EN8L zt;4v#N}xUQ4wW>G!bGFHY<9RXn`jeBJN1E7n)bu2b@5Q2dxp`uSwcsL?8%*eMdF

EQ+6vH}U>MW4^>IDeC2Wf?8#9=ivNhWM54Z zl2_lbM0*NJ9r}*Xem}%B4HDeh;3Gzyw;^5CwlJgVK74)G26yAk@YY&WvY#hG*W1kJ zdOS<%{?Sx0tB9a_*KfnSr-wk|gA|=y7lGUp0hbO4z)r>Aa9Kea1Y#7(N2eTIKI%q2 zlGcH?Y%(oMiKSI#a|nCx9$#-^FB~ZC<-BlF_;F4cne{G(JiBrUyBTC*;Aue#tm` zMA4qVeHGjBH!gt9)YClp| z<#s;RIlqD1*%r|I6?y3I$uS0hwGhXn+c53iaps!XQ_OLQ2k*ZuEZh5M9ED61f==3E9PMwK*8XokV;Xwtpt3E4l}pGsa`&dm}(W2T@fy>F~QeU=@=%+PsM z+VUd)X#a{4#Um(JuTNI`bhGZ)chG~|N|;+4^%wz#JIw2GhQ59?pXjvCX0O`|k(@sg zWX;MA^ynF7BAKL0rHU@#?&GFZ<6$xrwxSEZ^K|J>KDRHQ{Epe_^$+i~htjlOK`P-{ z4i{WoQAGR+$UXHU&*i`4__-HU`+6)%%BV(zRypolP>p6Ti^E=SK3Mpr9G>O)Le2NN zbm82~STr_`2$*qu$MQRve)=G>S~d@E&B}AbF$^Dvums`-f~v;Szare{#NaEpNZMuJ#`o0OMZI>}v6jaYd6AK#c-Lw>)XL>E7uGXapz?&*9{VT)dg^{XkvN%&un}30EnoY(!2B17~{eITWF}U@OcMJ`6EAgAi;e2d$jD zuPU?+ie&xCaos@}(VkDLzb&I5YJR}zg0&#}LKF^#9|MNlUChezBv+ODpz`woj+Co{ zj-MXoUr%G63Z12q(k5(0^I2>$`;H;aB6R&47IZ|`kkr>){yJzH`Onm@PBcXaCRhp) z#}{_^bK*p*^*WTiAsdPHAA*^ATj~6)^Wc_VPudRc2a{kI@_|Yco%(SQQ+Zbozb=l!m;;&6A8SbplSY}015w2P{0rFi@ERUj zyB@=Drh&0%FWVL-fViI&e|R{v@e@ZY;q{!6a6b1Rre4huN6ZFtSzj7y;Z{mmkk zQ)khdPkTYS_#&oA7~$I)i%ElfE}VU0L-OzchTWf}>9t&aP>~ZOo2q3=y<9Kw!p?xg z-4Zl4lpy&{wq(`e%iKArgc%~kjJK&Onk-v`CBer*XvIa0UH%fq z`ZK@t)dsr5QXN%a>(J`QCm5T*T>q^-hK*?KV>Wwiq(_X7GarvN<2$n*BeRUho1_XJK=<>RMyrkJofoA}-R2&*L|iPJAW8ryl0 zORp`_QG{cYwZFpjF#&Xp(u7?jC+WgHzVNX99nb095gZu0%LFbEB|X1i;juYOsJWsr z4Rq3_|0-_4PK_$EEHDmoy|&@nYfY%&WJGW4R1llTUYO5u-Kv!~(G3Pm=`_P!-0)y3 z<^?mbb-)tyL!nyC5-*>qVPJ1kIk|lI^=Y1-ZwvgJqc#YRaieb8NGED2f0dwzd#!fG;Cy`Tv zz4Lcd=>TE!ROkp5yt9-2pneUNaU>${Zw$DXC;qxE1^y3xKsk?qo)_8|^z?5B6IV znOob(AbDOsX8bIMj-L~;t<@EzE=v#}(J_4a{xDJCm`M-p5qeuLvwd4~@buSNV4!1* zOA77ix>#%Svp|s18$N|P1|FpUP$sd|vnAiSy~e@j$GALM8fyM6Lgw^pM)%Y*MnE={ z+!6Lh12K10wlul)e1n59jl$g5IE+%wT~DiWKdoA@Q}? ztM&>`g_@I@^N*l~nh(6O*+hEeR$^q}S^Gc#!4zdkm{BW|2^4oh@q2Fg| zcf(f*n&QH=2&LmMvz8(%d;~A+xmmKD&P6AOw6ZV-`dUk#Gk|I!(O- zlh-}LrDxqq&2)46=9w;;k!OQPId8J!a0K<-)I$&ajl)wVYNR;wDQa(CK>oOKdtfd< zd(m=aFKKs79 zPfBa(?(Uy8Ej1vj3Gyo!9JlKJ;<;0T9OzblF%`7@sU-zgcguN)>$$nJ{guK&n z?D7MN+_k)&%h;X9XAa}QFA-()*UOPMMIGY6QzpTxF3>QSA>--Kh-IG}4Nv}#p&he` z#Z*1=p)(sYs|s*##1Ok~!5?V)F$;~?Bonl_e4sR1P0~7b(=E~ zAVy*ATsa&PFMuJ>z07^-L~`LlFZ6_`}^Cif8`fg;z@u+kZb%DeeOZU37&$cQ2T8{wS@0 z_qc5P9Gc-ghLO`2)1ihO9G^Rp+6;2}?4CrrxIYdbjYtylC`Tw!1Oz`3i|ggo2MxhcbOKcflLPo>h@x)6HRcn5tEe1Yd|a|qfC%ZRe>20DFd2y2om zN4_i)q^&CqG3W1AT+-!0i))17VZkZ9UTVqhYjaRk`6+X-<{~+~@I3a$3gNBAs$_Md z6g{*G+ z0s}X%z%4F^u%^J7x(uABpFAX~d#W87kXnX9T#n}WpQF5h^flBpFCK^Hq!aVkXYrk; zKmBx86oZx)!PO{BS}{o(7OeQi*QnOxU+VUO+-0eF;++=xyxSBz=42A}h8VP<91G0s z3fVek8|&{ci$!hfsMLK7$Ig_&uHk>o`Qvl(ze*1{@6I`sl(pF#)>hQK)Sc#Y%-N;~ z+bQqN2zY%FCL30ZqPyD^()?T%YINi43Wa^~$*2|Du1}&}wbE3pMISG}1M+OM0{dX5 zBzfr`jC!&su=Ii`FDY6SJN-Zu6iOvG8o8L^_07ftx!qK3_9F7|cq@J@Q^$C|FPGyrAySUfxb$-j_ViDrCEJ|I z(OrFvup9*j;Vd|0;13oXgE7ZrI^DeE5Tr$Jqnoq0lZG+} za&e|6JM2>fuMWS%Ih8T6$99leD!^q2CbnSk+d+8!=K>661w!!I*;JRyZ&bb*LZ?0* zNL!uEOl=b;PC9?tMF9pFvvC!klb=AY4mz=Ic5m=ebSL+1ydT~_)+Bn(d&%YsG5UVD zI<_oagS-FDpn)HXG3C}24A>Qi{$8Hw%?_}mHU}U{;sf_SYyq>Q63oTZf0)6|T6D>Y zPN?3!g&Ih=@Cy86AV%AWjL*IVL33u4$P20D>(!`hkHQb(>t$!z9PKPz;-Q60<9_42 zrJd+puSVp}tL-yPCenl2Ds=C&B>Y%ahQ4xx&>XuLDwbOA;IM|EV7zM)hDH)c8Li+zjX-_+gJ?d1qble=3=-l)=U*m zxGcf-qxe329A(c<L_JA}M zOa6jNDb9nni?mdQ5VNk0?D|u0Vc`T-+;&Y056P`1((5JaPkF zN6WxPh`}J?Z8YV^f2e(UJNb+k6^b zx7?Jp?tBGyG?TemGK~yR@jdDEMT6kx<8e@I7({7tHY)+j6HmVy_x=@9fhi}2R54%BK z9x=(ped>?c>ML`Jx8MeRynGp*S~Z>S_gPDgr<;S$ zhH+eTa0;!zElb}QJHbGD9p?Fjk_mg=XnXBDaFnwVd#e$NGbIZk=9SJ&dPq6y^L z7a@8seJ``^W)RXG;af2;% zczwrXub#p0W#1sXkVhL^cdax7 zW^m_1p?T8u=)F`UO@8t4dz~lTeWgeDi%rDAS*C3C!n1tOfE+fFn~feh{FR;Xc`{s#Y-7Kg z?<6DnT*fH%4}9VF#cuwJc#iAdhGgEv?epaJhz_*yB3$(s`8wOa$ zg}=~;`jew@bv9-zDvcWzu-10#yb(0@UN4n0z( zvN4>$d!3zqbdeg#>P-g;+K-3*-EoUmEv>Par6Us6Aas8jwse<5%=%osQ7cE(%vMsH zC3@KUxq|)^T#q?%mtp2dU-sN>APT>oz-I-1bQhDY$I zMG)+3WmxCzOxCkOpRBl8fNTBs0e$xme>-p;hk+P)Q7%sZtMNePnI}Nw?or(E^)_m7 zv$2^Ki)plYGiWr);%kczklsFlf7sfI9B8z{Cv)eJ8$E{LaQGDMzuk&QJB{gfUmeD^ zD2VI{I|e>!iTK0Jnx^W`Cdv&ZP(8I6u5O-(%0~*(cUwGNas4T5RBmS{WCcKc%vx&j z-VpPg&7ftWFZ=lXdhC5NgNWW~V(|G>*f7x#-K@1?MR6RxD^ZMfqO+mXHx_n=WkcH0 zd9Wnj9}A!J>moL3v1=07(eat*Xu-ly7-jt*D3)8}_QUsi`(HQV>v@;aCpZTWycfe& z`Wfu8qqm{_{0wOF;`V*(7E@2oFLttMJ}$c(gXPWM#PT`ErfT+NXIf0TG+hi5c-^Hh1|aCOrBYSrI)*Lo1X}bKAFm-CW&xeei>Nq zCr3VgyUZ`l`M|i2*5V~@2eQ?rgi-4(KzYjtP#!MM_^VH*7yiCt4TKDd_4i@)*N!Bi zInDN zEXL$RBIJC1KMHVjQfHmXI5W10P;UDW7!*E&_lpm+b_+eJlwcm)@wgPMdycTmLJ>r4dn~>B za0+BbXF$*GaELs52H#DK!{OvQ{)@(i)b6hnxp`fXTy5V4SGiIN{WEuvpqhX1*No5fpYLTFg3~Zau$kxFUIk0C;y`bwHv8w595xtoe3KKp zB;tBGG)kF~Eq5a1cSp#6*lQb)%TZ^{+(L1RdOQ z$BKBXu3~1-?|`G7KJ-XXJnWU4#dsRs{ zHCW89dGSOOb65nurByG==gTHCFd1>HKwBOu>lNC+i?ekJ#5&L-B`D&cA z!HO%@D3eKfD+DcDgG=ntK>e^_uCH_y_vTIGnHUjH?HqXB)!slap@bBp#Sbtnf$l;jbJEysz&o|R9LDD`GOjAY_gDtw^J{XtuY#0Q9p)-4B3Yj*M8#I;^XK)BONbK zypLTk2GRLh&&1+eR@_)eiXIa!rrM6(_-^NN_~kpAMwY1ZhXs=Kz$&3*VB#oxZ+8HT ze@tl1vfqSXm7+H<{Khq&GIa2@JFv8L0t6&WP-^^(os#Q@?Bz$9MrZ)dU+YS`GzJR1 z+De!bwTd2irb+|!mebBzX0)@1<29do^tX{3J${m-m6SC;QjkQ)lV3==&Nx0SXbl`~ zPQh_cQ-ARvpGxkA+>|k6~qO3>5P}DE>4Xw`WbFG;p5a6Hy|k>Z{?AS{0io5`(pUoM``- z2${f4FgSTmg&JS@Mb2N+<@Q5XgPKkn)$IsF_5Bef^GpUaU4D^Ve(%Qbw~V7i zMv4D%eJ(Z~Gz*Wf8x6h1uPc-{&E%p~Gdf<)mX4lw3HtKGh+JnqHoaGds)j`9>-`IQ zSDg5{v?n-eZWVs{)C3uurqgL}>qJwMZ-UJZMezo=HJ~pq^d+0B(Y;$gVQxe*$+C&4 z3@;2N7x!hrb3G9?+Riz9WlFnN^rHRb+pwigf{S|MdF9qes9pOOUR0z~i{x-#7n34z z#E-*%AyV~zr#Vk8nuT=~OSx%J2gY`~(fF;H;JLL~d&AwFP>6Q87p zxW{xLZ_I5%|BXjrHmsq)t)uu>`_cStM-sii(2WncNqN)ZyLj>U2;A^u0)N#08$wqE zL93(|wB3%!q7x(NTIK!XKOie)61<^DIR)$&_mS^QoyDj zZ~r(A-_NhW%(XLU$d8p!?qH0%12#g3|4rC6?kDygjD&-W)-Vm(cSP^98b4v^!*|y= z!nq?h0?%Ozwry`f{+obA*KU6Ceh_cfwuEMrml%9g=&oI*4Cl6wg}3wDz*ze(1YdiH zQ;(#uZwo)+D&;CW*@=g_;&M5Db@LuLd$FAvZ@0pTkl&bnuhcF#JsX3re5 zd?c1P>cm|gXUHxg*EUKyhb3yS=9Bf8kfI`8uIW-P%uxPAh58D-V(%d^M5p7bf75x_ z)VXx8=Q7doMP^L8O|Ust31{jVlXyjFpPjVVCvleGZI}4ojx(puhuP=m@sd%?aC_}v z@rLWgFtApih4kp~g|~K#Wx79#_uo_#?c8b1&G$)y!g($9E0}~GYnAxlpm*4^#g(d9 zZpDF%NARSc_0;B=F|3o2=2#d^1M-Fb_cL0eS$KDYFYL}8g2%00_|26qsAF&z{=08a+mFUUNSGN{xRr?oz8{Fj zn||hAtd3bFDa>Qu1!yyFgsvfyv^z$RuFG4Cc-G7G<8W!{W3~5JZ z9?M@G025}f_s>qqhP&Wrh&t%1~kfdu=5_RwU%ju}d-fJMDDzK-_d3$O`W4x4l2 z&a~^b68)B|LSHsqV!!qW(6~-V`uCc(khP4UF)Idhdm~?(Ilcis0tIbw(=9ysvYmC! z8^I_0y7MPO|D#Hy9{oGwAWXga1PLvh>mDz4$QP&ridurIvh^ z_%7%@xDP$mA4%_28SMKajn*q&1+T|%Otq8dpS^EmT7o=RH%?*KbOY%0i$JF;x>Jkp z|5&q@C*Rg6gBfMzsO@(IMjd)4R{Pfgx=Ob(^H{EE^rO$@Q@=m~!ts-qoFKVOrhZk5aFzQg1AqHte6ZSqL^ZM7n;va4c;ga3l#-&iPk zv6c^M-w$0maU`XUHR$K- zM^(K?^Ra4A!75bn2jAL7nilsng-KrQ?izuIddv#S+^13t&+G7GgE~JvEd-4YnUe2E zYoW5qM&MUIgC^B-EVUj>E!C^ZvoCSsSB1dLcUlOJyK10|U-`fY|f7G3k^ z&W&@ZS78GV+kFDAt=$7MKh&vGLnu$S-b<4upTK}Ol8||57EHfT#D6?ept7TW0w0wF z=hbhJlBEn5eaZtc^X2}!z3j=)^%!}_6(r>B;e3e^4*ffX559E}He& zc=)b<90|evd`BB==wFGl&(Fc?4?khbz8;a>=PfjL?>c_)-)pdca6q_R6M4nv9DZk% z6i%;6!qkLf@R|{a5P1*J%GzPX{YR*|-j|;6NEV(OZRp&Pi7eL}r)&zss*@>vOj-gFmc6>_UOYphhi4Tme>GVHeNtZ(;`8{9{KT$ZEUTe37 z4>$m(y6qG_A5lUVM(ySDXI*%U;$j{w7tYgCB6vsYF6ilqBqyHOQ5W+*+E65DRZ^1l zi#P@pFKYAsQMNoUO9l!b=i`Onl|r|1G@s$4B6Nm)B>oGQ;n$;m;>1Y@@JrE!%H@HI zT)XzR=<>H|JY=Xk)w9vWtq(i#uHehJQ48UFYp%kotBO=s!HWBwGU5T+0x#YCBi>Ng z;G0+Y&`)a1_|-$V$dBO>C@HH9uHUkFnbsZ(k9GNi>M78<5$Lp=W#S0!NSvJXnGDbH zrN4jovr!-R;3^wK8Yb|u6_O|L4-;*<^nyTMegJXikM-0x+z#jM7=oR3gcr|OgtBN$ zTIF*M?)Ldm&#Fn(=5rft^eV){&m+<5cM$e`9>mi(3m)PSFMPGJluTW$2dbv=Lc(+~ zuW|O|8zS=1$hH7LeLnwctx1*ad~jB{z=)Y<54Uf85zjoBV;dmknDgG7a^wHB`LmtA znD}8W1er}|Ax2}l2bG6pPr;G=-vAhGA^|7u_HxUC8E6yREohy^_&#n0ub(aC$S*Tg z9B;wSzx)cnCuV_lS1s%szY+>XmOO2z1W~ZC1-*t&1VDuh_!W9yD;Bj7$FfB^!s%WnS3}VR2s>PT8oB+b3RP3l6Aq z8=;H+RLv;v>3=);x$c(i{xe>YL+jQ%>5D_g%2-CI*b znvxwL$=Vz~H8^s?V?$rxGvcl-y8Q1W#8!pl?8b;-uDIQs2c<8iGrsG>NUF={d_N8) zMcRBUKl3$ZUb$4 zK;}~}V4&cq(vE=?V}W@#OmGqknp1RV2b61_1vd30_Ug6UWnG_!>t=4IE!))b+xa4} zm;3~RTm&})!tl@=KfY}4a|g!2SQT$ zWXxNA5PwLnfZy)Y+$QP*?(&}?bdvmLt4Hh?ZLv9x{{NjO#f`7TpInnFvoad-)85f+ z--DgtgJGzt?FGgEt%F{Bp)+T-Ifj!+y!K)aIC~A@+wC^co&T!wSL$DOwxgZd*`$cH zRHZO(?Kiue;bUle@ET}~&l38ghV#1#e_`4fb?z;vONVDK;N8rOdOKgY6Tgh0kw$gk zee{ReS9&Q*2P}ZMR>P_9)mp^fe0aU7m<3*LC#T%?_;__y8ow6Uf2Nrr6i)HTT4? zEL}9i?F6)1NYKw*mww7k#)`+^n8fZWTz{w~4-DK$vn%2;C0BhUT>%hf3+gFn^pAt{S-;KQy*t!~hk3Mz~LotS}ccnQ6>G!;|0IvYvfzA1wG% z^FV^XKs|d`p1$odxXbHsX}3wVCGrUE5Lloa?|PCu{v8nO9t8GkW7t)833pUDa%c4_ z?5qld)>46K(O1QobQWAaBg@JCoA4*W6?ShrL_0GbMFw8iv1@oca~i)0r_DLa?R+QE z^1?za5YDCf3(`TqM+bdlT@dAqNZ`Pe_+9BUl>AvB(mlHh_T^YpuRlAe=$(k_UXO%1 z>ZdSk@hH+T_$E#`mdE3SxphOZGJWqTjTdeXLbpYlpj}fc9un~y239<^HNDw^MW`zp zoAg`!xc&gqj+%?AI=4v7U=>V$JsjS;@298MWng4>ERV9zf?0BxiG@!im~Y<14TBfZ z*6v&|Qq=*wEOja$cLA>Z$#W-_MqksLn&@eC$x0lD_YzY}&F=joTvQnE@ z2dU7Ck_J5U`IX3OgV42SBSR;6ZR8()H}jj;vXHyJkOs}_gi_3aKFcWnI(r?u9IOY| z+55qIWsVqLZ55G^(p2TaZtCKz&Q$^y;-UN1%u2kJuW%;Zz_kz8GgUhG++f;!WHkK! zC&u3^k3eB$BrSjU9$n4i035Yo-6uu5&`DY*@mZDcfB_N%{`XqwG)Qv502vwKpa17i zVSv;Cf4@!Zy>^AH#eD zTW(O~%k73N<+no*k@m;l{CiiK(4}h5=YMcr@)emY%r#yA0JwMM{}ahSA|P*`S;~)<|I$v%mew=xvRK?;yt`8WO%N1 z$n*bNO!*Xp9+KMd3dPb!WP1KtZsY!*XtSYI({}~l6nr!3DVlt4#wGr0Xa`EykA@-l zUt^HzI~Me+krZo-aPV@W3tIR*ejP0sZrF(nGLvyhOA{1ZM&X$mm6uJlkC7w4TJg;i zd3NSZ8c}@U1|OdK;@2NlxXwe4ydWN60#kXVl##$*cO`0eF8qN>Ed(oH!zVfKQ03=k zQEuNjo)dK#Vpd&ea-)xmm!5ioK|yE0r}iD}>mG@LC5ZMz-TC+S69S`T6kj`bwGgcN zA?zKCm`2YNv|RE5XUT{2#wqLYOmYFr$(Zq}t0rKNmW^ml&II0kW4EX{<_SKmJwv>< z3;YVhKX_iW2v(}Kia4hfElZSz?WJzW@CntrO{-!aG`0lqo6dwtI zG38g-uVGFYR--{D4K?AfNAE??iIteGBFC*(HVHD(Q*_Zfg^4=-XnskD&&&47;Mt_`n>t;82I)S$@P;fGemwB@)|vrMMoH;p6PbP$P6* z)$}@WpW%&QJ5dAu|IKBd^}(o@J6#;T;UxKd(OC3Q)|Kqsp#uXR+LG?I9pWM(pXomH z8M8W*2P$zk5MOx`4&d_xp_R#2^IQK8cQK`_&pLTrw$Y52^|WT62vO*?|5W3n+ z1`c;=aFZ`yta|o)Fm#$nv)1?%yHBgYa{GQXo)AhbBhs-ge1YBS7#kiLTn>TlZz11H z2WKV>2;V^=d)bs&QANC=ysJ}SpefTOqHP#G^bN6cScXAw8bwPQL_~J|La;rw z7n9~k!81_{D4F}C@u}+=Jv$SZZW~7(67OKQK^@3GUIvpZ-iqGO{06%p<&lAoHS8i% zTsCtkz4!Pst2iD@GGbQXo>w0PZ`}%b{&5U(3la1qV;Qo?Sc%?A8qRKvQKRNZqG>@3 zWq+O&uq>OuY}nx=pmXymtFbhrYQe!U@TDBw$&X;Ap(Du1%cJSYqb=m=TN7ApDD=^^ z=d&OQpj#FnU{*eYe~A9aWN%-<^2o1t>ht_y{qT11)W6EKG^5z{jj;k#B?+xog-}{3 z124vW!W|7Sm{N`4pBYi6+UiSA=$pQ6r;Z;i+;XzC!Jq1*u+>9+E^6C6%XHM4+P$;Xoj%XS#HCP0<(Jf zy9iubm;pXjM)-Wof2dP(K>X~T2@mj1qUBc%>BsYR`l z@1TkUT=DXwH8ia?R;)NS9GjPX7c_^fOft9veA1GzAzOjFd{d<_Ha6n+0ZEv3A_d=x z1*S6l!a`d)I8MEXq8x1@o7N#R?+vMRC>=+4dL04D zsX@I-FIdTEJF-&i9;gfYuo`lBa(E@U3G=qif@a+3dWv4Jjs*YiOnm%fgD6BYiIq5J zVZ7B!Ty*aYD({cL{Q}3%uHv6~xsaU`f-v}H{WoTHX&2iT^95ozIbyqQxp3~1#G^u* zyKjjnJbT?NzQC$6J;W6LM*qc#&r`9ukdW!=gV@1;(ZtyQrUk?ACl1X(h` zJrpi&ZYI)G6hW!gQoOY>5r@t+0Si5K`n~iGs#a;?z4{b%{g{s5FaKcEwDtL?+y~-A z6RUBpFu&Ap?7-F$N1>#>9gjunp>b{&98~mU;XUCnWSA^nDpto^_G0q7Is=kDl&H(C zd8|R<7}TH0#==+W zFf(WsxGPH`x;aEdc8_H(Y%iF~?q!uOvoP!JH&AK$A+8+j4r@p2!&R?Wa3sTtpHA-p z^{wxbr&{6l{jYGIojTvYA|491c;UzyFCoEn0WDa#l)b&Q9K^#4fEahMt?{Yk#F)YG zGIJSszLO98rzL@ny#_r$%z(8!snVY&`*3#O67Y!OY*FQ1fq`2~(oW13-%w@rFQWK{iT?mFxlz5-ZJ=kZr3TBKxj33fsAtGP{>l`+UXB6q-;MQO4 znpBEobbK!w6S>9!CNMPTsIZ8ZhPjDEJo_ zfggO9!WfT}qV+z7qKv-JXqw^9&!jZK#*YPLfRxbL-6KK!nGXx8IK=i0UItO4T&etu zhtTU64$qew!LENQ37+v*+T)_ zHOZLiHZUz^2ksixBVH!#=>nHoqEWO4f1i4qYNVL(sIq9f*8Ia|@$U?w-{TY(_7ub3 zHPTck!kWLcHs%*+t8n}98C-SyL|S;=od7i{>ZR&Al5 z(3D)e?a5<18`!oIBYNk^8#2r@7ncl47c}``8tUYTx)VOal)x$E!8u#VeKMav9o>(Q z7X?6n;RfEOU`A(du*D_si%GT25lqRJ=a0)1S#)M+<>EQj=$*llfM%K z$WxrKq8yS-(!uPy6mEMukPltu$kiisFt|>Izx=ovBXWZ1(=ZEY_p}zvzf*(J{33J? zE`lu!hNIqiE!tT)lsAsB2J?-0J$ zZ7>dWmf()xZxPX)d2nAo7pHfqa=SVM%$m0yhYkZA0{EyT&>gxH*T+67s7Kd!+aP8C{IK5{{{@ z_2Ts&M$CU>IX>~3jGEU}=-k(}qEotEY-#36+qIn z4zlP$iRkMFImUISaI48VprI&1>Vz(bv#S2++i?U+DugvCXc*spQt%En*^(2(R*IACT1K}q^lR{(Mnw@$Qzi3N>vBMzXb0`VDJ!n-e2gP9?aRFF$SXI@A9Bf zeHgD_IEI~quiQJBQq%kza3W{<%1>`dvXB+}_G%bDmCNPLhhF8O zymI~$9JQwu=Z+BgB0@&ow<2(y1!VU8|ct*gX8d^-$5<6SZ1aG|JGVg$eApoY>yPPcDc zt=K>C1ZaH}y80H`!-}X#+Aw1YVMM6e&r9O*XREA~D%zX$4patBk?;94VVQgyUWPXbWNH% zy{q!kH#MGwcX8{NjfC&4WzLe0)Nhg=W@MP*o18*++1n2c4;_bD)dl3!vlLNajv{$6 zM1l|33?ZlAKF8DoJ$|B1$S#NWq072K*wJi>X$_+xf9^{5+d&3vw#~rF+l;x=FLksJ z8il`VCFv{kO4#C~5Bns3uvNnYL9#p!Jaf2d+-&;#9T+s z`3yoWJ25x@Hk;U%h+a~Py#AjoK9Bu`V~=bR#a*}pXEROly~jJ!D3Qe9UsdIjYLeXf zgd_LO_T`h~ZYq1a)SGNb-+3H|-_^oAtJ7q_q;eE(^~CaL zQK)9MiG7k3VeEN5u5xQEeD4YYbXVrD+v@T9=Rs(geGSqspCk$Hi^a{?jWHwhY9;w5 zE1s7S4G$#Narjq89=3%*f5=)|?3YhW^~dvXC$zZ!bQf^m>HuBi4v`OU>}bYCLw5c8 z36yr!;OEuCMBa73?OJQBNp9|D{8DPpg3hc*rH<`T1Il>xU;!CXB7?Jp*~kv9n>Z{~ zg$KQPL}u2@Q3?J_*0C&K~ig94$U&#s-*pu?eR&EAiH;F~n<(F?Pz9 zv%c1iBGshJ_;=NM{8Lpxb`=GP-)i4Nhfq&)^WX(YSy%?Ar82~gdaf|KcoSUIih&yw zAHrSfUgn?(SZOp66%LO?c^PN&5RNd1h&RNhPGF1d6XW6kPC`rbdE%up9x^7E!WSuf z{_0m5-Zzs$+f~sh3V6*Hhx~zWqt;?s&JXn6^9`yEW%)6IoBl5*4HsuzU=F$maCM9_ z{^=5QwDg7eTbM)GUfCvE-D}QDYtG=S5f8}4&7as(O*!~;BMu)F-oi=F@?7@&k4o!J z3qeiNMDQ~_f_1`gxb4(PY?_#X|3N-Bm$|{CJ5^+2mMS&g>&XWgrsG(7SN!%c9OkPH z<1byBV2_00BT(6mnKx9qQ_y&LQs#@kQ4`?Tt_V~%@y35M!_jw9F7f=Ag?&Y91on~? zsJRF}O3!_yw@N}_h!?{2#9GksuwpMT7v63g%4If~!^%4zaQN&xOe&s)bN1vj(Qb37 zIbFfT!+zT8bVuVZ{lUEJ_fl@&Da9vMaQvD62kxjSf~i>z5-DX`k@6SHgnX=Tf->zZ zQldv!E#duyqse zc=+?L%%(k$sLY&!Q#NcCHb7durSByA9_|OTZEB$B`sH%m%IWAl(F_H^K)@Fru=M_0vHZ?>u2L};>z39)u+VFo;yRgI&a#2syQPKs{3#xPcmOT9dmI!e z8t@P)A@}!3iJyIN8ZU=h10Oe%7KZ$VV?D3n*6D#PJWb$+y*-M@Zt6jN|5M^HX&CFd zW=;mA2-#DeIS}#OnOp3=C(f;y!{>CrVoQd`2|7y|Xp4vQ$Yilt=hF@>+EhlugO8zg zSvYq6(iF5_3mW5v_?)Xv5PsSNh{v_HOI zn+F=Tx^SX8A3h(N33C1W;r7>+SgTM1cCZ!qrd`GRGxacMjx=qESd0I4^;VV)e2DD_ zmy?QlU*Vr(Iw}W!gmTRss5`a;X1>d(l|x6;rA!3g{`#;wR}W^J%kqRD1|-wzIP(xY z(5Dyo;8yQ)JmwH99+-Rwvo8eVz2C&SmN;Qlgy7xWQHH#@P}J-F z1IjWM!^Ql3jFKBkFNY7s^_`V)H0>kVG@uVw&;JUWmGi*luL7ive+t*xC@`AQ&Q_fM zL-bwW!p9Y7VfGzE=Ck)a;6!2q72?F-C^a=i$F7TgQ!*~kh^6V!#!6G{`J;(Hpz7) zp$Y};nZ|q;aBVr%|4f3U=UI?fx0PKr{DK-c&4CN&AZd>}sFIw{10oYepVd#G#FuRR zTf7n~|7i+*J|SutH65I$qyfphEpGWYhzIR2Vs{pwV#mJC#!*31bhXk+I5ggqoZPg4 zInFlbK7m82!N4ehU$tUm^*DH_dl7Nk2p*wdgioS`z0<<==((_$6vbEIB#(i7UaurY zw+d`bvF74nMZCFeJJwPzrlU7#&bJA{^JewqycD>3ycZk~aom}>0u++!U|*d-zMZfF7d<_}=8fMDfBSBTBclW+_QLU~Vs1p= zimp_)yQKjAyB{;m4B3Qed0elq1sk-AA^3G7s;d@>;$OHxc&{FQ_%nwWo>WFH8!75H zNE@P?!r|cNTkxrI102h-M$e+t?8=m4R09)KTvr3TRHWg-x-90HSVpvqGg0|{H#vRu zJ-my(h#{{oLE@popgK8H+}dT+j5iT{8i;MjH1Zw$HVE4t)VRM zvkEVGRmk>!Cb;ZPr2HFt-Sbvpk4skSi37dnoK_ zv}kIL8SIx4bbasV;)-u-z5`@W5%AtTORj#mjG$ww(X$dIGAC7NLFok8L$b6%iK z(KN6aqr?^ZUEs{5mCV-SEzXD&G$my<%$1UYA3J@(=j>VZhtF9^zw7lPg{ zZ?f|BD;Vp)L|_jsCeJVKBJ)}dV0>T@xzZj%ymu60^8Y$%I}`+d?OL4wk#N7VeE1$I zbY+zm;GPNzo)$hq^rtBJ>56I(-0(arn`eDxE2p}lP+wa?a0%IOjD zYtKW)r)!wU^IJH0qX_q$$;NZGCvf-K2wY(+7G*Ec=fVD3&=-FQR&UV*lcmz!sa+NZ zK6}ZueOt)tr`L(&3w^3mvXf1DqsXbCxv%uEe2 zOz5M?T-J(OC!*1!*%q9(r=Z&mdD<4gnS0$epip#G+!Ch%b0?I7x#~uKSale^Vv)w9 z-^`}31`Xj2L(5>}JZD_!Fom;b1)6)(nx_Tsg*Ty$Wu1s&W>tx(7`g%abDyAmuob`D zE%c7Mx8aSux503{7C&6rLdvJ^hQ${&>29HqQu9ZG-RZ}FMbS^&(S3h9s`#fu`P9)o z)bJ!s@%+Iy24v&(1!;KB%z-x=WZ((s$@Kg~2^!^EK={}rc*p7$|DZbzd)I`5^i&Oi z+7t|`IY<7q455ly&)G0f1`p4Kv*Xvkv4%s}FuZFD)RZAvdEp~b-H`-qLiWIw*kJfC z^b))G@E#`b?je8Q??%`c0aK<;BDyop@zqQ>bT=PG4K{W_DVaqtMReheFA1P#WX4Q} z42PSK2f;%}SGH-*chDL!nq_)cLr-iO(Z8`4OD_8gnKv`0?*1R2@rVdLNXhVHl{p<7 zJb|x#AI;;>H^Wk$DX{uSJ{#+}3sZUpKd|*hOvu?Hs=a%jycrM&(^F1}blgm#<9#+N zADst>Uhd_s+a_c48+E$0WGVi5k%Fg>2y8B=MyBWY3PyCV!20%O)Uvb$>##&uG$WhIQ5S&}Y7G@-{x-J`3^PY@v+^*oMhSS8-trEIE z45O2cf3h4mGc36w34dNElBrjmv3b|1%L|?IG0RTy6l+n^vhbw1Wptd-fmy*)s=l$& zf4pGG)C>5_mXnofhCKJ(AzZvP3=*T}l!m**cktXB-6gP#Fj@StIIm-i=}1N|d?_ z`!m%{RBRe1%A356OnrY_bg8|C2@DH}oE3&ErHA6N?W-Z%lY{-fG|^x$MNBBp5{+Fk zg=`E5R{KK|-+3K}L*L8oMqGVQCO6MODM7QEyE%nTpLCJc&q;<&%NKx*%LS5IsRQ>N z?vUH2t~fF7C}xaYi_!9>>`~1o=#uajI-63-Kk&w^EC5kk7~EQjkUMxUi>jRi)}shy zY^(>~EQv;|{-VkSX^a}7PUlQ{4NDEbuyQ4K}Bt+2SGojMB&X5{qz6uQyH4 zKZJF0C-K>^)o}T^4+I_TWk>6?*nfS-IiPM3~4dn-jQB)>O zh=}>pN)do{;Al8HZ)?o z1loBw!(;zbFjYr_It*!pu1zaorKX19{S78=ZTYO{iZ7wqYR-vO_DfE1m=jO*g5VpGt zf-Njzf5r~M&n-c#w5H+R$q9JZDiRNEO2hUnM_BauB#c&3<4={f(0|Sqte&cak{0?T zc=iN-?_>@r%^Zt9#T&8T#TZ-ln$W0fDn6N`$c=@})y0TB829=b$jzQ8b{|$u-d-+X zCfVni-tWKUMtCWkQ&Gq=$aMTTxE#XbQkZS`1@S4(F7VtZ& z3i?RYy*{Yl{}`t0Adxt714nlGFeg1Rs;;pEo7cCA>L&xRjdjFlb06Zb@0#E@ISuU^ z<8j3J0sNgP7z!UQfGwdaWOJ?zlYi!hR>m{n#@A>_d7y!b@vdyDL@0Z9IuR?DEMQF+ z_F$bs2B?MI2WEE>Ya5Oe`_9!UGD&9N`UAmgsUs_K7(<%M^O>9Q{H?jA#TE19aO|OA zbe0i#ZNsba&Vh1h3Rpl)cd9`~{Cf6NT^sf%og#mow?fo-6JZ@1M0H-8fbS*)$coQI zXJ;`4g*Kwo$RakORgE|Js^a58ryIkVe9<;Xd>5( zt9lpXxK#zFA1N9=|38)zKwh6SS)=&FWs)Y0Ao&zu$d z+e>BP_)dY{v`6TaY1YOWA-7W6bw`^3mG+vteT43!8eCa!n;nTj;upqgUG}j06rm!X){4WkH z;~UXKB?E(Irr^tCnxY+QR;04n*BYA(@rbU7o-lCz+LnXyux<* z#Nvj(0&i~JR=lPthMi`D2Gt|ST&`pgy%Eu*<;M?VUU`W9+B6%3PDzRz9!Ln?Nt>A2 z(rN}0+T8Afz-zp;fXGFUWtYB)g*|!*Zi!!yr`~$mc!veBD4Q0ry*fwaIHnmN7U#ei zzt^C+YXpD3e;CfZ{)l}xD*?G>`%uTi3D0G#@ZX<>ymZce@$D}eKwo4-)$Q$gwDpMS zmESK2=kF@j3?Ji*pA2l0QM`rFKfZr$%cp>CfN-?K`IE(^=Tw+}cm-7p4fvkj=L z>}go`M+Wc5XJgdw5IEgE224ku6CH%psLGq6Rb~{jr1xyv!I50cK$di;T?W$YM{F+D zG3ouv+$sDcRPNs=YI9A2qW*etS9YX756jVKX&d2!Zw5a5FCE(NY{5%4?xZ9@haNcb z6U-WQ_~9?c+~BYxcSrmex%+go3#;{EC+v zRt$B*W6_m3rfC<-cZR{Vp}s)NcZhYW#$d{0Wwv#}LmbmB28rv6=#cNoAC_!_{d+y| z-MPi=%SkEz;@dL%7h}xS{)8WGCF!uGS$ILJ3tcV7bGv62 zRO;$wRQ8+&4nA`9NI@W62>y0`b5N15>3si_-iq5a@ zB#+bMvE$1ODzQ8n6)LV{X5KP7e^wX?-a3WW4xc7;+TRrU`jm<6SNw#hTYrd+e#Js{ znG4@2I5OcGIO%MqG3F=e5thx;9!l`f%Vg;T`Hyf#>j*e)R;5n61+Ds#V4GHHmzf}2)r7Ovw|3lGv_+$CDahNE3h9oOOG8^V|ofpzB^;4lC6{WOA z+Ln+-tT|F=YH;So#*#^9EZQdtprg9${eVu zyR$Fy*PyID8p_rS`R;c=R~C643@l^jp7WOY|BqQ~hI==Y=>ZeR^eTp7#v57y9wHAV&GCylnLp<9LJ z-A}o)vEKxrg5{xg-XVzc5~Ux6H%a)nTqyrkL$t;p1NmD@*raqH!qHne#g7H=ARWevW37780X<uMx7y$8rgx(k8Q6?=Mo8bblCm*4y zNBl7O<}~v6zY;i4&CsG$l{W0DAaPI5Vwk6>Q183~2+O2!+}ablsPs31=Sn}_EL9{uhinwOVR(fLR5 z>%J&B`D_zRl@p~gOL-RHyvZ0o)ri}8K$iAj*n}D*+F|?8nN-=z5t<6@V0=D@Gj9GN zhROSgzn3%JIq;Dz3BL&mn~uQuOS|yax-4ka+5zP)KDe~?8x&`p!It`sApbQQe5ahl zEkJq6Gzv@Np9mBViBN~(0z4t3f#;`|qK~Tv-KBdD{)UHheX}UG-l{}9K@G9q zUJRBgE^Nunc2W>of&|73Jm1=UG*ELagNm|aNE#K_Gqq_!0m`3H*b}Q&~Jh@>~qcUjpjAv*uu^!G@1y1)RS}*oRKy->0osPtLB?7WI?>G%)jRis zpNTm9%-xTD(HR(7zW`HX{-Aj9DEe)c2Z-+0CRHwvK)-S|oY{N;#a)(h8#3q6lpRv= zwyu`YpgQ<7RvpQ3#F>w}5)bpy4T=#htN2aC}80`t-EovUtARG2H{-U$5qZerADM zsQ?>;L&(`YzJrloMDje6tLUM9Si|RFAY~R6;s1{Pmvz_z*E()m?>W%fXa;ecZsAC^ zK|+W4&gADJI5b-WexFUl)=87@E!vVan)w z&NJzey;N-oI)3{|HfgOO%LDAl&OBiG?Q^;Fe+PsW6Gm-EEA)B{IpbZ{}k(Ol>6 z<&{rH8RC2A$vDcu8LK)Cp!TUdk&)=+((jq!lRu|H+?cm4rsUX{sXh=~e$h_8zMC)n z`Sc0DW8pb`GGd^SEXTwnL_k)@119K-!t;PZlrQkZlF@Q_5VLuPv=oizIUZLfwOGbc zYp5-bL%XXfLYI>x(Z66hZZY@)tN*P4b+6}S(kv;=x4g-XIU9otrrF%=A_=gHMMzk8 z6?0?WbB=qpnVZKNIMVuD&>*@73W&K&wG z_%t*H$WhIm`s}N!9d~_YEQ}dng37b`0a|YYMBHn~QGBP?G;=&{cGjd`eG>&2rtloy zEEzm}iDMf3`{1ILIhCl1L)(igWK>oN331&@OFeDblqe-K6GWi5~fsTnE}ln zNW;m^<1nqu-?{bvXTTgKDEU$^;8q!LqD zCZI~$B1}7E4cpNejV?A$%y->wI9_T(Gh!7T{`=#~bF7ck>*sP|rrb>;YA(eTtWUA` z?*61dVm?k3(W8&~1^k|gBUoe76Fg@k$CdI-1dp)qFy`C=8kdqu+u|#5{PhxOIy8-L zdiW9)>#XQPiMxc0QDSRm#lYoCaaNYJ4VF1?g15AV8%Oowj`K4nEYgOpn-m38ZFyJj zJ-+j4C`)HH&ZJ?c`ZUEyld73*q@zE~qSx4aF48#??kBjiK)Dj3h-eJVnVv+7SE<<_ zT~~lNCFi4z?0R}@NPxsdpU>qf;$P5=-+$asQ1JSDzUm2>|(R%F=KHu z$$m46ez(C*ERcnpo*^|i9GKUmkJuWMFI*ZZhm+bHgsQn4xF`1;@a6VE`Xluu3j23+ z=LY21swOe`CozwUZYqNBhQ{o`rZ#x?={Kb8&k#2X!Vv0`! z1qp>M+Kl|ox{Ak~MVM)qIK^pmX#1O4aDBWFxzf9iIeyPWz0wc%T{lBnUiKR>9n%LH zW6j{k#tO2_4+V>EuLS+(>13NH@78>}n7T_%fE#a?vX~KkM}PeT?ncNt^qv<@M*X>t z2Kz$E(=pj>**YaU{+T{FpX!E~J+{z(U<~`PbT1?{$urBtX{1awnOW5A;i8%q@j~Yy z*>g&kXQ^H!1-HLLx)JYQ*ct_Y+BC3Z;bURpm-k?@#0*zGjiTL633T5c8QL)XQ@C@m z64culq1GxDOuSgjjdW6FIU#YdQM!_p7(9T>8yZQT`C6=RQpGNWIpTq3aTu8^Y3}9dx??B8u3ft9;INJbI z_B6wjMsL0$P`n)@Xvo(C#l~4I)&B^}Ux`Ll({PNxG?8V?#naZSp_r{~1aWuGn8br) z0%_Sap~SrVoMScz`%{CUCEy-R`?w#h&Wx_)KE5V9mi^-F_X}WhWURpT%oG^)+mM~x ze+Fw;+#>yT$8f_MUvAmcE>7!ACDADC!_@G2VTb-(va{n08TPIqT_Wx1-6}?p?Ac1$ z3mq6|yc_n2EP~ZrOxXv=I2c#y1P4Cez+FAR1giQ{pkI><2fB4}L*RT!ES^VK9ZDxf zH~HN5f)^xwU!HAyTqGRJ8OcT0-L85WEXzL~#zW^KEm*O*2F#-P{q!urpR)7drMoY* z=pKXg@RwCn15MEFuCw6QZ(DelQNVd!(87&!ErM@>O!$3jJ?bu1fp4GW*rD~d+`_## zuy^wpfoZ^hQ0;jK#l$;_W33~KS`>lKo}1uuu@@8HeipP;2;h(q>&M`}80*p7;$( zQfbiQa2TFA#qylA^>k&hAJ*MSV8=$Rz&*a=cFp%*akt8fQQ(k=XA>>y^4Sq&+z1`q zo-4wiZ9l==%8AtHVGev*J)Ulw-UnvsXW`VxwM4ygKI@f81NW(0xXZJ(*b1c-@}^pr z4UAS~a(&0)Wcfs9s*#1$e@W5Yi1lpvMLav!qDw07Jb)dOj?%Ksbg=s*MVB-elEoKI zX>a^7Sex@3UK={Hh{U<@F-@6feN2QuGEw7TDd{4!mjA^NYyS7HIvHn;wZu!C?-2Vc14ul??`cwfF z@c4D4+$fp+Y>#il!s$&oFyaK$DxHVdPnVHKPLfIOsfJ@u<(X3JVVu5T5m=>~ zVwkoP%Md29)F%~Kdc_=EO2nwgRUd9s;bQj6Z4%Xr^kGX!=7WhsC<+dl!?dl3n8e5; z&NZM4PuNG|*R#cV!sr^bV2)I3zNnuR7e4DjrCbJmqOk@eQC0EbK0s!EP_keh!_ z;`TNNnre6jPnk?*KgT@cc`9@0#tC6`lHUq^p4y6YqVK}S6c1cEB?nsqWogj82jCifFazN&yf*P0g2;!-82;c46uVWxrp33gL}D|^8#9ed zF}p(FeU)P~{{8_$)@z|!jXTdJisf^swb-!L7aB~bvctn-WaQ3PVNT8#rf;4gZ1C6* zjv--KEfb0j6PjSFLNu3`*M;=hTd1C}3m&CxMoEu7QV6fBY34&T-rGr@vCyi-_(iZ$hf zj9EP7#9qL0eD1ZV;2p|D7*L3s&b~amh2OgxVD~9$FbvBfJ%N4@c>EZ2J?GDJ`xWRu z_2>BN@y8vs|qPmDWbKnt(i;uNKY@G-(2Jf91jTUzi|&1YN@ehmsb`nc(N<+$(TQ!?wp3VcDkNv3%< zxp!e0JPhtZc5gb*S@xsRVzn?>IEnV3xIisOy&)YNl~HfM5v+W3hJ&B!NFN)LKlKJM zwQnh?6h;yMsRNC32;y#bIKtMecOfmR9C9_(u=?x-$eZWHiGIz;he}@X zcUJ)R@Vp$kO^%F|7X#O|iRG>pp>sk{kd>~N$t$yaWV_`tTz2lNa8LVZGI{B2+8Q`4 ztT5UqSpVb#J}~5&QJdalP0=h2Q_RGPMwj8hv=}b=N;LUu5f3|yPUG;C``nFV56OY? z1`vPO7Dnwg;pc{H@zd#4(2%Y}l^LZFC3wxf{L{^iO7P*@_vJ%Y?F+K|T|T$P{xo-R zi0>XdPoXbtEQxtdIXYZ=O7_%vVf}}95EQBk>rTni+UT$<_0n!!skDSS|2hQ?&)?#; zay@pmgZJLYD$&^=uG#vZh(H~i6X4fm3FE{gt0pVDfU5OnZpHC>yde=|FIfc~Y?GxdY@?7rFm(%$C>sGe|H7K?1$6q0rQCv{ zAShBdq^`3E0QSzs857TOH`d*-pEF&ATnqYvvb8gf}2Hr`aTgap7&z|Cmr~+MgX;F ziGbzhl!=_w#lEk9acx=#XU^WDRmeq7NydhWnaIFW?N?ZS<~vT=~Ni@oy#&%Bld?`A7{HAW9s-f85{tj)!sh%wZCmOg9Kcf-}5 zz93R&NWEhD@3^VDbo92%+&dcyYP8gYO8hk<(&uF8%S)%By!5qTpI>A3GoVS zm3J_GAqa#!dSc9C;tSj{HJ4M$(50GYDR{6;8O+6ZG4YwxxcVDMK{sRv>hS%XV5@&{ zanBCY@L~vhnx6CC_ckofTE#f2&})w6Ibb|F8(;Xohvf6lbhqv;(3tlGVy@PMmfuPg z*|n@nHh2%d_O*h(Wfm-Lw+bGA{vNvdJ~+KwPfmU=!o8QpS-D*tF>m-ma$Ke8re971 z@1L%$Ii25w$GgJJ-}TU17KGn|(m?BA0&vCpobP|lFe;%Fn}S}!2MGs`Z**gG&K>UP z{Q{x4U@P1|t_p${DcB58aJTjuINdM;<6TXvHY7@ch0b!wf?A=iCclfQH((xh8C9|T z(?4CLnygwJMg`{8pceHVG>v$}CYIoXkw?IOl%B9|?^R~XU+;U@vN*ND(`Y(zIlZ0R z$><^zI%?4=?%l{Cvi^P_D$1L(Hy1KdJ8%TI(~o0=_YB!lLm}pU6+mw87HTtj3h%kG zpz}pd=a2Ne?D7g6OT4+(&eMG6NSwxticv)sTl(bJ4fb?pB-|XT6w3BV zQ~Aa6RNp(E&5mwF+f+Um@G+CUwJt}A4f^cv%PqoSBF@Ha9m`tRo@L=~vGm?89V(F& z0u|L7)aK&>2I~SK(L;qj-?xM&$rjUS2w<`_uQ zuA9fP`nxQ>HSqu(3W&tC(WPLpG?UYwTh6t1=i^heWZbRj$QB*0COwUP!ol*XG-I(e zIhU=>EZ(i+`GG3IVm5K0UinmOeT#PY`x6fXEq5ggNJ)!knas#8K@C zmt}ATh>8XM4-V4-(_~m(=|{hPaD`|r5WsiK-wXsm?i zOA^R+(Pk)W>VU>6Q`nTH|AEq_RTvhMhup4o=yq>{%y%tZJ>G`EuH}0U522>BoX8jWk{-8L@N8KLe6^T{t&*Q%k!Aw7VFvFCK5Iiuj(!9GeGYU2 zpSvsxYKEktaM+i12tJ9;VCv78(m@SrHZSZwzTevqDcVx-d8h?;6_0{(TNabA{Yjk5 zt}meaPKuhSPoWo2hVeb1>qM`k7sbw$(tqz>L67oRv^r@BTg-W;!TL}(E@?j3e!auq zbvM7GO8x_daWhfrXtYo^%#wHIj-EXyMSn%f!Np(^9RGDM+Dsn>EvK1{`opB^P>HN%*vL@bPpb$@w)Gbd+lG>_rc5L3Ix7 zjW~#|8_!_W9Zzs&r$QvGSIwH#&utwz{Uzra2xp@qEkmb{+oRe!aL%) zqI-(0<6}8oStiQl^h3CT`|ebBQyI7R6$6>(yF_6upLtSML&wqyH2lXIP#r#u|MsY} z{L(|Hy}1f{zr@l!$-`CF*}oxROqTsB#}V|7+c>u1&^Wf`Vi3-`?EpLX)#H^68_b(O zf%{PY3=0oyvH{fr5ZPA@B2^0Xy*d-MB-z?DiLMdS?UQm)XNuIW_7s zIEo(mYeb({*TVaEg;2a?9v3+CJbP2HUr@5V7XqiZ!4h(K1E)quU8e%PP>}RWe%3 ze+I8j4{*Rtp2f&+fx>;$K}ISJ#7w_ofT9TgJ=PDu1-r2AbOkK-nu)odX0*p$1)oM( zlO_E8sb-o2W`E|dpNKD<`=Uo@$v5G~j$?F2bu7MGdI9Dxb09~e8er*abAB&B4_hDIMt!^~wU^JY-33QGdVt=1D2~=(n z6vdaKzeEwJ&sfdQ1)hT`W`6|N&r4F1vwva6rv*^F=o1Vqx&z)-LI@pKf=1OkpdbC4 z=dP8IFY~=1xnKnjnMLv326yPT-^Mw}$>V7sZNA6U#k0d_(NN>1AoXP~o#S_!wA@=m zZx(LAdAUZkHduf*N3-$m(i`x>VI2F>nF`CoWvK4=SCDdlKaQJmgL}4c3MieE!V*bG zzRU9#lg_Q7=8f^N|I%ZkWFpBD7ELDq>JHEsceju$NfLB+LNR$&@Ei91@ujE#X+T!N zY2HWDiIx|};+wi#WJg&v)!GpP*A7^LWdq;e96W{(7Y%c}QccOL&DY7*+sCPhfe!uq zu7}K>&c_&_z{Az7M-a`S^`mh8%@kliF2`~k({m9aSZ#O#R*qub1QY*NbbA& z*br37ZJGF|YW}bh-T3GSRIj?qRhu8dRUI+h?CVc(=IU@*A|il%yHL(YH=8u{Jrc$| z%)~@rEpY9=jD9!0Ip?_sILF_cSeOozw#$AbF4vlE<@r6P(|frMwR|p0V>G?^dI!vT zRYLB@)q_siG#F(lN}b$A*{H=l(_#Ba@Ym3xDf{D)7oCEO#Ze3&)kSta_UF{bM$+4b znr!&XJb}eIS+;s)7Y=WgWp)>yfPud@xBG+uq+d6Jt>15FtjhEzX^UszJk5vTzubhR7H8nc z-LmMqrv&NLA%Ss3sr~lTh8TP#3Z-8=vGwB@vi%cBQk|sVIQR1e%!yFJgPRkH<=SdY zun}dSmCO12nW36qHeS*`LG2zhoWFAe*D`+*?0PhSUp-qvch(LZ(H6mUB?g6GVwRE7 z@{hSeuSeMQ*#p|9Xiz!++jqk=54zY+gdW%5N009pV(cdy%KmI62lgBR7cDiKIyMkz zchBGs2cCpg({oW-DU4>GmxokYORCd7C>RuP#Y>@gz~X~D@`DL{sBK7_y$-|vjyS?{ zK7z!X>%6C4iM~8v0DVgwVSI}zJE|^#wHb+a@6RuXpffs@-N+NHDO!g9w?er?|8>Ky zL<`>A{hsH=#bZcTG9)O5a$>|7ElnKIQlVPc3plpm3kT@;@9Hom#Mg5!&8(LU4VIaN3it^E!FaMSb` zfThfT_%GX(4aJ`&#}^_NHZ;OhwI(jF>=ueFQDx?4OToC_%>MV9k)$&)jqv77HfhOf z=o7JI?cw=Y=O9UIzf&@h+0D(5(5JJ#=7QPGQE(~!K1sXO1eJH4XqAiz4PAQ(_SxZnW;{bsVKN?|Pe&|@;aD1h7%8x}aJ%kZrKA=rKV5f+Q< zF@p!{O!mQ9p;k;ML^PiVyDQ=>S7{|(J^L&6^8fSZvsP64lLDqc)CFC&Hna#z1=$&2 zFswQT!wO!)LD{>c?A|v(r9a>_yh!+{=>h0p{* ztKODj<^!PDANPRL?^bSu^Z>VHT8O}MR67Ufexa?|Opv`kBwV*elpUWcAiozhVQ4Mi zslNIc+{X7pE*VM3f-@9p>mnK9KyPf;WVVUBA^+naShGYQ+TWE!ov|TETEE8rv%XMz zvP$dnj8Sm z?qbZ*ubbP@Y{2^Zb!hQ6Wftal6&9pyM=q+JYmhojo?X#}75;Kue&tvu5^P6{7IhPw ztbOq3NwIy@JBEfGGr=uTlH5Co;>EL8#u0&ZarWz|LV^I;G<*%vo26)9)|AsLuIR@?I(iOJvi(ANrxNNs*py z;~nm*Q`qBFOI&yFDkMZ|(P_`*SiB&FP06}0n0L#K>k{vT!7oa1Jh>k)%BxZCWg~`+ zY{Bm>qBP*7qo8NK4Bnrtje){?JX0)yP1)L5slS`vo%R^(W!;1vlcd5w!`LIH0;}z^ zaf``qY?GM;*R9mqe^8P)IRegr+N3E z2fd7XwGqtdpBVX^odJh8>CvDN5(Mhkmmq_HP&4hs~!kH4bIh>OZS5HHXnPs0`p zjw!9f3t>~(@QVJb4(UZW^05gwuSt?Kc&NdO`;*YWW(1Qfe~YH74Op}x629N55(MPE z!VQ;QP~?$0tKoBK!kRzm{3Qz%JVlrumUCk|*TA_aktnsi2%|go+4tI~f>lEeU?Jy2 zYM&h>Dn6FH8!H=~eyYOrMtw}$cA7h_oCtasx`8_}333{Y=@tI|zsYy`TJ*Gt?7DIk zeIH&GV>ub!zlFeQj}su`Zc2^HC*W(RxukPBQ2u> zgxU|3SlinqNLX=)`0}%#fa~Vi=@Eh|t(UM?EgTd4=JJl9cyLj1M%kAW;nwvYPHub) z_p~PiR>!Qvu;_Q(2cLejCprutk5$GFpF*A#8A~n=c5x0uevmu`M?}121Uo@AVhP|I&kj6>3@k?1Q-l<5p z*XjKu%y3BOW@tEr%9BcRTSAC;3g-!yHEB|Zwr#j}@+dg8MFwq_rjYYyp}1+a34Zc@ zgSth#aqjkGEOxmJil?2zcV|!HklJ2!t4M~RSN4#mB*6EpD6%63Bvwa@*$AbH#h33~ zy`v0R$@6FO_nUwo@&#>of?T`__{j%z=QerZ`QhhiCUm4KTWVlo+duA7z+p(LyG!27 z{~`z6XQJttD<~q$;lU1`X(Ou*+`nIfqg$^DKW$tD*F386qj?;i`bLp8jQxN+_;YU> z{|=U37K@6Qcs4?WPX6{0?%9>&4wl9B2S{OLw>Hz^^Ztq_)OoL|1?2C( z3kwW4vWo*H0_p5*`{u_y`&(u%&9+itw|&Lv?r(>ntaU3DHj1&8fBax!@_1emmrlL5 z&nN2&%5mJf8L;l`YjEp}ME6%?F+8D@=&Rnf_t_}Kg8E~W&6~weHPoPTbP|ZzDzfxw z18{z`mbiV`gSvZc*~Y>u{B^ql=bq$Qbi;|95zJBK+R zSLE(Y$^@0`SIAWzCyYL|hTiEbsGJ-z3C(t#f!ZT-Ja>8!U(NjlP17$^sZ+|}a_TCS zeILsl(jAG6^+qU78BL~bX~My1l02L6{t9A$}(3PF=gq8u>JOUt|NIA z{j{SCpWHtWZ+@TQzjxf=iQj9O_%8?ZLuW(7or!|Xc4ao}-9JIe`Uz}7!5W-3%NbUk zTR|jicz*59NYu8KBH}9xxnr-^GTlWf@Ll{7t~QsTNBZWWxW`d=v0R4fu2B%~HuwOu z0z_GQ+;i^Zz%;h9K$9+xx&?_rW^`uZLYjI%9J?L_v6+J+*l2Jb-1b#L3yX)>tIl9h z?nON7DFO1{qiI&pdAL_pk9oa0xJrFCMqCczPJ9=Eol7h6(7`tN`?L^ceF>c2uEiO7 z@@(1lNBO+B4cVFUfNT;o7ycZOWF41|Lig1}m{G6JR?Ss~r~AcdIp0xa}2|jMc+!JGI(&Il4_MXlrQ%C_!J+vKmziEZ`-YdNO z#}WtGUo_iu0+TZJS+jg3*2O*|mR^1=ee*~N%$vg4y*r#(nm>}ibFr#vEc-V@jlM|F z1a_0Mp$U4Jp`H&05Bov*sg^TdWsY`-cEc~}TQJ^rKHtwr!H(KT@YbfAivl?kVp_U*y5&X7AZLSmoD!5`gR$hZkYRT}r#rri&|bCg?*}0_TlW;Fx#&N*b_==ppNe3|k?-IazKX>hUrBC8N@8q!F1-1X0vS`I zg`+#J60NP;1Ol|#yn$X==&ywaA_e5$;!)5t?j9tGPr`}>Bka!q%LVn93c;g`$hGf) zliJJS&d>tf^C1>Dy3axwauRgeejz~t=W(LOC*e6CA-Qr=8_T~Zk(MkGHs+=Z{`5EE z5(iG;JEM{C?`a)rd{jYJ^|)e~a}=Db&m{96^IR~4T<+h8V4RWo6nlLtur6IHym%7^#j=FS&rA@&->^Exq=-%|=V z^ymh*8lA*KXsm8FpVP9Z(HA;!ch+;x`Q{#a_rGiO(~vu)#EoE~6F3ZQHKegy zjOhA+L-fS14A5F6MD@*b=$tc#O>$D?vjfLqm5ws_@XW34LngF~gcGT%4EiTImKhnD z2``;lNyq%k$MN?+VM^maELeJp6EVMl%Pu{IJ)y;*eISy1kouP_*;R-Em3Ls;DBi)A z%)sAAn$y~$1(U3QLEDWEPNI7g{;gjoXuNX})LurxndK2c5>A5cxxIK}!9DJnK!NrD z?#JW@MclSPbriWhlU_a(%^~0Yp3$_D2FGfGpXUYP)Urj;OSgjNlXW!PWHsEhoy`VQ z6sVY26aLP834wBc0-KI}a>Zr<(iTN=hDztDX+|N+w3?C+>x)q0c{M~P#NteyH-g5* zEx5xtg365cg4&@E96)Ae4^(i+mW-_T+SqOCs%jx+bQ(Bx$;VaLmF6YY7Upx+?+7H6iZ-=Q> z*j6^PLzFp$+Hro@m$QQ8HJsLSS!#M-5?)^_SMea${YrPSoLy zAIXv_(dqDAt`G_}KH6?)#VQ@sJqwKVa8;$8H2?1h&FeVp+N1=4q2&Ca*T5t6&X^Sz|VZIg-u0?)f&{IyZ~fRKE~O@&ZP9= zC$jdP5x-Q>rIO||=rIgqCO&&$MP(KoYDpmP9414(!yP<0_Y+1)>#|=iu240mmb3C) zMh!QdCz}=KvPjoNIBq(b#rIEU^ZB!KP4Y1QkQZgsm(*ZPrUj;`=isS&IcyY$Q7Wm9 zQ_Mw~TkTVO=YDHuIv6D^#*OT(WhII|Cn#xt7bZ69a<(fPP|}Q_&1AmhW?RoEod<5= z3Zr)Lo~VSY<`xKsc_!wD2?ub|RAnq37{?w;cB7H88qPfG3EIn~(JB5&)s>ryjBL*5 zLe(wNB&r!^_7##hJ*`~f$9aOn9iIuUuOw0qkD%f5RN9zx0WF{01asf3U}*Oge_f5h zW3A&^{@af@S9Bp9i5)|=mx~B=R0`1QcLEe2<+IDR@3~Kci}-QGapCjMW3V7<1Uzmk z#on$`vdL#JJTz9IzBxcYJrQLKLegMY@ObWu{~hjOnj)7JcpK+WJ_3)TZ{W-Mdzt){ zX2`sA1|qjva%yG~{gr zI4KQYWT^G`Qv0eSg{n1KPYp2Zx>H(cmrXk@~rIc zYJB}T9CwV{WdCoY44!+m2(6oyag6svp>@Sla96qvr$3~i(#R;#+w+(Vh6b|po`+C$ zo;TD!_zor4g7Dnm(_m-(71GunhB-S1aN)>m#LsG+hIJfFkpBdGRgh$xok2OaTCm8y z5j=Iyf&GDnMATRfly9EH^!X?7` zhrQ4L;iJo_w)T#M%KJ78Rr2 z$QXQ5Y0chRO47Ub{{)-5>`-4>lFCg^=Ntt&!l14MjvdS-BDY?l=qz6_;yc)Gy7xJk z@syi;btHZ4yAWGUv|!2TLntmI2|F%0va(ktSlQ$bgHN`Qhu<^F!#G2@Iw;M(eq6_m zpRWd0uDxV?a6D8NRS8pH8elZ&YJJE1*tH}%X1D$aoJ{b0NgtCiig|Lp_!)=%VtUqZImCX8%cOz?rPx@&){qME8K=hk9INV%>#&6$q0glG#W>U%2T!-K< z@6{{sYQz1hjO2>c$fo3>UaqAT?QRktu| zcSZ)X*m1lV@(}#8jOn>}8F+m%6PIO8gRBQ0bkT)0d{JFa%baAHaEvBBbu%2V@Ezi% ztK7)LEj!sVpyBm zUPXcBa2VOYVi4TMdSI@*FV0+k7mxB@%ly~_sD3S#_DopDPV|J+OGnkf)nA#`ynPDt z7Fl@3g)*sU_hHAH+ZfKxr^_6|aZqDDiKw&(g(OY7e2W0%pQVB9l+iSK2k$TbW{*13 z(cGmU2CQP63QpU&jc7^az`IK)AS3A|H|2sQo4?i%F8Ww8Vk%DeDd$5;T8i+!_G_Gb z>n;ACuFX_+H)H*#82Fi84@cjpg6d!!1YgNR{fXi%Fh`sE4=G@X)kmJGSOQgvRZzp{ zE)6=hsi|oPHg1QOUj6^yKsq z5i*q6%qE7pQm}mB9VTh>+?qcw;8>ur zH5BX6=--p+Ud@9THc5F{Ix{a*tdIGKQJJO4p)+hvrV-OBSB)1WTh8nd2Sv8!EyEH|d#-ljdACUsYtjbqe<5E4UzN{uThG3M6Tm|B7efQ z(f-E|F0|eXi+d)rnYv$LXsak~o#rV>neYIe&TFzUM|7B3(FnRCvKG}pRiOj#dE0FJ zyQ<-xF>W37h8Uh_JfH7udE30g1-mz}`}^MutTMVWw7DN0jS|2rxCB><5O(873TK=8 z5Yva&p~1nor1REU_~>qeJ_Q1V?g@19nU^T8HH7gh?xfs4Qkd@nG<>%|ME|qI36-Oe zy=%jD`&P4K7BciduV{$mxttA0C7D8@qo8$fEeW`Iox65Por!Gm&aL(SI?pYv1 zAD#3?@JPa^59Fz`utVVfCmtH#Q>wY$58o_#jh{EoqWuT>4jAPb-y1$~Zq+8B{C5>z z6gdwIi~QlgcgrAp)IV&~$i#1DW%#&$EIqWf6>4llX$SnobiY_^AF&p2a2)5Sc!|8; z&vOW;#s~}LlxYh8o)0c}royGGsNMd})VrVqN4(MCQetv(aVFp0+9|+k$KdT z`=o^1+P6=z=K4D{;JwAoDT-X>MSI%lBE$6SzjMERlc`YK8^jN`gUNbLqEx3tn;)wE zkD~Jo-DeXa1Lm^q&Sy_dKR0`pH?$e?qBBDe^ zduvD~)&Kdw^9nDX=Q-!Tuj~3;bi2%b7CqxCMy&q>is@;5msK1LI(GV&Kn@7FgAA z1BU%;Waxbx#`F*4Dl35An`^`B>-t&Zsy8G(>o(X$sL-9=8a$4Ugqp#7*@YH68k%Xz zZyfz6p5EewA5?Ydf~E6>owYXHIp_{@ITtYaXF7b)Y+wT=D#(_P<*cwM7d;-F6y^9% zA}^BvRY6ePe=)~i%R*LrgRTRJe5rJh=%9X3pv4y5QJ)i{K6MFGojwUvx9%H++B0$x~k>oUt zgKE>k+M_s<#EpV zLLm+`3r8^5mLF{U?m5`iRR&|?jbXXR0~k^oimOA6;qiASs;Q^~y@^Z35BdjUH1Wj6 z_RDa+Ya__tR1&G54+nD@v9L$z1$jALuJfl7l3I=v#WV#->q`Um^t+}0Xg`TJ zNg>A8spMJTQ6}G=M((#;VenoZxE~mYRV%Lm-ueWZ;zaOs5uSyF6&RNB5C#kz2+Lk} z;XeB@Xm;!g>im<$fQhkeilY%vxVwZ!h1v6sfsdH(j$0VJY8+(lJH|ZLw8P}sqfyYTcppALyhr41Pm(!*6nN?5P@LxYO1O(Su|a=iaP2t}pE>9#9MYpu zcjp^!U%MBISASztr-fYM0|u(2OxPrsvHZg-FAy&(Ld&f~NRU$<95ym)AT>&q;UXON@0Cty^W25P+Z$C8dEWPGv|KfXc>d~5`U-^U@aLrKUC zq?O{v?nf~E^I2TdG8>NPPvi6EJY(xN8qw=?qxjscVkjP4je8P`!6>?hXnR@kAwSIF zUDaxGXT3eVj!y>jq%`a*+rkPe$N7TD?$JB|o?s3)^V@_slF2SjtdVJl!4z_WQJMR>S!xp<1hiTgd zPe#Bow3prjmxm~jg$ep}?@UE{s;dx>IP`+<$gvpvli@kbIMmkf#y?k9!hjc-U~6!> z$i-z0*L(X9=Z63tu&IKNuzxPH?i0EIH*8?vJ-YF3k{uYhSizLun#q;>>M@zU)m=V2GX-5`F4}h&LH_$(DF@)PlP}yD^ zy!kAYsdPB=ZO%KHnzt+Mn|~9BU6==5m)bziGahs_kDlLS=GQkBRzZvn#LXTkGojBM$VG9Xqb*Jwig^Ti~WkAW(gv|7?$Ju!+;K7^u zVvFH6=(eGq4ZM9950A}2Tl*|%Fxd)+)Mdf;iiVKY-2levveZOn05ws_6jj^J;T_*~ z`Nlo9IPcySLhH7ORrU-9wW6Ew!gn6bYly6TWPDf1Oy377`5rhQ6oPqgwxdhv3Yes> z%LQmNP|e~PRIY` z-N9?&1uzbM3GtyTh@`=BWB;-l}5FgcCa?8iV4zB@mhME{iJ|Bi#$LpB08eZB%u@!gtR>w%N{WYm}zuPY!`vlOO(QGzW{H z18LF9GP*F*n7;rSYMmD$c5zCl^CoPkx=xzZ>{=k4BOADrRi?#%&`GLjKec{>C%|R%)(*+wYd~Cfv)mm$u;@xnl@7b?6|UQf?z;eC|oE#K|YO zf<)se+LmYwwxg}+$m)DtwssF*dDwwpW=hidZO_qoOCw2(4I`JTE4W&?C7-Ay0g_{~ z#jhsJ0hO#?^e=8C*H3&V+ik<)Y?>+PMxRHM@^7fq5=;kcE91VeAJF{iY&yiE7-S8; zqx?@zj_c&9OVlv53pHjvPi^?l+F@`frweo@1jD)q%eemS_q_10kVV;cA2Sv|hXk(} z@^VTth^nRtzAI;b?Wi;w*=6#V&3n14u*2z=4947Md9L?kEdQ!3WD%TWAmoIwQ-AZA z#OW47>YP9t_Og;`Ps;}DwcF_L)DPOs&CTU^0{hhT?f0zAAHL~AsY@Nd<0(Msi)Y+73gzRp*onpt&p#^i6{ z@@oMN(mVq<-uhCR`TD%$Y%!clQvpMv3;9UJ7OwGpI-X1M7Ce|aczA>xT>X6-ePfo3 zR7|Fj4Bbdn?_!WEwUzY!5W0DOx=F^h z)t@mp{3=B0ycQh{5WZ0b!*TxniTL4lDm)xz%nAelVEI&mUz_O2f?8j(VICdicSI*P z;uk!zekW|#sAdwMPT{OmRz&BfIwu}^WP7`Cul2u&nh$%3@9He_UT+z@+VNJ@G1m*i zJQkyC%W62UQHUW^?79BtY|*O>J+?(<4J_GgfH70YV@>~U9Jl8sV?~jW`b~_3&n1Ax zAafk;D|jZHx*@{%lpt(Ts8veAw=FlAj=r#kaxViFX$$r{=QmrY_Y{5GuEWcv1L^TO zNhHSMEItYxfy%^C=(Q2N2$?59PwT#ru~dO;SAHPPF2L01vaD_5AvCk;CS3CdBzZ@p zcXl=#BIN6z{nCcL{b~rJ)A*pr2s_5Ez?gQxMHhz9JvU=H>B(I|Kp?wvvhwJ}h8Z2uPnehI_@fbgo|< ztbD0NgU{W95tF^C)3Y{^jl4^=k7a}XxDK}WwK25Z*Pv47`7q*O9XDBEN~=cgp#4HV zXyU6E3Pt)Fj}G#~JuVWg6X>Qja%0WO1t9cB~u!5odo6 z<5e{~Fur*ZjsCcrlVQK$zFaeGSU7+x+IoX#y)j>Tqg}KrSeh=|u0o%>c0#1GKd(ML z2P(E{@#~%%{6@-a5G`1SnO<{nzN#ayE~>Azv~I#%ffk~SgLg$wuO-oEs-3t}EOajU zETjbsMnT#D13Ewd8>{V6=gR(nKzTqA_jC5+*N6C`_M=8r1$*Yzeuw-VAB^TkQM6vu z5=XIkY`VFW-ut1+BD*9|>yaJ&UJ}oq=Ve|Av8nK_czJQ&{=ERn9D0^>T-G& zJd)}aw8lg9*uWB@i_{D{0-nRu+2QnH=yufFvXlpfjD=YT)oE;%8nYbi590z>(QfY$ z-sztPj#(|Js5=4Aby)M>QPcSJt!muKdYRx;d4pdUI1%%fYcTFvF~)Qhu) z8JT@b=_S2#`P-(y0kWcd$K zfwU~gjEVHmz@O}~|6A77auCc{7a^XR$KCuw(4cHTciCo)v)nnpo;d-A8C8hv1wNL_ z_&M~|`SpChN+K2(<)NNkA(QDI$PKkd@D7tu_Ah!UmmM3!8{4I6rtlo8s7P>?Dfb-q zNmGgo~;N;zlQ|hFs`U5kt`{&M8 zmpSkSBg;P_hSBt)!G>+!RYva1w-7uj+hMHZrft^wfFzbu~|FTGlUW^F?nMgyv ztV53Sq*NGviPGWTy4>zwt7xxTI6jZgVz!!kysu0XB1RS=sTCMgdO6T_>o4XAKR5X( zJJ_ySOYSn^?s-%dKcy9mBc(>rhMC_hEp`QSzwaSnR%=Q9rbXZ!X@4l{`3CxKD>2?e zgUV{i@iZZeD6vWr8+5Y4yL2PIx`i-Yn321eNOL3S2C$whN$tN{@?IZFTKl>KPu6?z z^9$Bs$$Vp;mX(WLqZZ)!E9LC1s|#P}9RoOFGL6_9Qn@y~2BMBz5UOg(k5znUekVfE zZL1TF_W2CbVFl#jOlvefBjjyQs6f8=W*AFq~ke= zc@zNw@(Vz_WEZaeZyp$Gb&~wHonTUA&2_@v@yd3=qjUES+7!P>ck^tRbEt)#Nd7Fo zI{p?s>qsSI&GR6-`3C-!2qEWQ9-w!<2Z$y~)k~UI)kr7pYf^c0O}{~oMndOv-MlfkmxN3;d;3?51(K_#|WJ! zc`JHFvGOkw4|wva%0BFL-h1?Iw!`w;Fx(#}oP~+od5NMWe!6i1_r*@Y_@@imdOsZ+ zW7UBtOaW5B!@fthlwJST4yX1!M~!4hTp53+GO6Vt`j5E;3X26V!GU-XL{DaN|D`xp z`Z2_AdW4Veg@R9ZADI;;$usuq@SwppA`e;vvD3P6XMR0eIo06B1WCO8_Z)Wlork!x zTSQ$Z2Ie3A2JgL|mrw6Y!-abk`S}f};rxGYct7+5dwXIFocd5GI{&5~SA|52Z;CT< z$CPXMbMa2pz7)gqoFs6fg#tz>kKtOe*U)t42--S$2i`L8fZdyqfTgp*NpQ)BWl`ZI z&>}uHZQgi-SVI}vzsljdUPocp*b-2jt1C%&DBlFj)5l6?l{O6+!eAn9PxMSBw zv?}u>V|3GjhK{5)Z;Q|{?lk(C%CSEt19*RDFlzl&;9*Wm{PVwJ80U2sSkNCKpYM*V zEI*JWIag}xeG8iF8TbsI#`l@cfH32Atof-V`mS#jO_^;&zPkCav55t^Q)epA$q&al z9htaSwh8o2g-)%kGk9}wI6QHF06&v%!umQp9y!y5@7z;`>xWO`KaPy#alWpg+8PA) zKjmnd-g741s>uhModyjiLoXPc@mWVAxI8Vyhq+#0E*A}UfAx4of(Eq`-tT}+d;0H5 z2ELseEwC_!PQE7|f^WZ)WbBD#^VVpx1HY@mzH%#13Azl=(%oRj+3gtnUj$1}dJO*k z18C-NE6}?#A0+GF3BHFR+|1<}yIbid=-(-LMk5jG`w?oo+d(;TEv($>4I+hPkT+Zm zi~R&f&D&Pd`FE-y=l%+c0`%$bqFG>YFB23j9zoIH52D4#MD)@DA1zN} z^ZeMu%+!6GxNpgGB6%y2zI-F(x$Twd_#qci5O|t#s;f^HO^|KGxRtbJM>r$32lLc`? zK8cu$iK6KR_D6RG{X8L!s0d!JD#P#KULQg3^vS_Un--X1eh^IVnDRYYBGRc)z+!Db z2t5hIXep8B6E{vG8Mf>2?CcP1op6Bt98Tf+@p>jLt4Hpvvck*CjnMf)@akO-hupFP zW;;?E{+XKN@I@*Zm0bdILT3BRrg@}z=Mb8HeHLh3J0Y+Lx4?|BYP>P{KFL$if+y!9 z;HE|tEFW7Am-Aim;u(3Os-#R^Z~ulitMpdZ!w-mrAhZq~!9PY;DZ*QDHXqzfJwCu0=tlCKQo7;r56JN6%3+KYQB|n&d>scu4 z)8rE+lgXTq)9~7*Vf3*)LV!~g1k6^4%tjwPuAqbBA)~vDo3)nPEvLJl$ypp?@}$ z>yckD7Aet1 zbkd87YmdNgx6==k z<$fZ*kr&~5NWe>Fy@7U0hZDI%EJoh&aVc#}ngJa7jG*M3_sxTVt zb_)#msYwpMn$y|%Uqj*k=Ows#g)1ywcnkl=b+c!$7m89|CBe1vO(fD)9}mqt2`Ubj zbg#P(sP!B2cD4uVOD^L4o~x)|ilqI>ed2C%6+C1-;OEU$aiaHjcEvz}`qv&5?9^57x*EJGExt)kNM{&hg4>oL% z6xUWAf^nbPaCLzKA0lgvXVzI`7YqRR)+8YhT7?bU+iY%mx*Yl*Gv1HP@vrMLD9CJu4LU~Io{^))yGYB(>S!Z97r3$ZL#4bIW zrP+_{>nX6hRF3LGzr&WIm#i-K5ZQL85DZOh@Tt(n|~mH6vg61i?Pn}S3OJKOGoHVW++r<)D`+=tNUEyY+Pr%Nt-<=~yfG-$de zc5+skrJoodb_ooVHWLfC`EV#@Dl|XRA>XtZ)}61%=Inkf z{O&-$?OKMXHl|}xTOckgoJViZt`_YJk;7e&yty!sl35DX=+Z^$ZdL(7YKdty0OQGv_v;KASec7gK;WojK? z1xA;>*wOR9@LlyYjHrE%CD%^FhAEREt9c03kJF-2PRF77Vu+Bl*^SQUpOb2@70}nG z1wZx_z|jnK^nQFB+W##DL+1eQIp3D54jPm4Ct$I%B+azYK54Htl_LWVp?)`I!SZ$;}9$>?R$O=A08X!(U}AiaJAh=96~7Z7 zSs?fd)*3);@4Ct;#kFvm`eE?!@$8ksN!ETo9%4c-iN9?1A-Z?Zu-3Wfu{g^g<04bA z`AIUG?i<3LoQ{Cv`Uot&wHhq1d1A(bQu0i@93CDvS`FFnoNJgo$g1TgI&GW_y zf-gMCSRE!$2}Q%aRA{*8#+_!J1p|=`|Jbf8=<-rrX=pOJFLb7c6?H*j>rmYHZ6Cba zF@}4FXp(gw#aJ#EhW(xwAW3sB{(EPRO&jOJ%n=H3x73%-b`OTdqX#hm{BkUsHw>;1 z3KH0b@^GU%Tx6qch*!QAVzI$0xIC^y#QH+nk{^4(UR#?-TrlAC^=$YwY77&vSmEat zI|-M!<1u3N9iZWwU5uJ9ft1Jlqqvl9|_nF@5Ue;A!ELXp!(P+ymh zN|popbQ2|TiFQKE#kaxy8^Z^s=}YF@5`sa?@ocowD&MEQ=5fHss-tnu_oHO$g7J8LTM!1( zhu{}sg_%1R;lMdxz#=gmrueFYN4p%X=~cj&J(=jKZ7S$iU*PoEdn7}2TdW=jLf*at zW>&^Pj>{-Ut;aE^lT|Q4{vw`UtIlPE7+a9>2&XPyEl!h}3#GnGF!B3#LC?7YsShJ? z*mNtrlxK^9%GJzw-g(GfZVD1XvXGcqfq!RTVR3^bx#u$vcr{@^MoArkUjZBFw2aTp z&UXmUZmMKn`(>DNXByaj*a-TD>S90hjg?!KuHa|i)oj?v22h?CK>nS~LFGJYjG9?3 zPS!mP&)5BgxaQ{~$SZ>8z9A?t6VB|C55wNQ!|A~ph1kEk2$qCCU{UU$NZURgXfQ4$ zms57*(Ci8{iIE(Y^x zeoGcqkB@*9Rd?vs8%N8B9z?mia@3I>!{r)<-ibU7GHK)$(qUeKoo_S9$J1-YZYq=D z#D-yf{w|?cGS~*Qe=nm_31^6gYzcUr(58J_gm)<@^1&xJ@~KAgaDG57d^FbMlfo{N zc*jT3e<77S+N5ElRtTLrU=-6`a*ln|y9Tr7Ord^Pvfy#}bMY62wcyw+up1PYl2I-5 ziJrd(d z#-(hRp;f>+a@`=4-QI8t#x@ir9RssrN)Yg~C=4>yg^xRfvR%bxV2PhVR(0pcyay=fe!Q^uYTq@-*6aknp?>;!+8m&CdwrQ{znOrPTNE z6b93C%jBVU;7mLsVMt5NVt7;5OPD;{1t+gpr&`yJf_hdf^3mP)v)iWdxJ`xd$W)R_ zj4`6(Swi*v2UA`X#4zf2IMIEHCcAA54h8?K=SPE4a z`-t+m4y+tg1rrCPL-Csf{GP)-oGkZ}l=z!N`00Uk_qG9W&q_j2@GWVUzYfgJN`SRp zRiHo7nYJoSp?i`Yc$>yubaJ~wy&I0RDU#8w&Bc}vyZi}qxuU>jR^?f_*3>cLDwcg6 zOZRNHY^{aPuQ2xrtL5xioYT)gBiHEjq5a^^~~6 zbH~CH4;>EX$r1$zbY`}=JOH_Z?qN7pz~$oaB5H@OSt%%4X~@jjKpK4(8-%E zJsSxvF59Sgza`Y{jl_)$|AAqr9GAo+XbA%By6GyJTy4e3(<@**@jtYGeGL*bPZ3kW z1N7WOoi|){M5WH#WZpy_?sRh#BvgFGT%TPqFhz`KeK%3tpJ_Z>TFf@@=*Ei|28fQV zEQjxtg}K6h7hVZGKvqaB!UNa*$sVT}(C55DJfTj7SFHSls|B-qrRh$LzkM8Z<~2dv zw5?osr!-GdP~+b-{-e9w>cC-MG(OneOv=ZUlF(l^Wb5X;XsVrsw_=v?&-^MFp8A4A zI|qoW7hoCMM22}ypeE;$!7*Xs*zv>O)DK%LjJ$)xRs5pn)pIJgT3c1P! zjxxAAPLjs$&x4PeQ$bPS?-?#Lhx4CqvAEO-Y`(e!B8BUo(tfC`or+Uczqw-9&m$IP)bJ^MFoQr1O_1z`&@JV%5E>OzzGuSbujT zJCi93qv{^8Nkk5020P&^%bgg@XF&Gq8>lFe2eS3~AnqHEshJPq{+>oQB<=u48`y#4 z_z*1bSYP>I;uB>5NwWE^YX9d0z`M1QR4HpVd>t3Y4h?n&I^`A{oEFQ| z%7;Im6H!H59Tx74gLOYE$jha{@UI47y2LTeiBX5FzwY?@k2T(%J(}EktO>D|yU{iO zD0r6J3Z3p(armbT;HdeKoSmZ!aUOcSF>o|m3;P6(I~!o`@KZSbcsrb^%muIS1yFKh z8RX2^MTSadLXGoq{(V3uY`mjI-;R6&MnbN8-OK}(sVDbh(v3o#@)$*bX%g=L;t9?+ zhe@7?EuVGX9|M0BfbGZtI_r@sy=%bpy9?w;A*3V~=D=tA0S*-DLSyr8nr3 zZ44)ukD_kH6-2u*L8M&q0hKo<;CB04@O*t4zF9nz-_{F3vvaY+-xuzE5C4PBHIjU% z`)H=65W>U?2=~58@Bx=5l7%atqbNKF4fgc0QyVKP4vebDxf_hA+S@ifkQI-P$&VqU zcr`dKAIA5GPjXl&6q?*k%OpPaCFEj&lDNawnP#1v3%y!>pzW{|>W5t-t;^29;=dOm zE94+QqCXd(zbPigvC&wgpa!`nL->xgsTf%M19P3*iMs6}@?o#w{qq_I50@W;AjLiO ztVAoO?ij|C%Ns!djwjvtGZ@#Y2ux4a2WYMP6*mozWCt?t;m%+$ZV)_{1V>NC>?K)b z;F@gARTxG_S^0oVc^3X!8G#>4zB0QV4={YPC$g)x5RWtAajYDb8Z;GCtp`IupDI2` z34z|}_rWTC6XqQ1mL>gRmQ6-gI7)G*zBhiHj@_!_FpZWVeeRJu!rjiJ$?rbI?>Mb9WDr#r|%>Q&D6K!tEB_^kU=3h_dbV! z@~JfcRv;RmkmI8kHep_?Azk?61`O5Tj<>osX~GzH(mO5?=S`G`ycb4%-O<(JN527% z6<)yB;g#%!)O2QY+Z%GnSdgI7r8p);nbxey!r$kXqh$JEzWj|mCr)Ynm!ATy{Co&9 zqtBA)3%~Kds4RFj_dTR~HlwcTRUA6xB0f0U>#(xlTE}6J=)iE zt>`oOsVsvH5IXNPzMc^$4@iMPa|K>7vYhygeL;3u%mj@?F{EufC+=Gb`L+8repI&M z7sb1H$Ph(p;51k~(d`_&xZYnp+j%c$x(C3LDGOM4&@k9G_9)gh_n^k0a)%N22&W%M z!2q{7%|{Z~Qw_aj_Td|=Tr#NPVnzAYSaR{gOEPZU zBdnjM0@8ns*!!YLc2~O%OdEtPBCBPg>A_G|qsq0X7_%2Dz0BzJL$E5#A}iL|^V4Gl zrppmWQFmT0^ItfRWlfGkw~n*KQhF(FexgiYgvH_9rhkNZ3Vmm%f?!~&B~KEPpOOBf zXsgT<=>Hjn>T3^(iy#-)8d~w=4)S9a`6Rj5w-ZFNM{!tg5*p694AOT;Ks!4~ zMvqb?0Vh^Mqg*#8{FS11mRnK3V-H@7s=zVAS@+@QWHEcN9IwkChv{rQ&6-`t<|Lb7 zqogw*+Y$-0k|$u~Z(nwMY7+TLiXr*-A3T@487F2M^3hMb(b2Vv;EO<}rY^?RlZ%C( z0WJR1V;1iWn+Z)@SD*~@B1VA^QRiz8=}Auj(*YCc#`D9u!?U6E&V${Mfd`mGrjSeg zyN_>M+|BCt3S9~cgW2$7`9$}`5}05XOk`Hy!v*JGg1qB&zI?+^R<7_5;y!GGt;ye* zwgp3}N zH+MSMZYZGfh|8N#7U;I?u{>qrT zl0n>kjyEP;4Z*drmOUKq&U3(l=0Cm+r3E)2w{AHJsj(&954>U8N^3eg^OV5Kb>fu} zj0Fz^vAcgGA75ZdVhprIW>pz@d66Pl(_h1n`{Jkv;Klg@!?dy+3MP8HsJDNhw-CD$o z)!zx+W|%EX!H@mN$aA^#qVr{w`0&GmuXNl&a<^tH#06f(N4c5IU0X|R^hJifnOY8M zvCrATp?Of*;6V@D?7|r)gZSFGR(PGYg9YBMLs|J~SSgc_U8ir5r@{w!cIz}4tKr59 zIzACI_Y9~FY5*6-92j(~ANA`#I@nYmC#L@{W8Cs&ELi&u9`Z!oQyU9%3$0**-vd~s z-GI;6rr`~NL)fltj;a#T5W3%tPB?lQ$8DMo7T=|Kr{*g-YdH`4x`x3UaRPMID2q}L z=`p`-1f7#{u;$MM(Cmm6z1#BwFSX8u<4bO^?qg?AD+XzTiF(WdbCKy+@7)LiI z;dbepM0%nY*Qw8D3&X!5^R*ECl%|jw`(7*(G91=chso;Il6cb1f?Vs86H9DS;*FB& zkeXQqfhl)Lve`knw&ywXR=daE4)P^eCceeJcTeNgWxIKx=PlNpWXtDEJSNTuP56lD zF)%LNjPDyJPp3KR;$DBjqtSH$Ozv;y3VBNCTAWO@cHUs;mcGF-i(ov{@kjh@uM2F- zx{B}i{$lKKJ3BWwP1N&$Pl27#EB(_8JbC}?r@xhzsscP7j;MQJTjPO zjr1gQNe`2^{tu37wu>ysH?S488^QLY9w|x;hC$;q;DO=`L8ED8o43rv^0XN^dV`=3 zya~f;O7EED?FLMKA2vZ`ggCr=XdpMMbBEF##s`V|;#{={A^x`@ewPjR_?o=E+jph;b`$2oP9_UDY= zq3zq@m_1D%wq=&%!9V)+M)O;urhSu1n}1@pf)D3#Ocn&)c_QAlWGeA)Z>apgCt&3x zLpY}`yi1V*xM=Tulrp}8tF9o1o>GKwKmEj}N3vjJLJje|XA6Co?;w^2!$+sb`1{Eb zrhKGXT<&=So(-17r^ZjQD&jtzHq^wAOD%Zo-h=qJzX9*+N>U@&o#--F2KHIn@Gt45 zu*=9pJuQ0@q^aYzx#AASzn14{6|=SPS7P*avS^lXLP=MA{#NHFm!W)Qiko;24v zLN)2ciO()#;?zF;;HiK)VmoME@du7B&lcDzOHt}nKCZN$M6Pw#5Z$6Fyl+qq30hwO zD-NWCV$^E7Z&EvZv9|}dJ~+oR%5Yt$9y?9f;r=taxW7=3 zkAAKORgXMz*_*{+dp*>lfFH(@Q$)~JG9GuQOYyaz73r*v+E^Zp*t+jHd;BT{p5;!5h35{5 z+-o0Uuf{ksq{5DO-}Ymc?Uv$I&mHL6{6kQ3tx)rH~s!Y%?&AFYIj zx$_{tEDkmuAR2!i&c;=J zN7$~C6l|9+1aXfvub#6W>MYwuqcgsPjL;iEownlep( zWvFn;z=pO+GDqOKI!`?S^$y7p`{NPHrZ30Y|H*-yu^lchxCApA1Yf9J69mra1>@yW zFlc2Tr0rBg^Q}GbA$kqB-unZbyX{$jtv^U*RKubtr6_H@1dnNCV9@4!Y}nLLD4Oqy zS*d4n)Y=XT%b1DAeGKkCOFHapQ73a1YO0msqV!8_Y_tQk z8Y|JYLKg08i92s?kR_{Ud%_OMDzY}=B{6E5PX31MB&+Kb`56DBq+K}{?nO+-i!P>M z-sHe7Xf7L?xIjc#ePoAj&A~I;8Q8o3B>r_6ArAP~B>Zj}zBl_NI5aNC92qBm=Aa(k zX4nDeil&2Vurzrv(-~*xOmN65Gs2JMyUE+OMd)!c2jpcwLj4#^qCUbBPR)8x^&_&JsM5n}P>t4d!8?nW)zM00LcaBmelGNEBx=^WO0l znab8o^U_uEJmG>k!aW7OR(WFoF;$+|{Em5t-+@Da-?GP#4})`W6MXI)4xfXvaNT2j zeqTzLIt~AYv5%(F`t6di(R@BO+Kt1zpPlI@DkFM(Qwlysbg`zLS!ixzhw9V91h(J- ztRct9o+m9RKj;}e7^ww2Kb#=1Z#{)5uLANb!hrt?>Liy&xWMWbfrs(36(0_rOci3h zA;7E^^NaLgxBg*v>c(eKs$7p2M|QyY^{YVZ=3^LqPVlLkN5bZd0^ftG(b=BDJR4=k zbxSyo^fji7Zv7$^e?rkWM}}TjyNX6(LZ_L+9-(VhjoTaO9Mu{DnN0L7qj0l^ot3eztKWpPOe`%i7HJa zHP5SAh^Z5}pPtNb;Te3Ac$BKd2+Rc;T|NinP&rwVS^G)SVb|C2g_SW(HO+*VZ5#;^ zkKCy3Fpm4qjKFnc1dd_P8j<;^W$^LYH{7CDjs7XE(ECh<#$FDB=bs3KOB%sCmEm+t z$sqFnj}48SF&m-|$#ZX?A1L`s&{n#Y`K#hyq^AqevSJcX)N$isjRCmjoxl>TTg#`v z^25ufvUI4|4;aw-3#Ux{ji-_)VS$?`rr*xNrZvxTq1ROycJ&b3d8Q8JH|(Ne`ia=o zs7+OMUVx3t30B^42-tr!V2@R<$ea7+0*rAu0`0uNrDIs{;Ymsu< zQ^ad?1?cq1V#3Qaq%wIl77rawW<{)}a<;EwmTUo{#tZgg+D(=<=?U{`d;?edrMdG7 z0pD82A>?=-PK}*{x5+_q-)0@Ac|8ipwRvFI>?IJMx&^+4^^5ILT5-SgE?n^Z2>v?pQT+DlDbe*Kd&%{A z?;&Kn0)KFHCi;A8VHuV8$RC9UVsd>VMmkGTSIKXpinuELSfn6i`UHNs%69m7rd_mM zN{V(_eT2nn=~zEZ0>+w1@o$4dVZtV9?l&QnnBQz5y9z$RtS#zP|Jr_Wp!ra8=jBZB z%2DB#^-s~q!5S}W#t?rg4Ql3*j*dY>*2%_!C!4*&7stNhg;`a?{`(-F4QOEzJs;pz z%N6m6?kCJMT^;>43Ho&FNpucdf%hExMf;c8&?-4&8u)q%9``WEl&15Q^}JsxfLTyADH7hk@&_hwSpW9bm7y9`>e(;i2)f_|>XuXzkwZP&}goS9(T~ zZ#TX0{k9CY*5)r*z3nEeZ@1!^qo$$}!EStw!BISSB^au^Zo}e9-Qwt#BGHI`RXmY@ zoBU9kgwA4JoZ{C9bA!sU<97ny**l1Yms}td9fr|1DnYl}-eI@)`SaBNPq1|r!B6+q z=;@~l)OI|j+rBP?&u{m0$F3l#9rYM$Jg-A%))Kxcct7v85T4hkJGng5r6x7uc&TO| zj4XIwne_82ni?}wdm{<&2!7!wvVm|6*P-{ZZG7^Ji;&~LrXu?9dW^`{p)ZBmq_1E+ zZj?U+<@*!FzA3w@))`BFam65-Dd!BeTk3@KY$ngOJ}Fu{seqnn6MD1rv(W0hJl(S= z9$i{02-FImzp>w;a=IhD&pL?xeu_9$`4*nFh~)Yc!)a?^5vY$dr6pJk+PCvWE0uPD ze%oO%UzJI|&78|e%n(ttA)m$C!;Z1jdlqn+m7{3je6;b9yFX)tg!H%a5bBzYn>;?Gd;vp}%9x6{9#VFUsWsQa+f|QiAPq(YW@HHg)YfPpmv`XkMWiElZh;s~Tcqighiv zXdZ#8Bi~t;JEsAP}Zh^{z5n3!HrEKn@vyIuU-An@Hro9?X|hg zyky+2QsD6EVgngiJ%&>cInOq+Qdd*+U${ojX^$CLfxt;JXT zSLcVjs}$&ktk-P6_C_ci_lqQ+ROS}r6{v}=1>`O*6dU`LkvTgDqSxi8sL^XhoVr)C z5Tg;aH}naL{TH(4n<5zhCYeeGjmO8EWoX@;AJCV%p7eqgH!b>!+xGY4?sF1+Tlf@O zyxbUC|0>X|?pvUDU@Fxqv8JD!USNz`In>1dUyB>;>NJXfWMn$7EncwIA=#z7u>pA;b z`(F3`yBkD9;tRkbITBZYU(WB38p(4BLCdYn>90TM@lM=0t}-ageoLYmytwvD)ahhL zHFes_q<7iawQviV&-BN+0*9+$hcw&ZH4*iVi^=|ZGr+?4IHU-?O#XWuFVTAleP@S) zv6MU=C+vkP<@(^LzzV&cWW>LQFJ!@0^_ZhSh@X2PhS-@8z%bB_c(>?N=itlazPu(K zJR=rn)_Q|ev%UR;0n0J1A&;C;JPAFMr_zM^)8SUEGT&c5i~i6F<8Lb>=(EU;c)~M@ z{5MmIN1XYKMu{VtpVUoI`#FZj{yBvQ=v~~Wc!k-x58h!mvEZ#h%iKfA4=&1=h zgxh}sNxLR6EWVFUA^!<_T|MZWdjv|wKS*J@DqidrxM2;lWLL5(zcEvZO&D{H4sCx1 zW8~vdSt6f{GVU;*@DWT*%*#e}R6)I29F$WNS}i>j|7*y@+GW?^f=h$g^s6aI)QCe{Z8M^u_9I+;>?z zaM@K*F8+-1&I4%EL`}Y2%AL5JvSVNCrRdWR2{3wU2o~xLk6T7!+j?)h`O8nVX^+AG zGz!G_(OXyvDG2D^0n(e=Uykd#%V4>tP)3<|-@i<5coW(Arx>jFMeL!7MY4_QAilCbqf z#AX3r4!HYRWkO)wUtRKP7^v-Wg%j7DU)072fppnJY|g9LzzhKS`E(jkcF^E3k0@6BKsV<32Z&ZY~^rc40`lYOv9Ck z)G7tOaHAx=9G3tQKE6_8@siR6rqvQM1 zA+KC`-;|4`qY?^P;eC1VzP}ik+Fv47LXIy}Z5kZ7CG<K(V)|1!5Ct z(GN?vbHmL0T550Ncpg(TZ_n3y!!;iV5-Kt}h9;Aeje zk?T&Ad(Pwd(y^&%vo4bOR)-+FXGmE+;NJz&?Al}lz^TvRfZbitcRI&zFC2$CDn2}P zxF3w{&=jbuQt0w=B0jUdNETLpM`MZoP&bQ1Z0tG+7rc!*g5K0!cUEA>wPOSLpx9Xx zGac{4qS6oIU?)AH! zsAz=ZhaaKbe8LQvx$d^8C12=tPE+O6?@Q4W+ONpNQd8cz3HWQh29fB=6zbzTn?q?l z30?RIKdkx2E_4!lC~gvL+aS;P4^%{J-#J{(~`)dT|WHCtrgsUv^#Y?_zy!`!|Ae79kBh`f4EsU7sW3d zG3kjJUDs|0Gmbj&w~zmT%IOfmFPUW7bVojhreSzRA7oi3aN`&u&%XQwYx#N~>Ly=@ z_L#M_?%Z9R_0O56y0pQI6H2^$kQMc|km1>eEBW-0*AVn%4>VpaM7gz6XnxNhabzR5 zzp|tz<7XknZ-HaaHSx){9x}3WH+F1E!cv=X>hI6=B^$4^7 z5QA^772vzQDxmVOPh`JS8BDgN;g{kF*tyx0-Re3H=4S;i+Z71{%Stij)pP7u3FoUd zlQ43*76*qy$THU8Zf((J8}c`x)Wj;HIiwS}ADDnoiWc;Cic)P8IR>jnkF*D7glmLrAO=7!F?y}0Rx z3HWpNkuUOrSEQp8Xa&Y$kZs z;tN3^Qn9gyPrU_jLFjf^C z_++TCE8UhMwz}2BRyi8;`7Uzs=BOH=`X%T+xS6RCZ&tKQ4ZkT~D3eh-z*NgJ#366S z!WgIjAm{c(et*>gEVBGaWI65Dw55Xcj3pT`= zh~&O1@>%Vvc7DruV|v#$*!K4k?)Qktey{aV?W@nbZu;Q+-O2EJ!B7k^%7=iI4G5#& z5rb*AcsgStiT134|WL- zQv6Yk1)mi#dX%pyW5rxvv>^~fm7T@Ks_R%%#dMmpIS=3dOtM=t?hM&n8-siQY(a~% zGni%cgXHeI!M;~|qL1ferhV!V+kPY!Z*>gjYo08CcM7KVTHDOvQBpjTAQ`&V;yZXf zGoT$AQ*mp03hWoSUBA?aa_?k)tg*Bq=PZLjHnKqEqdSOd+%OiI$$YUt9%#rO860DU z5eY=PMFl#XW$E>b5=h&y933cVj*_HM+oy;<@H#0ExaCw*yJ(CPpiN&;2`G7++#yaMWCwn zQgn2KB#o0dB3A<@p-n(PdsaFR*PX~giN6JS&NLq$%SAwmq6Eh&N*EP(Kw#I7r1I^{ z=;Q~7Fx(>-{W2B#k5RUu`_U9@V$<;3`dao!X%Ke6R;Y771Xtc)VI%qlIFQgAe z^U_$?h8ozg{wSLfp^i>PgYe)c57;aCNPQ!vxSHUvmB}8(Z#(AVc_#xJnLL&+@`;6C z&fT!gVFh@bTo-Rx9R30C`!sf+j(oDrYp6JAoBc-Olq zsJgQVc3-~17T(|_=UK~>$KzOxmFT`ApC<9*tkEWhn2Gqz^F^4(CsU ziJuqZjvig8YTA$P8_h83#Xfi(twG4)Tk?U^_t6)EwyRwVAHaLMmq#Q+y&fGxK7|rj^@kg*z4(s?db7zA>31#CQx5w6QFDoGAAlr=A!4;843h&w1uZpY$Jr zZJU+}y)HeBovLNZlfv*HT5y-7N|GA96lEstgbfyZX``qWA|eD1nvMtkF6Bzv*FJ?q z1E%p6^K+S!?N2y0<_x~rag?Sk&cv&KJh*|t3~F-y2I(fnG!cz?=nhXb>l1jFHox(4 z^gg~`=#rNY-bRy-WQd-}dvKNG*6g)y8m(RT0aFK-;L_|_GXrFCzZL9&W_bTz_}jN_-OG=Vx_1|!_#w!jE)-( z{1HSKZ1^FLKbS>FR;A+2j%*qt_)9QF(4(|ecyabr{>ZA273PnieKJUn3R+(0eSHkS zHUupuTG2^*eInWV?~L5=ryHDfuy0kKc;cT%_9CYl;uD;ymzjaU;1t6#zdYQS`W6D- zpQA55Dc1>>gU8sFl;J8~w_VD;T_PktX(4f+6sHvNW4UJOdQmcyizo-k>E za2|hDhCtDqvIXP5LM{%V5hYAut7uW(^FE^f;~SZ{Emi0#XK<`!GkzDvV}Ra0SQU^1 z>JNOOrOJYyb_~U{Y!m%)EEJrQHdCF!W8tcq9Ny9o!VLqq&|@@%)J!>s8ZoA*-SQ0A zwZ%fNbq^WaZb8%zuY!6nS-Qn(5CjQbjVmGrzo_+DmS@le))Reb-0B{($7cW>zGBYi zes;p@dIPTFy956^>Ch1t+L+s}L;cq@vG;3+^1Ozzbhj|8ia)GH=^_p8p4bgdrdmSo zNRCIboO}Qw-_9E7_=tCvmT^r->EV z7}s3W!T)&+Nn3n}eVc0t_ojY^rDKrDJuZXfwPSeb+X;9k$q+v49Dz&6lI;B)o`AQO zpy8D1;@lX4xvI94&b)F4rcdaHc8>$p(Bv?g`gA^w-hNBR0ecr^Jq@hVM%m@zvA zKWiSA8#w}fmH@3sH{!!FBj}FAGU8bC3Uf?2*n7*tf0t}PVVN9N)t0B0x=~`=Em^qs zmn4q+Dd;g{Z=$9AOLodwpN;f!hJu(pI6b%=o4sDbjvM#bwsqY?4%8X77iK_bj1-IA zqliCC<@nEhz|$?3{BJ%d|2FMs)5n(Ld#isaZE}vKE%0KFlk>?K#l%wIC<(qvTNgT7 zk7BX$E%G497e+46A(4A*p=5CoIwoY{u2~20sQov5S6D-yk9&kI2~Y88<_YwE)Pp(VcT9ti;kLg!i80x%)R$Md$lKx*)&YW+UrK>vL=ztd^{8q z>Yw119Alu`Z@_);B3S+2L~P+`4ppT=aBR{wd>J_dWLk8I|L@CCn5l}*?t5AD@d5Os zv?jFAsD(G3(xkRKn~WcAhdFW=AyLADUF>)Tt&f9ni)IQj-F*-@3`xeF(G753q7HOF zKO!`7ipWdahX}2c(0L~cjK6=xNgGb$x8+^9>SC2>YU)Oqx;+DP9~^*HtL5l`;G>{s z@d)ol|Af_bM{(JJeRPh00q8%QgNOIlvVX>=A{YH6_V#lsndkM9%|9B2>DM;HM;eLx z4wJ~7(eFWj$pIX<=?1>;`vlXH7!F?MNY1?bP9B^d!#!O%Y%47%xh<*UPX~w7P0QlM z#syacLG9Cx&v2*-TG!RC?@uX=Nks&0SDrra>XbE%Qy*T)wN zXM-}|P(6!0SmasOF!?3!nNlhay{kb$_c|8T9fpy|MG)_B4Sd)dEb9?Ma&CE~qUb1e z);vOq4`RHW9|;GhoW>x9aNL|`NH6*4!WCsjT59wZvY!1Sz8mBr*xa4#e|dsgvUf$N zCRP##`g~^VFuM4N9b6E)9j98Xg9T$#px(!b>xM3-J3B@QVUA}Q^KdTKPR=6QPQtwR z!HSMMJ`smZ?u8j&mheAH!+2!zE5IDH@u*Hfm- z!G|!i*OTbF--9vwO>CEz2S#mpib4N%!7aO=Fizl*&5ex$xx@4DeZMS?Fb>C#dF5D9 zBS$k|8iUpO>#TX{Xc9 zJC^?q2%~hA2^?zs0HTT{Na$LP%VIU@;)w$w!)ZSoc*_KCp1cK<-aLW3dW}TGrMpbQ z6=0`cxTw9`imtlh0D4C&q3Fy9flpfvw)?JNBGaIbH!s74TnbkmSKy_12YPQ>r08t8 z4R>E=kGWR8BB6wjy1E088TkNp@)UWok|Y1&V1bvuw4;jr0A88i1MZ?F^rzBAxYV={ z2S2yuN@J6GWuPRzv@{zcP6>JLMH6WK_>VBPqz)Q&PGaV#Kd|n%(D$=m=yymS$i4LL zvylgzuy3h=L{5#yg4E-za#J?W68iBX&3OqPh~nkbSfP$Xt-1JV_N8dh>^lDFnW%Sn-9yuR-hapI$vG#XQAbr-YuJH49*@)j^_0#{M#Vqbtjo^ z`4iV1cjE4E9AW33Y4rXl7c%GbFHG+1#;SjkG$rMruxB2QYj?`hlDZyIXN(HZzj26r zYsk~0+nec?lzrTyL7f^#W#b^vHtcE~L-QU*ahuIa@aIN1IsDL`%Y>Wr_G*qwz9D?u zHwCWhw1gf!{{l~`Mv_$zzL9C{D^w=w@q3RB@_94I@M%JJT&r~uH8t+T!Q0zes)Q+= zb=Kz!FGuj(>es-bK$5QhI0O9+WN=sW6X+`h+?Z}fKfcR>cjFR7_r^=|*A{a~*%u`` zbzeA|9VWa^$UBXFy_42V8H$fG3|Q#~4{Fj@3Ob7Z;M)2D+tWtkUuO+aP4nZ+E!tp} zZVd#FQlve@-@{Ph+`LtIl&+}D#Z?opf}ZRVG`|*)t+!=qd5#^#?gnswR0qM4+GvV@ zP-^CFzQUmz()Va_GgTSx*3|(qg}!*{`2*-p(c{r))cBjIW(bQG@$+#zuvYM=8xB5+ zqmx6$GBp}JZsY-w-8PUsuNX$@R>3Vmh9~C8_a{ zXBJ40rpmJHq-&@bFqRbU@S)GobhFdVjJ`fJ8$7Jfv7O3i(6C@N|0ML$idT8?Z|gpQ z!|oGcZT|*kqhE;E{>kDK6b-r4%)PAbz7IDKX@sJgMeNtyYW|hC;BbM7zgH>+ue5){ z!9E%AY{feI!eJrwz4!oR_b7UyEgs|s7NSF05-xqZ2xP2ov7g%CaeB~ve$3U4kBQrl zXUb!Ez~Zg2`Fk~#mv4nx=cIY&ktQ^L9*Yh`^6qswsaG*-U-&M=+5Yzj&p}t3+Ra-y9 zFnuv!E*HjM`4xc8x;oG^iN#?b-T1fR9r#5@ot7@-m{e%QJ)Si1ohx79pxM`0Ck}(^ z5u@=&NgK`&j>VnoKzp5rfsW);CQ&BOV-6ZnNuvw+@B4W?J0lrJt+3-mYz1Eh48Z9$CMw1j2V*XRG&xu!X)_@WdgDIG$04lrO9_IOUMYLemeUee7X;jV{Sup8`t< zGy&m=>yzL{IrZ$A0wOhiHCtb(S>!a|Zz(?o~N(25m8(KRD z!wW26L+3~1f*LBGzWg`pDx{I=J3}!?dJD{X`TC7$`M4}Ok*@xZHOz%H* z?EMV$*1jjEje4MZzmI)TxI<3wttQ`IiD9dYF*&?VMC)ifR?Q!c)v5;E+sJ|T1ST`- zVSiAsj$m1r6vi}Gpw%aaBj=q4Z_6&h(_jh%hHZcd<9A>n>jzVs(&6;&rI-|W7%cQI zz>rDac*6zo`C6=}~T6qGLT$>&{E%)#*LU5xo7^PiE(62rstZBzZ$9U(~Q$ywrFz%$02y ze_G*5pMHy?qmSzdedwl0Uv8v#9E^Ea`3Q0IiB@ze;&?~4(k_2Q3U6C}nJ8pk#Tg@u zF=w)nKUP~Ik}~y!8=luNZ-e0NZy3#|-3g#I6Q|JoIy&^@-4h@@pP)D-3Wi^w!Lxez zVeexx8IpaLTstSs_3f`oCD@_GVI?}pV>0~hpDVuZc7e?`@P++frh(DtxirLlnUE`1 z;t6lQ;|#+QbnCbuI4yJ%bo4|+^H3Xfy+`QSgn0bxo`aWl3ZU$j94Ki>;D36?tVY&pIcdiY{rSrXfEt6@oNC9w@jfFtq3yGZ{H>I)vQ7egcI+iVm1 zDMOau`~92!nJNY9t?S4+S7EoI8w;NoO+mBY zxPfg=&nP_``xhck3yjveljxMI9F>(g{1SE@$}^;3dx0tSsT>4dVUJ;Ja}rGUJc*tP zX4KHMkImYb4@D9$SjNjdvSPv@diqZfiLdm8&86?`L;lNTnZ8Sryi(wibM}*lG#6nm z(}ep^Z;({?A23p-ozN|R!7`@~O4K$}w^Cr5-=z7MHbrr!V+xs4S%4ywtza5-mMNV) z1*00?L5x%dT&g~X$(1^^AxIwtFgsk4y8&}@bJ)A~8+dM>EPX9NJWpL8M4MY@;k=Ya zdivxA7RH`Jew-`}aGOa(^{>J|`5dgz|08M|q0gpTr4Uu~5D4EM1FbhD#I0Ge@biTq zoRInp#{{3X!(9!Ll+dS>L)IWM*RBIrR-Fo5>EPh zoYY+3hUH(J8U1?^+^sILtvf={wKawWNR7bk&@}QcKb{;LJeY3&B*WjveT5L`IWYRm z4&JZ(j)dk+2dDGiB5eyX7!A?ohhqk!{bE&`b8!nS+mwmTmdio@k`bEr4CZmK0)_M5 zohmnRc%NvAO9oRq_-zNQTSn=0BKUAuHDH>|P2tRJU^k)%aI3lslD>O5S1a%%)(a%5 zo>da!##eYv=MBkOQ4Hs=j3YNERhOv?-G%R#Zz6G~!?1JwEvUM+Ow65p=)H@_VSa=G z|B!eHqtb)vlvNB91mA66L_KMD-Vb!>Q=;{|8u#Ac1kYMh@af*C$c3}ua;+xybxQ*m zNku&D;0p_Lv)HlR03>P#H09cUs4(!LFP>`Ci;9YfD|Oj`^%HTH?{ZNa=@Ne}enepZ z0egkw1pFDQ51j_eFrizD-*xfE?ZvL_Z+@USVVord-I+}jOy|O}Q#w#TRp=|bdjX_I zzecM+QoLvVP)e>wqlc$1pJSnApSfHLRHa;~f$wm-d`Kht!S_MZ>{~FQLKm(c`HCxU ztq~Y4uQ15EoSZS7g{Em@(ac9>81Tm*cQvTdg(EzPMA0)gFD8&Q1Op$awUL#V?1hEf zh$v4n9S3g{O7_gNNaMzjWb76v%+I(64ZXuf8mXt?#lCa+%1I5TU!F?l9k3+p%7^f# zgTIJ%Y6ZIKQ?z46V*|b=rJ0<+KbJnr%z(+oMQq{vOk!#|4T2Pe{oU1Y zh_HSR&rXYBfB8EWVx%MN$xO($&Ja*3juS0hp9;`f&z!f!W7J4h7y*gU5EE^m=b*|L z&1-^5SsMJb@?U1((1im-1wKTgH|gjS*t0u_VDZXE(44;+ww%r;zib~t+=PV?)L4a; zi-$Agc|ckh?ZGqECt!`+Yb+;UFh0ZpPlEz)Y5xCv@H$h7D`r#ur}96EYUKFUGF-Xt z3RFV|M4swr->%Ju`(hiEvd>_a=Psc3sTr{3Q(?)yas4Dq=C?T7_CK)yw;Hvq!U#Px z88@4#M!8T74b{xuN2Jh0DW`iLX7EHz0e=@M;;%IJ@RDkP;yd`|tAc&fvNDsyP zahvhyMSIU{i$B!fCD(e+lG6T5Lerw=z+YQ8p+8HLZeINbuO-EDm${>1_lk5P zGryS`uN#262dzNv)L0NbpTkQvCSmS78~P~pf#}S(=^(ECho9!};|H#-e1IdOFOp8hNCH1>=#GlZ}aa)oE|I$YBtsCsoD8d7#hQGu+ z+a9vgD>`_-b`YBpDcqa*QMhVsMEhdu@wxH`$j&fiJu*rngXRR7@@pLAuhtSv>^cl) zSH1Y6**`>v5>~V#NdiB={3I~x4#R@BIQ;NDg?zqz2#l1cQ_T=}^r&6UbH)qhGk4a2 zpYJu+Z5Ij0l{I;VWxlAO%^hqPUxe3g8dU$(ak5%QmOStM#XKMFhU>Z!bi*(`m^XI? zPu?6vbz`TI{c8kCaLz!ob!{X0tvU?$UG2cuedfF=0C0_ZB3Zqqn)sWkq2@Y!kk~Cl zGb@C91@JO+Ez8^m?G8!_ly2F^Y%c(BYrV$S?Jl-qa{%3|Mu zrP@duw6sH{^7kXO3@araBK8lV7&!2~&XORn^Bro{NOr~?U zS7W%+#+Rb}=ARg5X3MFb6phH6&Yc9_ZPRWmI_gg{WL??`L6Y5&vT2gQ`m*H%_3q=J zz*j6}#Vy!BHxpvX7+70u!Q087~fI5u}ZtWes)JAIF1+Kqo$>GvHTCVt0F zbA-K^MlQ_OcZIec6k@qG|RBi`~uE6V1`)@ z>HLD~2a$!;HReEH@TMBQJoyFqNK4U$$H(xi@|oh=H)B9C ztco4`(Tj@KFUYL21VL* zM)^5hy<#98)KJ8vAGxq0ukzThXg@FZ`VESm({av;m3Y}{A9&xDwmK(j-psrU^agbjDb~*kduKUeshQ}Y=dbk8E z>uW&4Vl922G>{y<6f2hBpHB*06PU!=Bf`uQz{=;^z@-oOVCm0aFl|)<_=#&UCFmfN z&Y4B~!$ovb_cLPm=p}T%XoM4`VSIW@F+`XY@WYdIaI?D=qmEsz^_u%>5kS-b(LJXswx$e_}++c?xU;Ji} zFoO(&W5QvSooN9shqjCS>0Ek$;Zaa^7>(?X3IDv^g!-qC$Ln?qRJP2K{k&9y@d-6h zr9GG=HhpK$uKvT`!Z6%dVaXTi9)Uu!8l7sQ0HvA9U~^I%9?q48)id4TPWxQDx}P85 z;?qQ|8c+k%UMkR!-7{&=4K1p-FtEp1wV@hwSoo6KiROyEw+Lzvv(2|UN^HM!}m0#WlsL{n`G z4BX=eBg!U$Ju&CTZU;<8(k8VdD-OQ zOiti!B^OJ>R$)Ii|I<#P^0sKB)>Apw?A?* z?fNHHFXY7PW*;W~jV`Ek>n>WW7UFB)9MrEG2MVVY;8^Pq@}kfMS2qE_p8Ocaf(NM3 zPv8Z8k>>((0r$s#!%52a@bhgDydF0W`zOb7hv_!>vSJf>CU#-;*HLWj^$uZ{d%}up z?=p4Q+4$Tg1hw~CGs9IvqU=x$nOFWDhyw-0|(|3saY$a;7l-obfplsYGpI~ zHQh{N={Bqvy@ahAjZAudHtN=@vYT@X(Rut8SVeqMZG{6UOc;P2N`^RlvkJ70lfoHJ zr-`I{4ph$n4bg|w@%+i9G=7T|oPTe{8%o~`dQ%vbMrg1n2`7kM=U;X;WjwcT+>1^> z7vbslc!*3gg;q@u^bq)l8mgbM?PN19+UJ7}!P>a%W6crq;b}-CZ-fVm32`0 zcz7_Zm3+>sBL>!rEXZO$+}B3d`?OCiS70W3W7f~ignNd6+7h^uC&PzDDnfkaV|eTA zi6OR^h}y~n?AW0Q!W3=z^j=^1K3|M}u2aOJvmRpU)_OP-Hio9^sL&~D+Mwi-ia*L~ z*r8tzqQvFq(6ljKU}tvY-%v+zFo`8v){Xe|*%KoF>1bKvi`&FPGnW-A#)~#MKEud~ z^`e_l z>uW-`v=2R`uo?!crZaWVEtvGCN6`GUs9aJBb5s%XqiT=Yh3|sDxgmt~Dj*9O*a*(C z;W+cO7sxqohLA8xGHc*-5v_<6H(O6bI9?4?Dwl%v@JSG=Ukv$&gr2?Ox8Y!lm-vp- zGWO|2BG$k8D(JhfAk?cLPIxH7kg7TG_Twxne(lbrr}q*6g=YA8{{?}OWeFpUm9bf7 z3y#vMgQ|nY=u>bwAm=_?ghZk2VU2*tITjqwF24Tb4qi8VEIy>0`?UHt9T@ zCnV!uD#o4B=JOM75Oph4IyADC^#5|j{6JF(=rVxK-!fo*sj=wh&~ju$)al~&?&#Wc znT(1(K(8IC!{9|0Y|X9)QXX;Dy8Vwg06_ZapHR#%<%3L4_!j>mr%Ct4pz+^){ zOFa=ro|_E>S^ouiVCgwn@IDcO_1BV(CXTR2ArGe%M}lwHcC3)i!WAugF#UZwv-&Q0 zTC6f*to|n)dsiQu4%l$NY8}Y+mIu}Coow7NNeF(t81JR;1*gy+5)xa#gzU%X-+SGL#Q{|%jO=lfP=<=apu(?QarF44#!J~ zoZTx$ZK(&y%oaKH6&M@Sr@R&0eo7&~-p+zBL3bQ=aUB0}(MJ4v(o6BUYf@y>qTL|z zJ($VL=i}{{4Pv`p@0pR%7ZNtnhFiQ|hv)Bv)4G>A)N0{(>xQZ+Qaa@3j&Qp}T2!`zw|* zdl7XSaS{tF2Gehk7ZG~684tbuC9nv-v0bNKLHmvhI_wfUZ+&mWPiY^Vv2g(%F@7-< z2urAB7ePO${$%Sv52GW0yOM1Mj4Y6OM^4yC)3t|U(LPy)sQI;t$Y6aQdMyC4Uyezi zK8Bm51U77OCXh6agP+)-ukhP?Z5)g17RT7fo%=~f4HyP)0-tMC$3l9cuLQedhtnPD z*7))0DVYCOnN0bjkMFC-L(`{4@HICbYagYs%9y`o{C{V_#^5y+9ZN;||4w520WF%| zbOF0P7O?gC4fI8-h%YsK!?yqD&ikgm1SzY(tl8ECM~D6>som*}qSFAE;ng8ph#xsJ#Imgh|nON#`5Ozj=0`BsY6 zh6!x_vKdhI_B*>?IUYxAI-r}IHa&NDKJ~lf3fW5%A=fLq?3Rr(j9K5sPRvMx&ZPsP zNM}0k4e1phaOoCJp0xuj=19R9w|4N@`vb0@Ov2N%f@n!p7*#SiC-qj@uxwovz2T(+ zi)TtAoYVj%`yh6cBK2FTbC7$+VOoXl?zg?_q$^rl)ep=+zbrS~f44fTV65soZOcs4I$D2z17Lha}GV7o#K zHf<3Y3P$^gCiBIc!_?>#8A+Zt{tK!l)*~~J=1%kO!;}Yvz4`f&tv!rnQuRYNn%9aZ z2Hu5?7eCp=&PX9+`_q19niGFLuMiIfs^OR^2hcCZ799#5FwQs~tk;a7or@PTh36Zo z{+e8}Qg|;(r+HuB#4f+*FSJ*~LSfPtpW2Nslg42EmB;_1l! zAj>|%!v{|xw5my7+L+3UJiE1G4(J&?@0=nfs|x%<^Ov zJP4W2_bm^jZmJHbeZqxHw9aG4#WD1t*)q|JLnp+xHo?@2>ClPix3MbyP&y|-n+DD_ z!aa}sLB(6p(rbs)j;Itk*LHz4n+)&8#lgDV zuELG)p7)aVOnVLTPxoNQ-&wRIBbdogJ%!m4HSndRhh<;R7JQ)^kXqa?DmrRJy)qj} zZH*ZXklf4n1Wv#Um%qW+eP+DF*93lU%44&nvvGRVHcXkj97o^r0H1-E1s;J6d=A}7 zbFLJ!XHKu+U6wx8veIVh!dU>XN8+$))A*X-U7!ea@xH?$@lc@$^Sy6>Md^ve}1?Vu3 z|L}8WH`CoxNyCNAMX}-`e0$>b{UxBY4@*B1eECpTB z6gs@?0_w5|c=S?%?=!szy;)mfg~4h?6ZN7q8c9?&`4-mfzY4Wgj(pDH zZ)}F0Gar!{z{NUNq7hxDRL>Wv-HfNK+(wOy);-7G_h&I|?Im$<=4}=~YcL!1?gWOZ zuAvhz7Lz)&p{ye260Vj7jGE(4*Q}4@Ir^Dp%Cw%8UM|AX4}{!jlrEj;oF^K8bs>yW zYG#SvwCi9lfLzLLaR10pxo6~PV_w8rAJo_OjaoSF1xU8nr ztF>rEu@kTD`T|XA8DO@l9L@!tBpbzbLRVBE`DVR@PoA|1HFpo?R%7g8XyanMV<1cO z8m_aUSA0;fvIKK~f3x4`_eL+lwK?ps zL=YH+7?TC+m!aUkJ)9Xnipw9{OqZMYkkPlVKvIbt__jpjf3~Ti_peNt;6Dp? z3i@8x!ymJf0Z5LgByX~&TPJn`)?0MBsJ=qf>y_q(J1_7eQQ zs|rQ03P|I*hdljm~{ z9VBy`7-hPjgN?tC*N%$@N>++%B(H+6NJZ4LU4t%iQKum^9mlAhB&YKSz;YdX^v(cW zy37yvwhJEqU6NSRau9a+)UzXN=HRread_9m3r8E>r(vfAp6T+5-0V>@DDKgrnPW3h z_Eih}tWId8nJ3My5%I5ZO_Y86Dj2-WhN=GyS-F}$ta?~XqkF=z`{Z7_bF4Lg=vM_B zu7qRW5(g?*DhpSZM#B5^wU~BP=mn05FHJT>>&WcMwezOK~~c3rps!(5ypBX#J>~yV`O9!5(ar%TV6^U7tRkf9bWT0Z10`b}$tZ!)HI zhTJNiGI1Up6AuLSA}#Zm#KNoHQSu-w7dvQEemOl^g!M~BvH35ALeZyMlD_+Vaihs=#kMjG=022h=+Lc zsNq`Vjr$!Ky>UD$X9WJQweNuE^7|gQH_3?X>|~Yg{oE%B84)U4NcP^8mOV2vLa0Pm zs7T`doJWOHv{2Dd+BCE@$^X%3RiE+ue82zi`}KNWcze!0=iYPgJ?EZt&p9}MIdx~% zEEr)I17QinAuz4s!+N?H7l*cS;6(NUc&3?38a}Fn!6i6wR;@#s4(ZgrUmfxT1QQ0H z7m$Ht3Oe{%kZfSCfo<#W5DyNilNrYh;P{C?SbU@jlUF~FZIGd%=|)ZbFzpm}x1=0M zGbivX6GY|7(P&O-BA9KmMfib0v^#x2+!LxJCYIOJnKZP>#^R6I@YhN-?jcInd32WYmEj;E4RjM5_=%gSq5JisOWWKf8lfToEB5@e z6kKpTjoM$!!j$G9(z;zwXnPzZIKT4^VHZrnkqH(db3 zfE=u?*aSN!v5mUtx(`jB;=(VA6~I$J8xZ1PMQ)01sFB?ZyZM0~AM~4xMeei&%gh`? z-QhOoB+`y0<<$XW7YDR|X@T05WJqYTL-kropykPn&%WY-D^qz+u1|^+m)~08Ywfnd z;z32yKi!Lva4rFU%BC@I#b&gTHx@~-yW+xFCg9xFSe6khd625paQZk6-Q>!}`YX-I zp@RKz`YsF3cbpAt-7p3M%X0}fJ1czn;z{6s)khq5lxy{Hcmk8@h!0Y#Y#GIoeP`7$K+U0zRZY(Q^mq;;^47(ctmS2nG6u) z-U)MZ+3ndj_0~^LrSbZoNmj3ZV?~yl0F@?tkxqdt8M5_iGX~37LsHo zmH&g0i5BqI5SGUI!eB%U`rr@>r@Y*Vaa9d`*5fZgUmJ>9tyjPi{st8foTC7f<5X3v~77nbS;=B;&V2DnNk4$=D9m`FJZ@r%w33$*Og%XngQA~V-}q8 z6&oZZ=Asavr>)hAE=2r(4Qy&Hl@pp%fiw|jK}&a+Q?0+l($B5kY8g5iqVe0K4oEH0+-w z_&Zj?XWwS(9_oB@;ns1COIRAX^K(GSPai%NghOEFN#M-Ci#D4v;Q~C1@cVO8k*;w& zVY}ZH&+*{HwOkJ%k)hWpi-j3YJt5Jwhz72H+y)q4&%(VQKR_pyq(SJ84zd>91ZG!C zF!L{=$mJF@&Kwbo_U{=&5AN9_%biQG@!MH&c}^-VIjIO~$?ZkWMR(!pdvnT0*np;) zYTz}~VRR$qEIKU^Md|PB;gO9wuF=DRwwAThc4@KT3v5YXzQqX^f(h_|X*PJBF$Gth z-7x%l6;=^*9Wx@=K%hn!`0u`g?4&ty{h|p%(0?Jm<{{ec#V5@gxJ!iVd!r4x81R1e!(N$uhUK3%h?t7wSbLy0d2h%CofA?aeSEpe z_ac$0ae~Cz9UH;x>rr?gAW5z{`3Y*RrZ8Fk zJk*ui4mpQkpeD**DWxQePoCx@5B4m>hhmHAV|gNoC+!$wsG?&pxx~O&q8ApeN{7zs za58bc2+3AO;vJHXWbl_Rf`iIMbT(=+n!D8*_UvAYRKKo+N7c%B@au78aDM=DGuZK% z*;ff!87e1-U@qqDDvC~XWZ|u*)#Ua0?bu2FLde?af)0LafGeT}G-boPNGE7B%&+VN z-fg`Y8~)lMo%P?o&|SKZH(X3{tsun$Z)-IrvoBRTyseLJEEN(S#TsVnbA@`WAOl$c}p8-86>T z-ASRBNPU8*`&Xjt$9u7^;o16uMRRF2_g)hdotLRvdP%_QbQn21+yUtUe^|7@A3ZHQ z0f9ZXP#n#N$DiXOuio1Ooj1FPgL^tr!RdBrx!!`fyN<)g#hb7%MuNEC2b>7?J^-e^ z^DtYvOVIc!lqhQ7M3gzJ(Y{y#`g}SR>3gq0Ay4js-+&v^eSHurmT==$r*%mD>{PG!*@MtYjyy_K{xQgKi>5TZRH8tpU-e)u>)di+J&FFG0 z6P}WL2m0RF1ItkrX<-h>wZdSuYb`d+8stP^_@o?`SYNwCymM>dJgf8jG!1S zo2KVT*+-pY0neQvPOPv)<5B&@=PF^mRBt}68k9(ElBaURn@^&#>I_UyGYW2fo-iHUZ5BJI1eFeH8f*--ar4#+Yhi$JOtXbCs!-LMDK8k#~2 z8D622uik-2`D#$0kD`~8-T53t!mSX>D=z9X#^=AB7G%}(tEdku-kJY*o)L4?%W z6M{@v)DRbE)neyQ?*~&V2YVyV0QQEG;PH|dzl-yLJ#R9NM|}z2dbS^9-kwgA{&1Ui zv@e~oI8gyboC2inxle?46A!FgC5Y=u?n7E-11LgiDV6)k72ju~h-dDIgAKPA!$Os3 zz+z6o-nQfPt%oI$kvtEn?0O#ayu6*La^FDtK;Kb$jMjkLnG$StuM~9;U>7|>WEPPA z^>n{ai^;`iDU=>W)d`~PYfBA|AWubpGS;6YhCjb(J3Dw8Bi&-qyBs;paFZCMvUfw> z>tay@C#l-vDi|7a(R zkBb4HL>?Npzedk#c}p~Gje?3j)LEZggtLFt#ylpSQ9=D4mZUS3{vrE!sIna4T!(QN?t540_#x@NdHuaoT>O`#`x3p63%hN!NhYWQF%_NrdFy8nop?5?yfHYs}%SHjP7_l{_-QjTh@?BiXctXnH6L zayu^~`>#)k+S|L4jI}yy7tTOWwe{&Kac@xUJAd#nt3lb4Pcd67c8+z^x3d`-7#U_B zTPtQ31_lle>W`m3ybP=i!9o5$Zd)|mUBg{9bj*wy8P>JX{o!fF3KYQ}N1A0yr;OEwDI+R_vwY7&K^9z*oj0 zTHS?yOdxX(xvx{2y!O!s?1o)X5CMbznWG z5m@|%$*t6Pc6&3?*PZ?7;*oe%6SSJNtD$OOJv~E;Jz^tY>?V*w93b;oW0bi6>zz@i&(%$;+8N!OK_@!KA9 zC4Vic)}H}8S%4VUw<4G1kJ9$MPJ*#&gpE|S5=T-aK+oU}wsP+c`Z~^8tih zXQ~tEFMPSeM*k89j8!}f(>Sd`SJI+20Z79>KLvmH8eCl*wy zI*H+dwX}q|Aws1ZhxydKkCd)q`u63XP#XOXZ6sUhAuPF2RbPNTI%k7t7y8ql>AFJO z*1beg)gaNjN1ards|_uq?F92lb)u#1A~Cv&neImA*dB&0SdT~=$n~y9{f;ETVfz>x z7_1}wJlV+jmAyoRBs0Ea;xetiLTuuh^ot~lY5I+9wYWD^6;SR>b`i&5G zH8ZNLE1=tKu|dij%w%=;Wh^9SC6ZZS3*CaBFa}H>#Xp#MQ|~aHCI~ zX1z9oh&rDPt##t)g_1I|J~$W3(qCgtI+ldjW)HL~tPF#mBbY^z9E?nEN8ZK(V8bH; zsz>)>LzPFU`z4hGN4f?|Y(0&hPVL0@ue2Z@tdoHqekY)uhoE!x<)AMQz0phAWNfui zKA@?lw#h|&$Ww?5o}S|+Jd}o^jfFbr+&9FGPM)BLyzjtv?-D@f&X!pEfH_>1Xh&vl z>csjb{j&?Y*g119F*;@JH9FteB9b$;4wX}$! z$uVNX^?qn_>kv2`;Y2GB7iTHTM!F;0#L?sELDfK48#=4$X6&Z?x!%8q^ zwQZ2pWP_ruk}#!1Sy$!Cw{4JA1NA~h+CAkAbiPUqtH}31xlSSk z%PK2|hJA7HDs>Xh-IK%*P96h4-*{+zJVocvh(bMzD#*)m1bx|`Pq1IjCUV&I(Qxo= zD9H^Wh~N(NcHV9f(iX!yFO@>cyE15-xQHp9kb@Afeuz2Xfa;@}pwOlqjjNPmXKBo! zur-|?UYd?#t$09y^$xghWyVTliArq#_3*5Yv;fgg##aU3uSvP3?)pV?Sm?dC5MMAI1vffn(Hu za1TUwT||@I^YD~gym+4QIAMEf9a@mZ0e6$7u}jhnB(qHfq2>D(n9D7sz z0JAIR!=>7v5C)Amuu2CG{L|blTHRTBn2eQ1VllQv&u(_Iu&)w*F6o3FD#^%<$raTq zFQeTLkAqU#5zPOt8yZca?%-W+A|zh<1D)d_;gnm79zWX!DH0L%M)i2O8o~*oL-R>_ zzT*&g?*N=C=pY1RY+&z+-Dsu664Ecrk-onrm*AT?1J$im&8`7XFq({l(GC%)r|H4D zDY#(sodwUm(~$+2^Z-{r7_~l7%w_j%>`4GeU>GIIydqvpe@UI$nzC)P_a`U&LmeN zrl`I6vNa1)ytN;kxIf)?pgtGWbN3Ms7V@LT=VXYNjRfqZ>K7D*NTTJp>(TAH6i96v zLQ{UNsK~Skwal+Y0X2K!(N+s=?%*aYO|+F3`?-a9)vz6{WWJ9+lFCH-yE@>|H$}N& z!-yfRj?hnuLY-#9gi z{*r`^R2t$(E3N`@eg(>#9Ya2O)<)EpXyU=I5>brOY&bb?j&T0tP$aMyZr&>*UUrsZ zDvW7uua`2Sk+*e7^IZuls@g-07A?jG=iR5Jrhdhil#hUF=0Zw-?$saab4PQp%p=Fz zMZhUw1=1}lhInx;P$?Zli&J|+PbLp7sr5rzjoYxd&iAn{IDz)rI%8IX_s}CBPjX_1 z8LsRYh^eZ7C3>e8B2lVN)3#3n!3RuQgIOVV-1kIKGZv*~mw8D(6I2fi`%b zO&2ouRlw}}g^=WnwKz}A3jF+AV|3iY7xV^dVcX#)&@*}k*ta!->-Gh3xqS{EvGO@_ zxTgUr$&L~nVI_!lQ3$^NMbYCMGX&+3Z-8W=`zT7O(7P3VPtB!(6Sv@kv9}}$7CeT@xhw^UI2}cbopKoR^ zxEyB!saKwO%Bn;pW>ZEeJ-vo3cmSyi9fm8-9LR1qRnW-a4o!;X5bNnW$otVVqW6F( zay)$n8Szpz1htA#$t(=RTzCl%*-Gr#=Q4s$w`&u9Hj1_9kHgBlRBVD)D9y3Y5vkb* zqx?IE(IE>O>5wK09iN|pQmHWUJiHM;33b3^!8Rykd1vU(-AY_e{q~crX7fUC6ENanmwp_IG)k*yTG-ZPUsb7M%^%gvIw6 zu&IW1Sd(rPysTit*BqQhH?6NEoYY?tyEe_n?X$D6TFEOYIqL&aNa;74OzO13dFixe zXU7OZ(SERtuOiMfMnl!T?TD@TJhtOw93isg9PLP56Y^Zp4Gde(5{XV)NTH*K=v^oW zUyd?>c+xh6>D)nKikfhD$q=UEcnYOcHgvthgNUuGn|Q&NNjTZmW1Un^u1Xgwf7^+8 zBCp{y;lIcPj#7F_iGl>`Q5_=q3#IYX1u;bI*-SW}`w>b$CLu$wAwulXPsjpxpx!BGj*S;VRYOOtsO!Fll$Q8!Ytarv#;20 z7Ekc9eh#a08PTYACT6*sI+weIe)BcjthYxOQ*4OgGtSrnF`RsIE(>Cm;}E}YEPD9) z5_&_0Cby@g7`8Ki#3Y9^k>wo>2|u|El21<)n>T#K8k&+pNnQyRs0k8^)Y*UK?sm!! ztBwS+W8m7mE@GC`0V>9{65GyHP0U$+3#)Odr4_f-fFFl28owus?`PG9+h)0#;;r4V zCw?0yEoz55vI~*p3l0&%b52ltTQP8|zb056Iw%{=63T|zj_K2z;JKP8d0r|J9K7ek zBDFWfa&9{kS&zVWUm?=HB$;3kk90@rbMK-twPCGn~_mPALR$y zOGpl85Luj_AhD_uYk8LgiZ>F`Gd2cHi!lzSd9Dz1Yp%kY@OVO9-W->Br-Nz5-yv?k zk07mwgOU2dlbEkf6}CTM4XSRsM;p{1A!K&$fcF#e$k53S*K(65?l$S8j+_Ky<)LHf z7W;g{Hz5;gWSoS%`Oi^ltu`KAwG5T5IgDuwj1ix8jj(X;J&4(-1Ut25EohjYr+dl` z5~uu*(KF^v64~h&XtFj9SZvP=I=|m8Xi_?lD*NRiV1frXdo+n!wD4G%%gzkr|q?4N$ro_Gk^~cQzJ1134)$R`A%q2utIu;Tz;fQv+ z-v+iNvrw#U32}SlBCtz$LOKB~a9NS^h0d;lY<)wB!V`g9d;}R&F({i_&*HO&gNU`C zBH-lF68Mr|hK;l&((O7pA>(o$CeolrFs`aYG8Zz@9r5clYTL)`p<@_D>^B!hsBHXB6bT8Lhn#AaWfvV zj-H5xoE#EioqEX0fy%AcrAm*iUxWN*SaIdtD6(^rDj|D%8WZx~jAEj4k^bF#lszww zeqr?-kj^qf$5k`X1||aA=ERA!lT73YmCLgxYMdzcSqf6`m2kF<8<_pAxrEMmvVnO- z0zNlz4T?HtPRo;wgWxaxI2Fc#m@kUqd45aLJKl1ve!e*Qh28ANO8I8Dlpwg^gX)6pduHzt^7J_^R zYOyn_ZK&H(2!D{kf|;~!Mh8`G!RTNgk=nrvV=eVav4?@&zKMZwJ6i_1CB0}_y#`oL zyn^UicZlIw0?u2|fn6>a=JToG8pVf@mux%SF)*XKZoQ8-s$E5cnis(7dJOit@-4^_ zXR#dF6DV3k7QK3N2u&|rM&%T3f{!i5NatoP6kd1=LbLXx*Jl@Ci`O_{6CJzY8kGxX zyL1K0s#t{Pd`KjCSoq;u!Aa;FnTI*qiNVn``w<@(0Z$G+1~D%&dUEQ16k41MXSF$~ zIv~xkTqX<;r1Cz#qiU{I%x9ppXD=dLlr|G=)SZN$=Q>n=6m=x@VGXK1Ie|S9%7f?% zDwm9dDZ*2SQSsCfI_B91H_a9x)5{KqkxViq_c<@(B07UzS-TrnYsR6P%HuF-QHT=e z#KHo-)$qc7N!vtS4y+N7gRfFq@L_2o%}&CYRBpQoVN#orI70~>mfw#C9`w+pCASks zQ(v$trIT=FDgiy(6$=}uxX3SZ<#6OpIIb#Xju|}7MDMm1V^1c`ftAimrc!xY*k00* z_u&aFwJ{mprWGNPV}}V}^FVw93r-BV`XK3{MNk!44Uyb_=+V;aG{ycA=(ur%h&@qC zeC9DlrOsJ&BbQQGe}NwRHQ+Z=C0Fq1BNKh+1* za+zrQ9u@ojzS?m6dCPD91FyW)4-BG||A2b_z5hV(oBzP(10TL$JDOzMYl|#CIKk)$ z75DNv9E7P@7uiuxGDKtvI(R?^KGIL4R%UH{#$Ul7;!&bWp__UB9^Whm!SDTD>cM{g zX2!D^*8TX2VRCbE2@eW&^LBAj4+;qMQTGXRb#+tscirR??i%J7rXCUQ;~%CT73vxs z>=7EK9vbHF66&w+u{k&>G~6SU%VpIJugp5d6X+Gf zn6hRL^|y;pn2TqGzrV{SS2w>X*HCvC@1P*R5GI>7Jk)=we};OvMTCZW1crw&r>=nG-_j?QoNss{$D2L!oC_MhmPclm901-J%!`Fpr%{XV{; z-`eE(je2hpZysv~BZ~03zl=o;MS9G4#EW_V*i)?#@n3r?@#mgO{@zn5Z*lJ*$(Q~{ zzIKR=_s=BA{6@mOza~NUClYi*J{vWHDl^o~%z__BaKTUH>xHON%61f#L*ut8<)SgOVQGBZurz+(ur$6cPmSL;ERA0_EREkbEcM_mX2u-9 zZ-dR*EBrb%dAi1@gmA?xMWxJl0+J=)vtM67*El5a+Q6|zLuD`UDSr()NuEd*QUApt z-Ip688W*RQKGc4+>G8ImVrykBCc5uDtPXUrWZb2!Z=1s$bF=!+db?XS<2xJDPZvMBs7}{>% z+=}uT<8`0A`C1)x8FjNf-nBe>4`b<6#m?XYTcN2d9*gz~4%r=v-h%}QcTW`P&l>g> z=g){7H0})Mh)%oCx?M=(+;Kj&)3N&2Zxtt8o;g+FmZf6N3eszQBf|6+7u$cj1a__M z>icC~688F~+w%k$bFF6dof15_Zh89Vb%za0jXAq4w#7YpXB>O~T4TY{70-RPO4YPV z$fO_EnBm)0;Bs#;zOAn{Ro&6v7PW^So>Te3Cvkf*+Q&SP~-aYVGAIww0w@qZ~`u^6wS52&s`}ey#Y!tr!_`uex6C(^Z651Qy zHM_U?o*P*_!~Ur8MgAca`?>y+{aOs_f5ZN7a#SNQP~%tmt?|43{MDQr zS96Y&-x*Dzr11|6;vBiu-)*%Wd>Q#9QY%U!G)3pyMl8gq?byzCZL#C^C(E9zJi=xL z4d<;icUb)}W9NWG#>UW(2lq5TET7EekCE*6@8P{6%&lpoP9IgM%fGqiYi;(5_Nd#e3r#!vm58D3wuT^LsK*c(t?iUPcE&0_kP__ zeshjny@G~CO?Z=hM_SLKb|FV)?Z_J^E6?Ri-r_fAdFh**JO7;J==hT9%z8gKM# zI2jOlobIvwd0WPN)#puDnyN3$UcQf~BdgD zj19MDweT=m?})zBac9;y<{uv}4WyX=`5*Ue#Gv%wF#r1{F86PyfpykJ%T7(9L@g~z z$!B+sSwvL2RzXPL$hIZeG8q|M5!eVwJ#7r`Pj0d^RW3UM{a!?#9o8)~>#%#%8FE#lLR~Xg)!e;1QnTQ)!5jm(CB2{Z=WH(_$CP)|hTqS*l=!%K zKDX2mx_r#0QRa;O{phI7j6_f4H@#La*I3qSuCG0rcXorl;jZ zMqxCEg>;HEt`QuAWo8Xx7om9KQ=%ltgv1zXj&N7L?4*wtv*C(V)a8=7-veL;5b zv=qCNj_+-yx|Zwib6+H;olSA(OU?~1FRViqlXTO;eO~4g8OE_ZSC`D$dR_UVjoVZE zyI+#?S{80lxIK&%&vK;Af7ZC;(dla44Cy*?#d-Q5v0M5)%VpjzXGHw=t}0b3bUXRn zuBo_c;+B2novj^>+Agw|S3WN&nPxFGkC$D4QyoO@s;D%i>OOoGS)@uvh zz4+tQLiT{BkfOn<{-&Oz?I8gZvF2S$GfaxJI^rxzF)8yOnPkX7`;VFQ{aV%gm+bn} z7LKf~SDZ28zY}-xy~yV0$K;Quk8C`%BtBJU?NyfI!T8Fd6WmT~Bk3*zfww=?CaX@Q z5X;|qJ_fy}pspJXG3TFc!ZUL|tbLb9n5GZ)Xs4c?bvcVGAw-S&QCIxlI57h!HmjNz zlP6_m+lIIcl}jaAXA7H+1zu^Vose^BzJJTDF1GTz&+O$gUU34FQgLvgm8m7KK5crQ zM`!riNGBo{rB2Aj}*PeJhutM^|mNN;Dde^u_oVlER zla)<$)!2Qbh>IVbuPP6AsPTwFhV>!!*Jz)^$(0v(68GI323E7~WSn7R;6SQ{JjKRf z>iK(3S)0M|-?H(KBi=WetNULvFd%D%70W_OfBrH*`gZKGrx8X$FD+1gmB;)do3Xr$ zic6=JcWmufiMv#(Jzj5i%@NBQSI6*50ilE2yO8da8Y z^JIkhi6Zs`w;Q?H1m$(!;Btu;e!>*9(tnxbcElMIiq#h;U0#mX{-sSnVo7si^!d> z-oOP7_BSK^7TzW%?ncVVzj|yvoOSmtwlm`u6NBcK(k~BWJ{PjBxVm0*KZ%*0{uuaP zCRW@*)O^8n$Br5m1#Yi-X)YTo0xbp)KC|8DrxVU}#>y_dWcWp(?jaHYekCn@Th# zmYTU02CY*3c#8hKBS)pLC#13SZbgEnkOiAT@`ByI4k-BGQ?UgqCkuie9?MZuXFBij zc*^#Xse$#LU4zFeRWpK(I@ai7*0#g0?%Wwy zsESb!_OBmu-tOVCHFTx4*1JI4o{!~A7d2$@A7X3HSZpAFncc_oM8=12icRDFO(x4I z9(VjBpN$zf|1F{UMJep11b4+`>k+-l6WxdaVIY3(ZQM* zd1@RSLzVvX7I{34J+RZoA~G$o$Xsg0xqeD`&Dy`$qV01}=2hE%Nd|t$(TB#dCCd`z zN)C&U`tYshUVY@yiV6G8+gFWc<&|ZyOO~WS1n2q5>9An?rpNPLp;@uVJ4;0@9wZv{ zM$Jm

nFl!*HrDPk*o7Zl0@lbG}?ry|^~)WCi`QMo{WTx6P+SEn*whrK{20YYNk+ z+g#0r4sm%N%M&6r6@+4=F34_KlyGE|)nV)Cp#iauDL-Be#seHrY!zD8eXdhC-_*iA zIn2dq*?GebPj|Yr$W)|=Zx8+PEAE-4g?*Ye^qE>(&Hp&$e}De}(?Q}NhWz`5_Q(1E z-^-uj&&-nxz8bAJaaP=-^>(=UlW$i6C4t_~NT3^Q-(?df=|laL1d7V~@NXoL!SNXh z^la((66j_8&l2eFUq~SBpCr)Xe~>^nb%tFsw`lj+|3U(N_*DY=uZXzV4hQXyCa)LO zjutPrEPb#Zs}HW)JH5H<>V}$huCL#=!985In-wWO{j&rz{!g{NKP?aKZ_DG~>VMm_ z7gPElf7gd?X&t$|4F?V_U0C5(bzFzje(0z7i|=|T zh3n*oPZUU&msQdjWE%R;Co&miaV*n!)a&b)sGU>mY_m$uwtd4N{2bf13M}jH=yb?8<8&{eF8O8lJ?6P3d+S}>#}>NX`eB`9mzfo0 z9B8_1l3GE>|Bn^)cb1rcyMku8^8E_>&HnNqte@x)M?SI#%-&M;@M7=QpvQ-WU6>dY zFQWjkp>+Yt!jrLxw0!#t! zFE_)-FSB||4Udfp#ru!PNcWzpa39*ca&g42C!B(NwA{8|7XG(p)J`i3Oc1T_2}h zs{isO^`5`0n}?yyrl25yWajE0<}qJJ4gVF;kOK7al=k@@r6e|kC8BRnEB@YgrFW)?yHQUAH8sYNjJ{Jn;z%OL(A zjqUf-UF7dZIm7;9V80Rni7zfKi2~{pj>y2?S8q(sKAXwXs(Il7dEp+$R&lTR0{`pI z<6_;cvHBn9Ze~*te$2XARq>dh<%%_XZagR&FaAWne!}~vyRj}^Wa@wxkBbxU{=|6K z>9J29`p>b^i2O$a=IbvgGD^7VE?NFiy}&1Mop*PIO(WYu*$f|UYZGH$-}1_+>qfS+ z-ks~b^W>RuXWO#1lBIZqt=h7HY^!@F!5&IVN~PMuVeXrf+NAqU7WwE4SD#ZTpWC+Q zwoJ<{dPBK|x?G1KXZ+E*t4ep=+q)(6ro8S^1K)J*1=ktfs)adgBc46ZwP;j+U-2&H zA)9p$&&8ZwWec_PxOqPYG&+uK6kYa$zlG})OV_GotGM86s8`|Q<3qC}t~6RXJ3g{P zy$_363MIHB*+=7Ic~{AbPaLv)Wgk80jNf?Ne7NalH42@KD#>rjyy=pzc57^ds;+Gs z@BZj{97#LMw$iz;7@o^$ti%+(MWJS)Cg zFlZ!zh>vUS|sJnrTlwl#@OFY?eDjVzx`e7+XB40 z&ucZ+m2W|Ge~+F25A2(^gnIcXjAtTxFn7jVJM;WK4U!BRzm0(U zw=mE!k5I~4>=XUX+v(!tZf3mTKN%2BZ39g`9eq7r?S*=}`Z_xLTAB+r7wYS3F4WP{ zG0-#6(Osyw&_GLfhC<=k`+CY0bu*8x730i+{T`{xm=mwfu#WnIdU$94@x$l)xK+)c zK^L5qUjJM8;*X%VRAb+RF8moZbGR$;x5(KaL9;jf2)gKJ(6hp?@BTH`D;pSpz^e5# z==bruKVs!~`4Lq6XVC9MHGc%PrL>9f`>OLZ==ZlYegw^S{SlO6){o5j{=&tNpjWp1 z2&(rp==UDZSwHa9DEbG`nMM5z@E^{!@7-+6e*os%`8)9c#3lMO=I=c`4nJT%6Z5~t z{D+kN6Aj-v8nk|(;dI>J(eNjA_IuCLpAdX!zeYbGAQS#81b^R`@2#*i*LME+bSM35 zRKJ_Yf9}Zl#zDhBnx=jWNcqoO|NCBiZwb@>0gratzsB=};qm95d~bunf531g{lCNT z_r3Yv_+b14u7Zqzjq4u_4nOzp`vde(t2yg`f$#5o`u!pC$DW?Z{{O{1b1?k5r{AA- ze(dS;oc{&BpL_a;82$bvp!x$(CvyK!%s-s0e(uxv>YDBkE!*Y)XD$Cd_1`OTLO *state) this->control.control_state = STATE_POS_GETDOWN; } - state->imu.quaternion[3] = this->unitree_low_state.imu.quaternion[0]; // w - state->imu.quaternion[0] = this->unitree_low_state.imu.quaternion[1]; // x - state->imu.quaternion[1] = this->unitree_low_state.imu.quaternion[2]; // y - state->imu.quaternion[2] = this->unitree_low_state.imu.quaternion[3]; // z + if(this->params.framework == "isaacgym") + { + state->imu.quaternion[3] = this->unitree_low_state.imu.quaternion[0]; // w + state->imu.quaternion[0] = this->unitree_low_state.imu.quaternion[1]; // x + state->imu.quaternion[1] = this->unitree_low_state.imu.quaternion[2]; // y + state->imu.quaternion[2] = this->unitree_low_state.imu.quaternion[3]; // z + } + else if(this->params.framework == "isaacsim") + { + state->imu.quaternion[0] = this->unitree_low_state.imu.quaternion[0]; // w + state->imu.quaternion[1] = this->unitree_low_state.imu.quaternion[1]; // x + state->imu.quaternion[2] = this->unitree_low_state.imu.quaternion[2]; // y + state->imu.quaternion[3] = this->unitree_low_state.imu.quaternion[3]; // z + } + for(int i = 0; i < 3; ++i) { state->imu.gyroscope[i] = this->unitree_low_state.imu.gyroscope[i]; @@ -161,14 +172,15 @@ void RL_Real::RunModel() torch::Tensor RL_Real::ComputeObservation() { - torch::Tensor obs = torch::cat({// this->QuatRotateInverse(this->obs.base_quat, this->obs.lin_vel) * this->params.lin_vel_scale, - this->QuatRotateInverse(this->obs.base_quat, this->obs.ang_vel) * this->params.ang_vel_scale, - this->QuatRotateInverse(this->obs.base_quat, this->obs.gravity_vec), - this->obs.commands * this->params.commands_scale, - (this->obs.dof_pos - this->params.default_dof_pos) * this->params.dof_pos_scale, - this->obs.dof_vel * this->params.dof_vel_scale, - this->obs.actions - },1); + torch::Tensor obs = torch::cat({ + // this->QuatRotateInverse(this->obs.base_quat, this->obs.lin_vel) * this->params.lin_vel_scale, + this->QuatRotateInverse(this->obs.base_quat, this->obs.ang_vel, this->params.framework) * this->params.ang_vel_scale, + this->QuatRotateInverse(this->obs.base_quat, this->obs.gravity_vec, this->params.framework), + this->obs.commands * this->params.commands_scale, + (this->obs.dof_pos - this->params.default_dof_pos) * this->params.dof_pos_scale, + this->obs.dof_vel * this->params.dof_vel_scale, + this->obs.actions + },1); torch::Tensor clamped_obs = torch::clamp(obs, -this->params.clip_obs, this->params.clip_obs); return clamped_obs; } diff --git a/src/rl_sar/src/rl_sim.cpp b/src/rl_sar/src/rl_sim.cpp index 417bcf2..f203ea4 100644 --- a/src/rl_sar/src/rl_sim.cpp +++ b/src/rl_sar/src/rl_sim.cpp @@ -99,10 +99,20 @@ RL_Sim::~RL_Sim() void RL_Sim::GetState(RobotState *state) { - state->imu.quaternion[3] = this->pose.orientation.w; - state->imu.quaternion[0] = this->pose.orientation.x; - state->imu.quaternion[1] = this->pose.orientation.y; - state->imu.quaternion[2] = this->pose.orientation.z; + if(this->params.framework == "isaacgym") + { + state->imu.quaternion[3] = this->pose.orientation.w; + state->imu.quaternion[0] = this->pose.orientation.x; + state->imu.quaternion[1] = this->pose.orientation.y; + state->imu.quaternion[2] = this->pose.orientation.z; + } + else if(this->params.framework == "isaacsim") + { + state->imu.quaternion[0] = this->pose.orientation.w; + state->imu.quaternion[1] = this->pose.orientation.x; + state->imu.quaternion[2] = this->pose.orientation.y; + state->imu.quaternion[3] = this->pose.orientation.z; + } state->imu.gyroscope[0] = this->vel.angular.x; state->imu.gyroscope[1] = this->vel.angular.y; @@ -239,8 +249,8 @@ torch::Tensor RL_Sim::ComputeObservation() torch::Tensor obs = torch::cat({ // this->obs.lin_vel * this->params.lin_vel_scale, // this->obs.ang_vel * this->params.ang_vel_scale, // TODO is QuatRotateInverse necessery? - this->QuatRotateInverse(this->obs.base_quat, this->obs.ang_vel) * this->params.ang_vel_scale, - this->QuatRotateInverse(this->obs.base_quat, this->obs.gravity_vec), + this->QuatRotateInverse(this->obs.base_quat, this->obs.ang_vel, this->params.framework) * this->params.ang_vel_scale, + this->QuatRotateInverse(this->obs.base_quat, this->obs.gravity_vec, this->params.framework), this->obs.commands * this->params.commands_scale, (this->obs.dof_pos - this->params.default_dof_pos) * this->params.dof_pos_scale, this->obs.dof_vel * this->params.dof_vel_scale,