From 0aee19861f927ad89d8cc4cdb04df3603fc879eb Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 4 Feb 2025 17:00:47 -0800 Subject: [PATCH] Jazzy sync 5: Feb 4, 2025 (#4902) * nav2_smac_planner: handle corner case where start and goal are on the same cell (#4793) * nav2_smac_planner: handle corner case where start and goal are on the same cell This case was already properly handled in the smac_planner_2d, but it was still leading to an A* backtrace failure in the smac_planner_hybrid and smac_planner_lattice. Let's harmonize the handling of this case. This commit fixes issue #4792. Signed-off-by: Dylan De Coeyer * nav2_smac_planner: use goal orientation when path is made of one point Signed-off-by: Dylan De Coeyer * nav2_smac_planner: publish raw path also when start and goal are on the same cell Signed-off-by: Dylan De Coeyer * nav2_smac_planner: add corner case to unit tests Add a plan where the start and goal are placed on the same cell. Signed-off-by: Dylan De Coeyer --------- Signed-off-by: Dylan De Coeyer * creating auto-transition option for nav2_util::LifecycleNode (#4804) Signed-off-by: Steve Macenski * Fix trajectory generation bug in docking controller (#4807) * Fix trajectory in docking controller Signed-off-by: Alberto Tudela * Ceil and remove resolution Signed-off-by: Alberto Tudela * Update nav2_docking/opennav_docking/src/controller.cpp Co-authored-by: Steve Macenski Signed-off-by: Alberto Tudela * Update nav2_docking/opennav_docking/src/controller.cpp Co-authored-by: Steve Macenski Signed-off-by: Alberto Tudela --------- Signed-off-by: Alberto Tudela Co-authored-by: Steve Macenski * graceful_controller: implement iterative selection of control points (#4795) * initial pass at iterative Signed-off-by: Michael Ferguson * add v_angular_min_in_place Signed-off-by: Michael Ferguson * add orientation filter, fix remaining TODOs Signed-off-by: Michael Ferguson * try to increase coverage, fixup minor test issues Signed-off-by: Michael Ferguson * address review comments Signed-off-by: Michael Ferguson * review comments * update defaults * rename to in_place_collision_resolution Signed-off-by: Michael Ferguson * revert change in default Signed-off-by: Michael Ferguson --------- Signed-off-by: Michael Ferguson * fix bug in use of v_angular_min_in_place (#4813) Signed-off-by: Michael Ferguson * publish motion target as pose (#4839) Signed-off-by: Michael Ferguson * nav2_behaviors: drive_on_heading: return TIMEOUT error code when exceeding time allowance (#4836) Until now, the NONE error code was returned when exceeding the time allowance. Let's return the more appropriate TIMEOUT error code instead. Signed-off-by: Dylan De Coeyer * fix bug in orientation filtering (#4840) * fix bug in orientation filtering some global planners output all zeros for orientation, however the plan is in the global frame. when transforming to the local frame, the orientation is no longer zero. Instead of comparing to zero, we simply check if all the orientations in the middle of the plan are equal Signed-off-by: Michael Ferguson * account for floating point error Signed-off-by: Michael Ferguson --------- Signed-off-by: Michael Ferguson * Adapt GoalUpdater to update goals as well (#4771) * Add IsStoppedBTNode Signed-off-by: Tony Najjar * add topic name + reformat Signed-off-by: Tony Najjar * fix comment Signed-off-by: Tony Najjar * fix abs Signed-off-by: Tony Najjar * remove log Signed-off-by: Tony Najjar * add getter functions for raw twist Signed-off-by: Tony Najjar * remove unused code Signed-off-by: Tony Najjar * use odomsmoother Signed-off-by: Tony Najjar * fix formatting Signed-off-by: Tony Najjar * update groot Signed-off-by: Tony Najjar * Add test Signed-off-by: Tony Najjar * reset at success Signed-off-by: Tony Najjar * FIX velocity_threshold_ Signed-off-by: Tony Najjar * Fix stopped Node Signed-off-by: Tony Najjar * Add tests to odometry_utils Signed-off-by: Tony Najjar * fix linting Signed-off-by: Tony Najjar * Adapt goalUpdater to modify goals as well Signed-off-by: Tony Najjar * fix formatting Signed-off-by: Tony Najjar * fixes Signed-off-by: Tony Najjar * change name of msg Signed-off-by: Tony Najjar * Make input goals be Goals again for compatibility Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * Revert "fix" This reverts commit 8303cdc141f3d24887f36a36dce073c0ee2f75f6. Signed-off-by: Tony Najjar * refactoring Signed-off-by: Tony Najjar * ament Signed-off-by: Tony Najjar * ignore if no timestamps Signed-off-by: Tony Najjar * facepalm Signed-off-by: Tony Najjar * update groot nodes Signed-off-by: Tony Najjar * Use PoseStampedArray Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * fixes Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * use geometry_msgs Signed-off-by: Tony Najjar * fix import Signed-off-by: Tony Najjar * use geometry_msgs Signed-off-by: Tony Najjar * more fixes Signed-off-by: Tony Najjar * . Signed-off-by: Tony Najjar * revert Signed-off-by: Tony Najjar * . Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * add common_interfaces Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * use PoseStampedArray Signed-off-by: Tony Najjar * reformat Signed-off-by: Tony Najjar * revert Signed-off-by: Tony Najjar * revert Signed-off-by: Tony Najjar * fix warn msg Signed-off-by: Tony Najjar * fix test Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * fix Signed-off-by: Tony Najjar * improve Signed-off-by: Tony Najjar * fix format Signed-off-by: Tony Najjar * change to info Signed-off-by: Tony Najjar --------- Signed-off-by: Tony Najjar * fix simple smoother failing during final approach (#4817) * new test case for end of path approach Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> * modify tests to match the more permissive smoother policy Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> * implement steve's suggestions Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> --------- Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> * Add acc limit consideration to avoid overshooting in RotationShimController (#4864) * Add acc limit consideration to avoid overshoot in RotationShimController Signed-off-by: RBT22 * Add acceleration limit tests to RotationShimController Signed-off-by: RBT22 --------- Signed-off-by: RBT22 * Fix flaky ness of opennav_docking test_docking_server (#4878) (#4879) Call publish() (odom -> base_link tf) at startup to kick things off and spin 10 times(1 second) TF, so that it has a chance to propogate to the docking_server so that it will accept an action request. Previously it was only spinning once, hoping the timer would fire and call publish fast enough for it to propogate to the docking_server so that it is able to accept the first 'dock_robot' action request Signed-off-by: Mike Wake * [BtActionNode] [BtServiceNode] clear between calls (#4887) Signed-off-by: Guillaume Doisy Co-authored-by: Guillaume Doisy * dwb_critics flaky test - lineCost coordinates must be within costmap (#4889) (#4884) There is no protection/checks in the pathway from lineCost to costmap_2d::getIndex(mx, my) for grid coordinates that exceed the of bounds of the allocated costmap. (presumably for speed) This test was triggering an off by one error attempting to read the the 2500 byte costmap at byte 2503 costmap size 50x50. getIndex(3, 50) = my * size_x_ + mx; = 50 * 50 + 3; = 2503 Signed-off-by: Mike Wake * Add option to use open-loop control with Rotation Shim (#4880) * Initial implementation Signed-off-by: RBT22 * replace feedback param with closed_loop Signed-off-by: RBT22 * Reset last_angular_vel_ in activate method Signed-off-by: RBT22 * Add closed_loop parameter to dynamicParametersCallback Signed-off-by: RBT22 * Add tests Signed-off-by: RBT22 * Override reset function Signed-off-by: RBT22 --------- Signed-off-by: RBT22 * Fix unstable test in nav2 util (#4894) * Fix unstable test in nav2 util Signed-off-by: mini-1235 * Fix linting Signed-off-by: mini-1235 * Change 5s to 1s Signed-off-by: mini-1235 --------- Signed-off-by: mini-1235 * Update bt2img syntax and bt pics (#4900) Signed-off-by: Maurice-1235 * bumping to 1.3.5 Signed-off-by: Steve Macenski * Revert "Adapt GoalUpdater to update goals as well (#4771)" This reverts commit 55d738742651e68934582a3ce829913a3950bd09. --------- Signed-off-by: Dylan De Coeyer Signed-off-by: Steve Macenski Signed-off-by: Alberto Tudela Signed-off-by: Michael Ferguson Signed-off-by: Tony Najjar Signed-off-by: rayferric <63957587+rayferric@users.noreply.github.com> Signed-off-by: RBT22 Signed-off-by: Mike Wake Signed-off-by: Guillaume Doisy Signed-off-by: mini-1235 Signed-off-by: Maurice-1235 Co-authored-by: DylanDeCoeyer-Quimesis <102609575+DylanDeCoeyer-Quimesis@users.noreply.github.com> Co-authored-by: Alberto Tudela Co-authored-by: Michael Ferguson Co-authored-by: Tony Najjar Co-authored-by: Ray Ferric <63957587+rayferric@users.noreply.github.com> Co-authored-by: Balint Rozgonyi <43723477+RBT22@users.noreply.github.com> Co-authored-by: ewak Co-authored-by: Guillaume Doisy Co-authored-by: Guillaume Doisy Co-authored-by: mini-1235 <58433591+mini-1235@users.noreply.github.com> --- nav2_amcl/package.xml | 2 +- .../nav2_behavior_tree/bt_action_node.hpp | 4 + .../nav2_behavior_tree/bt_service_node.hpp | 3 + nav2_behavior_tree/package.xml | 2 +- .../plugins/drive_on_heading.hpp | 2 +- nav2_behaviors/package.xml | 2 +- nav2_bringup/package.xml | 2 +- nav2_bt_navigator/doc/parallel_w_recovery.png | Bin 153581 -> 225991 bytes nav2_bt_navigator/package.xml | 2 +- nav2_collision_monitor/package.xml | 2 +- nav2_common/package.xml | 2 +- nav2_constrained_smoother/package.xml | 2 +- nav2_controller/package.xml | 2 +- nav2_core/package.xml | 2 +- nav2_costmap_2d/package.xml | 2 +- nav2_docking/opennav_docking/package.xml | 2 +- .../opennav_docking/src/controller.cpp | 10 +- .../test/test_docking_server.py | 78 +++-- nav2_docking/opennav_docking_bt/package.xml | 2 +- nav2_docking/opennav_docking_core/package.xml | 2 +- nav2_dwb_controller/costmap_queue/package.xml | 2 +- nav2_dwb_controller/dwb_core/package.xml | 2 +- nav2_dwb_controller/dwb_critics/package.xml | 2 +- .../test/obstacle_footprint_test.cpp | 4 +- nav2_dwb_controller/dwb_msgs/package.xml | 2 +- nav2_dwb_controller/dwb_plugins/package.xml | 2 +- .../nav2_dwb_controller/package.xml | 2 +- nav2_dwb_controller/nav_2d_msgs/package.xml | 2 +- nav2_dwb_controller/nav_2d_utils/package.xml | 2 +- .../graceful_controller.hpp | 41 +-- .../parameter_handler.hpp | 9 +- .../nav2_graceful_controller/utils.hpp | 11 - nav2_graceful_controller/package.xml | 2 +- .../src/graceful_controller.cpp | 289 ++++++++++++------ .../src/parameter_handler.cpp | 47 ++- nav2_graceful_controller/src/utils.cpp | 10 - .../test/test_graceful_controller.cpp | 154 +++------- nav2_lifecycle_manager/package.xml | 2 +- nav2_loopback_sim/package.xml | 2 +- nav2_map_server/package.xml | 2 +- nav2_mppi_controller/package.xml | 2 +- nav2_msgs/package.xml | 2 +- nav2_navfn_planner/package.xml | 2 +- nav2_planner/package.xml | 2 +- .../package.xml | 2 +- .../nav2_rotation_shim_controller.hpp | 8 + nav2_rotation_shim_controller/package.xml | 2 +- .../src/nav2_rotation_shim_controller.cpp | 39 ++- .../test/test_shim_controller.cpp | 160 +++++++++- nav2_rviz_plugins/package.xml | 2 +- nav2_simple_commander/package.xml | 2 +- nav2_smac_planner/package.xml | 2 +- nav2_smac_planner/src/smac_planner_2d.cpp | 8 +- nav2_smac_planner/src/smac_planner_hybrid.cpp | 36 ++- .../src/smac_planner_lattice.cpp | 36 ++- nav2_smac_planner/test/test_smac_2d.cpp | 7 + nav2_smac_planner/test/test_smac_hybrid.cpp | 7 + nav2_smac_planner/test/test_smac_lattice.cpp | 7 + .../include/nav2_smoother/simple_smoother.hpp | 3 +- nav2_smoother/package.xml | 2 +- nav2_smoother/src/simple_smoother.cpp | 28 +- nav2_smoother/test/test_simple_smoother.cpp | 21 +- nav2_system_tests/package.xml | 2 +- nav2_theta_star_planner/package.xml | 2 +- .../include/nav2_util/lifecycle_node.hpp | 6 + .../nav2_util/simple_action_server.hpp | 3 + nav2_util/package.xml | 2 +- nav2_util/src/lifecycle_node.cpp | 28 ++ nav2_util/test/test_actions.cpp | 6 + nav2_util/test/test_lifecycle_node.cpp | 45 +++ nav2_velocity_smoother/package.xml | 2 +- nav2_voxel_grid/package.xml | 2 +- nav2_waypoint_follower/package.xml | 2 +- navigation2/package.xml | 2 +- tools/bt2img.py | 10 +- 75 files changed, 817 insertions(+), 389 deletions(-) diff --git a/nav2_amcl/package.xml b/nav2_amcl/package.xml index 2ded6e5136e..1851c84f7b9 100644 --- a/nav2_amcl/package.xml +++ b/nav2_amcl/package.xml @@ -2,7 +2,7 @@ nav2_amcl - 1.3.4 + 1.3.5

amcl is a probabilistic localization system for a robot moving in diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp index 505a7895c51..357903df7dc 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp @@ -194,6 +194,10 @@ class BtActionNode : public BT::ActionNodeBase // reset the flag to send the goal or not, allowing the user the option to set it in on_tick should_send_goal_ = true; + // Clear the input and output messages to make sure we have no leftover from previous calls + goal_ = typename ActionT::Goal(); + result_ = typename rclcpp_action::ClientGoalHandle::WrappedResult(); + // user defined callback, may modify "should_send_goal_". on_tick(); diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp index 746ef610494..a774db43842 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp @@ -138,6 +138,9 @@ class BtServiceNode : public BT::ActionNodeBase // allowing the user the option to set it in on_tick should_send_request_ = true; + // Clear the input request to make sure we have no leftover from previous calls + request_ = std::make_shared(); + // user defined callback, may modify "should_send_request_". on_tick(); diff --git a/nav2_behavior_tree/package.xml b/nav2_behavior_tree/package.xml index 6c152f16c0a..7db46aede36 100644 --- a/nav2_behavior_tree/package.xml +++ b/nav2_behavior_tree/package.xml @@ -2,7 +2,7 @@ nav2_behavior_tree - 1.3.4 + 1.3.5 Nav2 behavior tree wrappers, nodes, and utilities Michael Jeronimo Carlos Orduno diff --git a/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp b/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp index 0b74a044629..133d45e1ec7 100644 --- a/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp +++ b/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp @@ -102,7 +102,7 @@ class DriveOnHeading : public TimedBehavior RCLCPP_WARN( this->logger_, "Exceeded time allowance before reaching the DriveOnHeading goal - Exiting DriveOnHeading"); - return ResultStatus{Status::FAILED, ActionT::Result::NONE}; + return ResultStatus{Status::FAILED, ActionT::Result::TIMEOUT}; } geometry_msgs::msg::PoseStamped current_pose; diff --git a/nav2_behaviors/package.xml b/nav2_behaviors/package.xml index af5c5abe15a..f2dfdae3e43 100644 --- a/nav2_behaviors/package.xml +++ b/nav2_behaviors/package.xml @@ -2,7 +2,7 @@ nav2_behaviors - 1.3.4 + 1.3.5 Nav2 behavior server Carlos Orduno Steve Macenski diff --git a/nav2_bringup/package.xml b/nav2_bringup/package.xml index ae826003a2e..7f61c9c6c0c 100644 --- a/nav2_bringup/package.xml +++ b/nav2_bringup/package.xml @@ -2,7 +2,7 @@ nav2_bringup - 1.3.4 + 1.3.5 Bringup scripts and configurations for the Nav2 stack Michael Jeronimo Steve Macenski diff --git a/nav2_bt_navigator/doc/parallel_w_recovery.png b/nav2_bt_navigator/doc/parallel_w_recovery.png index e67f3f77a53c9764b236877d3fd2953db8e76797..a05c53d86b1253c5b038664df5559833c97eadb8 100644 GIT binary patch literal 225991 zcmd432UJt(+b@b^VNih?>i_~4iim(xrK_kAx>P9v9h%f25F#ajWngR|2@q)sO79Yy zbQA{+y@wu<5_+!*ko)f7`2Wtj=d5+Ub=ST3WLPuFWar&)d7j_%d)j`XudB{}nENmb z3ky3;>@uvB8{EQ%Eq zxvg=Dz}|kl&Ll1=d)wOATorI=sVpol51?OE8y0zt*OzZKA?D{Ko!TkeO_X0b_Cen- z7BJuF^P!*qL8`d=bPg zaP7dq7s+V2|N8HHr?=^fE1q%bB?_K~d)-x`wS`T@IOj~=bCD__9?E9zfZsxex-vtJpQfKv zNt?Dr4I)c6zrXT3!L5m@t*w3i$JO)uSvh7OxuS-A98?ycaN4$gxZPWdbUr0!9+8<_ zsbIZTZ%Rbd*R$YdvJ_f(@$!34bXuJ!b5pDHqeG#CW$P$LP|BCyAR6DEQzN?e7x~jV z2+f=Ui_gSc-~|uwx|L3)2#`drmR`nrwZoLH99k1@luIj zke(hqviw5N|GWd<$9`x9zaaoq*&gAf_BrP&r}!{MWw=+f4oKqgbEk(7zd5GHN10a9 zy0(_W0^|O9bsFU}#GqL-L_H@OVHlg~Gpj~T@2+0RcW6+KI6 zJ$PlmU77Qb(6*X4H*kIt-*VhN!YuLB=8KZ$p^5pfo{*|uW02%)6Vb+y@Bm%A~qUL9% z)ls9&!*xH;RF8`9CvzX)ZkDIU`H%8YzLg?p6yBhhURgIaK;L!7f9=X)t|CKpl2+k9Gc^lHiw_VFbFV8w6dSK$`(m)f~v~! zQCZIm8{ep6pog}aQ4_}rn_sVzcbgCaQeXp{DLaFdamwx-WtkkfL*ANHSB(LZCHLyI zM6@``k6=^y4l<+J8NF>zld?rowMy;)wO;7i^vP z!caV6cQw_gzkkU4>r5rUg$bElADug|{|Gm&m^O}AKH&+2g z@Mw}D3&1W#Y6fi9@J|HuxP24ESz;E@3x0K$8*%cU%j?BeJEVmTN?_or%lF!CTUkFyp%L+|2=y-A-6Y`wMCrvHG!veQQx2S=; zRR8T!{+5Ir&z1{w(PE}>q%m!M&hP6?!0rmcp|8LZhVh#(5suUp6cZEE3*|g>ZSkXX zOl&MRsbk#%lH>VG`h2R9A7gh1D*&AUR=_Yto77k6?Af6sXV;x&rq^8NNo|e;3fNoW zhbsQ}%$Xook@EiiIi^%pZd6E+;VAg-OyExL7A|lLH{d&ytzI$z;gxtjG}mo#CiTu% zD=~2%^&(~!zH8XgwY3mA)4Az;o}Qk4eSLU?Ik;N;e91hO`==7JuMi7;Md**IU01d$P-`=EiEH6zT6Dp|<7V{1|AAq2Vr7+mTzWn}fDk3VY`#=f!mqbs87Q8jHG@X>9FH`e01)B)^DJc= z!7bbnr@_7`$+`A?JjYnoV?=C}QVZiVq|<6bPAy@Q9ZSyLfLwE8Mo5g5+EBZ>sk*)7$abqs@wGS#qoTvsdoRJ8S55E z2cxAN?58`^x4?x_kU4mIMEsku>K17LMM3v|e4wVQI9Jd}P*o++2dG5kO!w?ig(4)D zZ{&vFF?OmLs3MnMNLTGA8lxTE+;lPi^nMBx1nj_k%<}%c-PhkQ<+D5{T&zzY;S7A& z61cn4Ti|GDl65a!#4yFS@!eGz23NH`ZdT}I45Bz403_)Be@PSm+dM>O-5ZEhwI>DA zM{u51#SLj({l$odxns<&e9ZS7M1Sx_oajll3i#f-++R-v^h_>(1unVPHqjg(yAa5r zD+n@`RzH85N$8kAXBqx_{Qm^{^xxi>|KkYYe_cVs4=Ic;dQcObbuaHjM_!>b*}es@ z94&{iN*#U1%Gu225clYO!+z)#f~@YErW;+VfCKJYEj9IomG4^#72luesk*xqMg_{$ zDP{RP^SD-3AnuwV6c<37G9%i;imA%mi#75yS^2uxZ!@oGE!#WYpyLmkx~CvAYLK+2v6))=*a3qPdTj`3nWblwjPS?v%->JKi!OmlIn@FZf(_yGy$Iit zNz2I**NVDKN>9c29f@QLQT2<|Q81#u6hIFwK=GPTa#z=Q`AYL~Zl(w(q%aAM%%~W` zM+*=q4#lC?*0=JW6RS6W%+n8I+d(l`-3C52;*}NG*5VnLI@{X9MRPuVz-2H82^u;F z(fLj$O9kvsF8~23A;bl)+SIQ8Y0R9k`*)@&$c(=MbmswY2*iP{GWNU@-!O;)>Kg{L z^F)!$CuAI5T(mKrWHOZ<@mNj5^dNHpVLbC9&z$n*`hw!(RA7z)HFOL<%GKV#r!m!R z!pwQZHAqw`>FDSZpoqcb^lMT{Wy}{XD?@DwIAh0W%tb22{__?~ynQc!JwH4{BL*mIo zWFofmXg87^Pei>y)7lk63OT46M zzj{l*A|Yy(MEZ*Lb>=o+0Y9=nYR|g6!l$tRjamHo0}%U!+1A4IOJ1ac@+lt zpb-Snhm_Wk3g%c|XUyFWyh#ajo~p_vEa>{G5r74IFDyYHzB)lsr;Ss5iRr3lpuGqBBbST;d zZdE$fDHk=@oKpE-VRtiI@SD^_f1=}E1G0W?ajs_6z&$7V4c@NbI!alwTNE8}+T-@X zo;K%up4P1_F`P)tvF)!vmJuy4>^O^aF}JL+Z){BR@xp}8 zJO2@A)h?a%JW94v;z7dh1x$yv=@*Ti;D|NOKTvLxV`I}B%Ki27FiBctQcDnVXrDz? zhmNl#WR@2;GO@xtQx0EyS$X9t-N-zBi@f zmC(?)CYY3f?4 zO=*8meG$^IL94Z0B$1ktUC5bf%!5=Mi#|%mt03}Yd-YWqy^^?lkpD7oh=J)Z@~jA* zZq$8ATZ6*>)|7)?*Y(ggZ0D7iG^TbtDvMpHCX}8PdhZogGhZ9F2fWuDHfoa)o|2FM zY{82%=e`=j^et?Nk8ZR}7d&^u*ltb5;K#M;JWfbDHcDZN3R?U zUx>V7va_3`6RAnup?osSZTAmv1KMs)MjtEM_h3Og@dd7>r#a-_$_$qmveS*tb#jdo3#`^;X@TA{PX;nm z>o>>YPxHy7dfEExm~d(KOuhxhw8jz# z=UxSufg^qU!%HA@UQ@`*h_|13nag8&gsgo{wRi2-)Pc^x z$MW4+dT(B-3%ncQ&V}fWa52A!pZj)tbsNt-`Gi!aCFis7)bruLmgAeH=P5Z`KvXuR z4|%w39?=}O`)4j$OAj;Ki@D6uX)ns{yZUfPt;=WKMaN`E1t!P^EW;#rR{3G<$GU*K zH)R~GyGl}2=*7F{yZyH94H$@`2`e*y^!c!pgIym&6Ts3JKB$r-^N5^qqXJTs5SH|12iyCHDQ!>B&@ALgH- zvXn3CLI1$N>djSmdnV^t&XnqhnI%m>w%#+2N|Eg+C#$2Z;qtBHY40h9nIjK@Q6h)N zBVEXI{o&Fa7tejrEiEC07I~f@)K8TKqCL z_Baje4~Gmd2DU0{D9*(?J_|jZ{#P(_Ny8;Kp?F}>PSIs8lOeOBKVr9E4(03-JiHk* zP)&amZ)U~3SpSHN@!nV9+ER@*tqrSBt6fyp6vxeMY3^~To|l2KK6A?lr+11%UsfM?{$diI(=)!Vm}K< zw#?BnA(i0;g+_I;!2)k~!WgBaEu!(k%{zgii~+j0ASc73y>g=`SGnE9HnAluz>0C7 zOl6)>wP!qJDH4J^H(>U=J{}uXELu@B6|d^A7>#tDD(#4jpTQKa)R(;3!G;@Ru1YoZ z00R&u*5w%z7xy{_?-GzzK0S@OF`5bYo94lgax?IZuNO$i11}Qj9GWyvQ36;KR(vvG zXOIU=XH+HG8E)PZ+3Sme&Y9%iz zqfB#fM?GS0nB#dN#nk3`6yMj4Vc=LdBSn#x?5bK`2F=aj@+2WIK!JtFkmT( ztF<{Ta5Tb$Oszjv)E5;t(?u$VRn!TuPvi+=wky*jOd3=j@hvoo%>XK)Dt$FD6MFI+;F;8=0`yRIy zWlN12o0o{t)f(*mltA-oH0x>^Z0aS-mr%6?rKLx8NEwP)zsk3>=GL{SEZF?6B`}H} z6Bby2JAMp#vyJO51P2>NBDqak+Hulw;-0q_;FW-y3py|8MePW2DPJ%{n{rt^vXK0f z!JU{QXc0AQt@aQI4dk#w-r#k1ZeLBwarUkSEriHmAV=YBR8qUuFM@A&FcVkDH)H%7 z{0I~6`-EW%eb{W#^*}c*Zko`A)To6Wb#FYXrQ2!KVXUBieBydgvYqGh(+03uz*Z9; zb@|j0OmE&nu92P+qVBh)Il`tfzZ*6Th%Q{)RuPS~9p%?bO$e!q%nD39;GV)rwe5U8 z?K9X^vgnXZZ~I#WrdH+QnvBT`e9YL?Yv^`Lw2yFY2WoEsn+VK({=}E2RF;{zkl@sm zxd0QV-Se0Z)X-&MlPGV2acZ~+*tMP6+JH(^mkjfmAMZl(lpt8IgHr0OrA3Y&CcB~RQv$H2CQp@FZ>j*H(Y{ti^_=gIc6n!A$vMF9 zt}u!ubu!+?c|DloD6n&sACk6ZDD5=(srwOqU|R!&E3>2u-tF?bcnbxd_}#wcSmE)C z2aFXfq{CX@e%?^#GSb)~VAZclv9u~(7l8E-*^aEm*9pVp$`|1fX)e!=npcHQeek?a z*d={hsiy+q@+*#HX?m9*Rz9DA)qE!?a^qc+*LRraq?mcj&z?K0YbufZr)N@K~)TRKAxY0gKcCplmX5x2VB<+O!grXzh2F4MHVm?xe9(WHc6udeh|U}9!k6j`k~;^@OwQF9Ho zRcT&@@|cM>(%+{eT4wmu-CiK2n`{91VcVoI@EMGhxQ^BGXWQW(8%xHpYwJ42x}){j zP0b98Fy4=IONl3padBG{NiDk{oBHTjB)_UPgdQ-->_zhWFq5E@1B(X0C-s_pUfIasF`t6h;W*&O`b2E@vjrE#}=A#ZDpS z{j*$AQ>9pe%mwjyL{audO8mx1bv@maKRe^SX!srDJb|(rS}!L%VISn4LvVl2?!XZv&2q?Cvg< zzU1i3>A1k{yGR~lVpDIcocz{z$)Qq3pG^x=u)5Yohe0&}SB{L$9O3n<1&X&zb(-z$ zxzF*5$}RKrbHkL)YBX|u3>UQle6kU2nE#&R-J-`1GBEM|{kMU58yAah2bj3{u6}CX z`pS>_M^(=oaWS{@8Fn|sg)Zan(#xHhC&DF}ci_Rgo0fNu$a@^{ENbH-m9AEK?dO($ z?;_(}9rU|kfoH9=mTBC6SusuEb~sXSNf@I(O}TjWz;^{Mx&WhHA`7?4qQW9rxOD9w%-)@TSx6*5E@puek9o` zev;XUbf{QfKh`HtoeM$Oc_&e$&+H7XyTJJ9c0S%Pw%hFT@{Y5pO~R|)3-yFIkElX5 zx-(ORl+=moBUF`qrb2;82cVNVvXG1C+aMg^ecR1?^_i7fnSn_Bi}iw^-&ps8TPDUJ2{ixzHkgFdq} zsFNTUuCmiG^LW~=xi*Ek(;wcsF*T4qrBUjK*Bc))N8ucl<_BztKeca7Msw^%j}~W{ z#RPHgWpaYfR6&PwaW1s|+GD^Ak*1RCuZJ?{w%lqG?Pflq6|wJA1#BGFydmLYVOc%J zbmO1%ToaO?aTOFOurZ!GWkl95(u`gFVEbjO0zR@r{+3R93nO*cVMiPyT9`lU6k^79 zO^?~gn)|3V$}4@1t(3r%!rcwrs5f&tz)zDLHwq8^=F!T6f<1EilpAl+(1FA{d1 zhnb_+yanU4%cUHhVY-2?L;&eywWC#cX66&a#Tq!OR<0}z;e|sKhOAj6vQ$gMQRrE==S52M(?RfMLMy*?~Y1J%vR`ZGYLf+ znC^T6I#?y@SIn={o!+fRox5Y9)n2)Q7`sV~zisDsNM8s-SnFtDh-_>4u?JOk?+~K3OUhkPYdsQ}@D7a1ehiXRz^_;^ zKSu{>IEbap-iy`V2_wNI(sO$IFd&9X^l@yLz81Yjz6c$T{*MSLyx5qCT?>p=Ux7^1$!5FE4R9QsjDD-XvW>G{Cg< zT*WXku?3Z+pkQ8><2Q#U%{Rg99e6@;qM_zzLv=-J; z!vI!pj1rch&x|egW8$5|EH~ceH!Ktk*MZnfauf&!?ynQ95#ry$Gwo4=D8xe+&yXFi z6J6~*)+0$%xjOSSORzbQ93|%mh}p);iE)Zf=EMp7w275Xv-n6t{7n5C);e5iF;_6o zqq`roqWbo7g}m8rZ1d;$bD5avK&z(`Vg7O;04(XL%a*T1dp35PA(*~^J<3f`+RPQ~ z0TCu*_ki%HuVpRZ z79knsr5TBi?j95*oQ!TiNGc7{yhbfB#mRRMk+*0gse)p$TJ9I+X`Yi0#U3P{u1JmZ zOVDaddR3NNQBkNw2lgL7XE#r;GI$C<-n_8u%aqS+%$TuKos6uYny?@`reWj8X#M&< z)-$E?UGFJ8bX<-qYYx9;o=c64yXBV32*G2r zD(O=P)0x|qro)sNB~w$>Sf7)_$9kEDmWJP3fYHA{!d>&m@Nq9lx3Y_v@{bDNjS!xul>PKl8))`I)%aIRye z9Yu05IGZE;A7-Iz{8lPQexw_+rpr`;PySeT=Ao8CAE(M&BMus%vQq=ti0mA1SB<_6 zJ}+N&>ixUP?YBeTYf?Y9eJ03>YYV~SI^~4a^u+c>9aI%}E^^W3qZ>=!_d?=ByYZC% z>O4E1!Z$}U>WXr8YYC=viydtyL;az|Ch`N0^u)4K9$M5{eLv^+(##opT7hX`NMaM2 zC~x-2Z|W!#CHlYATrdsp^3L2`wt9qe{@srfx|+ zzB#p<|GoLxZ`>XpQ*Irt5@x=h%U>@D4s^7|%-*w5ST6urGZa4CZ=6FZ&iALR-C~=S zUKKru<8{WW>;Q$p&6o~Y4UwBgJ@HF@$HvkT+QHh|AVrb&Dcj|}%+d$j)=db|j8Tzu zpANkdjrZ{VvuCV5+5!08{V$X3Y$Vs%K^+Tl%SVfaEO59hMvMpJ_^^~rg-{ce!A)30 zU@Qou3`Uv^4sOw+bih?0>>&i)_mWU)3h;x0JLtPHchMpy-WSF}k(&QCm=Fbmm!%x8 z*3q+rQE|I{HO24zib`l-Ks=Bc5@rcW%QOn53V~Cs?pS+4fQR>=-WmSX+*?}a#Wvk< z`HO^(TKi~%rl~@o*1Z(U+xCN0{m9T`E{;G-*3NK>#cG}=jLKM>g86|HX{AoJm^$ha zRaYZQ+kc-OVm;TNGTpf>3LukaP^ZS(N z>`spA-Ddn=hpNmulRa<4&d%#tSsD!7qi=aFsE<_5`xkrp6Z$F?LH2QS*On>%x_|7k z2(JPmizq%YMxIMUSHI`-sw+GSDg}fpy+lF9pJl+-I8=Xyz=5>_Pj6)}ZJZ!$e2G*E zR}Uzh3-E3vb;!9}E+4I!%ABil4`m9De1GXlqS^7XO* z^U$Na<>2PXvS|w_h}+)XsA^%C8+aRwsFVlAL0X`0NW5eWQ@*>F+cIOdQL6p!%6nWU zb4Gg}=;GxI*S@Z_JsEC&50&x6x|NE^QT#mvKvA46;PcTcXkRN(k3%Ikh&TLo+Ugz6 zx50uXqJG1uMYuzzoLL15mRa>r5>k0)`^S4=Y7k zUY(FX)o%jWxJeb6EDXX|Pi(NkmBKlp4w?7^AsmIEddD(wXRTx;n8#x#yEp}uB<9;U z)!X6VQRJ%KHTjJJPeW7FjiW|Po}|yS>cKH(CW{-~0M%Q!@gkkG$5>Ha+JG+EyS}qdQb@f2_ zv60q73c5=IA;~#&h@LS*WBh&!egoSEwy5v6StJ*L=zf zxxQVQ%Ts!R3P(UZDzH2Xsk%Z|*!xBTAigwWYtM8H)$ za`2xYtO)~~#Ku17`@zBU%tr({+}YLH$M;53PWRj@b@JCLdj4%R8f~@t<@7`%|IR~D zHb=38_Hr3l6$i>Z#upg73sT7G&N%NrM`k$}B;@pUm@88ry?#_4;_-^RDqMcL22&c{ zszzU~Qma%!RQ|OD!&SaJHIVo{bS$e_P)$#y-$8l(mF-voNFLe_?zb!ZXhs(DD-sZO z)AP>KN!hJCwhqI9)N~|DX#X7{kh^{z9j#q{#b>+7mfClLd~ITusB56W*+g3z8w%9q z+j0X`2UA*;D{nC9Jg;?X_cE8Xxco{stfSSIo-xKr(M_?w+Z;HHBZYR6v=|oAnRZ&l zrWgg6*~sDQ!yK%K1M;FMfF$L`ZW8H%tLNDy26du0FoGwi%AMG5F<< z7UI$%PF7qySVvc=iuii2KT>Hu5PRcz{X!Q=GLAOcSrpCV8$KF>U{NV+y%dk9H_;gl zBBGMJw@Ia}4YZEji&g!hGNfmW7;T0g>2DGB9UGsUZ-8ik%3l(w0d4Q@j)Kba?0LL3U+$5)q(5~Fg>`u?m@xd zB&WWEa31D~jb^og$hq*!{a6r%esNmhbig$(1$nc@QDCZoCo6!pjs!_8`Km-QpH)^; zr>dB9Jnf}z+gh?HpmAD3;~Kg9-@o5~NbmB42w^^0)PUEfGH>?$5>?Q~AxdAjqtzpe zGHg2_FL*}E-Ni?>XW1I(-jv2ga?BO^{0{4YYi(`oR+xHvjK~#m2jos+YLpAA&z`xO zVJ`1Q%10zLn*C7tqw2hK^4p&}f{A}8bR)(X{u zgc00obWp(x_)zFWxEIHTCqQXWLmj9e-Uh0wrLL|nVG4XE;Knh_cz{xZfQf?0R7YHA z7cNwawP;{kD&c@O?Wji4WidFC!$mz3WC{91Ixer}}f9E@+eO%!IV`RK*2w8c4;Mjd8=imqNdDD%ry^zBkKhv;LxPoD$qAGKr zxo+FARSO6jbx0R<4qyv8ybB!MKL$LjUl}MoC%={4byg4M>C#8(eb~A?f9pbufCQue z*mQ4RN}S?k(zN9TtB+OB+C%3FTBt%f>BueajViKCgswWz=_tAes8ld2(^EEOf~P-K z(Q{{w>;R0`7AP@}d?j9bk+Qp9yaLJ_r9nY#Q|!=cia)4*Y%FqxZ{J{Au*ZBq*sogA zR>p#1Y4e%c>!vX`j$@2MA3IJ@b20+%=R{=->PtQHW~%`?MUQo3JFQ%0i_Co=a;&n; zO2v0pwV)J;dZlS8^~|&elJgAqD8aIbKhrBByN<)_pQ&k;JGv74-X#sFS!hYxo3wN* z^t9nWe?IhD7euISzrjfSyA>dUEm?J-eis4>4A zf=?GJ4!v3MZ7wYx%M!(=oFiSJ$QP9gH|ur}5wiRi7qeSAK%H+=o;7jIG`Xzp6$Q6C zMOi8IT|UZDR!k$#k%zKLA9#Fa)vG=W4&-q8v zHI`CJbKyD$U5CPJUs=1ya z$rqGyZh=*rY{z(=KrL0_Sgq}BR!tp20;{$&1SN_;jM%RAdl|pR|Y;NOc(t{X?dv=w!XQ2TUGQ)m!ItNrb~MD8_)}job*i5_vxR7 z0k{}boj`Oszyd@Q`NNNL<6Pbml-3(;w-A_QIpHuy(Q}VGx;ivYRhqf07-^Xjb)~f@ zT0P*91x~mD0W&X(a6a_od0fqjnZ~ zDd)zAf_21O-2aQSGH!OpJ&6iv$ITDEstM}=_bLSr(=(M!FgmnB|*fXU)E~juR#n2)S zAKmBcq%~J?I6id0cgjoNNI&D}K^G6Sf`IF7!2`cOc|J?`z)|=K0&;9-Zar={@nN1G z82X^f!otQ-qIE^?0^M_0(b_&BAb?xJD-BelW`jnRNk0l5UmM1s3)tT@XfQ~GX!XOn zzQTGE>F)je3BjEF;(>vI);M-Zx4}!<{!y8QDjDLZ)#QMpfcHh{t%=*p_BPoLPT~&F zKsu;$Ks-I=+jBqhv1`1KI-`R$^XI3%W#1*dw!UwAP|LbP;!Vs2l3l2owfISUtw*M? zC6U3fahHf~i#Lz1=G-u?bC=h7Gq+!<$?28OMnZG#{B&uY-kf}N`!Jg;C@t))4J?)1 z?a0r`(FG;YruOzJ-MQAeY9SmV;^Ml+10Jv1J30#QfBuD?OY$q(ZqK7*2{L7tqOw#p zCjZKT{5ltLc_#s;x$D+(<6-@%D~`Y4<;#@^OO@%F#h!}EG)+mutq@aZl`h#J@{lRI~UvrIBmw4={!%|z)lw+5KPS9=whzR^|l0e4wf zP*&|%4|_DMO}rvFt)oXHB|Uotc^k+tb&aRjtmh4k9pi)FyfD;woN(!-Q{;M6Ua9@z z_y-F4o;#+#3{_Rb*!_V*SK~O*_1dlAOdS_GvEIC!TKN5*V0JA$9Eh_Y^?H&4O zOS|h5`bI`c;5&WUSRL?ZXJ@CWscGQrTPi6jDUF)9{NnOsL&Xmnq+>PNRh1?8o$ z$2B!HTAgz%Qb<@~dZ|DH#X}*!uPU(0MK*TUyKH@aFtfE)AGCw1adC0cCgiHpAJpW` ziX8Z{8><|U`@j+;de6)(x{|T8FasJAURBZu7p8&tRrux07k~JvAQKNy&%#HeckJx# zooa&FGqSRbJUobCnLx5+{MKC#9yqXBs{Lbvre~QGtUl>9TKmR#EL{D>Z@(p&TBD5t za4sQXETwlXEHbmQE`!0Q=ZY!a;TP1U?^m-7`mZ$AfBW{f%gNZqB`ddKuLy?4{jamk zsF~#hCuiqE|1A&D{HImAG32)f+FeA&#hb}?`>t`y%gc)y#-O*C>cHw_q#X^k{(cC~ zlz8uQrTAW<0n2s%+mI1v`SjGEHkE2#@G$)Fkt1uMF-{j^ENJ+#pjSzyrREkzF5!c2 zxIs75fPl(FoP1d&p457$LZ{vBt(UJ~uOg#=tdjQIk5yKWxKDz}(b@ZdoaF)^K~si{)nV9K}+T(idQRiCmX z;4Uy%y7~yL#=QJ-9&~n4qnIyf1R0}JsWU_t%R3G&_^$433uw529p6YCPE>eoxx%={Gu}f3ADFD|4;WP)|f&-prYt)76t_gNC1C;r9fRQsS8k!~{&R z(4mFzuaFRDP#;e;&n_JeRh-oLQ8RS?*q+MhUAlO&bu>&h2ec$jPNfpMt9ECq+I0?G z4+-T}OaaY7B>Q|3DJerxl&-0(8wE}hKmy!S zyec0)e7M=7wDQ^{+dTR9t5Z{;nXlsf`SXzIs$3QpRtLj*m%;hbtKpX7I3b;wq}Q*H znq`|Lr=-wIZ~Zt>+;4k}uXHgz0-J%9cXv<*P(grf$NfmYCds?_Pf_W(qT_nQ0lSEs}bbag|m z9*-OpGb4T_3+|gt1)^N|pym(&BlO~D){L|?eSljH5%wUGVxX`8_NO+rs_pHVRqeRP zR5H%0ooLq(5fhUk)&k(slMG-Ejn^SE{fbm`%MSO5&+;8RLlTy$@WmQpv#GzNcc zY-~SuD(LhNBk~RSlxv{5%&{(%7qsmLBsmb!CcC@4mEuQO6e6+M4$0(RARwJRJ!t@@ zM3t4{0F7egJyR~9di9^l?b|~(i9CR8U}?8rym(<==AA91ho7Cnuq3EEIXM-8odS5f z0~+E8%gf6r`1x~zX9f<*37o{s(9rdt3L3L_3jVXRz4_)u+ZRJVRNkFoR@GJja9Rgh zS?Q&hSw7wG?d=6-qrS1R6DZZVcbN>D<^@ScYO1J=Ocz=3hqc_{W(r4jh|1>her4KZ z;^Cu5J3*IlMsL0Y09}?(0xw^^Dzs}j1?C10Au=lJ(w`lY|KmLG!YL-+C74D%@4$RM|`b%EUr|)RmRr|7_VHq_Js4q5%vB+r!u{ zK=G5RtFQk=AInF3M~Qn;GtvsWszjCPv-vSn4xs>mR7I{{Z38%aJ=eh0G<6Onz<`ni zcOaC5UnT3)r)z^A4PuZM0R5D<{r1~`#{B)qn4jOPg%mt&JI|~1SYH*i6|aq9_3Ho3 z+XP22x#r>FVV)vQ-y97a_fn8?Y)^`Ey9HYEMha%PL8@o37J!htr=`_CdjMj2)2-M7 zbcJ^t>M18jM4ZTmmze|!zaSlp?^$8tRABDHRCn*`rW#^}be!0J*NK+A zed^UeKUD*FU=PaobA%)|I64E&2TkpQJBuNzot^21h2C@Kf`WqZ+Qa);PFo<6g`nm0 z{NCY$=1S+WZ{aa=2t34W0(bpy-?{S>hKD~e8?RUjJXa_0DzEq0fF@|{FZ=hmm=R)Q zGeK9F1|fi!4jMtx^10{!pHvIZP=cZ7fU258*u1Q-ppMS$P< zFw3X7X1sDH==`<@W{yYB&B({61cSiOK>=e=V`O8Uo-`k<$+4YXvfJ>%cL4*FOnm?8;+%__rQ3Wb2e0DOaZAZXh= z%*jaxY6A{2GCce}(D9#Jm0+=V8zC^6PSDHR<^O7SVIdb>;xt|#NuyUW`~VZ0s$$Tq zkf0lU>yrV?b%e)k&sEpH0vNE?pvTt$jjjMJ+T!LdfPnWkwf5$}s>vLfC0gVm_|n+G z;5@FOi#Px@QXHohrb0`DI&CjXO16g>|H9&178Aog*OR9P(TR$+C|$f#`sU_ih@}DZ zWB&2}lRy9b^XJx_Wp**KoGtFpR-FH&2F}aL#bwr=2cReTJSu5=h-GpHfR$~2uWfPv zTAMmQY23q+wmJnA4WOT?lT${n)*jSfSG~jJnma?UBr4N@G^FUHzV8OM4&2XcbMXOi zPbMWzSy?_AL_|b91da-1fWV$3CmOjxG}pX%$QPp4$bQ#ik@M%j{43ZA{7eB13YY`K z>H}+-8Xp{U@X#TMoB~p^W0!H1#a$3$byb0ZT5?PaA|P-JJo>;0vLJwhy!qqm&(Vet ztM5(H1n7W}_Pd1R!n)r^+`US&fjmGugI+UMUTsywrQc+^9(ecOy)%b+{)%;-*C%JFP}QhGHH5-BLsL?f?&7TX2>(3(-~OQ4zc2a4?s_VMHUng_~~L; z?qk}O1Z&@wCb>fQkuS0h+dDhJdXIaQc!8%ROyd3K?*i8eG+QSpB%FmbWO4zVTtsxV z2!L=PUFmswcOjSchkxZcp>1~g)W0Yhq_Ri1Xz>FBmT z4U=8aXh99%@9*mFAU9rBitpF|yyOu{$Zkt>9zA*D*zk;p_$!1iT9c%PSVVHM1Ze?# zeGl?+n(VQ_$8mH_|A7;Vs2qSx=znp-_jl+Bhl!h$-*{+p{b(@qByRT~TB#d1UCbJ{ zkLA>AkkC9M^^yb*HW2@j91X`IU+3nzI0RDR+SQZxX<4mCh8@HpO zq476RueI%!7D&((d{@&T?+t+RG^^_76VMl%l5Uvl^v}zaefbVy@5c9vC5P+x97rg3 zprxtV-kz*g=-43?84)p=T|8s}tqPcD@WV^z&fNgd2k8b6DlxiycVuQSQODx``@zk< zA}zoZI7UWB0B(RkOw!LN!eAg{=kVdf2EZ8t(}O}bZ}?S*>Q3%$!SKyis2mD<@oK_g zZGgHLpy}QxPn>uN2nG}dSZPts9UHTSBfE@!zrPR$KxJfYz3}h-e{g^B^VV$0sT%q6 z7Zme&`SN9fYrm|RVC!#H*WRss;a8? z_V$RVC?S}F_v|}x1WAA~DDSLxKsSzvi@OX40E!Di?Y@26h>Oe-f`)3pdzTGXiUU>+ zYH}2ogLj*}3AqiQE;?x?Rqcdy>WjT8Q9Jx=q-L0=Lw@q}^!A>Ec-Iwg*zJ&H7$=Nq zS`%>~t!*-eC;=Yg1^2TI4GXDCi zc}msujC%G7g=%`<2laQ9x}tY0%PVrZYJVnGUs(ukE3KWrDK!{<*#I7WqEA{2W|KYU zt#Ko}QrN3Zdn0M$Y8h`TD|N_ip1k{KzdXQq^9PU{s;sQ4JiaclpRoiVS4MF zxMUetr`D1kuo-lRLwgCJCiJ?_w^1knAFo|FtSesl^H!f zlR|jsy6hc2)hHmc#wLPDWotLWV}w*(QdFG1?FnqZ+!oSE-GII6Y9FhMsZ~9{#j1HV zv1ul>ww@x!yHoufVZU>)o)PQig*7t0G`JXXB7Au8-pI2iX_u|CKrYujvDkc#vJMu^p z*Dp1N*A9;FfP_uZs~W(U($mv{Dd_?zV)P%=4jzY85+z}sla!PcCDOEKKNH--K-y!$ z2}HpAD$!-YPfqRZG|F{8yvk{kn7?~dmsyy>lAyP=f`p=q=og7YUZ<9iTzL>*4sZXA z6xx*he#fz0Ev3IH!8!Tw8wN%nPIRs&&_7NYxED;h8-@$NsW6OLhIjZ(b_(OK>Y~p_ zo{{MYW&cC;_R(;sm&!A*IJ6#--*G2})^RHs9}bm8CSH zoxL&jirhE9&~$Yf!i%JC zo7iMbZqf|j+hZy3Hr`98I*--#0~|3)@peWX=!O1{Y9=FU;a7*T(xBI6f@&T zj~)TkHZOFFTwYmGR0{5&ivqS(AYRGG0Jsn2BNF9j0VN$-hlBh-n<$CJ3O z+*#(7HFQKK(XxyzTuP^?bzT(KD2tdmgdP%8B-JT>(kyhT&Bxn=aFLZr3sLWKx)hVxa3U*Afx3Pf~M2 zN1UVw-vzh4{YA|JUUR`2c8 zLXo|)qtGBqWMr>oZzW`>viDAQ*%=vS^Bf<#?%)6aJg?{ZzFzlzch{Hi=ll7*-{*Op z$9bH`yXW4NK;iGN#!GN3i=q;FGJk_iq#+LuL`Ig=Bv1dEd<^@H*l6;6 z%nX_0MYZBTJt$`)1D{YNikFPmc1Zck%TvXu1giraqWzGbp!m*V7A!!LUkMIW`u z-#WZ6?~0TJN3$7+6-PGjBsW>gsAbBhp(9bUls-~cGDi}4o;P=^9io%{8CN*;L3zP@ z@`ZxEy6@#Z9_Gg~rFioiTiWyZko$*iruVanX$0%@W}BsZkPlzC__$(Lm`=lUyf$lY z=<9ZTGx{@UE~7ityuMPuZk?+!Yps`Fyp~6MB`g69o2J*y#y8mFu$gi-c{A%*yePYW z*)q8)2k69AR(0y;O)7`6QktvFvDmKYRDPQZ&SNxtPO={MMNgR77omF4=`7E&m@=cp zv3H~D)~wam3}bgv_{o}%+CJ7#d8WTY zm*_{Bj#b4JgvXUl5^J=u7k+ef9;Hnaw&=r^zc|^>RW!X9yz}cb@|)FY!$}quB(VqN zMejm0yl5!bC64i2e|D^GI(u)cZ#8{*2lJU;W8n*QnKE?Y%%*zBQj*wc=hy~W$WHji zyt-pJSF3m>Zf?3><|4hrOLil#+ixWN7xnV}t~J^8axS+9+VNjCNTCZmEtz$O_HK*X zcalbHj;p1TY^7f!RAsng+^J}}4+*N}O4HV22zvN*n5Tzb`!~~r`{~5y1u?X z`II-P3mO8|fRBAKht##G7zk}3UJd82by3Q$z~AkTkE8X#-qp|vL9IZGjuwAOsz%=s zVYOmtC5*r#6>-+cb&s!QxwwZ5A zTpF1(;^6(ktlF{KHs-d^VBo_+qVghMq8qc{($q9%vvxXJ$`&83-;w;oCZs{~50?<- z39jrPZ+M$2s-|sI+Dd}mOEgaACp(-Eh?Dn=@lB_>CNm$^_K5mx(eJ;xx!7B}xhHIF ziw>`+iChvmiu^Zsg6>M#MyqB2{wUOCV89p<8vqs2|5BEbkqOmRP*4EX9uOI+Rn5{i zsYVt4yPId@vbHR2+emlPDL)@9Qicw6^4_1A6Qp-|f3V?FJ2f8O-##y2ezr!yAzs5J z>C3YC-#eOJP17%8!ek^5kG8}sio~XS&|Ofd0>`Vc!OT{Xc)PMD<@KxcPS%g%0-p0K_F; z4~oVbv|^hmMw4FRcJ|DP5?p zkI0!EX`_T0Q`3$2ZRy!)Tsjm+ACC=_jc6x3Ecux3uBIxvgt&=sbY05dPmAvAoLmwD zPCWQ8b*(1VwH4-`H=&2_Gwm(9;v2hcYU~l)?d&~PRr}*sbF773a2~^KtN^pLXO>>~ z$n_e(sergj!|=TTSVJBu#wWeKQl?hA)Y}JarLob#Zmz$xf@>fP_d0rqOvfT z&R>4-qMW$0Fqppi^2o~C{=lS=q>0qIG`GcrEk%C)*0ylF1K zxKI*0vOkb^i=q;ZZZTDEVV9uw1NIr(`X65v|+&Dt!3*E zsjEwMls)WBZ=^P#b!{c)OLEPdGqXF@?>}Roa~RE=l4v{~yR^r!*IDXNd;$M0=AApF zeV&rf2MzyFbk@W5Ozju=xFVQ+*^)<~8kNMu@Ach9Z_2uiZ7NJ3Ntgu=*oH0_1gsjx zKB=+|&Hw7vF~My{CTy3_-`R55PVt#i62pagv+&WG&9T&rk(Y=a)m}YoIir*STA`t9kvU39g6B##Oxsk4q#xdD%9@wH>?V6hkY6)o$+2GWo~Dnmb}eVO zr(f}P-ld1R;$gpZ=-17g8f9q>oIWWbH4h)5vy;%xjT4E{dY~Ml!+XQw-iCy2%PaE@ z?r~{H@kPULpPJ~-)i$?rTy7#?KP~Gp*Of>Wq7v?NWs0S9my6W)a;e93AvW=XhRX-- z=KcZ>XIT8YqQ*j?u#irDViNE&+-Snc_d08sz&5*fAB*~ODmy@i|yZILp z@dd?Bz2lwyS!yEw)+?uHU)tS#|I*qc{)gg4clO)9)??O0RIqC^GQ zWUcihz{@lsZ8Y@*h=Ql6)kTs9ce1iwPdyc|a^^;+?Bvz@H^uKly~I(E zo9Gu>FPM^%CJO%OUifuL@yo?}mQUYg`@~r<`Dqk$mc$uP1t!hJ$~hVHp64*8JXN_Y zdVcnqN*F6uvfg59Q3d@%4O!693qxI2Ka%3wNY`3-I3n(7nO_jx`6 z;R?li>1B#nwtYQn?l!u{dMC`Dk~d?*;zt#Kl;6YewdDNULxjb%&NK!6GgbCNmbICW z{Wx!{%XLPlrhYq_3>v3`8gk+9HE-nf?6Y4SW4g>K`%C3I;~{6=wYpAvjd{x1+j+Mm z{z~W7@go1%#3>|8C@0Ox$h3uGG=xv4LW(u~Iqx^y(D-5SWs&I|C9&Q|W?dZaKhw{j ztmCqNFnm{sTq0WUUY^jP$&9tcn1tQbV;a|N2M6aCirEuooROU+vtQD>iJNUMbR8V0 zT|)ZLm5Gy#vQD3^|K`sXNn+-jKPBE4>Wzvlmw9o?(Xi?}ZOw$yOMo|`zPc`Jp>F-z z8h9^!SJS|yxwSvrC~ zKZHZ>QrnH<=(ZJ?^3Vpk%$4Hc#JmG>+1U;U*&i$h=DPJ0n9c z)6YvkZRQWXYgJThv$R{Xq;Y6!WWTJ)`Fk8JIPIHy(*=g>K&f3ljVkjPqZGe^Vb&G@&LQ>e^(v|z2`GTDmG!ywrk^# zjf8Hr00a%kw>49VvzBV@>3EOV z7Ha1F*|&loMEiWik8!QZrBqR(Iq>8}aYh2~>4~K*YrSIjMTL6X2~P=xgonN;d!*<+ zoXNkd*S!2k;c3%T#>BZGYwi5e8LMtP2SKNMwUjnAv#|~C#|4B$Xmh$bPpL^6s1Ml& z$G3$RU)*zigybrRa%dVKZ#}69xzWP&t4e16Qf|F7DL*O~v)g!64jyb=v>jd+TzHfd zc^(O!@1S1j7CE+@>%4{SU5{PMr7d)1yq7+6k~R6nhDybdlTdt3d3b#^`pHhUh+)BQrpM_*X-liAM}b=#U90pO*VhOUV0 zjI_^AJZC&sH9F}8G>2D%-3AVJ6c(q{e)O^SAW3brXI78xx^wUqc9C>0trTn8`|`=m zQl#&~*OHqZcZH4~-4!d*svl!)78oa_8|OXJxRCmoUv`-MfKHKtFMsnrj&oBtrP4lM z{Y4tt_&cap!;LW@TPe^c@o@-K(B-_}g7g=<3iu0EiITdzdDgV83#0JV2Y7qp=prBY zyxt7y0=wkAe-}_YW|z4**{(G02%!_wYuoKA4f-aWN@y+k-MU=UsAE$_hn~j$XC!}3 z*k9(I3$SkGPvp-r&7sOsdb>knce|v@PQ9x3B}=j%`brk6*vT?_UK3%d+FLY|$m>c` zoNW>cpK4y}M4Ja#=14`Ryd*86I^=XKk4t?e|0FUgUUM2-iwL0eitpDUJ%+ymMP`ic z<`3{FOBKm2edDNS755x9IV~A4$RZ~a$R%6cmlDVzC+YJvVnRG7nC|^jk=M1Hy5+I^Gx8PDo^1S-0tA zue#j2!!Oe&6)QBof0vJ#{kQxU)79Q+yQX{KHmeqWFYWmHdoXl3Yidm>nEseiozx`- z*=F8%2UtG4T;3)eGty6cM?s58WiXW4{6I0)-l94gx_;Zx3<>4rKKUO=Rt*NM3L! zS#uGE#yZ$4mFZ>D-!ZRG(=z&Tr+)vT^Cl?16Rw4}xsk;@zh4>GPgFH`B`@C7+Fzu2-*yv=7ykT2D#n9+{#>1uzLygF( z4ihD%iy1T?){M;sTK$h>p6&~_VqR0^owiUis5JEw8u>ce>-L~8dzc6#LoZCH!>->< z7!4Sxwe?!EN;ftLvs)H>F}{{*Q>5Xi=c$pPuwALnTz|`!rKk0BW~~pEItMNJ?!D8J zcL^rVa{N#j>?}XLPMV{}|M1mo5ycYnrUmnCfdFUu&i2E_am%kyJa3NB`jD%^7y6>R zmBoQoO!ctLQjzw@T^b7yi4Cyj!_Lh2-5^asFx;{DLz)yx+uqOVoPB4@rZ3W&cAhCd z_-XYw=gGCK(jFlm$CcBg)po7@%9;vKhbpHdp7%QC>v?7=I$mpLR|&9c&!Na^ z#`>OGBu*SWEYR;^_!ez}R~23&is7S`!yf`2W(cUS>h<onJ|Equvc+kQy%+A~tgSf04(m&poM zl`o&vUuX`{FkAq**nB;x_9SxL#eI8&O`K>X%_I+NUA59Z&J9D__@cCLGyTN=-h469 z3270X+=lr5;~!!_>Th;!@E13kzZG(BAv3W}T%$B)x|GU;3oK#dL=)^dD_vBKRmw!c2(!O(Os^*aF zZ*6H=fTW0crQQGEPb`Sa$UHyHtjP!s2sAMxgMnHBG=z>zN=C-yTKktTBj2SqZtQ#3 z|1m~=R_OPfzZ3-}2qEQ#GJ8X}eY?Utz=qWAQ+w>jI=EB1DN@Jhy;7Bwk!c~c0qD&S z4h@ar^ns^n`o2Rq9~zdCr*shwIM)GU6-Nz*jVpBA)RyAU7eNKi*^rEUaNmDgU04(! zwuB)gI-Dybi$hnU#k?pw-g^DJNree)h-iuhHl-`AHR--2fx5nArP@si@CNj*`HhTCVH9crt_@c^a>Ht zg6D>#@g7F;@ByPan?r%^IKv^!q=S_Zd+sKsXo!9xm_!K1(N0rVRP+sC(ntdF{$IC! z>G_t8Wtn!rw6v7h#|mBN8?4AW963bSzrJ0nIY27PLiXJGrU%9`NoNTs*?5G4r?g?_vg?9|G0q*Jwq*t8{A`B=Fh= zM_(DU*7GDSv*ZkEkP~lz7j1muPT0XCw1@8ZUppLW@=-v4U-q#oQzMe6JUKn2|e{nt@<~* z3yQH=4M_fV{MD-ZHQO|l(9%?$OE(z*^5*;xuM+}efApLqHk;p8LPsZBaDBzfw6{nD zQqZq?Hpzru5js`b2>xr>iY@3uALK6(F78}=-(D_|DYu03vf?(`+}VX17rMCf{=%Vo zEdyp8)!Rg3$_1W_ zSGv)5RJ{EN?NHkL=uJCL3n|VBXRczOR4Fxiu4{X#TxSTc@zoZWcHJ#=wv<`^7;o#2 zd%VYg%$X&|iCQ}AK2na>leW>N)Y@L@61hu`ed^PfowO!O8aE#)qWiB}&o!(bpkw4C z6Byg}%a$GILlMpY0`t8pO>@pB$N7zFCw%M1IU*k>h}O^4^%N^bN|a|yoHl#8A&RNh z*KRr;Znri%9%3^eJZ|Q={G-2CzaW2}2<@hei;Ki`iJ_t4(yw&qR7yTu144&PD6EDf z?p;C4pO||o`ju)L4 znaP4o2x=z-9C$`3Sq?MZNErE2al(`B_FIy>FC*Ev`UO|V_8p<0BFhBx>T*G>jn!YTdhYD2?HlvSToNR(;kukuo=VkfgUOVo#O~ggW!;8l#~eN8 zVr#8G9OaRg%1xh*9BPoyOz5W_P`Z1OH*d6Sb}VTUY#9}qta}U(HyOp5GcuedKJHWz z@>epu&VwL47)h2+zBGF|9t-z(0jH0$3g zW-l}PsHR(9`}R?N?XSSP)ST6zhqv_XOC^RE0k4^9K7raJa>gf~b zBzHb4C9S9Uv!R~j^nSzfaN3sxCmD5%8!hw`)6%ZlMOIF>?%F2BrisJz+RmwTNhA~1`$~ngISN>- z<>~o*GR^1iknMSD;E=%0pun5mv7%vHBjf0wQw=&nMm{?4gLU|*i8`C)o~Qo8uREEf zgS7Jw4&Dw4iGFgg4U^?R*$s!&W1v7#=P4|A(Nd38HNNa7b4r}`R0x&funSxX|Cmt(f-$hf^m!Dz`DJjv5|I)wL^i=C#q_-nDdzezj-$IjJv({eYt z1SHiFvyY99rRU`Q-9+AE7Q$S7k?dc?^UF4dBM1Vo zgS}GxG<2u==Ce9=*V4|jMZNAf^o{NIDixQx7{|7DX?T|#&FEOCYQM$dcCBaZ?%a zZP%MxQ4wKtWdn-6O20)&`h@X_uqtVhQy4}tH?Xt6jgO~ZFt|iyVKf`BuioP z$N_^?gysiYr&S!Yr;I@a2!04rkilqEETmKZk&)(RM{kf;4w@8RwB#yG<2}#w<4mrs zL2TYdOHPM4d&^vYN>`f73A5#|jO^7qV$zp5WOAF|}He7J&1dHPc^?asJ)-@? zb%Fi*F?CtztKe$GLyT>B?)}Ui`-bek^t(Mee5-6fVIeTO{Ya& z$tD7ofByVAz-I5>z1+1_1eBbuUUpjcXvEV`A z=X=lFGh~#`g%)IH=ePb&eK%#>Xw*59znuEccHTJK^lQCQV_S8Qy0Wp47Vt3A}Ks_#wfa2hD7 zCs-|ID2Q4uy<$lkpQHM|JUgqdqa~Ei#yi#W_mc-+|91Td6po5+7>{_CsULT=^zs>3 zF&6otRy8NV-B)6cp6+krx^&U)TqGM;ee!xJqoCcdUz#@65&K@KtM>Nfl(rTZr!7fp zii(O3#7)o7)A90#jEopSAglKFHp!beZ{UfwO-oDb#QmR_Qm&rc$NzK7TB^8NdLuD7nOE=x*CoZ{gL#?UJ=6E>5}lP3p`9vx*ofU(3+rKPc7XHz?} z+}Ayis|+rm=T+s+ON?naJNaIdlrOB7b&t5&ZJ|MWL9OiLa+hUOPwEPg^ zEaI{CLH8H^62oYTvSO9dFB!=KS0xoXwuM%OJ^r@sj?KC2?-lRYRj3DR2S}gHOu9jT zugN-^J4NA0-z*l*?H=BAUSjy=x8S4H_9 zT6M;2Z+C>&iYY1{z|7)5M_FBPGbRh?HIE)|e4+{zk!ote6qCx_b?;js*-EQzDBdWu~oZ*E>$eC^f3pbA+wa0hbjQ*AW%u;no zt;vsytI%5OM3(1%?Re4v0k33%w%DEg{ye)UH3u2OfVl$P)JCN8@VGruN11;jIgK>kaCJsak4cI@2Qm}RU=sQRc+pB}|gc$%7n$~F@I zRUP|mwlSY@Tvr!0bLr`ktEUADh>?a6PPhj>;r zM$fqMwQHvP+4JZ3hSrurMt&FPB4Swd7CceZQm$<;$1vFZ8<=tS$Z6v17+i$Oo|&YrRxVp|u=o zh}sUh>1lrcu5s@6m{+eJ1Zp`2V~Sy>%c_1F(!>6K3qQSB;&YYR4w1IrudJ;6Tvn!? z*})AJex|#@%EI(Jv+l3scQ+qDH3J3KZ=x9#J*QY$d{Cc4euKakHV;y z@c@H0nWu>>>AG-;w3~O_mJh?FbryP%a?ibNkADijVD<80Q~;MbZ;*v7`cc8Tkj(eySQ{Y=%gim zoRH_rIda$@Fc7OJamCqNKQL$H{zacd-CdLKxLu_zNKz$-%X2t}rq0A_Y z)nU#663tq#vzvFu?%ynye{pMsp^=Y?jb(v}!RzQ~!^YP;F=?aQ_1=PpmKHIr62e~| z`xzRPJUTeBR8(9%*&tz8WqmyzE$tHwy}yOZ9LJpU0V+*?c^%a$i8pqZ7JJg@(= zuLRlhW=?0V*BRnN?T&D9aWNkL8#CG87N);5UeA6GX9i8@RU6nwJS)|{1)kuxu5K`; z%H}Sa+%l=R8`qfYKR7&`iP>U(@hBIU9avPCamXo1mfaZGvi3TW-&}UR+X%N3Gbcl( zJ|-^=;WVg4=d`dwUkl ziDL4l3=_-lFJ6@EWlrPtVHVx0gBWIVX*C+`cRLwp)}5zUPJ~cA#!hcBe?0yhk1_ax ziO~_pgBXV-b9Hq^RM}khpS9mK#7dLj&}jWKb@dIt04DE|Ar8P6;yVVVPMd$yo$VO11~F*v?&+zEnH;Rv1BVW|wi@YT zRI?>bqjTJS^O;(PHt>bukE(B+*PS4+vmZ;0|7+jAc#H34{5TKrb7|@R6DR7*Pde9N z{6#`eP9OIKHdeuq>n0hD9L9`qEkY|11`!)+&YanQ{CM)~C_a}`Z7L29e+;KJrfUho z&fu0U&BiU*a{vDQ4E0p}UWnsLQm$ogS-`2mA{Q@i!5r}s@P-Eu9}Wpq-h7&7HX()3 z*v@z$=GjhmjgHg4bNFS1YVY}r7yC5wtZ(5|Rk(@qiHeDRo0>AWy^*`sHa{FgWYZu2 zX720nF9DFMFn3zvAML}r-~_NO2ke$F+^&BhC@K6Ust7ECEEGcYtH zCL{9?hP()HfrW#SWvzxH$9tL48)5ThSMnqADpXTWXZml&LR=5unGdMjU(r2qEqgxtM_? zaw}#7hwwJ+(SMN4fDjD7zN5#`?PsGbM1{oO|8ChcWo{a3>YP;UcRz3MKJ0-vI=gWq zH72Ssko*xPmn7yg{~{q_;Y;cg#pb|~%Ikf=#dN1mJ#hV-Jn4vNS^}&)uy~#jp&phJ zKHlCRpy-YF*+;Bu#c23KaC^8zWMB9CvWMFHJ5*D}>w*|J9FB53@zE$t`;A(S7X+Hb zi{rV+r~W%Zl)`{@Vu#4dGi`oc)sJd``v;H3w;h{6Wv54}FjDGakDWq7LYd#CIG%cV z;JD{Vy3?m0V@&!f=GVSWOqklHT)(2OevFdW`X&+*08=Ps{MY+yi^Kdd5+U#oE*_Ih zWSc4AB{r59kOwVo+4xxqIAddPWp*rJZ~%u0GoQbnJ@BUdgwD6mPv050*Zr596t^eb zk-&qMMC^%)i}MW%lDLmUx+EpT1nvbqc(BD`Zls^_;MfKz(bOyVH_C=V$r>hyo7d_& z|I-3slyvb4EDpTEvtA63HTw{*jtqezo>n{cc?_9Z z4YMLcfVU(8LPd6f4+|lD|6fX%yirSf3U~h~{48`ZC`T-ECXKwlA3vlc1s#Lf^hrxf zN@~J*{9p%QiIH~1{~%V~J%>FmUly?oLK%%g-;pnGP7`?pAqycQ(Lf^YdcN(18h{QC zo*%$*rl)9Wcjb4R*)nd#Q{%%3PJB}ZpDslm0uoG4T#QH&$e}h}p)!mKy)Wd2Z2yyGeg@*A2#qHb_q@YJ?Fq?8w zQ}cv*!SpV;rTjBFIjJX}f4-}d(v67|2@r#uJP7upCMJx4!Fu9=4nBNgyrh+$FtfO| zy7cRd3FlCKWIY@_M!WO5fP}DI8{b>#WS)LT>>l?D**GGCB<{ytsGP9yHUPSm8@ayt zx_y(AS71#0^w~3NR#sm@$0giJV_W6KTbRB7XjLyzj^XE{TxJx`i`7~NEeSpyZ_Lgy zP%va+`T+F@0wG*o8nIh9mRkj-jH`&EKPDy7Pu|HH>InxYi{Ind5P68K02X>lK$>{o zq63_<3c7fV6F?^@LWu+jWRLOwE0_+w3rbT`TKYS&HbHSF1RFQYU75;;2x*}hwsHZk};?+gB!zhIih!uNXf z!n(E`B7N#E;g65h1IzZgyd1IZ!=GHRb?er-k;d(aBFf4Kk+(`(RcfbVW&n;p0Xw3~ z*exft%I>_>9GRe+9)ah0kAWiZ?fS~F&~r+@!-zQqPd9rS(W+GnPq7(BrYuZgpg*Tj02%lfPj4m7Q3tSo@=GsmEav@Cx-< z0bl}A3w*x6`Byhlb(E-ogv3*JHdx4>b9*ipG@2?-SgF&iP5TJhQjO7poc z2doLV18dv=aL{HIOq|}03P5>yZ|<%C;{QJ9h3%flx%3cNkcKmLp1vfiH~2X$f~o(2 z#07M=_6hTfzYL9u*pQpLxV%h8Nhxb>&5k^*3t|Rak+?yTktgBvhEz85Vf#Lyy}+o= z_+Z4aT1HDveTdg-g;^MifYFCPB@H|Yb(ty0K2Oju9IB#pg&-0@307vdX(uup zz`Zse8N10BgfYwGm@(T|FSO3z>$H3x0sqv=`#-mW?$j&Ki$=<6j1t+6AB(%9?Vn-X z&a{yMSXqO(%uiqlt9WCB4sgOX<$sBadXV={-xk;@eT!UQq2se1e}zm;AjLoB>hwko z5#4czgYSX6dyqM7c~ET4z({NVv13wjfH}%%%ZNLR`ehouWXo@#Nl?QDaTp)Qr2b_Q z#X<0e_~$50o5sY)XTo*_ixP`2Ck&VQ7K5i)z@ITt^#S+#P3MGO`3BdJXp4k-8|Gyu zy+z?@8chGtS`UFsbuVV+-Qe~O56;`5S!%rC41t%Wcyj_P;&cOen5QpZ&{0u6glm-* zOeTO%N19^)Ca@@S32>!i^40U1(N&aiEXx4TN!Y4jJ`cm&$KXT9Xl7=nCr*}YhDgw_ zwZ23SNHdJ{wsr75alm>cGV&kf7DUa@AGVp2B&4N3>1DDYmG(HVI|5$;4r7}KU>-c^ zPZ=}d^_mF5Iq)Mnps1u2u2a4?8;OHU1|%^)D3Y#Oh|NJ13jYI@c0s65P$_)=f24$g z1IJWsbzuAPMm-fX>X|SULde(MK;xiYm4my+Hmgu9&%@`{@r|E=j{y2ane|_a>iW%| zB!j%5bmN8$>R^019e`mhFmD2)wp};3nC#*q++skRi`&|Ao>NUjCHMq^5(yy-EV16q zKqUg;1Tmsvzk2_X7Q~Fyh5{$6J;^ZRhAiF3_P>3eh zRHb)#@>-mUtR?#+MQJ zP=Um07CPvOA0$HJ{@hqYj(!h-%D`G)R5DyagiHJai-3h?`Cv?y{3h!~j ze6XLe>3jAhMvTW{?kw6w|4?vyV*o4Ltou(kuuIvxeOCrB$1!$;i&H&?*WeKIC$Sqb znwy)WJQhRp1jE6ok@pg7^aA{Mwr$%M_5-)>KNM~$P24bvy?!Vs(bm2T%$$q9)by`k zgKNuE`WTE=V?0dQ8-Z>8l4E`nbO1HhsJHjOnK~Xf;!x2XWz%a&)8NDMsz+ult@1x- z*jrSH!cK-9X#x!3T^Is_YhsiW_;nCD<-fquXw;finsMus+B<{&@V5clIsSm~Hq?FQ zj&{4TrQ*ho^SSOu6z)Ncpb3zK4xBtGhx-RhkP@>TGQ>5cb%YDz-XJ_-7soUqY7yU} zvZA67mT}+UR#sA7T|KU58P1+GKBS&)auh^F44yFdosB0MP@@zPlSHt6w47Ht@FWMT z1C{b^P2rr1;HwK_4gsq?N21sr(ffi-}mTfeM)X3e_XeecXufV;z0%C;VEMQM^ z(Q{!lk^gf{g_c^ewCcFPE@Dl9MHPEdX<7=bhoB3>S@_bWts8j$zX}O(H_=U^su>#S54Pc?V>$%#ub7CFMQPt zD6Q6T7(fF;kdX|1>t$DwR^~HjcH;Nmxs?-LLphPWtmg{Wxt zu#qZ$0iqK*2K76b{o*PPeQFP#{l0sC&OL`^cvotyH zkOgN6hyzrBlwo0Wp09(Qk1rHVh+i>$PLUnplp&0wL{{pYmOMGFMMd8}?eRaN*&xsp#S2mlk+}sI2gnGonb%Z4p`UwuBjJX+kDNTP`q^Wcxk$*!+=e?P zZS2O%&lR|F_7n_ym;rKW85o{{N^8bC8qRZE{vAxIv~l|e;u;AEAq~prtywoOaC9j` zv;-)U{yPoWM7#buauL{Pv@?epD%}3*Ya)8BOnsU z8%Y)`;RxV8%(gD@B~{2ODJy@j@Hx$6IpCgov84ZwH!=r&4G4;Y0F%&GL?MRJ#vjUM z<6j)`Q$2rd+xOh%&t!5L_ZMf3WB{juw(eQk*pzC&0du|pTvi2)63l1E1g}y~JY|Oe z8`pepW7$}W5LaqO0-i&q?QkB_CbVHNp(=ZI>G99``FQjOh-V8PORp}h64|Q*jVUA(|HVglNMC0x6uWL&PBJlnnuMzqZr;*}C?%w4F zxGu5jE{=)$eC;gK>IH1{Kb6)86ifKgJ3sp_5ls=q3pv3>8W18X_YYEYv;(IuV&SH% zy&`B!5a`J~{uSZS6_}w$=vW-pm6NMaHd_Zh?HwF^jk0lL4Nj_QYHI#-obx%b2zZ-o zdDiqOQwlH%y<_)ozIF&HL;e8Dn5G-396pWzOHDnw%s8{-F6fqID*qOC zPzBZ_4G#gn!E2e>hVcC;+0f&%(~Wvx|Xh`a8CV01*tiQjGCNn6`X;Ewx|;s)!ydW)Tf zrl+S-yv-um08_|mA_x*(nJv}{PLe4$8wZ3Ph@1iRuD??Njt&*-H z)EshGu8`tFkksJ_;}suIhis+$(S@YTd42VeE!ieqO*A7C6h{>pH6rghF3t5L)G@K~ zR+g5!B6e;Oi)ui})PDR;Ie4A@@J;zfv?u^33Az(}3sG-^*bD;cx>>7NTm~&?-}i9$ zSth0;qegFhFbGv(*|(XQi(rbASYq98)Zn+D5O5#}52v+7eNOY98Wf&#@b$6^rHj1p z3wb4((nh}R>R4G>ao_`O8U- zT`@<7XbbIi_@-SC%Y96HE+ASsdlX6mttzZRQx|sSt*?L=By9dBB_#?WqUgt}cmuUB z3V!(JP;+w!iJ!3Fv4I+5^7K528bTtgsgs0SI|*o$AX)+Vty?W5$qAkpv`pa9YHDhK zE<8zq=)17Q#ZQ2GeMI;)F-tvb*)o|nd9agt>b+g+7<<~I3!5>u8SP8Z;;6ULIUw4R zsPQ9#p$Sr?)d&&#zxs1>OW+~WaBho704Je7mqjQ4MZ=S5&O%ZBm`I$es_mBIe*WdP zwVniINY+|S>iU)UewaM*a6 zQNj)dG&vdksTrx4K&03c?e9%?8NEl4JNkd(Y_6=~uBYzG`6zSqY$vJ^E)js>1KBq^ z`V{Qpi4!MO3)4M3{>HX%efg(*1e(NwNaP?u0N{v{^*+4L;c?ZIYlh2g&zeHpQbAc+ zx%BDAY96p9QmNtuPVV}E`k}I_ifB28;WhxOBj#V$)1!q|$S{J;Z9P3pRO4`X51&5| zk`btvi>1)LVj>m1B&y9tUUU!$;(hngS921J_6^LbZvA+@O z2zwubLUov*^hBxBlAyqD*7d&2kx0BqVc*8aq~foHt06rd_J|F6vGMFhjTnea_Z;r; zzXY>w!M$gw6=iXNL_Nq>jec7)TA73=?8JB6b_d3>aaY2hA*SJKw*ZK@rD;^7p579D zF9xuOm-lN;0&!)zxjY{3MDY$~ITkn}7AW}n@o&KSzX3M!)C@tA&pP37uyT;W*zTAx z7->&G376Bu@J?o#HrTkbn7B>u3Y`K*f{p{UQ|&J6>?A6wt4h>F)+ZwK9V;uC275nx zv<;m4Sq26Mt4_0=W)$^~Kg9+}`|z|;RigWPhKvaSQ0E9h^i!>V7#j$ zJQ@9MnjX6wwC!Y}E4S|X104u6JT^z(Sn0AhVK^wuZHB2H&%3^Dn#JT*M!ow{yZoChN zZnIWbYRE5C?@sx_wLMZyw_Sh2<#lFk&T-d=`SV!qt*OVeXJ0@=pdR>! zOjSI-^hU3pdJR^+HkZkB6E%-#dpnt)WaGmx2WJ!$m_lsh0ao1KkM;HGT{a*~x^E84eK3-X@7Awr(_1US*?-wOTP-@Qw|Qq#vSwfW zWZSOEzC+AM{tolm8n$PdU?8cfxxV>`pD5`rT&drhm!HoD*KXiD05$g(W%PbbP|9?@ zj`|xGtUS(Z{6vF*P=lD|sOk{(6Sfx#2&QL)0|VaZ3;?ojHE538iwKAx^d!1F6ONQq zoXURa{$@h13%aw6D2{<(v?kvsWq|qwgL(Gs*;n|jU_(%!jW$M?A1Z%+<9xikavi_~ zYT)-KxuCbttG{~%xpbXw&L=C`_G3Ojh9@WMK#@ZfLkg&0H;8x%$}#)nuy>2euaKiV z8TWQxx~cy?`O3d0T03?Zx#d3z3D0nNZ-41~U4|9??TH7E*!on`tqYU+`nIL+eq6p+ zW+;>Vk{R!g`GWomAbhvv>p4tBL7;{423^-JDCM8Sg)`J8iIHT2hKAZdP#!3gBB611(42sp5#^`H>j<5F-mSak9rj2vI%3W(02 zOem)(9Osl26@^hw63jdx`$MbF>#MnO#-0_PXo|=LzoxpN-T|~;79*;tV)^1x;gMt6 z%o=U4vZnRdNUT_c&kUbpAKgW|JH|ZkzGEX#Lg!rBiPQIbnTIiCJs}Qwc@tU~B&QqM zT^nIz%6m*}f8tBD#$M`Eh5!Nl&7ffi4d{{MRg4fpyUKs=aj$?5q004*$88<&@>Ke zl~3T8(W?d|3a=(gf!nuZo+idH+@4_PCFL-4=6?6{8SIk5laF0t(x++@_4lGP~R;>vRLXww|lnP0pp0@+Eg% z>-U7Vi7_*0+r3ui!u87V2F3$3tbHT220Z^R=q|5(m#6#r)oWOLvAm@7;XP!3`N0>f*mjxNLJZx*ATZIz(RZy* zBL)k$-my8qEQf<8C!-N2{d?q8^z!=j!sL8HphFXZ0dX@N_F1c$ty?!L(vI4@X)3!l zj75{40G)g}kI`i{qA6V5xOyo%y1_J!Ew%@;g#8vR7_0g}t4lTF}OBBED)H8Yb zIJv*()|Zp}t`EJ`aONh-KF^+aB%JpzzCeEsXM?@t%cPbsK1`-dw@319yDs?9#qQL- z`pYi@_mG$$cjY;xE7AMU)8<>V;$n>rjVEt*U(fi(Cb9VCOMPWHx$c&G)N%i50c6=v zq%YhbeVchrtno^7gxG$i-#s36&2?`}RaE&RJYvls6;^xB=IOB9HapkZoya;2oz;L; zL1E!h9!r`C)C9Uv#UYfmeOAU+$Jrph;o*)Qs%V&#x_wX5Lis+IU#wcXA*OAzy&P9Vw~9324#5TV z_t1oW%nk208wMv)*9jJYR!FG0=|!lY-zR|bs)J-NbH=sNFYZUM(+$u#FTVV{jE@$q z6L3+5J^C>ZEPKP4&DY!gMjwHL0edHL^=g1shkxC0X_|E%!@au8M!taD+iv`(Sehs4-F z$9c58dC5s9a&KqJqLOa;OBHKPcuu1u&Y@>s0LQFG0*{S?~dpVljm0kV7{J?|z^?Jure`stJ~V3u@pxRF;pr z%?N26j*SgP)9g8R!7RAke}RZVnJvI36>$nA*tfw!0%AiifO`BbD7&J?q2mO-^WNfn z(1lyVt}p%;V|j?ye&&w~|A4JTiyfdGVGh!}VYCB@*bdTMi$fgk$s_!CFH{FI55w=e z4|w`B5Fc?q%cAQqspaAb8FHc-0j{DkS(TYzKmgJvU6f{n5%ow&QjX~iyu;KSjoA61 zx?>Qx>vR!>hhQLo3NHEf0{Kl=rszo!_!hw>1DZ5=b3ZKA?ngzM*20m(+Ii!Zv1b~G zb`eo7qAQkZH>C;pQ=8UE`+>GQmUP?{4Nh=dHK`313#3}luQIb+5&yC-AX;?0tB%j? zV8Oc+CS8JIw+~j%tqIgMYCa4VyR+=QoyCv=+{kTT$=*o&KOAP&$VvbZ10XlxAjCxGGR#)qB)?gxZ~t?>L}m znHS}c@dKM(ROJ2hL>R?`KtBC8ZlZ7$Ed}^bESx41D@yl4yW(X^&>_H(+aDl!HbcJV z@OxYmG8gD*AoSeA%_rLhOh8~jNQDSJ92nS=zLLkl>ia>xQ-hB}1EJxap_2Zv_p=k^ z&$%ig2vQ$%jhhK@gxZxLPf;qOiE#zROL(|2L)BJ*er9MuFF|~=J}b0tb*KMg=ChB`2@3S#agSX0Pg3uCp! zHmydsLc%3vN9bpSMj4tyykPG*g9=lDqi<>M<|9-il< z7qzxKh6pB+ewC^ujx~EixKy=nI+;P%xeG1-8qs>O+z@#@&qa54s%XwkS~O!mc`Nz} z+(mSq-z0BK}YSL zKbgwbR^(->8)H((J}X@34uUk+C(I^2T`X@hI(VSc@)QzNYUrgjLP`&*(SuMri+>fH zP?5j?-FgZ81oCq<5ToVz-a;n5Bh4I0S}u^2&)#T(fTRijB2v2wi-~Cl@z1NlEJ`>U zkoyec71>t7c>P_JIO{FV^3>xzCD9V{9 zlLb&*Afu*k2eA`Q9jqTjb_WyI9Q=hiH{lTVIzRAwHIzdOdK-NR5Tho~_Y9sxmWfCm zKtA+o=MWrh-7s;;_2-U8tetAC{*~{qAZ~{FS--!hB_b*bsEBMLS^=a=2}y|Hd3DTz z)>w^)2qKe!>U2h7*%E9mhlhtf`T8=+wnKSs=J14bZmSf6Mg^OkoV@y)1GV+=%$%jZ z=->sPgz0fvLA&1FpYeVV(h`5$g}L>!n3lVJ>AiqEtss1PLCQ~HUZN}ZM$^Nh2efUR z5+96CT((ZDR;2Gvavg}6UcNqnmm!E*_jc_;bJER;_U;)CoQqx~2S-mH*eFfhtc`z9 zI_qBcqCft#Bg0_{_q&(^&gBPBV`p23O%1BcW_$AuT12o3y~+*L7Cu5y$z}#e69l3? zpf^Lj1UC2XW!$qtr;%qxIlK(){l4R<>VCF8%eldRes6x?Y2giz=~3W8@RWQ`5r-M` z*ITdmy!@ZwShamdZ`$}gX3;b|_f4&;8VTB;as{(hqL-I9HOD{~RAZ)uDA13q=Fk`5 zzDPK=xD7>!t|SSiLZhZtUwE7|)`EgA+h2D&%aQi!rAsrbuK6Iegg>IQ(76a10jvua z4h{~!Uo{1xanR6$%69CXRxWK-P^N-bu@1I`etg4hh8U%8KU9S?=wK#u)}kxFNg9?I z*+Xi57up)%pJiT!nH=+$PJiq=XRML33=d>^R013pWceVFgwoTy%F3-NS;HK?D;EE( zgB|b=d_olBu+6Jg<@cMU5#8<8FmZ-MTM}nDA1fqHs`^_~K?7fH){67vp#+`b_tQa- zC3L>okx0s3DyxX9`RK9b+RUZxM&<8Us`JOTyP`?FJBjx}U~yHcEv1$igIQ%SQ%fPy z{C0-fWg?+fYXi)pid=i`F7))NlWi3L+N&z-^=0(plVHOrp~Uf&rX}87*QR4T=9xK8 z{c(*(fhdWa$VLuTC~~MB8-oy|i}*Uo8J5SZ>(bE8k9!V}Do$^NRpaoMP)x{ecvji( z=Ea7XbHB4(KfBV!^Yc!_#MoioU9btgN&n?M>x75Xv~iKyiJIPe>5QN!{rBkrzJMpW zaM4xalB(^3fVCjsFC9riTkUt`{REnLV9ie?#~lbFwH#ZIr-JsFkZM4t%D~Q^*kkXN?sN6K_G8zoHaX|?uvqV4oC`F)?+2gSJF{`o8FwOsuTl|oskD9}R{mEp zgKCo`41+|?=N+tmDpJz=*HN_2KkIfzKY2-4dlF-BeY?md&)(%e<;B7oEh7H% zwz&u0!pf1vfn=Y{e-0<@XqgMV3*o#nOzG%>=lMCcoy|^kaxa+tuse}uqE^jgR%_9S zBBhN@_@)w~VQjf=ZDXSc8Eg<$YSOd&bNec}BU~2_*MgF|F-52))U0$2f>70FCVR$h zlbB~tQInkF=k0-)X_~r^pVd!L%Uuj2rsTiKRmqtbu~jL38rHV4v3o6Lc)0=RdQQ=5 zhu-Y4*0?2ym%oeWSt=^qR2wPUn9@LE;0+M~S{@wk#|Ila>jEo7xoOaagLWx}_w=;x zqHyIz7ZB#(1_d#4bCU!%*279EheQlo5Wlmsc^98?R+S8W1_Xx{;9H+DYC zWgH&`%@k&sp&{hE)Mv=7l!%oK?L)(NIB1X$Z*Ff_ybJ+FGPFOm7CPP0=;`U}mPV0t z?&5)0b}V#dT}HP29&5oC;S(1(X1G{bu(&GM%%+0)dgHRPvgE4M-T&BGKu;CqM5I@* zVpIGS2Ym`8+L3?cp7tWq;6G7;Lhwftr&4iDFkZ_vet2HLq-w9XtL`GYLO~mLA|+o*I&Vys zq$-|h>TWw!7_!w+&KHWqzpf(ujUb48lU+EmPO<4Yn2%x8(&Rkvv6K2oGkdCwtLElT z13MrsxZN0sueFgC_bIE-a4FTzg0*sz5l|5 zZ*_F%#rrRI4|-J!TjEgvZW+5*dk7&k5Q8H8Tw%93l6H%N-q3I`7i7|)8b_+mQ1e2% za!{&&5FF%WayE62@DMi7?3nNq6on9l95Y5fZLYn@0xPpCDv}P5~*2ZWW(?=@_EWf`#@C7B%!z4l+;@US}t_jVmCs zfWa}4L|^rW)CiG0(s>^0fgHhZ>HmDbvTGY zpdpdwd3uaEHsB?J0xI~d79sluUC1+MLOVg4E0%xHsp~3xrnkLS52$tK@zyQewX+6J zAH*d7-f24J8aPJR-yJ%7GM`JlexY70I7c#AL`O*T)QDt@ItA60niKu`r+1&FjM_^s zpS$%CZShJ0ooHZIg$B)ZD5sOJTeJ}x!YwT=4B!fZhWe!I$}Lf`U?*7t^I=IiL|#o)6x*GH z#w=dk;}f8fpo8%MbWvzJo<~fu*l55oG`o^p+cY&*+i}X7-Z7gfs8`icWY9`_cGxWO zdwu=IIxlFwAOmYhTuD%Wfx0+S*F*wQH8r&wm|MucFkEiO3|*PogW7X35Cb5p4iKw> z0top1!jk@|DL5Bz8*hX11a^3&2M95HPsTHLs5gQ_6b<^e+K%Er7rQl7RQmp|I*@+g zLJ9}@@?~#0W_e8eS)lW&xxPOyb`DOBb~smEV0_UMcupVyybfKBIq1$II$Rt&XK!R! zbAy?>VF|i@c5m^6d#1RdqpA0~=WT2+*jTxt+}}dWYKC)I!a{2n?}g#$VQ5cE_(#og zEa=vQOG*&CI3EwSLK=o`n?*A;uE%*+h&2i ztpj62W!jO%5~uhTVh%?_8B1jaj+7HmJv3hwoo`34y%zRqN@^~pqJ2JLb~mQE{Vd1n z#^P4PY(FtiO;=)}XE$Fh~2 zN^2*s+MDg5yMbo9va)jOer!@w=!9jO5vM&&EH z_TssFZcI_+SFbLt=BW(W6J}D)iw(gUDF{PS?F>{QsDiqF*Y%Ivkxqn}s{$2+EyWeD zhN6q^>t;ItNE*MEg@5fNpKWRl8sb;Y-DRwlCzE~otaou{$tpBN82H;(@7?ZhCM&(v z$34DE0SC&bGo2cj-Se=PY{Sl+`zKafduQTWABoMT_}|Gb3-}i@2W@F*V@J_m!M3)) z5id@l7fMx1oFm{#|Hgf!%;Q8xumJsfBKHIL)2c2O$>n2_O)EolJ1DFjrrGgNW4N73 zxE;{yICyY*o;Va7T=ye+$$*LL<|jy!VsWYXO@BqMs@YoDnAwI!>Q(ubJylIjv(vp7 z+3960=_Hr$J?&u&LBr59%9Gxo6j?kub6%VaijNB8p6YJC5gNa96wm2+~e6Yk6Mn}p${y~cehce3=>mwe7WUa+P{sw_(-QwCxy8yFaLV>%cUU`r>_ z5#it*oUs&?pD5~-t=!?vaXNb}V}bTh*ZttT*Gk|L2m`Ilb23j4oD{(8rbxdlB9i1$ zttzMekmghq;4#fpQ{h(|dQS{C><4?xAF!rA)fu3PQ7U(Jk+y9bp$k@#L;mTE+zeZ$ z9>!B6R)@Wj4aW8`j~?X_alw)+oG31rDfOH6Lf^(zrW9jThbr{i?EzJ zv(ttv0Fnc|i#1`%OlFBRF|D}Ij=}_{3KCLE7UYiPD!WuLx|o&aq6Wx`#$B=`n8xmf z`siyi+?*(hFZz4A!YF?0hsb5iu{zwP5SFb$eg?l>Ol#9(9k{~#bW$c&ZaUauGvvEG z?<7GSQRg#d8|8u{h3eYMs%Si-tN=Z}`l;m|oxLP#mTTkl8x(h;tys^Lb ztEyER@ZUDe2n%oN)i-aZrNNIT(6PswhE7ScYR^Z5v{iCAcnzn!^bJEIO*zjV6kH)p^8e@Jn@#4`|6cq5J|sL_ z$P$!(pgH>crd+b3$A{GH1+1b0Sq25^OFtfkZ)+|{#xLIpmt|%fD0nm>n=WjQclezv zU>}=;x9!N8&5ntIg}W^yTV(j=3F(*vX2a*~e7C9lr1!{3H$1ZhniH_GGnoZuWW!IJ zJ0fOzLwOh#G4ixZ<{c0ISiCZ030IKc`h~qOiv2)tfrX2Hx^@OgS;LDu@&A(L{pkMuu}n}(3)?=7XmB3#>S5+BPA zKC;gHy&C+z3hyi*-*fAOd-f=CvzeiJC#|uSR^sq83}P?bLe)Amw}jGvmQQM=u*8*( zu#Ib5(E?MttZ~n(@GC~Y-ZG8ETEA=_fkxpyNF}(%YF{FcO{+gCri z@DYYl2c>OWmS>E4wtqt|dIT2tZMBCb3BMDzCx`Kho4+ck=|vaq1@S4@Bpt>W4D#6B zQ4Q0_#HF7(K5@3yqJ7k(j`5+@dRd+|Y9T%QI1dX$1LxI1LZpKX*KU=B(_%g^IRSRN z>*MdrvCKaAn@d`R|9;QQtH0{5Ay4G{U6N%S*2mTxm76=A(~E?fp^XE%4dYSDLyikg zDnr-@wK(qw>++PHcP}0$5xgPtZPy7fOp*%Qh^1EYQg|O|7Op3AN$bO0)uVs!ME}v^ zQlN5y%nSN4j7O^U6>sAhV$EufBv?iWJ?pu*P16Ojk|c;mxY|o()mjUN@xswrR&uSE zEPx@2zV?WehAfsNwc){wTR!4rN&eDScaJjaE$hOAhAZ++>>)aDih|2!<%~6OP+z+OBdufu;$NUBFw{gZp6Nvw z7@*JeT_sV>^^V!R_tBN!86_kxAfrzRx>>XNcCthowI%Md-$NuMdXyL<>rErKq(CB{BW5K z?Wx?XG$$}*GAzdEj?qGf8u+FhY51|iD2U$oxs@iR`!_i@>x(|ur<8VhZy2A`G-~ME zI1qgh)oB})xUV_LxVT=yKV&gTlR&1_Y?FWSZQTy1=gPf!rq9>$$Tx7UFDthrpxUtDYz${+&m+&8;N;J9 zbvu$5WB3oq+#N|VJg(_~H7_-lxO}_rhoFmgFIL>TcY~|ChooGJcI=#cP<_p|;r?Ro z=bS4y38P4j&L%fYj|x@?s`FOK@M>7yDPFV&Or7E@4%XMu%j<+Rxn>ZZq3l{~o*r^n z72%wnVye4d5OwuOd7=x@`!MK~U2k=W%d{)t9Xl1g?Cc_9xnUBH7K=-M5FutK=e44H zL&n0d^|4UF$9&}i%@;97(hUmT`va3$s7Y_mN?ktVMTP&i@4s)9@X)L2uz#Lux=Dc5 zyP3Y3ygAI4?AOtX>Nfft+u9p6zIXQPWt@Cs(9b?G#oBhn+OL0NslT`L;330@k#`e$ zDY$1gepORyH!T>@`4S$m-e35xWgC6I;{ij$vI zrDBa{U5O?T?`k@h69}Ti*qFatCh_%N>zUXe@~?~<4+^j@#|oL+IVi5juDa5+m3OJK zj1%3+4JcZQK+zY$0!3?eVZ+QFJUJYEjoe64%W=v8p>e zaw8F&NG$(RiB5SB>61$fTufb)LW~<`nyLK5>DN@kS3~f&#aqamehSi?X_Bw91=!@P z1ekBB52KQUIwL$qg2VkyYM!;;k+E3sdYfs(GIX)T=ezt16n5)Dz{}w?we+^Yty0;y zg$d_4scy$LUQVcYl+5+g&81R?oUeb#Zz}(>e8oPB{^3SF7gp7&fm_;LX-UJ7d54py zM=y%V3eGMz8r79)e%>!LAQwK0<*>>OOg3qEyvswv|Mj4TINN{!!N^&Q(b3-}^}i2Y z&;HvSaRq1tesELJ<3IMX-g}5=o^OP)-u0SZ!3Qfdi&^A7V_i!r%F8q<>Gd}vb#A#y zCyLa$5n3{)C*9}feln#E3nDYoHU)~0GTrIvS3I+BPLFU<%G~o#tuDKJOglhJv(@_; zFM#cp_lDEKPW>g;xP`?v=Pb0OgfPjZXreL?sVUTHg|csSmfr`M5+uaj)$}=Dq=3@# zj5frx-%Vq(Ql*03DBhr-QkasvzW#QPR&S~2_*%OJL4Z@tK_*xD>b)1@q>@-YlW2SX z+ZE+1zFst}Q#fuqe&J%I>ijc~6n!4KbW?2gk8jJ=H`Dvheyw&+a}QMr=y7hZ33wFa zN#I!fIQS#ZD}06wk@W1}x>H^MgtPzMD2JP``rQ8pCg_8P;S6zcziwH)Z*IV(W|Z#k zU!V3<3Td1%#jE0JXM26CnIpAC(l@LxMbE$qJBsUKayt5Q1s~c3FOjE*{~Co6(?g;B zFW3jOr{B~IXl~KykDXa2y4MQ)$|()i1RsUvKfPC@yE zkg@B-sth(4>m$_yO}Qw_s=Bcu8y)R65|I}r!4EOGGWSRqC67FDoVH+TM@ZNXYgWgP6Jh=zHN6HllJJE{?~ZFUp_ju*4pihD!f7B$4Q}(KO_YT#Kq3 z-Mvr3^Sg-n=jROfKWXcigKDox1rjPs{O_d{-r=A9XCp&HEnj|GT34FgW-`H#T}7C8 z?47z6_Y&_%teDnhsZ;$8O-8bA_smt{IHED5G1fms*v})0oRoa~S=tMt6_3PoMJQfn zzsFIh-eIz4t(BWh(^zXZ2{)I#6B6*%n(`Np%yiCM?k^%NE%Dk*!sPn55A3EczacEK zIQXiwBfgj>D;ez|F=&w(Pi8!;+;xHI15O0ldY(mT7mEQ=4G#r}#losY;-F?|M)zn9#VMw3-*D5Af+r#HO!C6zy}wckx5 zk(=JHb+~pdN<}U~#~p(~n0EV4-RDv!w*;$XtVY+PhheKeUe7U}OyE%yJ$^-+t`APk z^joe$Cqd@f0h>SSg#^L~Jj8v%=evb5lm1(Qsa;;iOxEe3WSws|JdpCcg{`3Z{`oP z7hhh}61=I#SyVosIMd(w$=U1=KBFQ=Y<3 zN_d@d6)&&cm9Z-P)<*6lbb78svuLb!@73AwT(?k(QE0UZ_+~^6=VQHYK~}4NzQTB; z<$9N~j->Re4Uck58}gLZ3)LsRo)FAG+MKp;7fwoww0$}Ms9?NTomjQ*?ej8Y+YKJ) zJ}X1MRdzr2h&e&wppdcg1TwW*<#m5%pWJ74Q9?JuZl^r+4k}GrM6DxlZ^TAt6e;87 zXa=T6NjihXaU<4CgKEL4VS7PX43Cb`vF`0#A#0HHg*bY6F(=!zHme6|(h9=X4<9^|U%}knM!3mmJ1Bf=Ns#4x;8KXwnZbu}d@AQX`)fGc#(YpQ`*iPFrK4BM9C}ze!c1N(;Xi&w_je~q=PZe4D!fNqRb)Pdb z*obHZ>uNkOcO-g_k6jPgM*uEt1j7HzmoF2vP+&`Wg*0}Y#S`rc?f(FyE7D9B7Op@Z z;LLEjqYmH+dqzjwpa46$;Ss;V`NM6`yo1tDb}?nLYtPL6bH}Y_Q{9oYJk#1LuM@tO z%mNM_(W`Brbl2tZ#x){|Z0fo9E*#FdZMMw!^j-7e(eUTKBP(Zxelm53l!cFxryK1Z(K;8rDy}AuUGq3O^k9wI_j9_|Pw&YqJ&3;(Xk2q^C0mH4 zULfIt^M*j{8?5jd<9k>NbfzQcZ=X||Jz`g&UvSQ%-qAC8v*u`&xNAnl=4x4KAhNw@ zJHD_UUq%(Ut?-+seI;yoGPSH?l%u^dz^!JgW|iGC+`t0OY)g@TgjBj3totQi);5w@fCEwuI_DsyE(SThV?@+i#w?s=uGr@^#T!KUwOIkgNa%?8AenR^x^7WSSS{;2%u{SP@gsxCcS9JZF z(%FoEQB6}tBl_mJTPW;+Z`eI;b!P*AdVZt9X^oCkjGJ&$9gB}_ zS}msj*OV_wrUDnd%+2Q$j&Zd*I5N?7#jRb<$C>TPbL3s!v6Y_8#QtOwfy5iW>5_{` zNKc7S5|koE*+o`QC?(udJfmkO>h1tOl= zxzA=NPhah92Yh}qSA0}iOq3}h`mfg^Iy;P zkL+{yg!t%nlt`Ysowp|-?^o?ddRtALA%3+sazU1~SK&z>H&af=P4X`aT3LlicJ-ihbpTg-FrcGO3kZIn_22Za-UhdXX)VeQeOymDBj z0GAc+>eS-KamVy6^nbSP<#8TeAL-7{PX61sd;9uCM5{6~E~YqCqt~^!+YE&a-pucImbKqK-3EL@9NRL8WQqRkH;@wC>k0vfrgj}Sy2@0&r*6H z+S%E4t5;N1m`96@Cbb#>MEgJ|LVKbzk>k#=@ zQgXWW-Yu!Wm-7Q#-Z~`r{a71XP|&8i7lVEJ~g39Dn+M(`pv?28a_v2ae$+a>z`V8XsikmlRMpnx@BRn*y z1qiP{sh1efun@)~`k=&hAe{JIUh@oOMq2xX0k31Xd%k2!AJbK;`+f@2R@UKIA*_8$ zhfQ6j+ug2m^IJJ-+y3)?hix5F`=@qVlhh)gr|p^-l_6~LPvymt`pp!9@i5@cX{I@* zQs=u`pDIEXww*)O);ybKvrLb9pHi-SLH56**@-{0+s$7?<#^SpDIE}9v>l>{^klk@ z3h!gK7<&1N1qx3IV@gt}tJ@Q2g#EK~+KGZ1EErxKqLD(P0*-cZK7Ao_7a>-OkzPg( zjT^_x#|6ynne~sxC^_y64bR_(Z~*GlQ-VhuE>j5A2#o2#plSh~Kx;<_)-;GVvUF+_ z0muO-H-fkUBfWhYvD(Vj%a`-OaRHjQPQX)s1PTX867L}NB5)5=1V0cK7B1Tx)MVx2 za;ixB^oa_T%aovt2gj=(n5Cfo)->ZxVIMvie+&x2z;vQgv!2`6Lx<`d+Grob4wl?dXntmxxUAxiH2^G9diq zv0;w6*{SY?o@R(a4L&tdqp^H>46L4?m2-<3X{WSP7x(l9E|BK%NiPVg7RehHklB<(9D*kguk!PeV+M|pl$+>FL82Z{59${(5ThC_sE`NiVT z?BH|3J*J|k?SW9Zd+y8gzC^Pi%-5aeno(9HcBc6C9pgU8sF&PnvWu0A8cCI1TIc&z z^9ZE^ePVLgaBg1@H{i@^`CuD{jmg*p4-H3G1Fi|?TcM@AoIP4Gaye&8wZm9ZC!d>%=h$bT|i;1%S8{V09sE z8~}wxb7(+DXM$T$EVpX=B7)5U!sP;}e`fB~9uXpx7r+p$M!o%3QZAdFS5vy*C>~1Q~yuQy)6KdHz((kF%uqOXhcx zP~EAA1RJBqy-OC7})s}hm>L1=J55aT){-}ua<0t;(` zxvZ$HZ&5DRf4n3I`FPV@QBrMQ?XEn3tbdbH#LkF9%?7Qtp6ipq|@qRlp2OL`Az<|*OnDT*6Kb3 zEeL$F8a3`hh(Qd&qN9Ny|uhryk1Y>iW-WCDwsyl+S{<5gWg8*(WBJw-&<2=$3fEn%LXxvewqzAjV-5)iPy+0Drgbjh@#Fpi|1j?}H2MAe~rkT$>nmrWh|cQ*cjN zON)kwXWRZ;PEH7bymo#io%I`?xaw#*ANa@S=5k4(M!JU!4Dr>p9j<`2kS-zDuJ@;H zE(WlB5fn1ObKe4N7mSk#9tw__#5%%4aHS#kHDu)hGUL&sM~5g)@tZ5_lMcmNi#Mv9 z$Q#GM{H>*Na$XVImMl-R54v0MY*-Xcpx$SI+x(kFYv=KkaM_mlnVkKv21Es2xO3^* z1(n@j*>71iahk9Nwp=Dg@yT*4pFAC_Q(p-pi4qEzO*y1?F%ffDJ@5LUA}92cw^j7l zb7sTf_I+72#qHZ9`caZX2imQJWD!IZx-ArfCp88nR6NAnlM%eZH*%vDtaxS_$DWUf zvj)c>~43V*G#dHODEh1&d2L9dFwS$wDioEJ?2FEUB1ae&%~LfsGD^y~^*NGxASko2uuw!5>P$t5YuUgK zjAG~FO8fGq;m;W$vEAtUt$=yJ`sCYgWEy%k*K|V_R~B%6-$Uu35Lnxsm8-llr}6Ea z(QX4DK<|}rI>1InMdf-S>Z2H7QV=#An07}x@YdJ0)!H4z`^?;VI&S^*UH;bV!sch} zED4f#4qtN}keRDDeVUP)z0UZQHX#3w<|vyT1EV5ce5HB&+WIdx=@-%;MCU@17Bsx} zeyYed4M>l+X|?Xh@T>9KKcyX1Ad&lyZV;aQxys4#41>ZclPMWHIfW8p@?s@4{%A?H zgCrJHrH9eU@BFsKzly{?8pVhWoV_WF$7^@=(|cV~E=lspa@BV^g;X$-Ta$Oy-l4^v zTu5c1?lom%Feb;ygye$UIrqcjwySsCOR&rxi|@{;*~S+$f9;Rq!{cLQDay_{DEJ|y zTtnYLYM4YjktDIQY+WPalofjI2b+kpwhtCj`O2?}y*y*y`p?DT_htP8{=N=fL_k-M1eSN2kUD?HWgIOfLDj7P9y4^XRHCo3xGL+p!`MWbVOuA{Mc3u z4Y3;`)(_9ruj-z5m0->Xnb)6I4s_TC(hvNL!G`Y(e8z+W;(ac7wjBn%d#(v#JtEB~ z2xA#6@dy;;BmW=%_g}_(A>z+xCvW@j4W}z^t}H|sYQ3zds>7ne*@1q)DQDeQ;O3YG zyB(9Cze6k^swBtJ1=ljc2bVEI`ZoYnx8hGjGt*nlQ)!f|Ny0?5qJJwcLS6!?;XdoH< zsBm+1Y|Jg%tuJs-XsumHAhfxnwgxWjC8+YmHuh@D@;2Th*x1$K-iY~mcSp{NOi<2H z6uAv#LAtlN2YEx;!Y4D=f?0L?U*O}19H8ES_pzE&hA-Am9Kw@}ay z8OtD+X9#l$cvlfou)gGw&lCk zp4EQK71hY3rd|`Eh;EfBw;0S+ePBU*^3tg2VpkF8fOG4-_uYlj6G9RS!`9UWOPYO} z3$4Sudaq}bTAbqgq7`2=%gXYZ{Zsm*e{|#%d5`+x&GsZuT-pT&3Qtc@c+dz8bkcd25FB_vKo{;t$0i^k zPyie4r?|LsU?3%|GXq!!vOR>&1z4E7s;XDv0KRHJ z6A=+14T@S|S^=u>Js4OJR;8UCA3RI&&;WNyRzrgljH$pg9i<5b0zKk9$jS-=CJD&R zmrICIc2uC9+Y*8=mrJ`pL=L;oJSdiD0Wmp*`hC5O3(x=v6c%9(0x-a%Mh9%i@zJ)z z+KW3hfa9sUTd9T)qCQqm&L$InaMC^k$sHK9yYUDJRvi>#v>hoCVjQ5qK37%6!_5H- zy2Grfmg=o~C9?L{)!Ook)FWlXc@dem*kfhI*yvvS|cb zqVIZLdpbX^Qlx?nvqXdgDVJZ*`o#^;`hxCgHj|9kc%_;P+D@~$Z^CS1=$9rpXkcKL z$7;>p9&5RUgJY?Ol`k+Nvl5QmR4`V<*%_%xTZTIoZVn%v8%RJjRA6j~nxi?ylIpus z@WL=;SAR2Lj^M!Jg*d1Uif*e(^%A*=En^FjuOIK?S$l|8xqlUn6Y`rV+i2ZVqX|zk z6h9;3X{di>_bG?wRP4b$;**V?zsEc|hF_}zb*=W}$MwJ!5uLniY|IRvCkR3GxhW`k z4c>Ha=j3n#90Wm#Fw{8=S7kbg2n(k}$|o*fGvt_^oh`6ZIjUr4#tz#fz@3#fG-QEw z^x{P#^9$SCL}7u6z(2DL9k_&=wO+74UTWW4dXMmaAn4u%Cm*J(&TwVV`ulI+ZeHb3 zuYVCFoDfpp1f0BW^~t0$#GGN7BS3z0oF-Ga+=BYD~m< zG1||ner$^V@HAuR*TEpPM`5AmdKJeHj3s?d$+W0D$c`)~-w=`vKg-u*P1U06NNR5) zYTeiO3>zO|BUbhB<5(#gY-uzm$QhI5#Va0=?jdm@8B02or2AGnC?`bYG`gICBU7Ft z5eRii_vnMGO6C-YQ-O~j3?IK?DpY8SfS%;`NWyB=_9!!&(P?GmlMXi}-^XY#nIHBj zuGwf@y@MBG9x$tE=wiSNnYW5Qw$;Orcrp^W%e0CvlDkePY z)sV|%TG|libb(Im(b(yiNbj9(9}Rg%6LSVJ*G8&^5W2&u#lQ6|POLQT3?NV8aB*?L zv=uk8pbLoIAY7hvYsu$xrUMwa6R-`3b2m&SAesS-6Jnz_H#bl6l^zeq)CKC%spr!2 zAIG#`GCDajIvoijrHl1^OCEX~Qk7f;*qGpkSR3*?wd?#T|CBxaKP`Y`?k9ztkkN?M zI1ZlY;J8lqAi+#E{wvGJf0u9DB`%$@RWfn(YCmU;>wospMjlf?#C{hh*nC$SWJ22v zLlMc>mb`kP8|f1%+tFEcOC~A~Z$M_=p+itUy0A-ixLOLsr7y>??5#I?+d*T^9fS4v zaf~b9wD23bqULWmGje~ce(d`cEj-u%lG@!?OV;9#=Q#$&v1iE^JtPk)Taqct<_acf zooXFW-F@=ejSF$CQ)^?5|I(*q1|c_~e@)i%OO&;wMema1R8NB5>Ar#U+-+ z$^UrFsO#(BfL7FOv&7lf2;IBoh1P0e5Yn5PngThf!GKqfTk!Dx&V}DE6GFQV%(9@s z_V+G>K6U23LUitKTtaSyXW{HT*~W5Lk?I(&!OOigV!u0Ixx(ubqfIp|^Nu6J>d~ON zKCjuM&UyEiXIDl7weGS<2qs&#dwl2(29VrzbmHal8t^lAkT6{{*Gg zSl&&hBn^uG`8BYI8{#i?K2mx9_)bgA z-^+t;vo&sO7X;~x_T{y;=ae*^N9^Ez2niutUS0-7wdh!*kcF#`;9!6M53mVz?{i09 zaXQF=y9G|WnV8xWCNxOKZ!j^V{ znyl)_a_)o)?jCvw@M4l~fy%xnZE0D(OkhE<8tS(U=LSOiP8w4@8w+EX@- zzR5`hq0j*2Rs^+(syZ$2Iy>z8v9&Nar>v>DVjT;C2$1}(D?|B&EKyql;E{xpRDjgw zrXcW`)Pax%!W4x43dK62IpqPNWvRqQ&LSbe9YjDi_z8rl2B6bq}PM|9j!M?ZAANk~bh6cjorZ)FZlxv3_21@dZiu4k&++MPf*0+i9Fa~uqOprWQOhky^t z>x+O%{-ZYa?AbG<)B^y4k)olYp#w87zZv_cmtO8&Ax;dzbYh@3 zS$S!8mq=IXzNrMh>;1MVOt0JzbAOZvZuM&QhqILNqx%!;3Pr5=)|y z@T7r^27%5Zv}&M%!2~zjVNAO(5(i&}E8D1MIz6mSNzPHdeRy6|c>3p@^^)uSPIaX^ zfx8rM2m`EYuc4Ixzqh6ootOsfq&I~|{6ecWp<}_w!*dBXeNPCMw>KM!4>C6n51pa! zU@^+Z&h7$rkK^K6AIA#)dG4X>#bkN8#_$a(l+ zEEU>9S3*1Co$)&G$v%RmfsC9G9Sz)b08|)I@b#3NGP)j-Z__y5TnMU1o)een7CxQp z(lrDP57Y+Wl_J=cNCorRk#Ua1e+%pH%_OfuC#1>9%uFdP zB;(?0uFTHJXfWX)Epo88S5{XCN=Sb@*gb&_MjX+44;EQcv+jfw1W*VZ_7A*rI}l}> z{aLj?d3@5;^Z-&!w_@txro_NONE-xBg{j{EuO(=Svdz)nTYQ%y-ZB4iHDSFh!D5OW zYJvhAetw8g-55NB0w_oOP@xLNL8dM!{lrg_FP}JF>(G0U@&Phb$%T9f@6u3rkp7 zwLRr3OyN&m`wz_%jxP#pGB}7A4L0od(<)OPNRyASHoscmz9)ltT$0e z1^l0l3pQqltxd`|2~cF+M2NJBiHcBZ11!f&zzvAChXRHZkPZk<7P=EKjVm7}guteT z)K1~M2UY|E8b-zt1CRO9lP6@r3k5%A2u!5m@jP)xUQVQDim>Pr>ME4@J7KnhT29&T zi=O+1Nqba7Ft+QSjSUZcF*s{1tM^o)zN$qh543Km`5S=29e^W#vJp3J4kny1w@J%Gi2+XYmD|w>9uypW$O{7_ zIz|8qf%MnFQm2U8d|hZ)4fFzlzUVh2jKiKmE}N6HD@FgwVhz3_(HIQRLuPpa8ucdZeNZL~N9xYb zzww~;xoAyotnY9qtz2_`xoXcz9DxFY!}Vm2S;D4b5_*9|(|Mtgq3=NZ#CERb5|E5% zdyAcrN(zkCfyr&XWa>++q8R^IL)G5J^H_w_VV&m_qKnxli3DpVeLd4mUM|79mr}un zBiFmKH>&J#Jtc?<>O9E@c*sNjFT9FAz+TMUZ~5-cNk)KQT*P!=(gw4?MCu16uB-B5 zX*&NVzC-O~tmCpg1xk#YLboA7ciFb~kxtQo^p+y@CEOD>8IP#UU(|#N%KTd@{BKbb zR-xn3AYgs?Z`}UZBed1=SKmE=#8MBNT_@z>?`vx%AeTqTKhSG}jTD*e20m|OG)xej zDxeyICt44_Ok8|?eZWB=Qxt(8kOsL7TYBOBPcQ(YaHqT2rygp>~IzqMxIe86*Nf@uH@kiu~!Sw z$GYL!Aw*xAka=K&B4-*>2>>TE2|0N)?7H#$Ga;FF3D9zb`B(bCrrS6h z2Rsu@egNa=)GteZD(ysSr*R7})LJRROM;aTc_#AjBQFV%qhX3EI();kUT2G5<^_Hr zm(t~?PzNYDkTAr2D09|%j1LrGP7gv;0_@qWjKuLJD3&AGP`V@$2g^$3g*=c=B_ae% zus0(|73}y2n?T|SNK15m2RP~dw&$~^S?de@PVG4Q;t1%KCsqOQKfBLM;H6I_kc265 zbJ3cXHp4QqvUq@V-d`HkbXzMPf(AJSOsPSl0XSH;;63SEa{ms=__D!a3P`-io%{K*(*FjNDM_1RSN*a1NhO z@C`mTT_c>PzK$-kKf27+(&8H1sjgYaoOj^ZWnbc5PhGWEU`AP)T;5>YfsIKqeo_i8 zx7Fr}0d&-qcgxd*vC=!fI&V-rXgwp?AHPnFO{F~1O_3P;KLg5~c*kiN`G*4FI~ov; zR$j>?%`RC}%GIgbBoMKHn;7k(br-z2U9c~?74WFz!^4B2GdBSF4lMP){{Gjswewta z`@}WX)u`>)KZ*f#)H^aF`}~u8q}M+!H6Q4rKm(+uyW1EdKCzYVk37goO2|hbY-fbB z8B_sC>F9_gfsYLe14R@*0f7Om7vPHX0dzR@*!t&0dCA5Gcvd;(u|Op;BAQ$aECyu6 z2{iU#i`y##Z0uoC(^~63(xXN8Riym~OAiK}ZXtUOyhi%Gu~3bF9Wd&7xh6H$AF5bz zR5T>woJ^n5*)fWVRWDY+u*Y$|?>8JgE5a7Ik@=|r?LdZcK`{{Vyu-irSXI@CY;&ap^m2c9uOVb;!= z(zR03eNmRX(t&JWi(>g?XSl~5wtu_`nz*tjoZXgM>|kv4c8`N6Ss2IT2nXC43J+Mu z*z2VW&uB3MC0i|9+{nXoedKez-_f*mz8>C!WQ=7DM@HOx$sW&_bpq4Ef%^!j=Q-wu zvEXw(dA=NG@5fPjE2wUq!&vY$D60;7JJlx zyN}zD%?tm(LIVgA{N{@=0|CbE3z;4ip@?EYkf#E91|Z8_#kig30sdxic5(!>OQF8? z?icMh8K|_IK*ijIe?MqI%M?0oNQ7o)W~QVX_vcqy1e9JK9Bu=lL5#_)14_kEP`4XR zIz3L@oq1PjXE6nw!SZ%HY6^-a?m`)elJKu`P~_RT6`Vpo(F!|%JHYCI9iRn!AiIj8N;WXfF^k8w-B4Rp1lXWeEQi7w95#9&+|hEHa1cW`2GM6lzu)mZe?1*X$EQ!^zTfwKy{>Uy=XIUY%7klCh5uTlrK7ju zqax+8#PBENz{AhBg8U(QwU?fIy+27IamTARovp5xo+Y`b>m1?GnSd}9bl_eV{K(wwIij|(xJ3Q`M{2XnLwKr zu}GJI_Nwm|(|_8G*s~?c49pkBIa@D6mtIYExYJMS51* z^W`eLumo)bnoH~=dzf^W^LllTbxc7`ZeH~bgrg|eSBUk})6hsm(^_remnPJGDnYve zcw>uf5liJ<;6=`>czVqwRaaW*x+P^VCLa?M75(FLC(rKQmu%#sP|6*XyOEr2Ep!TI zauC=WCHAB9prSJDutOk&D)pm<-%lSQtswseU7=D%J#RZ~LfkP(xu@a2Bu1>t9=JDp zrM5ks?oHKVn7O^Ae(B9GraVXczO12O*E2oCv_a0Q-7b0E58EAM{qr>XZv-c& zKZToCZ@H!1Dz{}9)x|r^dT{|wp?jq}K1Fe`nVqMqexE75_sw?C-Om)BJX<3}^@v*Z zZJQWHXk_EvP}^0ls~#{i@XG4T&Xw)d4b5D-C#W-J(=+5*q5Af^@@>_het|-onY9$t zH7xc$dxN+i-;Z89V#g8|zeW51EEsaSttV9cL)W0e0}10GR`mro3h*USSQ+UhqeVt! zqj6C8{@XD?9srO`sz1jaWfHB4^3>L?ThXJ#OH+U-E1JIM`}b2yV>K7naZ-v)N)BO1 zo2ox0IGyiR;#nCOGLXF@R^t0D1fJq+*eOr+TG7A10KBsVTp+0Ckrf)?%VFt4&8bCf z`reLpENM(@fyM0bzhSURNqOrx+8=GUvdQOUd%Ry=UYs~w=jBy2Ha{6Zx1iKJ?cRpi zM$u#G#ed9if)<4VNLQuS4OGxPemzOie;EUCWHWwBN8&fHgZtSp4E^QTT7LC}?(hO49he#Pflm;LZ8 zYxGDgFh|0YLe)@-hh&-7hD{^bhfZ=^6gz?td&#kQzIGF9NdKV|>wQLy`{(V)uWdVzc>~p)-%6;)cdYUBO4O81vF@^&ZIbsNH@d0$ zV^FllZ|l0yza>>o8X^bhujq#qu{=@hHkI6^6P~!2E`xp2dhllSMJE-LW8%vvtMBAG zyJZ+YoGiTVzk_Y4T+OLydSnenmq2_*{+$GRXg{U8WBO3GySPrLSUHasoDhegZ877ytnxAsPX^g;aeAUb~TG zz=6yCZ%=VBLek=7HqnTNvNc3~CQ-#X17t#x+GkdD_WxfaF|q}s66nboA2_fF$rjeR zc=YNVKAik~0*kueJrY#*ywl~j2=Qa(A00P=h?Rh>38cy%wFVXrW82WJ9^bs}KSAhA z?7h*_+>#tEqju$C#PGMbvyuz0dN|KuH{Qc~kG z-@ktzAMe1rbRA&TC^FIVBs<5^f92WfnA&9O*j|&Al$54%J=jyG!-fJC0OSPi4xD4#RUc5l8vy5c&( zbDe=Xr;PIb7cNG>Ze0F(Db7Rsyuzbu?gJ;A9z3~M%2UpF`Bdo!SvIM<=1H5oY7~+) zyAQ7s)viB%Td<=)kbe4lfilk4nn^v0Ag` zL5)sso_#FB4SeG7Xerq_>Zy%gboFCf_FbLP?iEs4D_mV_06yzL7LQ(`-Zz0KJLGQ7 ztL3Xo?b2BFVb#Eq!s9nFk?r5W&8GOubnTs5jcLVEx>b&w+b?|Wl-+dIKr1R|K=6&~ z8|SBoK1}=$ZY;i4m+^D?j7PbKefghL(vM37mbLT?=FT6g?Fir-V=ij5Twtczqpv5c z(|eJI>NQ`&H9MTnVdkYz&QJJOMJUzM?p`D08<}c$>e!O!yM*@X3s}&Rci!_^bf3bU zm=;Y-^)VBS_}Ka{R^3s_TWQCo-cfp7?$;40cwp4RbNK7HjIi%OVERGg_N&==3_Rss zp^Bj3oxVpr(Y` z-~NUB_hrfZRWqpQ|9BHn5BbNy$0{E|4=O)DUu~?k*iP}L+F#!y`d8l~d*jBwkB&01 zR&<}m*cMhrXC3pes&4!1+mT-j)zKdrw3e1X+}>JxeP{t28W5=)ijN&9Xy>=T>5_jt zX#zMIpdiXpg)Np}R(bV&G(*bvf3{_PX|1Z2)T!l*t~|+jzLmcJLPeeWuX%p02X_a) zGdI+hkL};e_Jy_9S8}TV|J@6Ho;~HYWO?DjvyH_pHMBP!q$i|&(ibCW1`HmpK62K& zL(=rcxdn&&elv`l_wV@o@b}W&wX4)p9%y|$INXqyxM67Xs_wZ#Jsy_?no)|+Mf6VU z-|9-4YyB9h8aMdM%+l%Yxf$${{W{x<|Sk%{N~`olZ}M-$Kv)pG_^L=x55ZUVFIRf6UiP zc1=t4%tC6A#lgCl%N-y6b+kPmSW@(B>O@?KpnaI%aG}JSmOY9$ii@j+!%kYJRw6gN z(=R1SoM&&=CYiOi+rr-N{SiTHVi#^bPHTM2E7vcOFQ?;WRs7=7E3{r;uKRZka3zhX z(Vte^64-m9?C;Qx{0{Z&YuN3}CKfEtRZFuLE|g6^4c6bdB)F9|V$@=Gna$*#>)&YB zfR6{u0|Z~({(34|IpvIfctKdy*@%9R_8VXGG$K->bC0~QGLpO-f8~av@Xzpm$x^Ad z5Xz2iVe7a4ogWJX{I_u6)PJO7|E-SyU?ykZ%r-+f6=VuVrA82b*7z6tB8!O&$n9(hA zA=<-4!rT~&n#W>FSKkE8s`M(sdS^+168iuU)h~`si*$-GDTOl#^bs{=EhT} zw1cmlpzr)7CQqpw$rh+vF)A{hlf5nXb9Kq8%Gn#@)%Kr+)#_?#n?u9Yrw=%>B+0+% zoqHEaTXdKH=TGh~zl}P1+{`)6R7Nktiqmg$AC~Cpc~qC`db*uC%u&N@Cfsn}mjmxA zjQpq{Rj<0$8a`3@`oQE;S{m2QYmr+hs7n`i7BSXrvU1|5Hu=22#%HNqOgQV&?PCvU zf21gIoe|vjQ`@#DVlU73hmwVdIE~sqT;upF&RDyb`jc$-_QJy{pKF8Z_WVt7I~E?6 zPm^?nYKE0E#)vZNJay>)mT_*A7|QRN8qDhp)~wyyr8F2Cds(L?iXrrit?%gU!TPwa zpv7~~d&SzqO2Yl(CtdZKe#sj5-7}3h9Spj9Tl;9_%BHt>T!%jy+b5=`Mq=^gZGS7! z)EuDr)_^biBqp9cgs=mF&~WZ;RvLJXN_W?>Cm1#q2fyXa$j<53%a?Oo*gWal zZdlF6d7N)5)VQ(Ar#D^CVZ!%TGu2f}`PIM9>O7xmp=W33s&jlEntinN6Ya+(WWYRs zhBmx?|9+63Taah{dTyKQYuxxW-<9dCyMF8?SQEBvi+YF(XYG!&5C56d^2#CVf4Bg6 z(63Xj?9Mvk5M0lt@zT>pWS7sVif9*=L|u*7U02l!W$vqL{vM7@&x6}Nf_HkkS?zEV z4mc=zCf6fKKjh)5t7KvD?~F!HmI8ALRAP9z*kd>5rln>2bc{DQJNqIe69#*oT9n&Z z1=X~MT7Axa*U(CN;4F2$py2+sr^AFV74U0`5;9^z9cR*Q)i)(LRVTcv+ac~9*D819 zeb&)vCE2adJGd{|tXc>@WajAbAyu$reChc6!R-!4a3c730?8!$HDaFP~?|Il4xQA9*sa>i*7km;3st0AZzxq&H9IT}%fl zEie8_U)+98ETV1ok+AqKm+et*SxG0i?!3>JyY*muu^k?pY!#*+E@RC%P;SbtclkbMZq1h1 zUw8?iVdL}X%y_!>z??t*uvloB(lRf%TpeRhpwuT$lVgKyk^5@4)4)zxvT+B48|i4L#1yMZGB7hUkCj< zsuA@j%k692c3a<59%tT$4IR%hrOI56xRblCn&P%H%Lc|s0Rb-UJ)gX^xL@rN3>z^W z44$W_T(j3j&9_zK3cKy!Pl<`a%I90Ut+wh!+)%Ymqh5BPOkt&e##^ZF_;vrll8uYN zgpJ0mL+4icKPd_Ulb^Dr#ilnpk2%T6Cs)7N9b-flCA;v%=jA59C1r zpIDkty%N^GEkS=_!s6xy_u0+S{#a{0+=J0#tdEaIJBAMO7^ZET*J64Mgq={RQ|*c3 z4S^^&7Q>s29?~+8=sriSqR6bJPJM0<^#T9jpku)!+`*d`wRUFCUv81BtxgCEo6ic$ z)u%S0nd}w}Tg}zGV|10p;`+*(y_`wz?(_lzYeJ+vl)?=a8)}2bL_1$UzEv)Mt>7J9 ze*f0MDiJ{no1W&fqhI#*uf6kV%r*O)!u#sMvo~b26tHT}`StqzuEU&d7M80Y?PSQe zIL5hcw7-tY zPBZyiyPt8uhvMZIGnsw7h_~!q{A*drfAu!xNofw-NURp#S2h)N#9{BU8UUH!O;4Y$ z#!AU%C}K{a2-?e^cj(D+S@JH{uElb^(vDwX_PQPw*VdxVwxcjF*p|DVT1)5VXP$`% zjvMPe@6YnhN&8EbmN_s}W{-aBJy0acXc&1m{Dj$FlQ1d@lNbu^2yszLtqHxUwOQ0L zMVaDRCT;ah(vPL1?$xfk%0b^;M|UK;UFCIY?$E7G5hvm*_&o}DP**Q+Xx;Edk!_wz z`ib<1!>@C*E*k6KN%Fl@#P4h)!^Ta=(?hYlh~hfGo4R8HT~IltaaEeaf!DdVH}?oq za0jj#u`%cOW>5NfbF;{8)|Mm*Q!Sx4%2jx9CJ(|NA3vhQx%Wfww(90H?`LkDA8ni9 z*JgCKD}8L$ZFYP`pVnC7{H9|yzFdGguPV`Z#fe5kylqix@(L%rkfELB(@$;=6>Mb!fCyZ)`2^H-xkXJZb!!C1JHPw*N^1T*7g`{ zF5Az{r`?t!!5nl;+{8Njr-=OCwpaRVvo_?o@(b3%X_$IY-@>_?PD~)74cIuW%{l?U%#H8NbcDy0Y`qRkPmgsDwc}{r7-8~qKx8VRuPfx zzJs^?Ha|Q2=gaf;eUE(B?1b(#c~GMU+HCoC_&e^gh?yuBra zs^?Mg$%~YwdqR2>Ys0_xt%=LLs+BBJyf1vEvP6u&C#>$84PHmk# zxmr|ZI=a&L?qlN*ER>_jpvn@=Q_nlKCBh@}%q{f;JuD1!+zd5z=A|!sUF7ZGu3@NQ zR8eO&_cxlX4*FXA$Izr!El7Mi)}A_{@a)HmTo=E#%C**GG=1-reNdz+TJUn7$jw?x%Y7Bqb8qkuP> zmASDI(TR5%j4%Bvzf$~JxZrKjfZJ%SEZ%vb8?*6pA$Um?M#!OJgk=EHBxZ()Cc{?Q&T3l>aHtp zrA~fG7t&8T>P21VE;o*tK{a?@BZuZpZ^XpIS}E0)v&j{;o0|ng51&ZmX`(0#BaVQF zPn@?XFwb2S5|WT$WDF7RRYEW0od9%=E?5+O$vYw+uYcl5UMN&1_}mK3B_8=qZfa}G z&d#Q!05*f3+PEavPfKYv|KRiG5AO*JbqMwtwY`L{XXS#S z;Yjf}?-US%H>jxzgonQq%X#rlVeZKv!#5LBUuWERy@U3|Vw|E<#VpHH)QO|3kyu(|MSDF=J3Tvk@r%ZFZ07LUBy z0qJNLTh-i(7OjE|?Eo?t1_lO=7y(t+1^$>YiO^q1vou5pYsEdoeQC7R*6!rgQl%@b z5sPqpv6bd0Kh-ndD{a{Vl3+b$+?*WXaqXgoXcI&kpR=+!`NoA%PuEVr2F zJR3ICRnD$=wqZA}63DpOHt&`tKyB24vgL1{S4qif+U{?njGh<#wR`wH+B#)ujzp~; z`LVpl*=_F^DfJz8+7r({EY>&K+18xAC_8f1p3*~!`oa5?0Tw#P7F~|@Q`u?;^)w95 zB;FZ)cV+Pe-<8KYS*zJMv~J5QQcbZ+zok3iaW%k|>Jr7Qq~zp=rY7n=d-lAA!Z8L0BB4iP_lE?EU8}p>bTq zn5Eskr_84@@Yx9FjpgS|XzHK-P%V!{FY#4jcUX^3md&|yOb|>U%gs-}yT1_%%~9yOW(X^}AZjh7X#29Wf zP)3pgL5Pov;%9$d4D<|}UcKS~Ioa9Wy&2S#PeVf&(c>?C{;uY{7c_zOhJ5yDYZvf$ z^}X2s{j7P7uLll7eM18l4yrVO#a03s63}D5>K?0n=?FN>8 zE86@Fsld=w`r4Jp%E!m|3&TzIuU?swWU#UDFm<&0iGVxbE0Pl*`mIK`A*CGjRX6*t zSgmJLoR4MiljOvs(VT+gN%BH>)B7OIP29QB5-t~C@d>jDD-^bTMUJxTTiBlup-nwpx} zO~0$aJPXEqucRb+)WPT}@)F>2YkeHA%;&a~DH0;Ce)^avcSh*0D}+n@y91A}B)T5@TC)e}(i71^<4?TZ&LpfF@S-w8SDs1eky z^3nE=Bgs?pyt2m`3e5{HfH!0V{^y}eXQ4CQ`I!?uRh{ljP&#_%`3SgZ!G8NX7{VE8N zwz9zdo2A2Ny~DXwx<~c)%}-a{{X{vTbM!>$NpJls?=50aWRiPdj3jKi+^-Pt>cV~Q zz;7*$*lUXucjh14r>B&6ux=fD_Ed>3i$Z+V=DPogbZvzBK;6E>RxwOY6t^~=bQ(57 z?$?B)WaH!%1EyOlWTmw=$r)$``By0Msm-ZVmodJi#~&W1U*HuYqOla=?<(9y6}g46 zF1?XYXRq@4PUAhH`{hTv-cXlyyX&`qpDWOB8zntMC$0$ zwFCHsG&OS!-)+{=s6a_vPTv3IJU0#P?HZz`?$np6U-= z7D5jQU;*`p2wF@B{`&l64bYOasZzP9-6{i@Yu`^kf(}rTUEwzsH`~*v!w`*|9zSNl zjdXO$$iW1_F@y>9@$m8vLM9+d*$e6@3vMX+WQ^LLoXtfHR|z~eJbYfMZbT=CyV!>I zVd(y1E7cyCC*l=9sw}(YR6D-27weeXCJISx9$8Bv-%BB}k(sZp$-84vLD9#L<8-{u$;5c?fu&vb&8Ej+ZKpdD$)>IBlW9NS zCKh~ICpg8S#j+{Jh$1GM`t?zY=X4Ru$DHQEAA0xhdsgd|U|QDPBX79eR9-#7T*V}+ zMNxP@OQCSrjF&Q{z=BAt`bL(oa+ZBE1~4{Ft-`m@Ovllr~#IXzh zl)ZX`EQjLW*FUJ!?lfI=oO|lGd{6vU`06Kq+y(lpR?q?6g_1`woK$YMGXB$JDf0nt zy|uyF;@+=1xyP2*Pt$ztV-HdG-Sll}Zpm9ivMDfOqPY35(PB&azLsZcyloYRr#Ael zPBP7K8UN$oqC$PHl`3i;RWNnhO=>XG>Lx^lh3ze>-B&@jLK9M*C0^qn%WiP%s$!WE zpRy+t=DbPb@UiB6mr@0X$-BXq&(^U#PtA!oDWavN%>;q468Z9xvePC5i=uw9(DR0Wv=g$dH40>_SVo*BpWc)Re>8NsC9&B0tU?jOmW@}`lfM(ZR-S@0m zL0HpiXdOaDv&6n@6NVYGU4~lcl%jJzCMW&(a|{{f(64xjnz$a9&Fw!9PxxwWjIs>X zWmKZmNcbD{vsXzo?#Q>UlivM#<;h$NM7A;~C;_V(r7-0(}l22TYnTTk(uu>&08P48wyNKA|)EuIu|# zliutV9M^vx{P{=e5e{~f&F!=z0h7h=gx&16#lxzlZ6>?mLG|wW9ZtQolvh?aCz;S!sv^ z92dQI?V7ctV>I}?gO~@l?|{?^D>~-SyF*}M!eigDh=h>(?D^MnGSYr_Riwy3`=8{n z?Fo_-f2Yo>oS$X_2J92iq`GktS{SsWro-uM~eez@|vJ^yM<}oGYREpO4#1<>p8#jUVSMv-I0h zLUYxsC)va7aoPQCb-f2|Cm2t7H-P9J=(i&omqEBd~)&F)^p91PCp~gos6Q$q4MTudc;Vz<;aQtVtf9K14m7C z6V`YP-B|B%^G7ikT4`!X-FDRlEJ`~MXnQjF zSR|B#5b5%s`@Qjfg;NaPRDlRV1x(%Eo77iTaCb@0JE{BXIn z8NiG3YEJg{PrjSb)(CKoJlH6S$_dIvByYY1XdAmXgJkSlk4s34w#TgRF#Po8N~v)n zXH_xNhR+d6XPz#Mo%rh^oncBLeQTV*s z6)=*JN==g3MAV@?lWmmj4HDyD3`j~-3F+kSNdP4Q;JV2QxnG?lm$04Z1}SID$go8 zXSR{)FKJ)1%=7Gg)0!D%YCV+l(lz%~MU6jw8kD)t`lG_)gI7Cg3u_(r%qZz{vb=tr zd8j~?$!~eJdBJg^=MCXu?O`D8SYzJB+0Cs91?c^K^9DY7ATgs$rE%<-AYQ*_j();R zJj4P!90uOvV|A^9feXP{1V^=Y?TPOre|Y83Sc6lo;P!L@6N2pcnI=plZ?gBo@t}4a@&6UI)*6jvFTXmud-kP z!48+z*c6v}=5-;h8p4k}N|oBY&4DRsE9EsNUl@=#s6KmWS8I-V>8Y0QCM{;EJ=Y`2 ziNVZ{1<+`sV}*2>-tvRRm(9ZMEv=JoC1Y7)rd&^ajx4_#&vMSwQ!nBBLH#(6@gL$0SzKPe9OP^s2vC8oJq z1qE-mRy8o_nEIjevXT|Rj??_T_4QFv8kY-fk3ci&7(>!d%8%=XucJMEGx+0Hbyf-i z0orQ+^hsC8UTTd$YX*MnXSg_ZDsDz!XyRaoUSLK*#h)pw4>U!^^zV&0Zie4)cknCr zy|Vdz3JXpA=K86qtgD6gfhGP|W5ng|ue(t(A$jJudTsdM*GF{SoQ1Pw2e6f<32Ijp zV-@`X)y+l~hTH#Z0AZvoa2804P~3^JivWcuuqEohT;=5ZKhr0o@InyB?qM_vI&y?2 zyr8^_c)WFH$14nm|FoWfvi<9#V$*`(`*#)JzI}9yQzfsnHj3!AgoG88+ooM%(fCI&(0DMT<(1*KI(YOsWoc{ukXcsg)gl=*JanTe zv(h6jB<}PI`X7Qpmhx47S`}rj#PfGIW7J>_A4Dt*y58P+U)xd z?63M4KyXi+)gJ9Vpkm$GDXH=V)v z@NbVl0t-}8m8=bL-D7b3x_oi&#NEy#DuG_Y2H z0Cl>O*O}|}8(AgE)4cajoA+&fK%vYkb2k|*06U%}N{3Cyt<=BY&mG%-X1*XPckJd& z8@2Dc>$l}--j7^62oPuX&6sdR@<*TdwiV44_b%rcRQ9R z-Fs>aFO@7e^KfGB#PhQ{n}mh0S%EEyVU~+%XOMu7l^MD}*PCQQlv@yk%=H)%yaZiD zn~pS9q<9HRYmsIIL!x&GP!#k{cOhLMJ3o<$=<{D8rKGEn8H}bt6Llkd!j2!ZS{v<$ z=BnO$FJ10C7=P%Qn?^s)%i=8_*IsQLR5PxU%DB7D<67U{rP)oR2hR$Tp1i3L0C(j1 zEmdwK_s-8a{`v9FY*d#^-`JQ9h3`dd*cb%(IhQh>5|;mnfst`H$s#7d>_g!a5MX#v zoHI%O>{<-*O1lhdEr8dWnsyDhmCtGSiQJM2-QkB!i9&G8R z?ru(0{a8X83f@9kK0_3rA_sI-o8rWbFamYnqRLep4K@6Vr(Wq2n}moZKK(R29D?z2 zVdUrlvw!{h^SS%DmeX^bc5rhpVH#fI;1`t>hZU8S2GN6Q-r4U*jj;~$L}KaCY`9QU zqiSkuIxs#Sle_PRK7T>uZIf&|VBf2dzmeO-4aBWvrI}clBA6&;xf|$^HSjPzUwz$zQSJFe&_cn?gvNxWOpT83=62Kz5N#xORA`-WEhLz`gi1< zN}S0ZNQio_6K?+ix!>@$fLv)6>g2 zyywK}&_M9Oi$DDJ`}Zbn79rRtOmoF>kanA}zv}D^&dU?q;n)|3@;VbXg#0m{oFR7h z;1JR|Hm5|R$mAzj^fI>14CKe|O_WMdGE6qk(dR<4F9eC+(o-GRmC)R;@mQF3!D(27 zIkXlOQ#RmWdx)BnAO`%W6-kdYc3~_r?S?1DbU!b#0Qe&$H}vS%;tUZB;1XC(5TE=; z>qMcfN2KwZrs8t}-boW&qEUqtp;1xH;1F-yVo}M4E<`*oY!X7YDf}7h<<<;kBDEFr ze{m1d_7HGEI3Lz=*tI}p-e;JI4AyMN;4 ztHJd8_ACGk4Lv>F7}Y0pl^9_nhhIxu7Yp*hRXJ1_pn84l(NIjwiAYH3|I0(USeDQ1 z#y1VGeaOU4P-7ZwJ)^`nfoCc5d-2IrYHQUXksOZt2x*Mo%Eb{NXF)TUcKc$mfK6C9 zq47!_T(1DE5Vkzooj{PDbLZ}?9Qv>*2;X9j1M!HLS@_vFISCDoJnfKwmiF@=ENy9X zf(LSg(v2bvAxtCn;%wlUQ?Sf;-P9CBNlki$e2T6#C>2pxbHxF(Zs_k9#DY51%5A8l z|6SSu2g>y{`JzY^#5>(>uGIFr!r(k>57 z@LX>>GhSf}AedXxnp);k*twH|UIha)a|puA>NZKX?c2AL=YYCei`*4X)xYb0eg8mG z>R2rkzV80xEj#M_>*VCKn^ZM73XxPV4yj1~uO*1*euAUI00F7tZbh5@^!WOc5+06R zlo&CICJFXnD_**JlOJf(!r~%25^G>-t8SYYaCnY?jKVRpgZ?~vN|#scoTt0Uay_8H zQ1B2_Q&R^%eWE1Hnk~fCUH>!nTw>~-Z!yjf?C8_jSQOk0C{K-K#vFgV47_pZQ`6-Y zTZ>y-oH+(z`gH&jS}-JOl4rkkSdTso8eY|mOjcXup9D2e`0xCTJ z`^IU|`5KJ9 zAf%CxYSum4F2v&~a8i`S$7Y{unYrh8|KIi6_|d z=pibhO^8d_^lXg{ykwnCUI|WQ9=bTrbH7iJ-Vn@zpvWsuPs`tromlz_>l z`~6;pcvb>17xlniBnH^w+ejQe=sgR_yjCtgRetUr6`ll>pc)?*en?}GNQon1HyHsV zOdxa@|Cb4*WzMu^>sFV)f9#1BW6rP@!p)hc1^+_1`N{w8U?aH$U-iX5Yk;B<{duVK z!nbmL#E~W*d;mjG^>xcjlElB6ekb7vRwZNqN)%f&SU@i{)yXnF_xP%ig7>ctWG9V1 zW*OUMsHv%u2-pp`CnTu{s=?1-FVMDs_9h$t&$W)O*qbs&>H=mz(Gymkr>CcBTV}wm3u0vVE4I-vD`XZ+inyX(mr2h2sj1^4&g zwaxy!HWjh+7;I0BM7H_m%a?zyMVwy#Om`3lmNEK81^kVia6Q9JW9!CCs}7ae(qh#j zfim)m`Q9ILCVdvzsWGbw0Wac$R_$j2^*ryaz} zyi`%K6S$6)2VZ*&@C$&R(nNp0BV9d_BuzM=^>1pzr%0?OY%v9R(rcv>W3JyPMw ztfQlY54&=RBRX-iT@ZUx6dl+T7LNS0vO?sD#JmZSsfktnQet8v@$&E| z8~;@*;UrJJhQs~~)9zqSP+4MrX@;&zc_ixIDp%Ay(1ijfjD z53=}R}rKU)vJV( zDLpQk^?RFw0uP$}ZCGA1frSya@Qhn{ge5j%OEy_3<~;k$<`9Mf`7bk`2Jb>4a7m?h zc5rps*&ddyN6JW2Y!ds>b(rz*^w<@=B~rfTA9+xSV}If5ljEefU3lOwqnDQ#>4t!e z8f363P6@1DF6v~1&~@8Sk|qX^{25O8V7#)+AY_=>G9l z=&iC=S>Tuuvk(lJ6#_{+HYJ4=voOou|B8qls((eqA?&fhI?JM2l-Y!(}F0@Xw+;`2__e8vxE|X8o(>Vvqm3wojI60dR!7F8t)USoQnQ zSVntk24GP70xdkNlptd_5+sAv|NCBHyH z-o5uq;PtFm*|@5L|6jSEA0A#NhXf}0&rOQPJ(0F+Wx_TSLG&&zBY#R$^OsnOOTv1; zw#gwmju#`@JCL}0NFdI2kV6Er@qA zsLBmezbP!SxKW>o;5eq5YnHK`r;+*e_=`YpI!%a<-ZI^_@8~90kB50 zBDAkutN19c;#i`#K6Lab;oT880yp1Gf}?JZDM62ttDhmbigPmd)ddOyv;8C}Cm9Cz zh7C4pky#)lTEu1FI`AL87>q+Z(2MOuzG|J&1{mf1=c@^lku3CK!6>=6l71%v7a?Yg zLZJo3oKIiBhM{Kt=PH3%1RgauT*gRll6 z6TfjK2~O-&xMNkr3%IEXt03>8Cj56}ga9LD^(YJ*wn>2nu3gl>^AN%O?>yYVEh9&? zw-A$;=R$xRFjv%S!IYy7XdJwG!d-xofDfQ}4o963Z>@AK0{@G*$Ii>Ul1$;AC@IiU zXF}Y?-0c9u-09ba#Jxsb`VXYRLWTbmq)DJyvt|tm-B|cukNxqX9cuHDU6(+;{+}AI zT?^MoJIs4(l!63Kek`Gd^yorDJx&d8EJ*cmD|R*bn9TB_p-Va3PBq^l$V{`z+?lCi>J8yP_Z5%G0V_T9V8 zsH@==kOmJS*y5Y>ZQqsH(Yt$il&TipzP(yRLX^7UL+vxSgFfkSID2Hm^E#=n&3u{#(*@|6lm0pKp_J;RZS;o*-hT$nsD3*Q(-e zCk^?+E?R&%>{Z|=wehFNh{^gklfVvB=f)QSu@>UqUK8 zbdgm}1DkH)Aw~5K%xiJ-kzt%1Rk)RtL)bQ?Yy@f0!;n(UtfT9KBKX~6R)4u4gg zi9Hbz!OdkNc#{{KcSj_PqvTYF0ML?p#A|rBrzM&KCO)3S?OY^t06Ue`uqJnp$gg~u zrpC5V z14K5&-653FTG)n!Fh?*85@|5iqIM-TO#dnhow5fHx|TjvRaOq*y=~#mI`{0^Gm@sE zXEuP-brnh1ehTc4t-oi}ByH13bFQy4R$J3t2xSKgx0D6uJ7_?)356}LB;ESR{+eKc z1Vujg@zFW}`#jRt6kx_sY=G_KU(_S6i5lvY0KfAGP$tpfr!mXB{9MbrWx`%rC@u>w z&Cl$3?|v@)%lOXVq9Vg^{$AZW+4noYn%TCANJz>Wnw_+_569)Rj0BgC3Oy%qFNv|> z?0|QCj~vz1zv#qb@v^%gl9v_WktOyscBQOPu|d6AUYKNsC2S%CO(Jhy@_&%@mW=yg zm1S9@kOn6=_D2ljd88Vq;L+-yudvt<{LkO^x} z^e%7!3STjNSNAtQH_z&u64A`LRH=EQ!%@&l?*9GIeZ4PCbuv|CyW=voRlntpLOf$P z;(n&FIB{wJ4p>+_<^Q${2{OOZD%3I`h4Pjik}rkx(_07tipN9hK7GZtEC~)IQ6NP_ z)OR>OLf2D8ftYEIm#j5+&~@@E>0RkrUkRkL(mqx9{YrlK?ZL=<&I66H3I%b-0*B4t zw02}m?&YVZqoX4*E_#b#@R%bU9l`T4Z_T-Ni*O{~Vk5DipWnde&j5$BOd)ES}_Qk@oq0oB#)K zVk-$e7d0Sb_-jpUK!rCv(_<#i>Af&3gYsWrdc}V({VV_B_4#;lAP7nYgBe0fO)SGy zLP%)Wm>cGSFnheS$f_m+sC>4&SH2KYoi@4d0oc%nlA?WxKQP0Fn&&`%SE`*8k{*TjX6-{ezU@&K0NdgPJ~m zTxnIJB9~R20r!n*{fr&fZHYD#Q^-0zD)qM*d>*? zmp|E+(6EpqlL$wGG@wpW_$C{`Ie$3!J@D_hJmZAi0}se;|JUup2TjFvQzO!NaKAr| zj;2h94nvl}+QA_Tur|rkIPye=3rJ#sz=d8g!wak_o}L8~VGV{ml3IWj*;paTkt-_E zOYC*_@83amC@;W-5PZARj^bnn%nfrBl^ECwzAx)q2548PT{Z{_QM$Oe0A$xhGaC*K zLor=M35#N&87J%DK_;<13c-Uy(NEO(W&e?=3N)G7<-M><-#_y3$9|4Q-% z8*G;W8=Bk*l0<^h5zj!bhaoXCG(0g8t0c^>2aufzp<%phHyUT8L;*%CA}&q{)A<%v zvdEz?!V&B9C*(g{k55jhSQtbg(FQDMGJ1UZGCjox5ZlSTsKQ3}giG*B!*Bh!h~$`t zBSA?t7M5TEo2eN^fb+~xOG4&B3ZNauD^Ec|z?u?qJdp$?S+03u=If8u|Az~}!JeSd zBOk@iF=b4=;qJQNtoi@_?W9VV#@J!I`@F>rjtrnHiW6bT5 zb#z$yEdrv_-@kuNwMB$i-GM@oqobpJ4>j^1IHTR5A)x?!3$Z>VU8071=Cug91KG=` z#%qUeZ|P`@34GDM>HKbv-EY}Aa)Tb59{BLavgOS8bGH`*9@Lc=IXQgLces7v?3Duz z)yCq&EY~xFRT!cwK%0oQA(8XF?NFZvEAq@L=V@lY32`K;10 zWii8b5S)m8o}T4_tjxW@>uDFi-hn>`lS) z)6+K09rn9dVCzL;`%mVS1k-pOfv{A%;z4YnG5c65g002i=$iIL5;ssgJep)WY&`4pYoE%x#RP^X~dq9LCgG;Xb&YhE3Pn*?w`bW4X zGJFW++DP*dEgeyN-LNieRLn$%@ym$%a#imXSxGpHwugUcHplK%y(4$8_d3%UKzTxh@` zq&5DnrePbCta@nb>x|dCUJL0i)Bo^Y^FC!>xpBLg!Y==g1sc~LPb)zsCW-qQ$5}7M zjQYP~%NNajYya|n#yx$Oo% zhR0>t`bT4<)U*_5Z^HP;T_u|88I7TAAK)sb7qTX>gA zlW$+q;H(wPxW%q-opPs-xZS*$2>#a##fuJY75UJt%GAm-7gD% z%#NG+%`9okt-oE8@|^G8+~#!E?H9X^1eJ%?Y(qOXZ1Lnv5MxPwQxZ0LWl#2}+#8Oz z=!B>mdRX5mGGK67ItpxXYHI3(BX-S_ECLb`pgL|nB`z!U;uuz}S@?d-f$6+@^XAR4 zC$>S#pM8TQ+m|kT&F(*!$!MT7kHz(MOmtXiUlb4lqr@Yzcr5CIKQ-$WJU+m6xp9xu z_19d5 zW!qIh$dyQ7J8oxx@%oXTMafbjN4iTaA&obKx~5xA8NxneJ0AldjTN=Z z`Z%@`s%`xm23z;gMJGKO_^jQ$aq9*(dm+tD7SA`T&#k_==edw;*oe`Q>%(Kh3TG6k z8|l1YXFO~>cy7PeHy_j%eO?pusmsyk&0vpS%6WDATK_BA-){SUIB7GzHnC@T?tB=p zEUi=BKrQ1@3!;Rl2gNMZAPT-U0yQ7~I}fiMK22?H+HEy|Oe?}y(_N&D+S7zWWG;Pq zF5Pgado!YyFDxqwMo8@9|p=fSllVRKDUiqrRhZ72t z?^j)}JJ2>YkZ0^!|DZZftZjc-spW}=fcHmkgb7x>9Q)f@8W6f?XfFLWZSwbUe&yn} z6M35Z^rZHAoM_(o-0QG_>NzEfgb;e)*B@go(@m~^JF+;e^@eV+^~Ja?t5Efqp`j)- zBUNo*UnKyg9_LG69haSWcPhQJukS}Ltx)saApU1e*8cHz3-8J2J4^o`zTPq{>TZn} zCX`T05Jgf%LO{AZR1~Cyp-Ta!5$RSzX%GYvkVazYE-C3ox>3537&_j2+1EW{%-;9d{9M& z4&?TbrnvGNo3D^F+~I*RMdza=OhSGL1m2pGsKI@9< zLEUZ3%fU6*m?SYoGAt86m|Mi=`UzQf)n+x*J%g+ z@R^IH5dvyqvY>}klew&2Ol5%i6!K!hnN1*Silo8hA zp*{W7d`)~VgdYNx-1jGMB5KnomFoE*|Ei;Gmb}ZYVFSH1qiXqxCspJs#9G&)aw7bt z7|G)w`=rIutf3^5eo2o>pmehR>RrrO?Dn#MNwslBVGODfd=ZGsxlVFqYuUM=20G(XNh@DN*wdF>D{|Fg(?Knv60 zoP=U&482^cuZ?JueOgFKkc)y=HktDi-ZMUiDoaOa`?jZ|D~4jq4;u{7R|7Gd*H+Q_ zgT+UCIEE>Hifc~V&er4$9=)3R`n}BFUxN$N+iE>6)o9jcs=CjskSw3cy}!LszJe8X ziJXK|;c+lSV?O$dwekvTXqPO~q{V7eJo_}*n~+qseEXJR-B0Ar#R$|{9i~v#NgcKP z34}wL?c|L}>Tw&}8A+j!ebP_n)4kd{mR@de(=n;)ud9m7lgfAZDI6Em;ZBhyC$pJK&F8`srq;rXksg?SVE zq`#dWDXjgj#CUipJT>q)%(sQ7b?qmgfBdR6LFVcsjUf5kfeC%CIn(d@o^1{86Zz9_ zx#&AylJOHUAg;n=f5{@RiH}Hbw8BkW+Wx9L6lv}A%BQRb&v)p`_Y-=nNO}JqlczG@ zuEtWavh>dQe9w(i+?wo$Pk85i>ygplTW`S+&UB(AO8FU_G$#FR_m9DKfmtJG;Xb-E zsi&hhCjt;KZ}C~&5UFu4@2s-4{M{DQRk?e=L`VF)obxEqP8PM1SBeKEAK!LRAx-5t zx~Eek;u;f6#UdOLsPW2Z=HtjZxlbAU1>=)wiTYFb=+s}xjK{nC9zB0(61h;v8Mk;q zg1Z(wldYGbw&vNdf*_lp6Oz8~7+&(Asw8<{&*$tHTHST(5(_o;z^wmKJ#)GKg_C*+ zNs1s$PdcE7=n9y??cH6p^3dn@Cct8XGWp8ZUtbbWb}(UZp7BKce!=-3(X%I%JpGFe zjfg+Py0(s@`fzN!04O={Tz5j#8b9#$CM)n5F#+*;} zO?xqM5;4t6-FEgph~75$w*>gikczex=A+~Bg6QpUzrTj_sng;nr5Mo}HNOz})vsl2 z+xeUKZJX~CjO&Y54gJF%4@V>(&Nf-%htf8rvC+*Px0drf|HZIh+p*&me!Mc*RXaz> zM~QmnV()nwClMp%qtfO2$zd7Q9%l}F|KBu~Zb?8yc+2>#|!53a=e* zGON;yB@I~|EpU3bL%$X6X@~*-F)*P<*&50COB_J0L`p%?w&i`{4%}RAfP6rQea%&l zzUkK7!a}ok`BV$^LY^opE`U)*GKklfPrGH;$&$fAh6Xy$C-V*tDeL<3!4olMt9X8#$+pcL@cVrBp6C05GD8^

SF5DVM}dwu{HLDlIY{!w#-E6gc%U zUJn9ZG?&@DRfz~HtQ=~Dl2QTE=y?i-=ld_&HF#TMUqmcPrX6=p*4JOl8;bN5(%#e|M)pT9EG(Q+ zM=gT|2C=vIMS`FhK5Pe22N>ut6A}j;7&;8No^H1ufd)0mk2}T~sQVX71A>vNS|#zRT(93HS%K3clmJ){zWiOu;&oq%=fD!%$U!WP-H4>}C9WnicH5GY5f*0HTt-V1xvs>hC zQ1s`x{cDXJRoCj0STJH&JGl>ulB!sOwu5M$RxQQ38#y-lnq!MoCbzQgi*_XKXSGTp zZnJic{p?CSZT>a<4s{87dQx9gA9zYHx;cn&w)E6!($tk{1iq=AOIb@;Es~^HYJnM_ zHZ=6m_GaKS+|s(lULo&EYi?u11jaFSjU+cSVLl!XweHMwe;a^99+of?MS%lwVxqUs z_>GJiz(j$r^(HhlmQBDkB4gu+BRxJb@vHU-MrisR{3sOKy3|rC$t5JOuN*9|I)Yg& z@$N?m*J)tFgb*1!Qzqy8(X3EYPa1c9OkX0+s6W;H!;|N4GlmQ%wb4b7=L1qdIQcGV zSsh8-p9F#+bKA)+3G`y+s^OG8ZQh)Z1HHZ8abWymlkF`2_A~7 zm)@BeG~RT%oO$IjeLyJkK?@J+lA`&? zqz7FnJZVh4QqmnPbJghTll|scn}n109>*ea_+A>6PYivb!MV-VAO7K0sgBU!4P62y z1C#u9wNI4^qlLQ#I$dTZBITW8)>jAlO!$wg&2#QCnT+RREE7slSO&JuT=3u2-}Tl1>X z_}e!mmxN*X%R8tQb+-Su3+i(}dXdBNQ&P+HaO3#&*6I6{%Dq=x7=4o}PY}cjo}i_<9O61Ud&#kL;hA+3)} zYfkJs@tDO~AC8e^hnIXKw!01Sf*+?9=3Q5_7jO0pB^7ziS86IpA@qi+QqrRyS`vKf z@kv>E!K%@xgVP$@$<}aKlai}Qj1}#|T2=i&zj?<*xFY(J`6@c$@%J)X-NNX}yt*Y_ zaCPl$L+N1|a-2+{zc43H#gjPLu})cy-{mL^_g;KVZ2fpTZA3|-j=CdlZf;;0c`UM? z`2ot(!nZ6vFQ1cAp@I22tNrcQpDZUlZ@HsXxyq4EcNOB?-VRA38+$a&@({$Y#xtbX z7F_YOqTh|{Rb)(>A~_VbWaqMUC3O9i;BC#?dB>>m0qKqCbtiY9UW|183-%b@^M|qs zOejhVzfNeqzQA23Sf#5iOviiM)qOGBpLqXaHgAP~`p_*mtIkKZf1j^9dN=)^JM>$p z#}7+I*C}${dMg|?^$Y`DE4A->J#;yBDK~yX;mvq5T-V`k_*Hg&S)p>C zIsb2CV5^x;W(vFQO@{OfUvw!;eY!dGw0c_`Ze8KSv+6_KR+2x1Hl7Q1!Tim9Ls8r& zKZk1Eh1{^eR8vg5P;n5$f{9hdy#KLYvv3_~?ObYECYAzC1`yu`z)seFD&xA2_ z*&TmB#|LVDulpWh5n-bmH6P}Y8WHeP9P^>*pEftMypJoy+46q{9*QOxK4ZjKuznUG zj;;SHdaHQUdK>pa*4B4-M5%KP=hF%WeL)V4(j!z6cJTJ*-)d-^Xt;xXTM zRH=}S8p{>J3z+InyX(9Bq28bV>5tQL^cU?G?`lLMk3|d3pe7BoUB6@euwQfN+?Nbq zJiLHX$@CSQ7-s9S;BR)gUebACW%~QO<=cb~T~8>k$FvQuouj{&e+l9EHrwwG+=6`Z zFAWJ%eXy=U%L|*v3CRc6WC``Tz3YvFELW`EasC`WB`)wjrNP~qVqn$24{ltJk)Bw>gDDXivd6gu%8i6w9mfp4*G4D8L z-A~%ro?|1D(G8MU4~$Po;#eOsT>qYJfeL@35`I~O*X8n_jo81uGPtY`8~tQGOhc|J z1vJPv^xH+}p^xw|-#%)5ThO4NM}!x$ramz>#iKlqCBjIE$pMXh1>3)NPxiSF2@04A z#}54nikJxN$#ss>*$04L!CSyiHGikI9mF-+Gsfr;Cw==BeRJ zmDN(R)pyci%^gcP>7Im;bGf7&2lCeB$0Bn!eN%Ihsd)n_kcpt5z(wi5yW-b9&XX5C2^N^b@A!t3$!eb?Jdm1F?*s^hzxemG+-Q$Rq>h(+kbBu`CZjZjr)n(lXgnYBugk0lMsPBN~Repgg{@=~GY z-dHyB@ByRf{yinXk1s}?l;qZ*HzLUI#2w3!8+N7bTaSMZdOs^p_y2eXi=Bo+ygy3q zg5gh+e#w}BG>$3M^E|MR&7B-KXh)Y2CB0q-o`d0BYBAU%wq|*D7Bfgv>laM#@&_aq zHRPVDcqYd_>Jn9{u|cX^o0pJC%@v7KQBidQqGa@kYq6&`3>tu>GOs?rxL5?! zD;QnYgGqBI5VAzAjSIEVE`(?+lBg&!@IA$j?>W=MgmDjuBfe>8jCL4%1+HL#&iTxSu`6aWqb=y;*;Wxf1h!~?jb zN_G(9yd$hFE>H)io}jd;H{2V;i|f z#|PiicYj~E#t+yZIV<#t61|zeCi5*Pg=W=VD%d!tfllV5jH<}p9<_GKYsONq-hQF{ zi~nqb=3Jif;OFXaN6 z`xCJU-6Z46`7rxmj`41^v<|VjEm!uy0-3a z$Lbz4z8%1{p(l^vAJ_wEoF4ImNm<}Pquu|2yRokw&v$7v?BA*YOd1W=MSBD0*X&ce z)gj*_ii`wR#-Zd!7fkWmBZjdgUl}o_MG6q1%J_@RHV*r|oovar_ zAC=d*CD_JxT6U(+@MaNUui_7uI00h{vKfcqx!wQ_n#b1G_g@yrz?}Ovcs6YViuZsu zp*ZTBGxhur24A6Da<%Vf#aEY7si>n|F;ZHjEyZD88R(pSMe1LQJ*fVowHBfFA*4=0 zap1BMzt1CLZMLN3>o|%ZzUUx4GgeuA?;=;lYU#O*l2Y?wvXf+Nq5ecbwVhR!Wy2N> z*9i2JUYO_l4U7Dx?K>zuc_`Jy!ZMnd&LFz?Jr>8hi;z_nAFA*hypbkS(C;HzX#Y>D zBKizHYU&}=2s-Xl*Gx)4LPM{V;AK)i!m zA=-R6YhOi8tq}&OZD@bIS7)zGO|Q|>DZ?B-dIAtNXfj=1)hd#se5_M;Gwgp@001eX zVNWokRLO7zy!l*VD=h;zcX-`7Dt{Rjs&Eqx;{{h=v^q|Pz$Xs$l9~6XNm%xRd(Aw> zehWY#eyunFa3>1r^E}R*dgu}yEN``d-3p8+@5DWO4p{rttgHaQB%=}J(T*^e3TlS& z`y7ZBH23!QrV5-KpH-?X4fYbl;K7p@Jc+ zt%VuyrNp#B>EpSh|E}r39{$q1<2!AKo=@#GeGnem@x; zU@IdIn8NqR3?XtlRg7A{OyOF}TCD3yvFF8Q!aJGN!s;B$_;tHiP9AE?%dZVef&y&V}3&nwr>LuaoAs$HDp+ z_SV@o5 z`!d1W3Us8V1R)2G3!8S=R_Pv58Gl}x)I5|^Gh02XRAcKgUCRZrIADQC1~fAos;t*duZHN3dmD{VR}Dg!N|_uRXYXvif#yv z1Lhat;0BkD$o>5M{0tkm|@}ISd6Ya{XUUK{}zDRKu%uR9)%+S#))6MUrI4DUMD9X z8v$oK&<1YoXbuo%fL*Dpt5@g~>xYdU3Hcn;u-?Cq68gB=qNAr5-29@@ z){-Yiq!|=A10SW@xqA@Ph=A*QltPNE@^*!L9c(EU78dYv?3P#rlvug-70soSqpO2; za!G2EXbsK+=EsgV!{GChl%#`m{>#ik*bwC)vFkwf>dkaG9NPb6rjMJUX)ff)e?2=b zxr_6`I7)H?C6PO9C# zMXvbUDYC9UF$`5kr;)Gfc6QzXVzkeq6h1Tw@OnghkOz{p0c9L_P_fI`_Yz22ub+5A zYmg%35kOj7Kv{sBf?(g=34mm-+s!wDJvRpyqorHBV1*1l(`NCp5d@PUl!Oo|6x3kiu( zxxi|w2|(p^gXgnP^9!_W&_Dm$lg;YLFJE?gM7KVD{n`eqM4hlV;2+R4Fksu-+IDnw zXn`?yZf>pzpz8o_^#x!MArm&$A%Ji=7`4@G&CWKic;1KuhFu`i&H|`kw1eVJLyvGY z;G|Uu-Wec9UjVi7Epi`ycYcnD_!%NNy{sxJ063Ic^vR7AAOwmH4-d~FD&Ko*uCS-O zdm-L=njX|wz_mUgh~t^}TbuEc0N@BEKr-+a^bkH%W?Rdr0b6|g=T**8+w^?B$_UWQ z+?lyJzv=DGpV$J!vU*Uc(eui;0yYX!Usj-;b8Fh%Nh$bcqZMjkccV?y0mj0AbaX^5 z;qmoVg6l_699BBJ;o+s^OB{eUP=&ip$UhpFZ$aw8zW|v^alL`tx!DoyEzz-0Zr~qI47(gxpX9fDA zu-C2Y8m=H`(IlEm_)i<15b@CDbsQfC`y&WBXzNDi1Q)E3M`*k(;252CUH`!5;S&_( z1z;`UYjG;3U1osj1*sZbChi_$Ra6s@8)yUV2O!BzkWv6UBV}aGbu}x)<@Y<>^&v(e zb=JcY#(;=E(+FR4yr$b zzg{+iLpRm(UvF8+BmcnRT>$JeWIKN+X3on7A}yy-*nfd52=bJTiRXLF0H;77-3`Pu zv0J-ncX@D{mUVNhI>R{!X@t;p!O7RyKr{a^ zS-;hAa+S-#Yb0L#J-ZLBT?5qlU1ymuRiH9;O zd_j-DKo9jEJ9|m%T>DYiXKSe*QFP6MUV9ll&HrR2nPoSkDvWuJj7BC_J*fj8q8=8U zBwD!T1kw7EN!IrWKA+6B2xLnnslVbHH@IKgN-reM*b_?y@TtV&_v&5~(lNoVtwCm{(Lugpe{~*!=j0{C?)y$1a4L>w;G@sf$OW`mBlq z&EW@8Qm4~9)UMni3k7R*tVfJT0tnB08;Gyxc*{SkBxuQTX(U^ps?S_?{@KuLblkW) zns!DW==9T{GU{|dpSq_=LhXqlzbleXjV!pLXiclCf8b=0#(8cxtwww+(&39I2FvJ0p5HBq+h6S3pFos$2?u1u8D)_-#cB_ZgL0U1u)nI2lytyW&@$T zto5u))L`?A_4JPz5b_x#y9W6~3lJbG;8)y(v5g>8*J8gx>pFi8Xd@MXajO8^YSF15 zTUm)fP)2ix(Ra#dD<9yQ(eS~rRx2(F3Xn1e{Oi7#qX^mv#R#-3GsK1gJg8z|VB<|g zP2B~F!A6}dY-tSige*Rymy(ha&2&~^j7gZaJMbFwN^A+G>4f*9|H3X*vBFs*u@0ku zU;y6FBn;T02#o+)e2&_~7t!XURe{Xl01KC1Jltsm66av>i7p%kmBc^H{@cY+zb*Z* z8MplSKaqM!9bY48uGHIMWJ07vhQpBC7rlD@)uX#!gdGETH$}a~{W=ps!;SQ!cH z^cdOR$vYLrCLiN9DdAqQM6n}E)EJ2zZ~7JcR+5OQZ|FKnF>1s=o&ChTrDoeQqUKJS zEAPZ}m}Qc`eBF#)ZJ_AZshf8Wy6I)-1_sD>zaHM)hFfsEjUfyJIg2R;=E;BxgD`@I z92|i;651jd9}lmf99-C??d^F1#f|}RJ>23kt3>(lP~F4ci-?Rgnc?K+{S0QTCjwx= zD+VN)Nyia=5Rbq%D%3&?9D|$&@~ox28%$nbA+xhxA&J=7aLgH2H8dp7q$(BPcCbQ| zKrKq2X=}INFQ3H9v>+m5Rw~i7N6Qz$YjPkSL1Mra*Nv_KK*HMKU}D>)QWrp%Eo=F8 zJzxxvw$g@jo?6W1Q?#Mim_d9>wvZL19Rb0?C3M9gA5sLm9MN$-;wa-%9c@Tv0L=b6 z2FnII6E&2)^$^nak#+!J|CpUug;Z{#q@`8**Rp{ZGgs!q;MZ4yrcXv1u}T0@Pu*NX z)7+*wkSUlUz%Cr>u-^c0+4UhMUw4gc)DH>ocgF{2Toh=>0+9IN7|0b~qkuegp>io< z4w@U~%40a6;^VvF{_9&C!nIcJc_nTQTTpoGKY^6qSM)!jlw}Dr@v=uzlLPVT7MT)A zuYLSyGpLOdtu70<`*nErDO3uY zmzt<1dh2d&*^IpN%;=j%tBKW2 z>%6v@fY-)|tK;f1uXT6L1fAQqgk#^(p_n=6%lB@QiXjENjuc)W>X8=%~~J^}7?0kFZMI|v|^m;)!JNv8>G zjx$j84|LsKtZe!t#`qO@CB~ywj@h1KQ!Cx0K%l7rh8L#eDFlY2W=^j^JY@jf0Meha zVHrpt?77t_kbj=u`?rzGyf3^UcjclCflea2dtg&{<`nHz9f&;`G6(r3x8*SVNfBsc z6odQ?1nUjK-|nkRpfIMcsX1Z1)i%KGQ`K&uuTLmtW5WS!4mvkQKx|W^WXm*9hJTL< z2!QXf#M=eWu79negH{_)N_=r{;fO_Sj%#>UrH&4 zDrfij)HDbzfi4@)Y)XE04u%&N2Tg+au&Kw(+dDe$h>K52#7E_xCH$X_r1w}y=Qaa& zfB)|$d5pUiUDe%9C3JeNP=V@1Fk@%k4AL#Bb z*aV;O1U3HzeZmfC->eHVfxecdtu0#G07xV{I;;J1Iy#hS=IRSo?@6@90IZEWkWf@f4u!o5?jDkgT&S+#4=GChuok)v1A=-&5$KwE$%>>}-4CX`pgJ?Oy~!aVJFy$LMwlACn3~yX$3ft1%AfRiQ&LcpRS;ZUq&NkLMwg zKdl5n41m(>bdGLf#MH#Z!ObwYMtc$6|*O9=2#T~;o}TCTTW z`YAraEosV>+Y4NIb963Wy}2)8jwhAjlX!l;qr>R$Z{E0yfkaPqekJ2y z%ZNsJ+lBHRilirFjjYsEr8w{YP93Nra4^WA)zth(X7&RMz0JzxA0DPN5N3<|;PAtVwXx2e|ee$rOR$@aF&+d4L){iV}m6|RJ3mfNW0bN7=J)}sy z&;baD{RPTh6?=AO=5J80E7No<0Qf)ienH+HXxb5g69k0@2ui?ER#8!@2PJZ#92|uUc=`!p0^&CFQ4qUDHcY4V-jcibn@cNW&Z{Pr$+C-u?TG0s_OS zg$wiZ=--1P#d_xD)^rVMVf?ptLHBH~Uq^FwYmZmipqYmjVS>N|z0XWFf`q-bO}KLf zpw5ERmFRVRue%%h)YRPk9-YTuOhrY-sTNF&4(hi}O%G0rK(G=NReB-gl7%-Y6?Qht z>Wqdg?>m9{JczXrYGe@0ku>r>Susk<@E6K$??J)%q1->AQeQxVasw+kIi z;ik$#D~QVGt@kkIxwXLoR7vc-2$lA{cIkmrf=s8t!gVPls|@{gDu4QUFcGcIZB$MR_1~6FZo+cX7??dR{yh45T=y4VWY)6WQ`A-UkL= zfd*z!W#nB-z!^=1kZ8Hhx(va+!WgV_tz z>lk43U`(J@G-3`Tb2z30QXM|RA;}bbo`2mmQ3WdH_^{4r! zA?U4yS?1Ra&lP@8PbY;&8_X5gH=-jWRdjU~JUzvs#7av}#(WF10?@CLF*3RhJZok? zzCqKvX=*iSOHUQScJTBh6k6Sl?B8^eI^ z#LN61Of_U;jMxw_$8y05>20tlVXcmT*3UB3L->sLU#rJ)OPz>J5rte;j3fjj^t z(h>wXa`;`JX|jt!6BjZZ@b)Xz#6`ozp;Pu81R^oeaPocQ=R7fJ*-+O7a#VRIj6ZA> z7c(zen1(wZ_=tPapVhH zgB)Q#)h^HuMw?QgKSE%i^OR3HQ9(a&aCkT(D(a!UeBi&X*T1G$&#Uh40+&MhmZNoE zv)+65;h&Ns0z}TOCvOht`?>DwMSo96ZjI;-puB*&lJ{UxSGOFQHMZEhHRYA)iL+7H z@#@ExeTXs%^`VNVX)Z>Mpq5UuiD23pVVMLm`PdoF!q`He4oYPd$C- zfpg3N$^?B~eB%ijax3~=0B1``TT)*nayB;AvtL8DFjgnK)Id>HZ0@t}m77iRjS(Suqy%4Rl< zm*tX=m#KRh>-@&C_#bNYELqS1=f%J7lEqFvryc@0JHuY*3GNQW`lD zAH#+pQp$+tFC2cjxLO~bZ=lfh`^nSF#dbBDYB6u(>S3|YFfY`~z4FVhx93~v|TVnVq|8sD=rOo{Min#w=Fxa>GBSpMGG zk2y{;WVMrXQqfo=%4F>(rrF@d=h_YO3+dSS5LrlX%3Ph9 z;Xw&;%T|>xqZ}1-3enJp)Ix`bq}|0YS#__ro0VN_Kl?#%vD#^4b=L_Kder_U;{BT+ zhb(~f@B5YFARuFCXb4i6KQj`Nk1Q?O;12NpAWY;1*8woz&Ay#y0;C?Dl_%Xsx!dwl z{xai>XSMs5v$|>_FE5WClXxPdr$ciYQh)iwG(s~I!|@c_9D3<;DlqCYNUctS0^fg+ETYPJkQ1~u|sR1zaMTKG*Pf-x}0sQd0_kO80wJ* zpamZRgH{PZ2vAsa49O{dc$5kv;0cgVNSNoN6|n3;`S^I3)ac>E51tlWua?%1vPCy% zp-xCHEc})54gTNUaozExx!)>96J4u9zB!B8OC&lU|3pvYF7}Ug^ruw17N_+EPtLXw z50gtRX$C%2su|=Vi5wkHg?v9aitB$Jy5dLF(3jjdiWe2ddaZqUF;lhR&3B}Wi9Kpa zMUOz#xyrVgtzoA9D(vsOS(Q?2b5& zxxFu2*FtgE($9%65xuFq_>i_p0YT5r#o@S-c}B_ja@slhqQpi;nNEoUqwNPGpMZnC zClzNFi~dwDJFDbpG#{a-@vcjR&6i}U;w{D3Q;d1yUr$^X#5NE~(vk1Sd55rkhKea#|?mrJNpfsLbosc;~9heUm` zKEc^&z1!jf?)06K?wpib>OYEBX}xLYVOqm_GOT!)hT@DkuS-$fg8>EzbV zJ>naV`g8NTso~)8cvHIbCezC%#(h)Dkhv5a1!F=STkjGPZ06M2Lt08!eFd@j6)h^H zQXgP!WgY3?U6WO^poWoYr{onJC5@Y!2lsvEMF%e$-RMxJYDKuQmd^oNEIDJM?kzd` z?GQ6~VRhDOn-pW^uk<3t#olB)FI7e7#gCH14B-!<1L+? zoeSxrQlOhf1D(Z6b+6^MI6r{b#J^a}%qVo6=V(a?ooWA10*hl2OQ*Z@b7fFX(ygX; zf@%%oVgjqtw{R&(3#%FU{nf4ocdu1bku_1y@van;_$wv=)R zJG}=nAnjQjLcMnUI|n@%Rf81GSwVnB9WQVju2=azWoD%!%PsfyAt_R%X!IhYg3^vBkzeyq&t=d)eo4L=zdp5dV zkwKw+tJs_M?NhA-(2k$jMhzxt5Z}Czs%y%|^fPww?h z$)DHe|J^4xZ8+N^6E?YmaU$^J5ikI!Yo$$Wv^yrN&z}IH8Mu7@fOplpe}mmR_inE{ ziAuZpie&-=r!k=-id^sD#1<~*vyRq8zfvL9Xvx9HSIyqTeDeX+L&w^fTcyg z-B+K?iJ1MAVGJ-aQOJO`0p12MCI-lMMK>!_XI_j|IkI8gySMaw_y@^PC8%ql99ZmH z`EfeRjSz0tej1FN-)$nZINMoR-I^4(H#&S>vBLCKNY(n}XsO`EhuC3-YybuLrpoDO zEb7!5Fis0CT!1%C-|+C+b%Pmi;`~~q*ZGR_^D!R&&|m_WbJtRjE{Z6169wwyUT>q_ zmk9kQsj6xvo;v}SlH$!kswr^e@A|g#*bB>%x_{tLJ}{Yhc@a+q681dl-_)LuKijIx zE5+O?mr{s#d(FMggPN+XHSnCaU{Q_INR6N&pOW?rWgAUrEk6Dz(?o%1;~kpKMHu_d ztK4UH=oogdLh8GQV)gfmns$66nY{{Sy?WcxnWn9Eewf(OmMSNsmxw?9{k59hJAS$^ z@v>SXvR{4WaT*p%%2YEzRzIY!5X*@ZVU0SDG=wCH@^QTMdqbq@us~gOMk)Jr4R^!6tvL^B=qp3}C037+KY0V?kYSUFjRy zQghyLB~+n1#7?Q+%+C)+jadu^i*l9o+uyMy8?g0ASfiZ^ZkR~i`XcE+WRcvg)tuLx zXgc|wn9F85A1~n6lTBia+L~XyTX(qbguhFD$-NMJ(Kul!ex{dD7guP%HTRL(+ek`F zOk4L07T0ExA(!R$n!cAXGa)8`^100h*S!LUm|pz7gw;qUqR9{X9YZA|6yD4rWns=| zuOT}8|0f1lVTfBLyXiYg>8H`SXQ%Rcc!pP*Q3*VQ-At9v`sXsU(D?mnY%}%ClFE<` zJ+nUikZs}3O_qG_8;esfsbj5HppRgET19?xA*p`}S-_$ZtD>+b>xw{*{?=JcFj9GJxUu8V&1^}T;Lr-&tJJJ zrJJp?+&<5KGfsAsH*vQTG%+B5(|n-mE!;yorZ zKEa8BPY4b9Z|~l{o^ssZePK+`sqA&p>)k}SvgKXg>TxR6)Kq`CJ>6=>(@;KBMt)-TPQ*1hYbsuv+oH0B*fXM9nUMojwoRkY; zk<*dVtGG{=&ZrMLaa0yEZ+B&2j;! z8pf?J#$H%wvkx8&O`{&GUVo_C^Jq_(?jd~E6NNPxqQzT?$l6eEBbFzrOV_Alq+Xj~ z$ue;m9mL+uyw^$3ClYf+ocoi4`e8%imU&M8&k@N!YgfB_pYaI79q|9y$!6tqU?ttT z;7UKf5I4?t_L0j>Gt|gJR~sTZhS{fZyxK}e=}*m z;3>((eiYqja%7o$%#Grlz2L{;0T!0UCvH+qE`=R|1Ce96AU&QL`T5|H!Z(gKK<^JwDcWR&L_U-E_Z*U5;$S{365Q{Uq&w|rtrTOKiC;9yE zPjNiBcl`X5vRvvacGG*JU09Xcuts7%mL-W+10M*@cc*B=u6ro_S-AB)O$|1pTWo|+ z1W%LECr+ZU{HQ(iz⋙e5-dbo;pV50$s*k5QE#Nr9C)2`tTU{MIj%yidurg!-i|o zbZWVth?V3Jg#bl~u)eR61_7nkG&hY)wc3OWde(|yN&lGJM7Ar-Vad?DempgZAzaWl zLPkbK4`tl;`X)p+<}2{232WE8SQV(rFE4M1p^y715)O?Q|man^3*Ju+Ahna&+Dux3CnY+0h$Jz;f@JbT~t{ zMtkpAadS8`FWJkU5<2jj9L|>%SJc*_yj#|}93RJ)LZ#_(%B|<5J@F=8vA7!RUB!)< z?mI3zwR)H2p*bvhetr_6)OABy?uC-#hj|nCi}@v41o`?j;fNjxV7>~QiL2_pmve_w zr4Bz?oW>v zw3%;JUayzr@+GU5SaTo`VBp+2p4|1?yB#wjk+MFB*`I!~hZ{B&Zu@1j{b=O0c8Kta zYGmybL@1suX-3JEZQNhNP0p-(jM*0d_!@>Ayy{EXINI^}Je6^kI0a?oL{W5pqv1R5 zE6=l1lYdHtPiigH($Y!BOww{)dw*xcR6uaNSq?F_Q|!4q@UmEl)HSDZMw{~<`tc!j zTz$mgv487yo;ic=WJf{RhHQ{plu6Q$s5H^Iu%0d7|10x7e2Jq6c`CgqvQCuARe9{L9X4D6?@N4oSrLKIYlP&R?*`c(eByl*?rc}my1%*PZK5rG-%t%PC@(B}|Q|<|+ zx2`xTOby-N_9G?@SG8xDw<)adbhGf5du^3kUHc~Jq1PcL{fdm8d{IfoxW?k+K*4{< zd_uLA{@+oFbQ;toFFQ|gH=>d4HS~q6#x!H!SYYTysg7CZz3*ZdB#MhTtE>wilEz#p zL^B`%@PLY1;P*;=g}85?8tmPRO3l}QNk)lVUQA~fYDAlayZ>b)C%o5jORD(^%Q)xf zDuEo0La#7ttcF68DAv!@V>4p|!2*%8!y|ozqjzQt0~=L5v;05adDfICQDRDACeZo7 z`tbHOLVoqf+UI9Yv~{NyOK!+F4;Qt{eQVIZ86(c}s;H?iQa?&*e&jIcN)rb%u-0z_oiDg@zZEt5^xUX`( zjW)oNlyqM$!o*IS?s|IkwXa9YUiK6Hz(YwvRA|m83L+#o4dQ$`b|LZhO@8 zsFFymypF*kE&s>!L-J2<-)o4kI>m1;X8$`V3?LYc{wAtC^}YrH}6zgbb-`O3NzVOCNs|+z_t6ZVLBF z1d{p*ci9{Q@78Uyip$lvg=kwQ?=D@s)cCtHLSt`&nf?uzZ-zg4bpu9W>TT!Z$ZP!6 zk7n@Pr_I*{OssKy=%^1#a106BdH+AU-UA#9zWo~~g(4%$-bJ>Mz4sn*7It~e497=aWYSG#_zquJY}Fj62U;$6``2IG^gh$YAF~># z@0Rg6>ZmNNMYpYEY@{Fql|Rg&%{nqlZyj>Z1C8e!wB<~(!mJvX zdsoCaTtPP)FoZt%r0hnF4J8TI>^X7Lqy$~bVtR!#S=$#B`1`BfsUi?-5G+g>MpoR;wDIPx9BfX^r2Ge(`Mu;XbO(^Aa? zN&63V#NY9q@hRdb@m<6D&i5ushvC5~`YW6IzBG!P3lW_82)Eur2PzijTZM&v)peE* zcmxl5QD$7q$1-JpFdgl0n?<+?(n@y-pYp$DsN5v_8xy)}|HecxoffkW4IgL20wWI% zPA^k)k*(m4+$K7DcuLPs67$&R`5WVh#Gb@_&*^C%2^go}_o9%UQIe}UbG-0dn8WrH zmy$#=kwx{Zz~#TyyV-e#s=h3p#&*?0)nokZ_bboI5MKdx=p&HX&B0}M3wJK*%QMUH z29$Oia_uW<3&wQZ`}>X&LN%0Rp&VnO8uAu7few`JauYsQIAR4IoB}LY?e2v0K47Sb zlL!oRVJqG(+bsDc*=cg4)xH|>Dv*>(aYt4^Q5Vu)lHA2UOAn^m`|S{jHj+sH8vr2~g=)I)c9_gDz4CBZ4-|Z3Yr%w|NziP=F$Jo{B*F1K?RtO*I`O1j5 zqkdYNJf6aLTOmA{+HzQzW7VB8Z#|B@{3-PwmOSfXPT{J;SY~ba6bc%Hd@c2`sjazu ziuD_7cJVH``~3Hhv?kv{j7K@5-p2W-bo$<_V<_$Ad|k7p&7}1+?n3!>%o_~O9ij7- zI@aGP)h-Zx#or>1c?JqATP z#tKu4Q!4EH3= zC{*_p>yLf-`={VD#GX5xL}W&Dzd_ZL_4ic#=NtZcQGy)`@FLM?+STmUCp;S?J^uUU z&gAO zXJubUQu%uIaLv!|9z_4j?$;R8T^t`-YiaMS0tC(J4}!@)T(6+ySKS>d8(DYFR9*eE z?{_?r00~T(Y#D!c@eiYLWo@*;{yoi?qqKDw~&y9gW6GY=}HwTRI+-D-HN)0?uBp zN8)Cis;>Kzt^>o#CE0HuaeuOGKb}2NiA}rTF)I7y2?^N!Pykj;SpAYfRY)8JDIYv| z@bxT)-4Ka}2P%;ukd=_MKej@4R#p@6Spfub+sff58BNXG)EAe415tncc(4=yKwse0 z3amn+0OvX7bu>vCrnG|NZoJMP`7QKzZD`n&ssHzBDUey-nCZQ7e{6XCW1>o*2w&BW zu>800x_ua?EIK%!O`nPCc^xdM<%Xd2Fs(9S@l`yN&nmn`vlZ7QqE5VC2mB#a0-w;P>w+?JiaJdg zA@_2Czu`Mr)!c}^~$G*AtgZ`@~RT9sz=K0236e zUnb`k6l50lUAm@>T4jQj!mpF5_XGuYJX#~mO7+We3&Q{F4H`c_a6y68qcBZt$#?bb zp$lPFWC^~E0c5ZDl_dF7JwERKIq=>!{0Y%ZAxLIPNp5YUipb0{&o0ltFVq2({d=ap zd=9wY(uijR#6F{isQ7MHXZ!N$k*yJx8^*p8#&OP_ipLo5A}TM8%X|(Eu|GMnYK8a{ z2x`M6*D_T9L{X>9D9pw!Wi^5&{|;76ri?G$t&!@@d+6cy!NI2O<^q|OxM z*xvs&+1X$_P0QlK!GAW)`Koc~eWIJLqNi$-mf@>&j#!iEC5jhk9a+e)yQ#W~o?2HG z7rKRruZRkYQ!Y&u_?}$x!v6DU^`=S39!>>|?e=k=9I2Q5nhQJ#OXe}}qGFE&to;yT zG0jKx0X%FA3_auy;}9UI6?OF+TRkHoTN#-`!zTQjrwwG?Elc@jw77oZ>@<&p42~kx z6W72I;yoa_K79D_m!bu#dq~+tBnBL~WJbWK0lU};R^2kYPS)~o;A+KlHs!WN0rXtdka{ttOX<-4E(t&LzzL05lBr)H!$#K>;Mz-3Q*=lIoTc1 z^g;n~xAP5KA3C6$!MO$iu=vxb@ohYaHABQKuxr?i!?1<#xHnE7Aagwkt?N1UNuRH3*FOhmr5a#%0pl^$W2-h6e58QH z7uwwC}7DF!1uU_Ok1r7Kbo_Fzy0>8|w}AYCc2ng*WfF(@Ux z0xl^DkZQo96|}o?f$KVIwfK(A24x=W49W2Y*@PItL>u^AID_>-t!24L!XeK%(0yCm z+S=Ac);pIkHtLG9nC%M<>ywep&K!-bTX*iX0^Ssms53xE;{wd8C;TtSw*!On)oUP0 zbj6nmS1U?$KP0U39=Jc4`xKt4H(^>;(x&!WiumH2)KK$yxdp2fd*d=RRI=F?c zF|^V));w0Hhs!-ASrUoO69a$=^n|p41{4v>FNJ`cpmHrCIjkElGt}3gUVbr?TH=jj z&e?upDKhz^nb|Wmsaj=)^yTG|Olx;_>;t0drnr!;XG^(e7TJsqmKLT5oxB{+$9};f zAlvgP4c@okMDkf-^4TrO7t8Sdr$KaH_V) z+6_>nspheBx7OZbb1)LP2vBZW-F{u@wQ&bMv-`z*%~{;51>5U4f^39&7Sjzm9d|_a zyvd~{QQpw>-Tm^*az z_t;1o+Z~_-IRGsqrHmaAO332`bj-w;1(ol70Bnw=BbX(BB#i3rAmK22JzfEVDJO7% z{{Bn=8ur}eo%jJro_q~d(>nC{+o$hS{#u=Z4q#Z<3DohW4e^qs|W*boaccbuJ zlAMNPZ{S4 zosPEySg+}vRqT~Z>XYb%2Y+DVxS~>E>v1vC@}V3pSGD1N+r$ytkDx+o4)Rq6YFDhT zQ{lw(JC=#nztPkUm8#Cl7=^<#MwOiUbx>{%EEOM*8ehHY|0p6!T)vy~c|>bza>56Z z0JOE~FK{WP_UfGbH3lkvk}?Vjyvtcn0T;)bK z`E$MR?xAoekjYVcklel|8%X8QU~%9kDfYqZO4Xkc`WxZ4Cf#2P%Qr(5$U`d)=u??@ zagB3D^}CGe?lJ}a34HVV%Q4f>iN+{@)l$kMtYz80_N07|Ju^MKUj*=HtJX5M+{-AJ z+11Twe6D~zFJshN^wsR(jBR)OQrB?L&nRhCuptjXjvGb1Q4J1a(-ZRmksb?`FJPvx z|0H@3wkb;h;(Jdi91l=>nJ{vBpnOKsD_`NWo(At5BuN0Eyk8fP>|dmCDWrGszD|mn z1A?YYFAz8ZT&UZr3z+AIh6c*D&i3|aPU z1t{h=Fkl9Q8#*?&FtGOi2Cf+(XAY?V1*w;E9Sh4C=r({Ae$HK`od(Cb+`BI^E=~@h zTH5x@C2sBssNjGO^f(WsViWj}9^OY^`|qtJD;<4+p#nnl z6YUV>lh&pb-IUPLCREG+yBLf8JCx}ldF>;b-SwtO^bL%{7Kxps4XPe>ZlU}UZlQ<(BGbAY9G{k!ONg22QhjTpb2%=eE4Oe<5Ml|3w}d#lU5PC>A{TkpwC#z;$(4Vt!Xx zS!f6ixq>}3gh)`Z!zD&~HIMCNRrKua^H_VROG>@n>KzsokaQDZPED4zBp?G9s8jO* z@qYoFP$0BALRAQu-v+3gRDqAeW#)2;+YByRB@n29#n(+@O?F!(K{Ax#MwvX+_5fUQ zXsAlQXi{oV=32cpy=rn7s97|Ce_G{sBbFeckDW>(2|_{HT*$KL%S;+6M8s3UN(J* z74h=i4;Ae#gFI>ehZwh}Z*R*MP^EBV-J5PncWJoGU43wy;ck-7=Hi|5bPYT~g+w44hk$svH~bIRUFM3Uf)FFd|ON$36Z#kZ%70(GSaI%?+J-l!LW z#2o3mtDBY-;?L{{wTUzmOFugsMpnM*PZXZKmEvQB`AeDpMwqo_$#n1+PDOGze7a0l zmy;lcZ-q)CTe7(7`VJA2WK$NC!)h7|gFim%osFQk8aPl1YKbTxUOuF-jIDM&lir6^ zDX1Qn<-Ps3ny>qCX+7bdD<_9_X7D@07A$B6@3XTn0Y~@i85q|9;p3p{Js42{OL?^3 z$7ih$L?*7Fp+VQZ@>mb14@hn^Xp#N)0`2Dc`T1A*P}h2c8Ve9aHojZATG##Y#j2PM zX4dnz+9X4P3YiPUKfbD96)amKKo=Z%9*&D$&kk0Hz(y_}oN%~or-YDP7U1R8IBeK8 zKk&-l0Mgf0(7kB@t&0vARm?NSctL@**fapdZCGt4LJKHn1eIKyH%4qXJNB^N z2Dt{`x18gO=*DK|ejNDf=TMv8xYvfJK==c`2-Z%7n6)%zw13-3{iSo`TmU{lN7DB3 zvw3ozad#WIUSUc&vf43VWz+n;NVQq_>mAsB{1pGXjZf8#L`usNa< zh=yyp4)N!iLb0oczIy}(;*x7-r%89tKEH>I<&MY6b&Ha1EX>*E7~H3wd4+7PR;v?D zWdE*ItMv8bf7RIl_!6BYrTjaN%Ee#E|ZjyXH_eg1b4( zmyl8dEiQD*L#qNA_k%q^5Pgp}`t3P)DCXg5ie#?CRh-5jz z#f(QpG(3Zp!79D11F1lyK!LBHUwc>Am%2JiV2zrX+yem)khB7l94bBs2ulp~_KLx0 zfdX$mW&-Kb(sGvx-HRtlGy!nVR+CkwLtcwYGF!Gsp^%BlRH*#&wbm@gwem_s*FHeN z0Rc50SWGBtpcw&P=r2XZ#*1kA`71jw(v4$Yx}SX#`M+ASEtuf#NZDef!D^wP==l;t zZ9r}F;N(P*nnU8M5K0Ti-P=#jiAP0BuldeVKmTS$w25#3$g0YUX#G}s+VUN`pkM;p zD+(22WowEHi8OmJ1U=BCaLTf-<#ohxYAl6REDV~$THwJOKKvoV*AMdV{kHSSPu||~ zo7l>z^Jd-CR6bDqKyyHX-T#}wP@d`G=e>N1?z1kMuvW_>`z7muRG>R8uDj#WsJUf+ zA$QbH4reEBde+O0FP)@=l_rlDN$<6~YK(0?{;qNIkJ;Ner>!y1%v+?y?Y`HKj&x4e z4&$=9+?KAQ;YISj^P8@dZ(Xf_<&+Md~ie;qr_x zCQrX5gHI~_)0pC+3IDqO5hvgb2yT6P{eUn1m&?STpl15;rJtET#anrZh3(di_wfgg z=>)QowYCofcoGd#1alROVPfOMC|H{EEspRMH%UTg0?(z;?M7#FgnjqqN)lu@{!H_ifU<{|t)Wz{BnSNQGS4zbi znju20{AhUR5w z5Ymc%C^s7I+>+n*s#3N?YyJ52_tH&rPmDC6guaJ+=frbpsf02StphYzg zK9Ngs<(q(V2a<^jS`q3xIzORuTbZt}AMiq%YYm-)fpaDgW(7TI_jScv#jpYYtYx@Tp zE*>GF6qs^=nfyZ}7ZwKINIy*QhIjx1J@A;6U=j{V2Pug3x$mc0ikA$00{TEY$Wbue zg46jEjI)KjgYtVa_sqD!e=S_(G!UqXcRu$mA9!7p4jCZ8`7I z*|?Xns`l&@fM!7$CJUyd&;WOIcAmgUh|g{JF5HJ#(b19OJ|91Ql7~bDydl^eG%oO= zMm*hsPIjhxtF8%JWoSE);x!HqoG_<0=hEs*5-e9lW(W_+5StxwCdR-}1Or8<)u*a) zN(jH9)r*=>4yH461VMcxTzg_$-iS6zM(s!L!Sl->yGVEDrf~kER5*0>Px_c(7AoAT zI!&zL-C|$ZGkq8l=xfDTh;xn=uf*X}WMx*vdL^+aBrT2HrIt0PU1s`zn`<3vLlMWU z<)}!VRD6#wj*4`pIyj&(#Bl;dTUck0~0Jc?$?P4bLSsHJv|75_$t z!L=Bfk-e#v4ZhNAVPD@psdqIruttp{e@8=9-n<*kN6_NTLU4`5R#NQ#d%eM;wQg>7 zDeRe~aW0SibJ^*9l}fW1Z(oeJ0OdXnAo*%9COXV+Ou5kg zaGf=!iLpiYvBGT~y=BK1HuYSO$}cYLwN zfUKtLYMX|^^wDv3kP)URnAqzz9IOzDFtTBbo(Y7(H?ZnZ(a@bL>L6Z%Lqg=`f%?3Qxs}t74u!_1jXAJ~2h4ml9uEfutO=V%NW5%AB)^44SikqnDnz>L>ZDaX< zxa2hRU{iA$Jac`tD@`UVGbGkC3j3P%hUhdWBjB0BN+ zzQ(p-FFe^Tp;c5jzNhqVQt{ay7KdGW;M-i4_7FU=14a%_ag#F794&X^)!;O9_P6)M zFIDVY+efLd#JrK73OtbNcef)uROyTfD364}<{Bs3{$XKw%XNup zJGIBu0~;L;gr}AViMB4YJ433kVW|> z=aKNqWjE`c2gB{@swjq{pKLXe5tG6C7n|0P9aKM!kGw__=WZrQzqIx`_PuJwYnu%1-^G zf}ckt!z8`@Nw`em;55L=^$?8Wf!cGk_Q(J^6h(^mAotFmUT44Ko^yWs*|lDY*sAh_ z(_da72a0`qb`94=jimIAhjKMxFa*BagCa*le6z~+FyTS=Oh{opC2Ddq#hGI*2U z)RD%9!oux$fxaRLq^ztYb#jrDk*z&gP&Z>_W6K1Od)ban9MEpvxL^D55R${uCwt`X zfFw3_leh#047SErxXpt5H4?vuNup%P8ZE7HoS@?0LbbXGVBt$T2q+nMyYJ!0a!k%$ zYs_{;9b&PE+_SmUmldS{1N}7=|GUxezI9Gf-0UQKibrK=-)ZmP&~~xYjYl|HyTIS1 zKS6Q(W+hWkFDI{+P<6eaR<~3B9a76qJ<7ua#IqQ~n@QjC6gB8>mYQ7kKkSM%5xwvA z#qf+Y^kC?VN^MSglUmhJm^4Gtg9iG9TN`RBO`vHFbXwG)Ts^_w+1*AU1j` zP?qiIS`QRhY7emYhbpXIn3?U37>6G`y+~e`f28gTj3QgvmC&NB%F0hrbsYx%eG$oG zL+eCL89Q);hHfYya2AdYQmf2oeYGg|%^7QN6nhyGsmu|#W@6BnwLr$J7|Eix@A@3w zDmTJEl49twfbPrN53!k4C9Lt^-g7rpHD*1=7+d0?u*i+QNV-kSpI5FdI;28`Nk;%kaE)?X9$w*8yjj9#g0oV z$j^W<8I{+5AIX9`^eumJ4+={wfpcmNZ1RX9pBlbkqRl(ce$Jn5gpifgee}8%|4@tH zI&l@BQLRF@AXJ`6T>k%KB(CzY7$)GgI{!|B@ONX8CSE-C#&yg$kA@YW7S?Ro9dlt) zpnSHClFrkt{N_sXz6OUDqq?9RIbD|+d!&nbFTm)}39<lj5qhM6*$#eB@<;$Tcp?y$KuJ z*XM2CJgGlA#lJdekL25|2p;eM-A#9lh72*W8y1KtJ9~Xr`n!^wa6CV@7rEHifMY*1 zh0{WZROW*{D`@3&!d_9U4ejrjAu|}+MO(;n7AJjx6eRMa*SZFR5bKYb9w zl9-hiL!dP1|s=YR>#^X z(N*{1lsFfXYn@y(%S+!DqyrWFcoUh5;N$OEbh5?vL!Fc6o-dfXoTH&82KdLmGRLKhTs_cf(ETRc+liUZ zU~fk4C9>^_e^)vyn6Dk*bweSMX;}JZz)WmN>V1cA7f)3;4)@>3Vv(^6QwIHlisO;L ztmhGuZ`)15)BYQf0Rs$2NxC!{71Ecze+)VXr|i8`Cu%A?^8 zhj+&D-&citHe8P0AES$D@~pcNy)$H-y^DNq{2Kqo+B*imi@yau>&K)NM22oh=Rb(4 zQDf&PtiR?dF2lxx%jzbdREwI8XZbweYpeg9$y+$}3Y{Bc|!F z=Q0FvH>2Ze`%eT;&!dyZROP#qDZ^H~zEo7i!D1o+srC=5CWkJ326Jm`oiM~`0G&-8 z&=7*E?>Y2>wG{uwLwWhTeEQ{i-s0bipKzvRe#OYyjS)R%pxoMININk5zJ&mGJnG*8 z8?CoRHr|`iyzt60>&lB+qmc}}WK0hPV>$_$%^D+tefUt?O&)t?&4P7X8&DX$?n(M` z-b_wN>gJoo(Efr}(rVog)$aQE0&1&#MJlTW-I0%t!$v0j!!C727TTn{=9UHK3-r6~ zYE-Abk56*V5@8Z-MUC)^4BU$Si#Ft^`wzyrgI`Kt6Q9A=N5y2O$cC|JSoFi|)Nhn| zYyX4OdU`~mgP;#}j#jE#bsdaJdEU0vQ&Ce_koy`S>-T?7tUH}4H9gkF5%bb~&{pOp zW$k9bE<5PDvb;wW%@Itm!AfE%G~M(u$qiPy2w50?R{AiO3VeR+Jw)>k1NuFv2C!T8=+$UptaqWE; zQEQ!w2@WCEcOM{%DO#CnM{-9g*6kmjR8oWs{$5(&lWfgPJdwIdEaeF)w6puRgmro!G`x{n1gSVYqg{V` z8;gkT3rPQzH~n|BKvcy2CS%kdLr1slEdgR zQa#W~biiRHdZXw?LaxiYDL&Qz!t!L4S`>}WXx@1iC8}EfuriOqGVY7M;Hj;7HsLen zZW(!kJN<^(pUWy(macDo5h9};H@i*q$b(jWKC%-1G-dd3q}`U< zdwpdXJMR9`dh>AcMu9#xZECA!rR(C;%K9>oP37uIVY&m8ej<^}*(HjPlYI?#{wW*dWev70|nmCf03dY<2fB~wo)QJ2kbvn^QpXjFfGa)Q|xuy zF=@%M@m8vkh8DS|iK4;Qk1B{%tWh09m9*BqF?P#4w@Ur( z{-7e@hsi(*YUp1-&#cbv z@wR3}w&PSwIqwonN67#O=MyJ1v~cs@XmvKD@Th4@M$X5MbR|#E3seqb&+P-=D+S}W z9LH6YWivU5Dl}NvRf?Y%kXb5x<8u!lS4}S{{`RXNv(>%Mea$7_n#*5q+!`1IdLl&0 zy=Idt%1_vwqpuA{rOYr5+ss4BmkDC()tgm$fcfMs8#FQWKDn2`WBnZP6EIkVlJkEe z0npF0sl~>$E;)Rt3s2NOu{y>-u%PW8J!T=lz?H&@zPQbh%A#>cHpZmmL^CUOpJVX0 zWS_yOrOs)_^t8mAv<4&|T-=WvVu+p%7{a#lyOQ;*FSJ<2_0iKM^(ED7&7p6a8EHrO zxA6yKs|woKFP2`{+gw zLiVq?Ef_DtiiQ15<=n!&>@CS&c+nkYUL;!Vc>kcDO(j_SF}z%-|G?ryIYrootdzF& z*^A_dK3PjH9_}(I04o@Pnhx`QRONP<-9pkF2vNTPi(F_u?8mLk@xd1eOn!`EQ6sMr z8R20bb2b6IvQq!S((l{>btVeI_V?lhtf)#AIgmq@Zz;Svmg@gun9lIKA#cp zR>Q-WVps1JtfFNXvYF1E)zhg@F6htaB!;;UoHk|#Eb z3ToF3GKIEYckUt|%a^{`?=}G~*qLRGHbZ(*rG8!3RL@GEjv#)$yz1Zbz^#EwxNMqW zvtYV*QQGBViT|C-)8_qzWHX>)1Mat8p3;#-qrfBnbt(r>9pYtfaG2w$SIVC?Gp8p# zz=IvFJ-sH=QyY0sN5)sVBueb}xnjQiD3Huk1jXa`Wm4-Y(|hrmbwdQYqm5VSF%6NO zQ|H;^*cZ=Ab-r;w3HV zE#wBL5+{7Kxyj3q<4!Q_>2QNBJ(Pc<#9amkhF_7;Z{sx=AjZzxaviE0af-WmyH++t z7)ady@$KHiT<)d#!1$))aKRS~j&09s4hzrf6*gC7p{bMb?Dv*#eMX0Q`Rwu{y zO3t^jlfHlW(QCdNZes+{8iy5ODu<~I+@vygK-3JePyYzC;N@~ywC+L-F#%Dp*gL0- znxC10n|{<<32MUsU%;M=F4d2*VVh@0t4aXq3lGx1j7i0-e)_eteZKftav*t}3gVeY zk-&tft8-}Oa%`90Ic_YKY#*MOksLQHBcGPfsnc_=zH|vOs2@b;v>KlWaBx`DFBx8V0Amn^ zFlC}Wo4?)&vI1r(W%HW@+gC$2u16Po-oK3_+X(JN`i6%W6rv!Zo_yZtd@vU^vJL3p z*x#B?0ck=|bW#25qXV+V#l^+$g8#EpCcb=gI4wwfX#cK3HgUB2sfzaM&W^CY-khA; z_p@V9w7UP(LWg#_D$p3m^=3v24i~$p_ypZ7%ek=Y`b~}bh?@jlzA^(c zqjD}x5INXjP)Ym)b_QlJ_yIo*zek^CcHlwS%{B*Z<|rY{L-Jk{d+2kxUWfX`+{V(v zBHX;Q(>i~);ERhpA_uWet3*fBC+igALDC;!1p#9F0MY<>;jmRYYF+wZcW6PVds zS))P&{uLVVBI8gh24*f5Z)O{bf7mj9NeI8x ziF;E+_fNC-b8FpX#+cH}i$68G_cG66vaUhwP?V_Qsm9_tC({&|clSUWiAn1SG3l^! zvvB^6+x_inDksLd?Qq~Ey(1#og;!l$1R;pk66`s}Y^BAa_BpxeB z89LwlP%W)B@Oo`&L8)~@r!DQKB8oW=?+2knPNo}Sc%t)H&O>RMGnAS|IilWvA4SR9 zU~cbDy=#X1Kz{CNr;=Ps6THtzVvd@5{(!@T{pvQaPW&$^26>00=KV?*??Yl#@n@84 zc`QOQGdo|qDi02R&pitI{9srcO)ajn#X3P4AMb@W+8y%o`LcrG^QO2}eXIzH^a#u_ zVobT*9N#Whr6`lYZFN~ibvF!sh!7ui z|3TaF(F@t!hgG9N%gjn$N?uPDz>XM0k{3tHa7j34NIlQpU-6WO?|~j=36MnJ;ZjXO zD~Abavh&08dK1WZECw}kFwokWaO|;fqj24KG5s(p3b*`xqoGf!sGZxZ#VQN6oSHv#$b7orAfo;i}=%d294*uvM z;m=Y@HeY?)5OY&-3|(ebbq#^+%mOQy+%P8jZq;i_J~>vns2{3vwzOX`&H& zfB4COFr9ohp7Eb{|(YBh8HGl=)SM=0}jn;77o|czC8z z%=PUlYaH1cM_C}wt^UQ}inQE7Kzd{?RD7;&xM^2?ZK42Z*>fmEIEFNDjd5aBUQSk%JUC!z#wL}u zu3Wpc3@`Md{-ul%^*Ex8-Mc{8pFh!0%Ek;Lm+hpX<#!PaB(cbkZ?aSg3Ekj4V=_)4 zH*Mr;wJN1~mO1~}8;9a!V4_46j)NA{z3A1df@!MZkuI93DeZ%rX`9Jq0ndUqXXlNx zA?MnHqcajkUtvi%(W9|*J=gSOYqe`~V&=yzof z2vZae^TVE^%?#%9oGS12Eln>Q6q&^zeu5o^9@@zW&BUX1*8Jp!OXY>4g9L=*Q%SCc zKabikw71Zs{5V1d?rX2~z0B1+SrpH7@TdK=vQcNiO|_HWHZ%R=UPp9z{5T4aLC2fB zspl!}CB)y)&+4vZ8($TwLCkiF?sA5kxYaIDNJ?V;tiN&B>T0k7$Yl z&I|K%Tb&9aAH7&-G74=cGKo^vsJS+d=LVb($RyG=F%A;SJicZM93=di@gtx3#kY6- zJpdP^Cm1p&#s>!b{PNdnY_iC`X5(($FDDv!Xs$PNb}r{uK2$R&_PxZ#V^iDD6tQkU z;{21S!iN_v_Bl_@HV^aZtNN~kdrzy(Up~AQJ9jDJFkxtJD@d6sob-{9;C0tNL5Fco zu#ffHk$FP7yNoT((V{f@u{CzSzGrXq{x7ykO%l`!;~A5hh8radht+Lbjz?^ zTwIn1mQGT<^W~kKoW6kp0r*rA12JQHtdtq3DKr8hfyiIEy$5T<$T5x6))WOOxd#RZ zHx}quTh7DJLF(B%RMvC^yoCG)C`0ter|{YD*5h}Ou^AeA6F>^sK0XMA`kNoWmzK^f zF9!mhYNE!C09J2Eq6la_zou7?H|mID3=9gwPm%`_Cp?S*_+R}HEF-A}Cq1kD;d&#v z=Nk1S$*(j{>t6~By?njcR}{R-h@tm%gsFVr(i&ICGh2@_>v&2OO{(XV$qQxh#6xuT zjD4gZ8)df;?S{X@^8CklrX8YGUrqOzCVTp`Yj=D4(}~K3IzuP}e7MXD^nU$J9W4pp zt4Wb};|8RcE#mM$k&uq2qpXQTOz|XrA|5+9)+aHSOy7&H+2){mGSAFjR1l3pvR+o$ zcmYf5hW~laZT(A+_%wNpK`x$_(&p{9tjXFKloAnR%EIow{J9#r5*M#D{b4+N!Nr+| z+Jv9gk-k_MKJe`W4z`6)&b&XEugp43{BA4PcM`?Qz@`Hw)`#W4n)R-eLnf(Hy?URc8wG~%J!^I~t)ru& z-qv~?JqPMkx<;;EiinpTEd0St?#gGG&_>`keN0GT{x_ngQhj}|fQ?I2R~I(ePc?z@ z4^Y#p5#$r4Xj0qa!g{Y>B7m!_S3<;ec>6I$R$`V(Gr9Grr*bw4AS?UGMEx zQC&?36bcw5Ztw3)IXQ8!udf3P2m^jJXcuZa(c|N55|ESA(&jGSut78Xjk+C{L-J9E?Ulio1?OB#oYX$uThFh#UQ)6=LUGf+^K!Z*b+|?@Ugx4oO!s<5jM-;B*gAcZXjcFsnnrC0;!|zzE`SVOHPl{f}Pr` zH}#r&3l)RrL!1tZ3?L@va?t)-2;%p$LSWbzqbWBmnOHgEDV`kPnW zuzaY(f&OZB430!ailD-cJ-aQfTLt=i}_fLl^#_{d+6?lH5n`lqB&0X}L6&|=0@HEwbW3cdjW7=uGEFUQTmcIcrCp8|lT z!258d*aXWPap8(hB|;7}eS)Ne*6-$hR}2gc;Cm#%2^wS+Aya1(w7>Wr+goxG51gPPP|-h*}1cF^vYJwcHvWr zwV^Ek$)B)Xd&<)5f|ups^6o=?9-Nw<=DNk^-6{EtR*t6NW*E%qNmkrGtMin?f zDZ%e}7B`odg5Z0RjL~g_QsuL|-jKTMO^>K!b-Qlo^4Z}bb;(S}njz+6n={jy!+HA! zPU>CeRFi2RHmoRwPRy|G)PvnZRM*JYJU;cVKD)dNOp-UJ3Xb=#p~U~T^}884J&|R& zXw@O9b(!atE62tz>8&NOkDVZ%uDMiddv-a=+zXdsnz2xyrj{>;TY2jAw;|?fgD3L% zl=D-s#pihL*SKOiuReSeU)3twR`BHvgyIj1BcAilsJ|CY6l&_M=U}>g1))0YYqh-m z@O=2lHSP28aE;bZY_l-O?$(e`$~eF zIDdu1y{G*9{Wi^_`oG*6dqm45_~kT)<=iF`>z6c1OEGL((HK2Y^_!MNagO@m)OIEJX|L2Tr7rO~|ZIY0oBBS5~ouJ9rEV+}w(UO`7kC+4+DTqcZGD>M)W zdzD)OxKyo^)vkS|FSX$&`V7`f=gb7ip!nDU7OaxMmztTMzpALHs8{m}AL^h|OLI&$ z8x8u{&b~rJ(LP37J#bF}Z|iX29XE`Pk-~STN9KYr5IXFG-~L-ad3$^Rzx5O9a4e7; zUo+$2<6qy&{XcxY2{hL2+BVM9M42;ZCW=I5mSk=~nF~=#By*-RC9_aMr3@jNLXt6K z1C_{4h|C)9QmB;5^c|OHzwf)g@Be-Oz4lsr?dQRL|9;nXp678K=Oo2c7uzZF{wUKe zYvn!J{|Is)d=~QP;fv90F?@P9cldtg+ugSQ`tfkgeOl>-m_hv1w%l;(qpw-dYbp?O3SF05?1o!=Revk8dSdi@bUEzc8+(W`p$GWD!;~Z zx;(7y*~UxFf82fN`|7-c{)M?&%6ArpIQEXsW*?%1y3PGFx!4@ozG-G=dB7Q?J={VN0 zKEfKfk@xR6s_czI<&CJ45;y**1xvdq1!hv{q~lGLI1quZIqFUk5w>^AZsTmMM&8+f zN^~|!s)S|VVS4RiU5XofOt|ijOnt2DW3G&)`vL|{pKFhLu(bu(U7Nexy5M^`H|x^l zi$UUU$Ia6JeY52a4)PB&%H|C1)oh2@&4Sl2HLZ~U@=_*X@{fv&XRW$+$=Zuara7lS zU#8!*d9wxZ)@(h*+!`xIZne%TL{pxCv?w>OD$ar4q&(cxld-6jmZ&tZEvN9)McAu8KGUhhA zz@wH~Y_wxCFCl21e)*D-*J@UyB6D-|)mR@+n&eRd9!}*;&ONy49`^cRn?vU9+bgkJ zs}T){LJ8Al%BYIg)-J$WSr*itKSF~Sv$V7{xm1{pJ>Jkqiw2;^XV2)+2lg0qQglAj zl{&l>NeU%CXW`%o$ICz^EWf?IJ=V9Jzj$$-wYBvvG>9!~ zL`CIUj*p;JF8?kH&AlcEc!H6YJ)=%9hTmjk`v-oXMpj-v(5}!gkL+f(gHTHCEfFNk z?Oa@3C}2#cE1ZXFc~GmwiluLqI|dsl%H7S73rM@9~i`49`r z-+3ydMP&5Tr)bo^>SyfY$Mo26I3ucDaw)PMWEwz9N{Zv_yaX!WF|*$Pef$0{ z6v|syxzp0q(<2ehm6pBz`0?Y@D2C5+8?JwYC8Qvr+7bY6^1Ve?iVxg|1<-z)OHFdx zjO}#f0->!M`d&P0+HbkMt;i}{CZA>u~r+5s~Di>(`_34UR!wI;}fvs*G*L|xt1i}-d{qqu9=uhZ%2 z=_x5G-Gb(g)olz2`bu&$d=v`hUS%a$S|%H>yi*u_-Q(_V4iKsfkbSC#9;t<avpS}aK6~$py~!61^I5U}{7;vh4QlkI){0U?--cm-GA2pJV+GPPzN| zG}m}f{I;ApgAaMq+n+zy5(C)2&;l1#phq&6qXJ0#SzeI!@xk!lU0j7fqGL*ywle+<7@EX(bmI z7uhXN?JJXr=TjC@i6d7hPZt~B&*L3p%F#Wy;a%9zxf#ZuBL*nC^pkJ)S`bWY>ckWD;QUvSV@$c)7 zFDu(|<;s<+{*L`Bfq&)r`1p>xy2h*d|Jr@vzyU9aWM=EJ-A@?i<^Jo-;XKq|w&y3b zr>k8=@$3l7Hpxa?VD8m9y*P+^Iw0>g-z$p9{@x{7vyy2LKkOjFq>jz#A zUx4CO+?5yTP$Ww>alV(ev}B%lcCulM>mGgmCur}uI5#_WarvE(pi3K<`w8A5ZtQCB zPo1j}2Z&K)CJ3cI(4SZ+WTULEWuq;K!&nlpFK<}Mup;b$B4;EcBg4d4mqn#I7QZxQ zf`dl)3W1myrP*LvSy`4e_;*R?4=+=QX(B>lt+w{Z z*K6m)1j!UL*VKztTgPKBobx~xD=rG@Ao%k2>*$9M5r`#%=;7fY_d9re=`jI@O1_hP zK41G+xw*OFRp3&q2yNfahFMNz?fv&3KXl+76JlPxdes8snMMP$yJOy3bnRjN-wH@} zWGUCS;KhIkr+b-DK|SJdZuw;|CZwh^SXfxheCk@WJ%s@+ta#RU9S2uw>*--Q5+fu) zh&8Ji85zmr0aE_{l$$X^r9SJmvQ4O|QE_&08J(E82v$S%Wi(S<-+6YszP>)udU1@; zPHd;-YipMa5W#MbJ@zsvk|W{c=huPL`}($04{ejg<3Sh{l913NH$MNC{OO+EnFo)4 zfA>7g#A&0Nni`R7l$Cj=YJV`HCo;;W?%XKu{(tUE*o*e|X5`(`L>Yn*bquAWN*Gdr zx@MhRGk;hs`9uarMtq_aaF{MW5nhcRMtVCp_o89JRhR~zD5|k>_dtE%26Rhl;jD3P zA?8Jv8j{IlcsE%)qNALonSh!T_9?+m(a#%)%YUXkbFEWvF+bXb-RFL}z&i`6s#+~S z#ASH=d3wP%%*vhrwi+y*6&v6X8gC7+{Q`>31SCD2_48sb*}XLWOP^M4}l5I62L#vS>c zJ0~I~wGP81T0o04OG;!^igd9t_CjgtHuCZ?N#bIAeg)d|1>8!?k3U_D-W&rj<2d1K ztth9t2=_w(3!DPAE0=j-aB!Q?mqS!Q5koPN0*aCn4D%5{##)dlJ+zl$XxkBrviv?> z-PN$5V@HpkN8D#(W@YX6TpRummYHK2x!OJWM0|Y)T=T`n#p{Z00+WLe*B~~ceIqky z;qQO0lcX7fFjmfmqth>TgCY~&og+$}sCRj>?2e8EeSGMjhdQe^v#-TsM|Ru5pB%du zf7_vBn-}pftIR10M?Z#v0AzF$u~--nQI1?)U5TlRu|-q0MY4D!3Gfk1&CV9ZAwBJm z7`jY!08Du4=bf%uyn;M_6*Y-h6#fl`*5{$X zqb*>qmX;P}ue>oR0!GQPu&|J|wQ?@~?CtIC?!LZ}XdDK(&*BYT{?e~8zkrgh$4nM- zYeh0~q?y=ZQ!yi2_|9vKXyCiU0T8g3K(p}oXJ~r50Hj$_m2ewl4Gr3$KkvDab>+r( z;osOujb3^N$J3`T8j2FQaBgF7iEYcH@O7m=Uo8(=T9SEH%Y5OkWhQo#VeEzyGE0&w zIl3shVL)uSg*CJ|j%<93tVE{==(r}=20mO9-Jn~xY#D(wMTGkP(^VvE?HIw(^zvwo zJaO_Q8K!0JLS=jyIHy4HXo`LWdigQPN`E=(X8!)|_aEa5@Tljl@t@s_xq|U9l1Fde za075QVTbmu%uL~bO_v&un|v?ek0-eiy1Kg8ReiT&asvbKFy&OaCLrPsxlKV|FHK9U+Z33P zWN^eJB(0uL5jY8e}|0puvjnTEr| z;c02%G%1_qjX`icrbjdg1wbEa7#e4(w|NgBTvSw4Ok)@Y=)^tX0_wzs9fU2%H}{0C zj~rnY5NIDxj*haSwSeF*a*W_I2webpF^2hOSW6MA5xP1PE0ZxU!*8OflH4H5hO6o6 zOgnb$Ajeumde`z(;(=XFV5>+ZNT}pAlL<9MeZxhz``TaLL7}jwnHFLRw+PG}5t5w5 z4Mn$j#PMS&FOdbBOViW7-Ko@RpslTm$sTs7j6#)iJvGU)1$P37prf}pvaU`IW10T_ z?!VB2bPG$ux#gXbsO$w|$Wmxym=1az(N(wtMKpqVUr3g*rRkFIUVaFjynlavT_+(S zfy+OJiCB1jE<{x6VkB(*2U7&6as?BV9d_&2;XQI&l2ZE|wJ;%fkXE`xmRO%x|F z&=GN|#&?QbS$N|8NOdIa`_}@#VJuemfs9??nJj6>Qu2sJ`0{zS4QMU=nsDQWBw;8+ zms3;ue$UO>0sdUxBZe1$$^Y*Ri#*I3}gzISGPb09% zSX}?QkV^QF5U2x5MiM3ll1zE%>xOte0+0BwL zR%GSpkHas$d;dNYj1m{H5eBK9OW?GTJmgJQ_#`#gr(u8%S6FbcMteed2uFHTy=p1VBwQNoPixfuj@a-(%9BtL&M0jM88Mk1X^ zNzv9e(>2IExJg@&h1KZmHpdPjOx!s0=Ku#%nURn_MC9c;@J*<%^And3fCg9w^z`x2 zkN}P~>&%{efE58hyDdnMJ0<``;QlpYp6I`VzL_Y<&vp6JoFHqmSei?Y0wg9kp{icDydMUAxzmjBWP)9NsJZqN?eEQnhtzYlqj_+LX5@T;x zAdqamRQTv~Ptiq0MWO=2hl8!xk{5r@08<4b6BE~~cu`@xreQa3@FMvU4K!(ozlKJ< z2uKMC|ET+;r<^6e^Y-y#+lKhfCU+ViJ^H88ZCDp+5sX&os6OLBIW@zUm7Pr~b2xy2 zbkQ)gq5S`>J_yDG@PWKcPfzdG*Jof`zkVBbjiYnw7Gw)qMMaE;VBWrChYnnj8SlR? z2(<_r_za5;1*^$Jfa@GOd>9kYLfpjgLt230N^nxZksI*x1GxmNX8x-o+k-oAZ%1eb;6AF;`K4Xzv9n~;zY4O-v{eUa4u@2lVD z;O52*XoB|^Wte%*)YNpwZ`B2SY9_8l7P6MqjSy!>arN;P)~9K9YvZNhG$ZkC-@JL# z*xI@-K0f|m#Gkh|`Rdi~SxfYHJL5d1OWteT@_2Yv9Fckx)Xq*oX4W;s( zi^oWdqZqoiEKoZ4T>#&>XqZL5Ll`asMm-z_rSItK3WW{@srRUz-3obmc}g^do-mTN zplsk;zdjT~z{{J82fWtS{d45V5gb%wdpi?Ms|jFlIri=+nOQIcvQ8epC+wyy3N5C*lokP940TY|E`v%5PSiY@+z`}-FhV5{Rmm&BDvGVzaKRp)~T za>V<{#4UUOQ=Xol>3^C#v1UGwKprTZ{}kkjp!%iM<*mZZL@zTF6O)qP^etiwk}cog zw;lr~LunQc%jp?n47@WzC%kfwH2*>cK$fT##0<3Mp)e8*G532okW0oU48)7%6myLT zq0dIIsG9 zT80s3Hwa1u?th9nF4$1Y&chQ;3eb@6ceo=0vi&gk5(HXQCE6yjx?1__mcthSi|tTM zBCDX#jENEP*bo1xt&I^*`*Q1hVj<~|EUrXH<#j?97zb%3zU$i7BT(2cfa=>#k2K*# zfdM%P>3~?kz_WcNfCLnb+sjTXf{=s8Mj8P2ER(zlYG=+md`n{U#Jyplr#ALQPh$jV zR#nv@F9Gskby>)iyi8ZyfQ$gqcfiDA0I1#f7xKQt2;4me208$lI=LNEfT!e@a7tT} zZUa&bwMklK~P%5jfncxRd^)HB+5sqssv|(pM=?k|+*C3=Gc)tw8pCrTz$AAq%hwJEFR4L3 zlSQRCnZm&qt?k8Yb|0AmGTZlATbmBpy!OYA({IWgm@!Rj9sWbA3IV>e67#NLZ1OSa zGIVrwyTR)K4+*cszsrOc4nZ=Hb2&X?#w#i+I)D?97H?_??T?SIA|bG@i7HUW zLjiV@(1%liP8>?k?1E=`CSIqIsA#B+0%gOsl$2;_Pey&(vyVm_J3Bhg163h6L?kOj9db0~>H6Z2U#Ty}0?v6jMipp7Fdv26A%X%@ zb3|!{uD-(8*LQ0rndNg^1ft+Ed;4(Ur^j%d*JNy)F(MZ{@3D@a9^j6R*J`uN;o++= zW-bJZeU|Uk5THaZRjfc8PlON?4!;7Km|k679S~|flzG=~oR4twK62gR>P#=XlUOgQ z14YK>K~$Q)c&N5Wi1k*qNuJ`kO1TLx83MF;3^n{j?#DGFUc1{VBqRj56ZN7TX`1D+ zhS9)!Vd z07G9+PTmLua#C83`#F2|@An`5LjuD6` zqhG$nA_o^^m}$8WIW3T8EdbgIx8Zomz)ip@V1Mv@qZi*2&uvCz^6T5}*MgQ4F;QDb zM;JmJ#4FA;T{AI6AxI|F!H1QENdjzyiXG0$1NsOeAtR_fLBRm$8VFPtY5Cy2Te@;KYM{BKq!TZ89SHT zdl0kzNk8@-!?d-~xuGK*20Jt=x(~4iY%!Z49+M~mq!b=w>K6<635W;LOktNus)hsk zA-+kdB;Y#d_5V-RSgBLDBp?VgMqL3lVmIdSVtyQ+MOoH7lo9j;jVil6Jhq{*AP%o4 z$}me3$=r3wHKA!xSX6WcoCyBnZZKm3H~Xt8DVuS}3X~UH@i~& zeq(tDlzjU8cg=nK)*^R90PIx#9Fw@XIH=t2|K{mN@=yLf63i()xQYEzLod7*z6^xl zHm)sB^Z<0EE(WiF_*l#;By=&a895LhfZ0n>74*E;8dY0Xy2cT<2jqF^-cedOZAyiU z6_RMZ6WDX~K^PiXs9ye`s5Aqm5hG@<5W zY~~{fmk^qD9E>>1(6&^Y+y^IjD?2+BYUIwL7hA-|b-hGb%|w@p?mj3<-7Uf75fDli z|4zs_IytSqE5b_BZUl_O@lVgf!Dwll+6^LQjO0AmPBpcR>LZ&H3bxD2!kg*feWAP| z4&*BvftKi)Q0r{}_yvTd;y|22-@Q9gRa27%Q3ipBPz%r~xNK3CI8#!!iZg$lJbaq| z|C5G^nx7A#92Pr|93w&kfhssUoTad&&)Sc;;g~?A_R7`C-(~7Ty(M!9rsjFpg38|BtSc5ToojEmXO=FdS-W zEa*k*&a-TAi+c_n;7Zf}2f>(uR9PAt>XIr;&{zA`tC`U2$#sLDU-o%y3I8g)X3)&~ z#~b|p{2E`qV*dPjzTtYmYtw~QztJy7Cg5NehRpI)CE=yb;~#=TL2GAA(=ruCRO8-u zd?jS4Fql7~K_us4S>YUw6CTF}d{sAzs?JhS^^7%?>i?<*00a!nC`Q&li#G>lAS6}r zwn7@Y*foNJf~l&$Ok1~Z&Fb2-D(B7}oHxYt@+9c(u$)XJa*=JtkW5Q2wtN~XDJfDG z2Jt%>ml4V`K*yt^mr>Ns0T$Qb5WY}yxpAew0X%v-MhX1*{+*PYTza)@jzN8CzKqI; zFYvgxm&>!7Pe4Eb{!B6%1R1%e1Q_#yU4K@RBA)+1fK>J1#pqU4s*+)(G(_hIpBLV- z!$ezwoK{Xk>wAQW3kZJ1ci=RMDq@_UROsJz2IxRbPj3wzG<%xn1v$4NK43y^Qm!^K z(#Y)DX}2`^;w5yvmU#Zqv^0JcEz*IRo;Y!$_PYnd_0Vo<*62sRJ}~x25J^F>R^dHC znYbXJrij%IA-HZ)?MQq4A}MS*SU*3%TO>1cCTb`OIdmcsD!LAwN5K{eK<#O&gqgrU z!pThk_z|j^NrQ^b{VkxBXW#lHx!Nt$d zc>46|WyUHTGBYy+fh!h%ZnW&xuE(hLIcRAqsdCX2R!Q>9|0+zsTeMCh*L$`$`7m^s z>Xx%!gZK@##k$m}0!8^%OQ*$+c|!EoCYT6urD@E(xbJ$W>Dlc#Dnr3Pj5DuColHKK z7taw)gBj(5^>dS|pp&^*T48aQ7&j=4AZeoukAdsAStT-WAF3dT)Q@Va-AGO0rII2u z^>Vcotfm2WK~f`R>ya9|0^CE9bMmlF;-SHPiM=3rvo1pjo$fuTQj&$NK{7{KCVO-+ zq479`1QKR(V~^n%RH98y5wl1s0FXIRDoE)fDhx2;dTGGyB^c9cTU*;r>}yF)8Oks^a`yJ|8lSH*$ckki zdmKTu2&fO*5(zOowrvYRb{4pp6o_JQ^l>cvB1IfTEM{j919N3(XWvdF`&eGLFA6fzwWNV2CoZ%b|>uc*HOPSN{wQbV~va!WlWwwJIEh7;N~nlZva z6XW9zIZTZW-2WpI(Fibiww~C&M~n@rX|n4AsXujG_f6XqOznc}nsSW3r$+?? zs`=8nY_^Jtt;9EYf;{YMh%weRUi64qe7so}ofypBVwLp##QhexfosXhWY-!(4v`ZR z5?GPg)wy$JEv2U?0(=gWuh!tAt|7HPs4E3Bk!1M7q$6Tj4K_>_JrB&z#Xhr35l$e_kpYk0WJ;0(P8B6Rhul zgr$}2Cf*VdhL0Yde);3Xb{gr=s0g7mXI01=6p*d6^P)#^{GAh40pbdx$ z35|Tq-5>2F3cQaTu&AOU7wQFIZD;3aA*-CQw-;7b-2f({h4LmK1p(V$)K*~1HA01d zZP5x6?R4g+f|soqeQ;SO&V6&(pTGd;qH}4gGqGJ2{@>@9iF(8pkYb1n+O%cM6QuMXDL##kS{!c?4Aus91ex3dC0Ref ziGIuk$uLu41Dc-QfiyouR=d$M+PI%Oe0cNPb(5n_3)bwM16s#4wgxQf>xMQ<7vx=w z+EdHy{JHVqrFE~?n^gcpjpk+qotv-2Gg#OLh6`&&jNk&0$yL*sYC)2R?j9bjhxWTU5Y*&Qt>3oS-OA4TuQ<_L5f~TilRWrG+}4E{!+6Y z(j{OJsOg2kt>Dsc>cP{^iOL#S=%&qQJ-KbRUb90jY6o;sQ{C=3oCpx%AC5+K!1}JQpdZn?q)bo1YJs~cdgWvDb+2=54UT!rqy?&`} zRPnOAx}cL&KwHM12Necl?$oRwPfo$BWH}Yx-X!SpwxOx+?KO&h6nnGV&oJ$WOs=-^ zPn+VpGKDFR)~qwU*dAav>EIyrE;4h|)@K^85`JVBSus~`Z4nYZCNnholNSAH#nUd< zF@5JntsF+RGEO-5o;@en-?dc9a4ml2h;%D!p2GlVbYxHFCiQh{dgrvvEyJW7G(FVk zB(3Yl&BhilJDu_Ii2%bv1_jBx5zJW|1xA#|I9>`UyM&?t?`dIDRub_2xdbu?>rI!l z>Dn|{-F6{l@EDC1uv|^tAZ_?#(z`*^_?~aov}4?U@AdC9YJ!7lcL&~LZ_IyiUvjHh)<+NO z_jj`a67f+5MFUpX?wxr~!><0U=^oF+j{99Kj=l0>5!xHtRNiDqc2&x{cJ252AXV-0 zX+-LXO~WxMU@GoPlsEk{nf95YP$w#Q)4t@61tiII8cyc9YneBn;%?|3Ptnq%nI0K3 zh`n)!r7o>OOLc?q&S!NYANbca-ks(4x_6WAbZ?HM{kP(Kb6VZ6fPjc-LqaBC;5U<2 zIQMQ-%tF?MtUZnFL*`xmKbkKf&tJZI^CE81x?-ZKi4+V1oRcsQ4%aYU9)k=gp-WZn zqnaE&MlQ#lo#%i1>h7-AISj??9*|Fnndu<*aQ;_P5Vcms^ocrQ8cyuJ+jy^$0Mon* zr)AAwZlzQFujS=3YGREhTxDI~n(Q8&*c->(T)ysDiC3C`Wuj41Ml@#{U%FCV^eI7_ z-M`{~aJW{bbH{UjV0u+sdv`|oM!n05uQiM`G`_~;2hoki`5{!mR+n~_r7!<4<4W7U z*~o$tWWczHehqp{29~OQJ5I-HWZ(^1jj%F+CLK7rQk0#Muuei9Jgm-gu7S1N5+Q=5 zvB7R(j4$eH;U*y%6yAz;61B4%mq?F+kp3 zh+#dxnIn73VNLb?r(kFGfXf%>@6O<_`v~*Vr1O5MPV;1^>8Pz+2%Zv~95js3+^Tiz zTi`&0|NC%8WyP%{O?6g|lv5q!bKj{dG}B982G3e2n=LkedsR2k8ZUIwS%fZ1Bxdf$ z=@`qar|kPwT)J%9OHLL(e_m1Qb>q&Rz!#fm?{ASV$8ZlL53SvttS6EKBiH%PEqr_S zbc2wic;4{r#QXhIKT`eMXHzdW22RfY5!g_~FD&Zn7B8`lH@QC|eYDpqzWVHJX~F#K zp1-!Q1NuK5urS$o*yc*kk<D}o7ZE{buYL&(2pKDu*Y zeBk>>?%IDMFW;Zr&*WywaJ|}N@tolo>wQmCSKwUkz+-;CwStE%SoE_+OG z@RHBb5B@H-UtM`GMd{(}?T2pat)*AK*ojU44r_e2VN3Ekn$9tEldCtQe5dzpXD*Rg zXtY?#bOW=4N*?fN85+wOy4F|CF$+n%%0~uSW6GmIW!-}or&`^Tx0hQQOdjqMahhglk*V!zeC4U76!Q-Q62e)X7pF(SwBfYP%8uP%cDEM*|F zNKu9IVJPBX!Ko4fwPiiuC7T@6rxUhJ%*b&2S@r4B08q?R1XxnjN%q`9@1KgD#?j;a zt3FVFo^!4HX^yQcYtQRuH#sX<1z8{!;sAm{^czHdU|v$Sh{RnQPes)W`Hf8Zrjp3T zLlQHR&=V_GkW7vVU&qx61T28j)bNgn%1$z(9F2xVdK6b+he10^G5kPpRh5t9(luNa zW1<%>-Xoq!TXHLt-?brl@SlR19nt5!l=Dnyz9>e&52hFOdcyCwiZN&E&D@@WU)yL| zjrfND3NJ|P49m>CI{)B^DQEia>DRQy!PFf+^(t#0_kC7aXkLhaUDvwpra{sPLHn21 z?-~0GxJ38#{n+@+a8jw}@5mR*I=t2WTYh#wWk30Z5pCM>=-)FiTZoJ%3y=!{M2 zgZ+aKQ^)Q;j(s@CzdL_1vBshLeXWhfN7dJ`#$=daM9`A zj`SAF9-n~&RU>(O7=pcJ(N(YoPi$L7&Z`lMZy!2$93mz0a`!=WFKoFv>12arKzKfm z6{qu)z6}pkGwF%N(|NRQyV*9sINKnhqSAjw2sjW;k0M+4YJy6n@!zRhjZ(J9o<(Qy zdrGSK5bZH1@7^Q6BoBddH`1-uhgnllb_Rl%7LZS+x##!o_+-OU5K2l^lr6~tM=T%k zA)65X{d_8ayBhZNEo}6y^BB0|msReoQPgw!?1>dN8d~{9&vI*p!eK+x%o$;2{xnbf z^r#g7m9R60)bH#(-|#x$jRs2JSN%lquW;PYpFGFJU31Z-Xp+p-R$`6W7$(8_Oo1$&iw8_PW=%VQuSCzL%Wb`GyT{0S%6As z#=e~96AJf(2V1Qb-RLz!9gaKRoto~CDRzLigltR72DjP-C${#Umxx< zNh6cY$KrQyG!$PC&%XGzFMAcc(Qc!&45~i9wIveb4WYUFUk!^HdVHlgm7`IJBxq5) zq@v2_k-Pyy7M8H!ibaA~dv+Npe!~u!W7|`LY_g)_vKu^aa5cLh3GD;)x;Y4vD82&hhV6 zUEF_ZB;jgMd+I=BW@-F++7~x>CK??Ws0_}2m3P*Z%fa*S?*r@({KuQSPJjB)_jbFv z;c+>qIO)aFL`uK%VKaFZ-^J3_bRp+2YD(3AESb16c3lV_j?Qy=P}EFw`P%&ziG6!q zbZ8TdURm}$mvR0_f%hS&)_bw1BO_zs4!hs2Dp?ADnJc=W{BZU}?Hw#ywf^12cxJ=N*(dS~-c^>2%~g!^;r zJg*$zVzx&neBEISVeMY88oB7fPZP2?4ZbRJW{Elr=hAHY?L9c4?vp9T6usXGYuRdl z_E@FyM^x#euC)yH$+#JZDx6cgmFsK{I6H4at(QG2YF%c8!dS8j6Q2kRKjA1W&RX#O z0;8pLC$Y#m-s%3~ROEhXOQpt>WK{KRqh%>9~mpUS=%C~+vB z!@fE38gJ|GvbSF4oLVMJ3JMk4`sN>;x64VIMSs}hye(d%BwNT^qAs$nqQ-HU@^gwB zu=RFBLgjqgg$ILAiu|L~S$n(M%6ubx&ApBwNlatDSL;@-#vnW(+9px#RPobGIE;F~ zJyp5ugL0hiW7IYsM)KLR=+}1LjbYT77we3p7Ju8+%th|_!8{?YxPs<)!f_EIy+nKyjP3nm!SanjLQ69Lm}Dks|(L;ouqy9M#b7abKUqef{JB@c)P`DPv$i2Mk!7s2Bd?qq$B4sYxz^UA-s|NjyJ4UQB|!V)x}Zd5kCS%NZlH)sR5*0^&~;Vb`Slc6!g)WtOp+ zJ?(4(^@w_*{7LQ(y4f)P)=+#ZyuVCK(@6i&kc$KRb&17#%n_afNNL!Wy&!ed~bS(eL8F5hi%f&L>iin)6S10}MECPa&H;vA@_3f_559CQC2p5rfSW*Yve4OkTWOv+EAlqnUi0kfnO- zpY_{ZJd}COt9D^xu^q6*<5gA?Cr7YBgf4tW)Z)yp)PaDM#n-)FvtJ|k!QRe_onVuH^f@u@^@<)-QU!F=R)_ z82At`4Wr(CM*^!BGjnLz(^byfSZGam^z92R>kdE1oaT}rWOBJ?y{ew#OL5V@ zy;hr^E9(Y&Z=+pt=kQ-OaD&$hyt)J5eQ6lteiF#1H#PcB+%2a5rtG`%z9$xBPVD0UB;)b6g`4q3TDa@3V~8{qQ9rTW4^|dtl-68*(f6b!Vco2W4jgDcS2aqim-TaHT7Rx^Rzp<)WYurl$56Ka&Wn^7*px zx5V^X`pKEEZVzq@{4+8zm~pE~am7JQrrc|&S@?X3hOzv;DThPFuIqjJU^{qy=Z?sC zZ#>+VtFJ40(eT)I9-8-AIW`t9${C5=j7Q~NZT4-ULG;>ecH~vOk=d0~pAeV_ocIzm z6OsmP@1K4jK#c9dW9K_}w)8r^{B>MqI90~$$SboWH{$9ue};+RKG~n$d)4RT&BQ)u zc-SPf2E?znA3JX5NmftyzBuvPGINI2 zS~tJWoKqvsiomJYwy6jg8~kb);O2Gu#Iq~KW`%?7(eLBhYV|QO7fgMMtK<~lq!ubo zTsA(Gne6hYo7al3<}7VT@FP*+ipqVw|J?I-f7(uo6INW@dnKYqHeX3BtV)D2?GM)j zA49RPzmr}EN_}FLV<>wb_51|fsxDju?fIUea7tyJhVhr+{LQVIHF6sgDUA+LBVGFcTBv);}nFnV}){@qD!;Qy2|L$RqO8qOBUbnik#!w^F zO+*;x5PXJB?Qx02z~Itx7$kzOQ4-IAH`gCp#f?5GmT~v|@pK|JsBnK-e$l2|^#xHw zS|@1_`Z=i|)>HJ{ZnJk@x%SkyOi|aCsV_Z_UyFk6DVvRd1@w*ndC;2yZ1p0Gp<-#u z2yaLOgU*{CpX?HKYHi^<9~EZ=JJC zy|wKMou_Wxe83UcLz{7MV&y_?=KjKsEwzmByrSKgoIP2;;O;XO z-RCSKW51^Q`P;h%6SrH6gcn_ie!=7l;Xy_J3DMdoDx5UI;BEfV7Dm-P)C-rX$3U5=NN3C!?bB+6a!IduaDSMq>(P%BrD5;*t z`~y4OKX<*hxOULwMx0(_qxlrmSH(%+nTL}>1+Dk#1r&0h{z)jaJ^Aj-HR(%g|A?G@ z7iwIn@YtbF``znY53irJLK4am9SOeM=Ra^^Lb|ZmYyP4W9X{jjz46DgOUqAmFr_c@ zjgAXGqL^)Nn;PSJa->9JWaM+4<>0*Z**9%6Y}@{98$b3% z_B?x<&E;F~!(LasdJWeBn&O+4D-$V4t6M9}xmUmPYxfMPd+z;X@p+z=ZQ0CQUm%Y4&>Y)jlafxbb`9i%tO3xwf^aE@{}GhwASY42=oe-VnQ0( zmqq&N9Oa6JMzeY+{s7<~u5uSfPr%nO$8eUhF?LQ)%NK#C%Po;+M(QUAO~7eT;IgE) zr7%Fn`074~;6FcS(5P$YpnSE)SNZATNFLu=Rhp#t8xx4g5bz;^F?Hv(yyDIu(vrzH zo_rOQYOu;E5@1*OyA{{-QJZQ~7rpwiiHr@Xzg zdGubIK;2iOXL~X{A;%?7(eLZx# z8)0!euG=f7bqCprOD$ zF&7;!o2>_3v^QGq6YqNUl_o7X=ZZ%4fbHP@CvQ|rIoI@DPUMa|ed%b;+498{D=>@p z!G)scg00GN7afG0Hb^6&DpmcxMd`Plwv5`Z_d<$JxY&bBJVr$3(PezodP^29J@5x?+8*;_Bic)VZqc3VmG{_={k@4T4O z^0v~=0o_k1fXy_{?{KoJZ^n3y+HcJp29F~Q>C?-V$qL4=zW+WjGD5i=BFXLCT;)ZkS25I*9U8( z>p>b5=Vo$)L16cb4=sh{=s)ZkT2*eT1@oZEGj-BGDLU7?Sut-VV|sM(?{^9xO|23R z;JZ6*UrU*ZMpa+^ z#%EodSGbAV5%913JXqL`e)f2b`AI@X2jz%uAaZYOcd243gruaTim zlJr3!7kcHdparhh>eMHWwf>i&^2UL!n9t|PP%;Me`s>ZE>#v@vaaz0MS7o)1%5GQB z*p1IOL#?`dSoV6{RC^X6JjCInv!6d6{?RD}AX*hxD7H0;7|@edDrxuVX@+<8dV7j# zTHiz!eG4-1q(Ieoz+(-rh`HOrpXbzILSkxab?dX)HKW#HopxxSb8}Z$A{-q`;s+NK z!&rK6PX>+hJ6U*r7Q*V4s~3I6v(u~GmUO96Z}YddzoWjIVgaB(xwG!-NM;$>yiecy zu(-N45{kC_)t}~G8X5M@+PHa1|E~=IscxVe$z^PFg(w5J5un+!X^pAmg~)-xDCSjzWy8Yx|n{ z@6AvWMEN{wKU-0Ng_YnZP&A3*FSJKd-izg{wY90}b4+az6@H=vqI6r> zOKNc-l6qju?&a5|k!FX6$3xYBbf4UjEYEiJj~mi*)0h}JZkEG2f){!@gSQnF&B&Gd zd{=Wy;vCKU1v}U83a#GZ;2X_@KNWVQ|Gfd)oMnC*#>TnRAoC%_xLaICzDM%;`>v++91^&Pyq8-umUp(;4v9L5&S55e_ z+iBl=k{w~uOg(^7V@x#@+OZ=Mtux<8LYa{eyU^$S0riRR(B_%OpT%O4min#;rYpWM zsdY!a^u|LQ^?2x7K3n{+T$oY2>cgLJe3NfZ`INuK_D>;~q&d9(nNyzL9u8c&Nii2+ zp31W=TvWX-?!dD=&Z&)O5-X7xYs`K1#(Z4<^9I?Qu~%$Ii*Eod*6hB);ghJ!LOV%}=_D)Ezes z#9WtCAc)!;6<=%k{b!BTlc@!$oJXUx2 z`gw}=fJVPSZK&Si!JS^kUv5j!?0o30xW|5=Sih@}cKOCxuSGL8rZ!yXvJFT;yWjE@ z0rUhXqO!aS-=jBbZ0tCS+*DN=JXUQ_(I%(g=(C^qDFtLYSDxIVV5y3`lUZLA2LE-aKXvc$#nYEqa942g-M>+FfXspd zTM{eWI6@Mj7%3aMdkWfp+)8pPGXkFLyv@R0nqLp4%3J!MTgf;vU8CajL(^_zx69dG zhOR+0Pu%?Y^(+L7gB>^1M8Dl74&BsQ&Zp{6*yy_tddM5l$i2Q=e%<8oBK=GaZ)?vf zgJsDnuBV;;{Ds$Ppl8Pvc%B>fcV_nPJN;2R(7V)(t@m4z;H?UZ?AXv+fowcV5%kI;$7gM z_!`I^)TOHJ_U7qTJE?nRm33kZHqyE?=^@!JmF-O91twNjQqfvtS*QVg-uudItE}un zw#X+X3SJ*ySm%M*0OAIcctGC#mnWd-}iGk|gVE1T#6MXX#>s8g)9PKSwdfb-F3@wY@zS+dKC?NReuiyK2S0AK~ zQCbT!KHul_Dz}$=Z8kFO#s(}vllng@3ceoP(eo(Vmf!wEPuufVH~U{L=Uv}1No1?? zUt44AzcOAqzO*0eA3pJV?CLve^=naH0lXl2ar>La20eQIvuot-t5-7Lbm?O%Dy=Vg zntG!m>C8{2Rk!43m42G(gvC|AWwUj8&x8AeassO2ByB-p+1tRPcxTHCJ?+s86PzqN zy_oD*NyvWoCN%=@Cyj-*uUQlZOm;mu9Tq+%o3}IY&p4~5b?RVY#z+0X0ue(q76Y|f z&y{BQ^Zm__ex$w_xW?>Nl>v%>IgwrKb#|*&kR3~JZS0QKO!jg(JAfhN%9AJ6E%#){13!@hil7HF9|EU zl)iKu+8Loz_$k#^ev6!E)H4c%+s|Te-LP3?+rgq?PEx(ziK6ScelOvGCGYb1y#$KT zQrzF?EKE$HKqg%rHKUL)Ll{g(MGeyII5q!tFm2{~q8Nv+Ja$G0ZdtEQP=AT6_OwUIwVWUvk4Q zHoQ*wXOz-e_(}s}MekUOv2EHIPo(yz+|Z*MyPSWE<&m`4UbLhTsS_|kX?=jAl9G!Q zSTZwlc&Nkey~Wr1=r=7}LPEQ_6A8yq+w3i{;h4dR(#IbUE6AMf*gAQ0adB3AArl$4V?|gd4TKi7_&L;E-(?9P+uv_hp-J551;pcu6$^ElI{p{T7pw?N)N7dF!{t1LV9gR2ZS;)|=sB zwY_Xk#(_!Tl82GY)tzt)mpB`z>#pL5Z=mU~_cFU%!8#V0ph$q!t~X70+`^qHTs_53 zw>xRJWfZAG@&ImOiMZ6Vq8i4>e__@PW0nyTO+gkJs(c$qOyk2!xJ-|F^4%lv8J8Zx zf3fXv&bulyM9uX09FBMTijESkdK!kNt5H&3mOTS(xPRhZnkr*x)e)M>VKzQagOpjs za$-6~R}uGHCIGV$7>wZMHEai~`WmQ*ByIL?H_Uw`$Gp?^XwQ@8leAvpg^BGl+A8DE zR{Xo+-t~9^f>Z9oPUJ&)zHV8z_59?e;cPl&(dnWCYO{;Cnv=~vdr}pnsZ)^mC&=kU z$k;t!MTXJV-aJL6pdzwgVq503KC;*bx`B%Rdm|Agvy=f3RcJOD+4RqD8Govs zG+HDDj8R)j8wS!32oE=DLgAumiCOx!>=jvUL}k&)o|Jxw@~1A1M9>-Dz9 z%nGS}?9;!oHKwe2J)&6lV2?0w{3C+mbbWQd^6HLgHtr@V`&|uGnn3~QlYEki1HAs^ z>2~Ni%BOx0dd*W2poeX0UU8n+U)>WrS8O#l7EN=|`Aur|CNcmC2Co_HmiV-Y>J#xq z{w-2y6zI%R8Y_Aol1PHF=11=~Xk}xlB;IdV6J7L>l}x5}IZtIrJ)0>IEO_i)Yv(B3 z8Ri>_!?yafBzfyIg&ouVT4@>D;*CrdvSJash95;ljO_1b$HK!Fct~uIeM-o2Y2J5A z1@AYy$+EwQ`kk*7bI*4h6+Av1fZ%=12IX?;01ryP~~|*#Ty#lf6>l2j0*wb)#8i`judbk8QNrUB=C{# z3rllfQ0_iSz!v6Ci9446vrS_iurCHIFde#mVy%TBRotmOYO}1;ARxId*D-t z$79An*EUyV`P?XW9^J2ezDC?A@Zk3JaM2UL%9mBAM;X1VE-;xB{cVJ)%TBK$GtO_{ z+&>(Mmk7ukO+&?bJ(px=0?INO&m zZ6rFSGA1jw`yD4~X}W(R_Ng(09d)lwsoiI$LFtBg=*4SXg!*$B_5o z4WZlKVHS4Ge_RAK)|z#cQr`(H|!!!EKu-Lt6Ccb}%H5D$zp zsCvXlC#ig$jHbS+6p7L!th19T*b^a=@C>&=(9$X~Q+S97jo`Z=H(?5Mol9blJ56?0 zwogCnzi$foGcO|YTbQiTUbk~Us5p}Bs`{6I)n`nKM*3vbcIszqXmtom*8=pn2b&_T z>n^~-s&oz1Vds3nultyWuN{WJeSeMe>3{##A@E{Hh)%UO`5^ zbCEbvA|v)cNDs<$4M3v}-tohb?S|58=SVm+P$)CsOe}sK3x^43LGj1gcXrWw9ZyaU zlY-vZDVVUr3HYr<#$bx+AA;Nez860%Er}PAk&S~b<^evM$@={rME z0rn&UcI}DZhw{=c`H-K+Lpbag+|P+MP}QJ)swf2>Y@3vsbW6H4G8+)&5D1GVHR4^^ zQ2ckD1wH;&ULK2RI6;ho(1CV#bv^ka2eyI_9zJXZYyr@OCVh6~A7I7<451U~m-{zZ zySFOA{~2tBVaDsTU+xB4gH!PC_MGNMxT=GpgT7i&PHzy)Uju!H-Y?0FUp z5{JRMnwL8bptA?w=O8%Yz{6zTVq#=;UjAZKxt5vm`1O4de;uq3-_zEf;hqF;%*Rik zes=TBOc^GCfDK_wxW8G_Th0rDzSdCI`e&dWy9T0Zzj6FbEM!^v%)p<3*?3(YTsj9y zQ}>CvHzN;6CtMx$(OD7p?toK+Rw@J>R5?IZ2%ZM7L1zSZXDhJG8mJdE5z4~s!a^hP z=+t!jJGS7k$D`vfPWPD=b^U@cbKzBM&Zf>F12nZYrVe~sy3@5h;kc7 zCiKrH!}8OJRV4|LvdlUC?$;a^x4epW`Is~R8?T+KJp3kly}bzeW0e;psg9#*R2vf| z*U??1u5mOQ!0yqT{nI(a<*$?Fn-biu5yN%o3r1brd$I4-D~VkN#2?OXaH_no%N@v^ z=RAn-o08JQT+qH*CUwdqy2BuQ_^8H`l$efJ_SCMx(=NJKy9}ed{i&7rM-$nMRPCew zX@aMk*-%$ymJ7l#_{zKZ)_BJaGXydTG*_B&>FmPCv^tHPU3TGCmq=w{0oWDvJZl8# z=(vef?PFD;K(W157dZ7)RR-^Hn8q){t8uTEW6jNG3)`n4^QM-3ut5R`MZs-hj{+*- zp?gSmH~*9z?;W7h!E(eX0LY~OPX!-SIRG_9cKH1})#n03PI?|OkstKAQ(um&hp%L` z%+FZOXCwsyliwy1coxQ~)d!sIo>x3@pmOY#rQr{^k6a5k`kjl2njKG06Ait}Gg8=I zfaQDt>n{2&lTZKU0!&%)*CWoH?3lQ?8?!5;?vvYqQf6mm>74vs9#~XWRRtT?{ekDK zS_8WvtptD2A(u(ekVJ#ri+d6b)%JjepvRqH<=W#&u)H8dH`N7Fx3qX zF?FHKA2+9c^5heUhRaT>1(Kg%x(4Senrz#YySrmLJiK*4#GBM8#<8|c`0LAohxz3u z1?L;ov#@K@xdk%)9W}2^>T`PTH#J?cyhCZnXey@Y8~8j{@=s3RE25FuFBlLuu>A2j z`|2dbUtJK#j!nD&>$WRqJ)ug@^O2RM0m2Q3f*ISbg2hqEpqcoRsyaNO#(OJ`6$aH=T(x#EexHj!DRrelr-1r z7k#9YXSfWvI6kZle+Cv7$^2Iu56BS@44g&Hxfka8-7_vB=V0Zy;o2i~C7I7I;Oy)S zuRS+6mw}0?gx`>pD8HPSiItU3NGJ)cn<|JjK+y{d7C4x|2{-vw6o(uw4&pk3YX!x) ze;Me_87V2=-@m%%48sQu;!QRnYT>m{#wWlc5D}Rvwt%Jh@bvUFcHgz`D{%bYgUp-F zepTtYKvai>rDegA4djvJYIv1#S(5 zV1-(mS!NSYaQ`-hK|}I@$)RAW(2CtCVRT_C5a%)4t?R4saB z=hY|=ydBUa=ibacnm5@xWGA=}$tgN)1k84p#>NdTRh9fPi_|~X>iC9YSDsufH((!* z-EESZ@rMb-ZTagPJi_OsTn4fz$s^N*z23hRf(N0jE5|5^ZAU=9+5E?my{97!Pe%@4 z0&t=aBAF+4OBUjN|934i$^68&Mn?+MI=Ar0ifda$6*1WELM3z^)ZX3T`84kJM{G!s zsegVgB<%q^yQ z8{3+{N$)Mtm^{;rS!e7`d6{ivy^E4UeNJ$@4&%2WkOrBz5KI{=!^`<)ewgiZn0%I( zf(dEP^Wwao;pnArqpCNc=8S}CF)*(pv}bld%LUB1nnJIU@vN1Cq5uU5Y5>URO{=IU z7fM*9mDMs7>2fQpsrsem9sXQs!G zGl9yHHEjApiV9?-%iul=8qI^mMiS~9Ai9wVIwK}&d@>osFd3p+ioC4H5kzlJ1 zg06nk3;1q^pn8tgkIdW}iC+e%EN-|C2|10G63h@T)^#5H`JF2XlQ6Ju8OV4JC0d?V zO)Qw)A&eK4)YX5%U*5sMFogQ)0>TYG%h7_wCj@Lq!0-~p{U5-qxBhgQ7$Gb1y4ok- zu3903JehjOb_=t*i8sxkKNEnfF!*m#(9#BkgxsBW-C*&A91zC^Ful|RaS#~iBFV<2 zg7PdGTpB@1Foh8|xCpO61;;1CHQLOq3x0zEif4^kQfzD+{5+5dp|?BV`hkS+fj5F$ z1J+yMz62&xy^`H!CQRkvO^c}Aobq;CO3NT3!9~@Te+c42M#h zMP^^mb-J{12xGXvpi0)|PH+KBLxeaQw)!&2)N8?u=sp2kN^9l(x@v6l?@TA7L3M2z z(H0fh72=`XK+`-(J_%YXlFipNd|`9S^nJ{@bmgMP%$+W3pF{5iSNl7PlTWVg)#Nzqz*gbvmnoipFDz!z@o9XS1u>%g@KyW zOg#*~)W62zRm2xhNx-Zq(#2V54Yi)qx=&83+r>Xmj~Iqdn3At|r%LE=<=5T&j^U+v zc2x+}exR*Nra3egT6HB%0Hk4x7#V8*%z0iS6MlI=x$jA$aQP4Hu@JWhHD2^F6mf%)M>?bY=Xl-9t^91b+xy4CqlP8MAJR;l6Z!12a&l0>7d3QZ z0$f|hb;~5j!KdyS7!N=?7(akoaNRy}J2HoU0^xTDB4w~|c&>{|AM*;K9RqnOOFJB> zy`X3AGffb2p9YIekRi`!#Jzo*@v^_KPZTUsavy4gt4IHuJ){XFf{Gt`BpBf{OAsan zc76i2WGe|8P+&sdvJTj>fk&H> zY?R!NHW7(BkSfsSXuTCSIpSL8XbuJ_iM%#GB3HW+NZ{au@Eb#djcYT_3uF;+rpy2j z2ZTwezLC)&2(*%~FIMn03X-fyyg~o*F+RRCx3E40==Wd=Nkc)A+H7_?VOD6<#ZrOL z20x$g1D7N9D%*^Vmwm0j5BsIbGvNM!h?F=uAG$_IAgzG8LllXIh6b!TBEcCJ907*r z&1m4rf%K2p7W<>q@fUlC)u+n|;}Ekz8x=e>r1I5enGngc;nLCbVpm#*q`HmdYFD0U zg9#Ze$hb=AZB#19_0zfR8!KD6Py{YK*@06ss4hyt*GMq1&d%;()!qe8`p$Jo=lp$` zA*=$k|EGA&PA{Ou>DwCb$Frt(iJqL=n0DDA=ow^J*nrX;NOl)yGRG~B^=3U53JaBf zR7Ytvi=%s4S65&C8K>q-8X)3om&45CkFTANh^A62CvA&1Cf?S<9ANFdfmXzVj_m3N z+v)}(_dZaem-hBios?7~?}%Om@F-=g0P7^K)Pw0~o=SD_=L>=_(%c_`LuwR(MEPCV zx5Q2H<#EBI^Akm0hhw8zK#ArF^&hUBjzEhX(DZ>9$=sZDm19o15{`xHn|;&lm2S6Sn$GOZ6lvLzbWSz{OL=$3VD-nvcJJE z;(&jeT@-s|L8^riJbVcp1t!VvU83*=#W9z2yr-H(mSUaBKN1849#FJY{a@r%OIvG+ z@VP+;$@{B-spFoAY+yd=G4F?hK0g z8b*3t7|FFsk!VII8~|_kXLj?(?mgmO(4A^7zrIT$u@dDp4<|sl#VHSrOK(a|dmD*T z=W2)OFOzf6POk97uusH`H{uCY{7|l*DLQ{HEBx>X*h+F9_JqKxhxw|n8y=0`%A$hj z1cHZX%0*~28%@Vb|Jcna0`I)xZGn1%^DT_j1f!3d)}S7-X=Ql)n3kH_52iw}5x@)| zfP>pg<$urMGhX(y?2GaQ}jt)*|eLvQn^O!PIu&y#;+?#X%C7lP4q)0~NC@q^7z$9@zD} z6%Ci@N)J*X&6qhx7YUpY-j`R5o@E>@eUM`Ur8+1+JQH}6so1Xp(krJZg zd+Xo|Ab2#U7h4ZpDe&8ejD)XeXRct6*a&Y3%h2_bLKb5RY)sEED$s&n?vKGzgieBO) zMPV(E-9mn4D=MqK7Of!r8GG~LDA`Z%yZFaQpwUM3n@FwSF&9V$5hqbGj#uW%!8^el zx8H5d${NhcAo^!|j<4fhbxZMU$WrWJ(1QH2a#|Ca6wR_I-6=xpx6S(Ik!k>6dWoXWp5TBbe5yQi$j zceXEp^da$*9Vlhv6-T$uKEzAwEZzsMcZ&bI#G;5~P&F>4 z%&AQvz3Qor*clnTlBo+&F+V0(M}4~Pg^USl)eNr-j*fIW+N6Vzq7U9YeRM!um!qzv zgsmiIZ?RD@$y}5B?dr!yLBaO=d~pc6($8XgQi(UKsWg7n>BrNCw1b{riNC3%wdxL^UDR*BMpT%YTtt&Mv|jW5}=X7OrAqD-6Dw85J3 zUN5pztXs%HV$@9u&J5%`5lK>pdZpw%WgPd(oK;Ti} z149L7l(&PPF(H8u1^A(35fYl@UxP=I4XDc(*49iczL%Eb=D&I_;fL1mesN;+K`M>Q zKT6>{!W;&WCyhb@$i^uvD;wd5y%+b^HCSM~@&*sjr@c0Pc0>Xt*ejboeEixOl+|G2 zzu=GmR;M-O;U>g#s`6*Y6MfUs&S3jgclsazx zu!h_i0No(2XW&ZB%EsQZn_iM~K71|CGIudRMuP{CKFXk;0P!>Rn zNzJ9KXT3_?+eUNtHxXMIpRJ>BY$T`G=RA`zQKb(e5R8g1X71U1d#iD`+e(*xoq@Lj z6W>Yk;%RGLtm`a?88O+kJoZA**0tZH8VSX_9=#9MyS-Y)Cf8@*`$l31c;;LawWfjy zUG9DEhOnE$Y(@pt+1WU+%uLRxX&Vk}8|6WxUk;$NU=R0N`0Wl^8jf)Oc$<;fFabL7qJ*IR5qg^wVrs|9t`{ zqd<%2h}F4QBAKf5>$i5vUw`WDOKI%gLGs9N6v62?K>hgl@15n7!HZ7BLunjq#Z3`(N zz?E`-GJKEW(=%!jqjc+MlxsgFFsfpwI4Dux7Zmv1mVek!<^QxA-XzFEJ;dwEJWn3& zvdJrJnX{bl>doCD!uq0v-aj2V5u(X>PkGXPZ9SgsZ~CT&xK8rB{H6-+#~KMZPn>BD zVJVad@aHkX_j%AUEDE>>KptSwk0{F_0skBks^7?w`#VO^y-`m0!;92IkjX;{wQ*n?8AfT0( z*`>ivLti{KdgAJe!IKoC6(GKv6mD$rPe<6|PNWZ*c41)o#DHPE`k)W8+!uC#&=x>W zTfPD5p&eNGLwS-{UeVJ3#24#WMFkDn3EZcl6#=8mP%@^VQb!2&Lc)FcFty(}C>R?v zi6uE#sGlgPN-cL76rV$>d_|grdmIo@LQO&O9z4R-yAbxMZwo81pU8M#apIdHk@7z- z^@nFPwV31`gr@w}3$IQph@QnH~jaO`Q z;cCGN?u84E6)8;n>p^wfZ{O2vsjjYfo*spn@zrez1@xSSab<{U@N(f~t4lnVjiY^^ zp}24ZEhD${&4_#0`Y#go+Qb-3vXMZ1u@{u4i5>bWCr#M!%{BN|fzV#3zkh2C&7OIl z7N3WL%%X3kd@_*gxGbvVp5Agk5<+R_t9|K@Jt{JtdI@`i60wM6?BoJ&+xBj!%zU1- zvB95F+hFpyUTq5AAz;sCKr!=NSA;qiOW3-&EDyfbUeBd563A$PgrkF>)RXdHY9sliwfl_A*|bs2 zA){s0x~AG6HuBg%dU)Dl?y;j_scnM`C)Q(<>+)_-*LJ?EkNRVYGoL(9o_Fr|up7?{ z#r+vs-n{xNCe`b9yUa?xJ%;9iOa#p-Q`Rr<&*QV$Xp%A?2=1#y%2Gr5u8Ah zG#I;YQ22Y#MFA>LxK+ju(gxSS*vV`V!y7DRl(n=hIA-8(nTJu1J{U2MoNi?$gTDBc z9tyTPB9$|Gm4))WRQzagU4Ui!-V{2}?dr z?CN7AmyVjh7$HBqOYj%)YJ)mU@R8t5rF0yqOPoF=J0BGZ9%pW$G%V?`OsM~P$!`(p zzaDvSDBAE%L{bdpw?xS)l%}F));xw{c?%Z|u@`A@2vb<@*_yc+Z3Pr`n>m#5nRiW# z;q1U)dL&L=VZtiK@I1wrWsi7r_|>ayvfSg%_s*A`IF^Lyt{dkCzmYlbxFEsN$lyHDUnr=TDUOFU(C_#JlwT*fb6eDo13%&5;nLyCG4(UD~}{GI9~ z;Qs95k(cHR4KrDe4*6*YN%03Ay@@&Izl6{(SDspS^K~99qZ-P>_)cF585(1IX3!HcEcTH(vIJ1uP3&T3Zn@NPs7T zf)0G77T|w{O#$FKWQjz5{MZN{YitDf!EyJcnwm7Y6T;VkEn6^nu|kyti3bQDRfxd( z3$i;6<($`jre)Ewv2UnoUxU=n06Ho#l#GHqw4tI74qTAC0unykt+IR`Ka#c4Y4>p^VlGoez9V8I z8<)Kil^8gM78c&X)&w%8Dn1}irDea{+XDf*LU{Re5@Gj$OY>yL_JvGK1B>rjSwRTz z_mc6=zRxV+yomf4W>%AE=8qlokbvL~^J_#f?{aUl70&Blx^9qJn!5p5mx8KlOm|iI zX3?<=xMIJ2@!}m$zA4~U^f9stLk5xBw=K!)55kiyg$n4Ot-TcJZeFOVbi)?eLf&99 zJV5Dp^kgU2j(^(LANJd2)lTq|YQhu)$;qM6vA4p%qpz{U!fGMM^g+J5A0=(t&o}Az zs;TxSAwQJAI<;B4C6y6Za~Fn>-J_%&7}H3u$RvLzviETOd%6ACRcl`iACktq@J^FA$Rr!mzn;2vdbuFj2GLz1Hmii^8yJ3`pIN}CjcsBP@V!-!F!u`#&ox+n#%$zQ1w1t( zu4rjusEr?%ay$4+d|SeLZ7%{x8F~epD{rx)U}1~ggEmK7P$af_rdHJWIv6*DJe>_D zuuFXUNf%&*dnX%Jc%xKHwRLTE-CR6N+fu{fFvi%d>&-X>PI|tD>@J=CO;T{0x;axH z_lG2S@f*ym768d;ot&J^)XaDZu`~m(4u?&-07gIqI6?=OC?aVIx`(&!yONMD0c?#h z0NnpVqwonP>#(p91G2P!M8X%i6zBPT0%L48DAl56X`mXSf&GU{=IjkvND<%^z~EqD zW&NI)_W_cY$Xr(`*xA`3cco%D6KsN$P@wdP3}<#LxrvGxH@)l7Y4Yp1)RkY>Iy}nLtKQUajwZ9Qo+kjq+u3vecJ0a zR<9M5Gn)5WFYNA3HivZ;DA!K5th~Blhx2dJL3#y*8I(W{Dw*>v@>`EXRTxgtS=MZE zN6Ti2>sflTVt{!WdW3_$_>rGS8mZPVi|!ofY`yw@cUe?J!_Z@g98bET zzv9W(v?_NYwp}vP<8F6{+irHF{T>!#h4~q579yW^?T|iA)Mhg0{wb%4%uR}SA3J|Q z?SaO1YjzN|w#nbxaHs3XwZn@73_PE2gUQWb9O6dXK9GK_x)(X(Jw9f0xjlP9OE2iT zyM>!{GyamV^1pky^nrtHtaCiRGrKqPEhN6k}qrLSJGR@w>O1;fW0T_LO_bB*|l{PrG3$yP)} zobKmmWzmLopW^nYuFogK2o5H=H@=fyB$ARd>+RQ6>?doZ+Aa!cynkyn8Fk>UpTi!U zj=GR}v{EoS0II0f_1vsN#z#zRZcx;I>+Lh!#U%et+Dn>|$%zx=ge5ylTj&L~YlTo$ zP(l4bJiGa?4}tj(%YwD#U5;xG4$i3D_mVBSwH-C;Zln=gWN(#sI{~(FIETaF`F8Bi z)s4oz&7XhpH3i>{j*f=LNqZ-?{Z>+A9!N?>vY^Q#x^`dX0(yC_TFE-?u6x?)ez@cL z6W>gdsY}s0>KSg z%)g0}THB>1Se-YE+QGAVUxy5vlcHieJ|~D)frHQ_*0K(@%5xH!hvFz+htF7`f;QiH+!x0G%KDC5e{q z^c?!I_yM`{!s@^i6HKMgj#xV>#=rNnf#7Ny+gTizY| zBJAeAa35F&I# zj`NYr;JMMuJ8AV_HwQJ?2#I)0=Uy95UB9bI4wbMidzpmVe#J8K?y|r)%TW8v#WxCi zGK^Y^@EFUdN-9Zir&|ZXxN9{Ylw$9U>L&iE7>1xdm#Pc8np9nXKKI)djc6d6bI&$H z646+yk;m>7c7Lf|v;bV`O^n-N$YMCYLdxjKx4j4FW~0pR=-~h0p^$!rzR+_mz)-Bp zxsB?4>tG4~5Zp;OMtk^WaR7_knw_yQC7j7I()-uVNuww=g6ki=P(VLfUC%dwrU5O4 zXn3ydP}M&j&WCq)o-5W~(0PP=Ig=oNx`RZ0T^heAluO9IF!#y<9i3=MnBsTkPQ!>< zFI|D&P?*=+OSi~m)V;!Fs5hW(FnBmn>2}maM<4&~K*C-8Y;tJ-?&_o=aqI>%aZyhz z7T1Loabfd*@W$hs{JZ`*?{3fukT62mdmuOT6N~%qUPNOD7u$g)#o~+V&^Z65g_L}h zLM3`$j5B_M=}i~+ZR9K_P39@bbTC{#cJ*`jGAFcy>H`>wV&-?gEz%7B7SU%6f_m=`qEri;g1aO)T7@E8RD# zN?1fh6U#2o5Ag1RpXaOokN&f>v#&<0s;ei^Vws!Lwwn;>q6N#Eu{leTk)HJaXpHAS zcRbcwEAxEra~bJNs9bBlQQQmv?I8WhshWQTKp60%tvnpr_RyL7D%34fn3KZ@F6!#V z`gf+Mr}Mvg%6L|t1h(2V?_5a_lvgnH@V3w?-lyg@WQN*TB~J5^>507N`Cooqg`UNX zP1@_J2qYkdguB;77F7uMt|la>7O*GZqpPRdZ@H$IRn%Y2lMW`MxcZ4n(%?6ABU#tH z?*WNW?B6kyP4zO|s8q4Mv?0%QvXddx!H%sRcEjls=Mz69$^p5yesqFE`T1|%JIswd z`bc;EIaFI$fFpzSBh!}5^D>!jwJd$}5-mpU(QBCmG}vt)&acem54m)=ap10aHhr#r zckl>G>wuFrO!oP+cG6-E4K+(AVSdCFzA?WXJg&c3!&69S`>Sj*aiS?D`1x7_8@~6L z%yUpa%Wsd9nxC#brJcEa425Po=^Lx066ML6cL%jbG9r5!Wy~gBGX%oNHa+C#wy*fg z7PK;_E+21yt>aJhU2dYtNI)f&Zdm?1+WR8W;r`4=WVwc85nhI^d%iWUL)tH-|sZWya{yi0*fG z;j%q3i#U0$fwW|ztM%tK(faHnozBpBtoC*hqBl-AN;$e`wVyc9N}BO}u!f8BKbte22RnERr1nh!NTO2gc zpA8a?iZF*O3rv?W9lWT{L5oN-6v9{+xGV1<6E_)kA^5Qg@LW`7ZPj1j6)~uP^gh!R za?i^BMfL8;YWGe^)i=kg9Cre?Z3Q?mAG!Cb_Kg$BEDlN-<)?yqJM<{sMK_4HORqYDex30~=`LsKFs z2GC&?UYQ|(4k#QJiBQ09McwA#&$xH#+J3vmLgkrK%oYQy+UB^FGy)()IHJP zjpzBUh?_Vwe9Xd1n3|+kC!b&Tc;xHTcQ*z);B4?d@7yVxVw)pOTf{PA#2d z>3Y|+X7BZeaE+d|K1QCNwe51ee_?7iL#miET$c74%6f62|4dFXUcNT4%H7y@J#^14 zE?+LFJLji1B%xrTyfJhB>U}ey_i9vY8ve#;e%4tmx`y|pKOPxp`R9>~si8kM4f;yq z`6i3S&nJx%CF12RFSx_xCQ20z)iUdK8C5ug}?oUm_Dj zp2;0eRT+Zl?vyFLxYm}L@0f+rTfeussTF2EtG!FNDm3lL9M7I*+9~?%=xe#ZI69Z^ zrIrRg<<4!)TRYRbiS5Ez7Rc$BkIweCCOP9`i`4sGJ?#<39#&hzd~Y*5NuZO$vA|`V zI{TS-LWou7z(_|$>p%Vt=upWH6ifiB7@?4gT zbXJH_mitFjiBT!tbQuXRO$_S z)cO;S=E8HT-9fTP=LdL4g>F9eckBo&bZ8jPM?RJ=?X)O*eFQWb(FVh;uY~*pavB|w zpd&sXx%!k+Pu0J%j+mIF2vf4VNqVwN*K5eU-e$n7|9De$Ahuy)j#$>gh96$*$H@|I z4_yJGlrHJ;>*(`t>iBZjIkLfU??tm!Q!@{4Nr$lm8_M5<2*8>@LX#!mG7$?N;UOFm zY`Z-?c?L25*;`39f*LcA`3*IQM=+=4UzEY*woVapQXrvV1 zNcd{Jt9NUhdOUv#FjHc^7JTU&_;l5}{S0C&BEL!j3I>r~64@%Y;IFKOO$_$FP#_yY z-wlZe_19N!Kq-3P(BRdM|J?Hvv_f#rOqQ7mxm$e8;{Kjt-1Lc_^UwQ%)<4xxCh-aw zty~Yubg$1WizoYCEPCHQpI~bEF;-sKaC1Jor{{eq6IP7ctmNT1>HhHRiTIkM?Tt_i z4a%xFY^#20A-4+4Z}5Jzx6)Qu(MFM;#-WT$4VA=AYpHm5LGJgNW`~X1i)IA84L_bZ zVHY`yW?V{^ErzwNhY-~aZ2`BV603bvVocf25WT?M;1 zZ$CjP+pLt$<3q2fL%7^`=Pd)H(Le5SIZLBaC_XRt^htd_+u|h|vJ;6*antn6OATcV z>1*`qIkpqWv3(T%ExZNGESy7@CW;8rBI<1}(IFFIJS?*#y=%OEj^!6c<-!-N1h#a3 z_jjh8BMR|0uCb3pFW+;RrS7O$M|#EngTGcSMjIySj1&rIRxhH|j0&~{cU!UTUq$o{ z$Ji}S#xQ%XF4NaADt8SIrJ|j4-*OKvnmrKpB;t!fi`YQ_mUTtQPdl#!TG7B<`KZrlu-I-bKFb?>zg@tRiv9|U{ z!}$aMKp;$r4mdLvlY79W2obD!x7DC$u0QB$>TI~cwhjbGY>pNAPFmK;hXlacR`G3g z7@Km8xS*;{_j zzkJL}J}|ii`ccUZ9ngM%5RVtAm3 zXpw)T03{y5!5d&lOq~GBRry@`b9pix*41Zsk@kAF+VqDs2A>{>C-rC*W{w91+z0E6 z{QBgd$~zSy0nAX4Sx_QX$cZn{Z%ayCFb{doodjaix-PPSmCN^X!SBtxP}Zf;FJOHV zUsmtBaBH6&G9k;BURxKl8F}J(vGNv%dxRW2gf&~Q@DkJLsfxPQvvC#1Z+=H__BuOq`Z|7ynm|YrTx*dd|V#VM%R* zIap#qCO$L(>HeXXnY1>h!Agr;Mh#Z3x&&ivv?ex=UsQ;bAMbbk32`FQIphQ*Ex&NA zwX$<9)VlUEVXL~#ab=_~{(<>HBjeK4)XePgrNpK0^$O|gW(w0{Xyl{%6&Vp1RPrW& zL^aiHrD~7Oai1P0Gg00;wv4@+Bx7m+mTfHCx;%X{B|pA;pvNAvDiIz&I;<>VH89#d z=j1n=y~Ft=`QOjzG3z^DT0P@FC9TMJFqB`AMnVgc!wS($$>b!iD68)s$VJw|9yf>D+%0EEWA9HH*>^OXw_;liBPUC%{RUrC@CY+OAy#$C45=aKrYF* z&Z4}5ve0r~Z1)Y*g61Zt>sxM>ikXP0muP`crF}XJv*q=~qfWB;H7?8vd;VnMV+ZqZ zHn&dSm-+WGJ}aQc-Yt23u~)@p5gtEz-3d0{Bdp*y(w0XnLL%9{uz>s{~n zJa@3~i6(bE^^3ZUdWJ2v!0|+&_oH{_;ihE&SfH8}MSQ>Ny(j2Fzl0y%6zRUjWk`if zD>j8P2PU~V3^$e9ZvT?UWoQshe_WE1jf?I1r?!<>;Q2mZX`XLFXlRZdsd2hZZI30E z4Z8j|-nTTnnWw54Ev%chTK{=m;qj68c=>8(ad5?J#<3vPU#>YpKtA&DsGWqgAtR#fBGru zm+n$%&di^?m8|9b_|#B+u94;pK3_(SRo?7-CA$2WjgvFP`8Q?L$4t4P0QYmB1We~U zVnR}NW1j(r`9@)pVcgX!o{pRQYqc_YU6Vp~U8ufer1PGxZ$;{>#0m)_Mp@IGw0ys* z8%=HD|FcWsJ9lLKlr$hFEieCJwpGbxkl8qnPD#gA_cVZ~%;T?>k~2!c%)M>Tt%|jr z?Rb_WC3*>d^BwD7)2I*eAGsB(Yh%9F)u{OE7xY`hQGvHJIulLoqkp1@{HOTD1itDa zJk7)~S=9}8<&q$!Ze=flr`J`KVPBeFli-tCk^cF&42Bq2D-dSIo&N)0nv38=3L{E%g6xMm#9^d;EDf!`M3Il%X^x>gA zao>wU|L=PJGJo$rTv+EAFDm-aNsjn!aiIU&HLC~Ptn&9CT^3`-mX}``T9~>=z3`?y z{L#J_NaUTLY0uafFy5=BnrrcDb+wu8ZhE(5n}&gxU4*=T*FQ}76J=zo^{&pYAUw(L^|Jgd;#t}Q5uL|{%t*){kO;x`M>Tnm&;?$xR*)&ay}*On&h1$*ubTIO z_GwPFc3W^KC{?@uSZ(E?#~tv}hJNi0yLHn81@lwl>gv024J%dW5V$l)AxX6KKHb9a z!S9WrVfVyHy`;0Xot(tYB!A@EBACgl(b_Y7ynCu0fQ7~P!ED4*dK|^pI59rIf`8g3QF!yG27NX&&e=%cOklLpMI}sEh1|dN&oE6^HuL)B>kj` z51j%8;^L$aZ>@YTJz)uK1IScwPiyDL%7XU3e7}pJ`%~jS6=jXD&w+|?a{HKWzlFAx zD+8dY2t{kJo=sQssJDSutD=IJZi7av4!Rh(d#QJGzrU!id}4Ve8+bQEGCtN|RRFyNy*Ju2h#Lr?tRwc|{*&Q!JCkIu`WMQW+I zw=aG-kUCPE{(nJOX`LBtXVjyu@^YX|45s96arY~!nWKjjcEKm}#D2NZ;;LVUIx-m( z@4b=*HoG+YHSmPo?s?YazwZ_dpVqutc`YF-a>gq{MAngvQ1extU zkc=MBX)7I(N_uu@`QhV_};Ne@%*e`@B{2qAoI?jdCsb zm!}=$e#KhZ%=o=6gwf;4Fs(gCLE@RH)yjX~gh5fue_DjKv6>^1p8WU8?8xt6Z4C-@ zG{O;A<{rzYpR{_!Lk~mk9KzPR1W_oce>!4J5En+3JX6GDQ<5Ox<{<2`LP33j zk?xjOy1P?A1f{#XyBDzt>8?e0cXz`#*WTwj<2~>B-oN%3j;+ArzUREIU*-|vL;spl z05D+RHK%ecugBXK$QE0wLfpJyO1E-dT(xoaz#h*6zlh93KWuyi=Wy&cOmejGyYdqG zkAfb*nPjmqD%!sj{1_1g4R``!O1b&1x;bT+S$f;~$cNiwSjQg#AWG*);IhTRkyIAzv0$NZ!51^eO_j>Sq6H_&aJzO|tToN8Ky$4H*FP)IEN*4(B!2I`^g z#&QJo6bvkBlKQ1YzX`RS_&^u%kHFDGfUtkeSXUoxm(m*eVI5HTpn@-uW~I}kc>wHw zo$Yfdl!h~mrW1G95~iwvgx$YVX9Kr{)AgB!(nQ!f89)DOH8y|)fgX3rROmUcxj8jO zM6(uo!Us2mUq~;xRTliprfBM}NQ70ijbBDhyb-SmQBaSz7cwuR9|Y2y(CI(*3?V>~ zaEi*~)6AY<1$ME3I`g!k&+ow|vbKTf>(4ieuQEt6jN#uuzn=bH3EWE{Le9P(mMYefCUh_eGJAMIeJAkkNuHaKd0 zIQuN=^XQLEbGJ+z9y5o41`eNap+b<$dxPKV#N%}oq>39Ta#Hh46ba?$&kb==^z%sm z1ZORr_RDIUBw%y9miSvKhP@A#a*;!l4JUzR?YZDN@I2*ypi7@m{z^aHJxl&mU~S9l zdk%)2DwPc8oq8@kmTgACuUOTfE$Ex{g%MMs?ft`#=@th^7#Otjc0}4QX*_Rq5tm{| z9P>q$lFJC>n_k(nZVQxUJJ^BY?8ghVCX~DfpWD{Ym!}fH*)jpYGci7yDPyhopbU63 z1#J}-G&ozXfMc5noQ5CXo{jtEo1YmDTDZD)CN;}-PV_}Azz?tUynfs>h`aOUFQ(gT z{wbc>2CLh5=^}kQ;ZoowK9*<}+xlbKh45}z)|M{){a+e96AyFSVOc{fg`1`Qw+KIS zJS}HJ?+ut^1@>@)b37+T+r(Ag0MJyHDpB^vcjoQ^X>oPeyQTYWl_eD+U$eu^7BavQ zpd>^pQ6c?2T(onCX#U%>7^BL76Cz?-1{xGWv8n1`nV|p0H1=QG}u!< zY{9|%Aa{xV)hqrPmt6u3{fKubHq$166e04BsE~>Sk58pYv-Of{u9@JEe+R~Yo~Uqb zw(U>;P|bQkKj*R&B1+{|)1BfWM5I`_H$=StHUHG*d-o|=k|RRat5Ph}VKzkS!^&Fq*sJ6R=`56R8Ak_Y4bez+5ecyl6+$tM`TdH0 z^}g8H52fY_D=3KDi-9|v6%*_2sT%U&f$52wVO9d`Slkzw!as1OAJb+$loPV05BLMU zHePB3uyQMlwnU@iCCl_hd>|Tx;Sk6ADH*!X4_J2y*5=Wr~ z5r`(pKQD7HIF=N3*}RH{GvAJkX}J-JJBFPX(NBwq7@$+)9HKRGxN5vp$aMatp~21j z8%zM8IB4b9g5{%63bgVyc9otxIM@=RO-GUIiBI6jthBkOAFOaiQXTSVnEfs)h*4^7 zwowMxy@FsYkpS{=W1%BVPi)a+^U2?qu5!189y&A4y>C&hddW2btcOpHZ>H{+9-Db= zuwnBw4C0lga{?hL;Bsh2BEe52hTdYvBp+HABPKEbD3#{{^?vE7pElJzu-p*c5a)tz zP>hWC>D3oaAg>2R5_osunlE5&Nf(*_3>$9(2Z@hL3E%$!YV7?UYP_$5Tjms2{{kLJ zK!G&eR|Pv!FelIKgbVE2qm4RaCI1h5i@>SBGY2(y*$FXFh{;`^zbQdv*E0UcQ1GAA zy_RV-Mxa^lRX=6dIp^EjXYVsTXC}m5(8N{H|5OB*t?*v}t`fPU&lGuQbojogprI@K`0Z9fC*}nku z3P3L;g&$Kyq^b5AND8~hm;qGbZ};9qO*&*e(jYvcUI7ll{`U_8e>lSjNbJ%1CBWkH ze{Z&vSltapcj^ccVwM%pOh?%#zj(1HNTD52`k}{r!<5)k{wihn?yn z%U>L?#QQkep!6E*|EIC z4F6QOtA>p|F)1229})`{66Bnp=^Eu`q%Yz}U^hMe)-Q6`exmz3FhvmPLKA1t*#K?s zPxvtez;|M|+s2U$7C$?sb9ngQHWWvLB@L*C{xG3^AKjs9wECHvE0cJPfUH&tY6G<4X?jS_2hLko!RtEHr;8aF$P zvUN4u47N}LDf^E=;G3m#aJg?@ogG<8syz(EjC0c#GHC@(f=LaXs4nz*H~ecu9fr6c zzL!a@enLsA?Ic%0mxn9$t>AkvpI~vj8K^ZJw=7&MrXjL$rFf<3P7dTO2&i#KAHa!@ zuuQ=Smts(9wzoo{TD+Dc`{sjW4pS5j#b}n?@68x|Oz`l8QmTfaY&T8Bd?Td`Zs677d<-8Qy&{pqnpu zJ~4=KQwqtxnPt|kT8h5Z|6r)NS6+NwYNWZ?G) zLc%>bToN3rXSp3Bf%xn-;1i%5#W!a$9Gn3McL1NpZc3EY6e2WfI#l+4j{=+`Z!bK_ zz|HL;_e3bD+?uDPgof;FaRW8s1S(y%NNKoQNZQ4`yLqa!SgYV5e zwSDgO{aMHgz)%6fjnK_sMBzLLWOX%_TX;qyd02YoPtlF{wcx85IRuQ_Xrn*wEP67{ciII7HPT4FbUiww(OE^WrUk z;2>i2We3YjT7EthzAm-$%~TXX3_?Z+x`<=JccZ17P08K-T3!NEEX?a}W?y(KzXc4-$i5L6Yb<|$slkfp>>l{4!Ng+Vsg`EdGQyuO zHH`72BH$gL!0?=j-xr&)Z)`wrqjwRRE$sgo^(CG|aU*(0+DTp|TpApB&Gvv)X&(JT zQJ-Q1{RfwJRc%jE9W5Gs9F4n`7+j9-|>^K5GIX zCn%4;0^%~0PH58pg-OQMf&!2$7*r&=w>a!`W8~GUWp|k!98{75N9yVHboRMa(t^T> zsp+t(sTs_YYudtHDeSIxb5TRZ(~n`D(AHXEhW?iQ_cU72A$T`^_rOaWdG^IOu%*RwT-F#ck*EP1%&yH_t&N%sRS;>2W{-S^YzYf z78Kq90HOjyqoRa>#R~{{*wrCsWz;vD86k(q$2w#AN~Z@4DSI>3D;pb~p#9;uS`lPs zK!nI0IKyt<{hgYca=TpeL&fI^1!m4L;I#p%S1+G83#;ED!W}grDIsWb@+-(ef!AFQ zr3w%PI|I83NHhTvBcpi=Z`myp&p3eE9tO(}N?Kjj13kdO-FnL)y`*JfA;pi-C0Edu zJH26t|7MpN9`+LWmie-k=>D%^ihBoTiW?|C#B@3x7CAaST?N`=GIsVDAhEBQqhfsk z@sO9NBQkKsFQs(iHxLO4tU(nvYvM@ggsAXnh`fS=R!~g?oDGNI{{xXQgX2Z&-GhUj zdQ2cW65hW>{6+X5s{qJ@c=P5>p<30S#l`V=yXT=71|zZbz`wQ#qOuP0#q0czZ!63^ zE*vNrJp%Y%OgvunJtRT(7fnqkep;gC{(P4km^3x#=9_@-hIg7BwcOU;^jLq+#cb((2<38)V|Jv&6D_}uGh?vmXM!;=xghLwJ zkBGEL4MrbPFt|iy7Fk;BoV){o6~T&y>np$k!xb{y%c#XS{YV45_v|m@O=cDO60eRP zXVc%XHxKLPcFC-FIno08XnPAzI7doNG*B7$QD9OCJ{C0OoBq!B{QpO0Ly92Eef#wP zE!zRm_HtJ>?Qc8}OrV$nV-{R&6$(y0=sBd45ggnAduTP`e=g9uWT^$${=(2b;eH%y zIH3Sl(e-=~In7o7m>>xNZ&vUvTX^Vj&m+nuP9Mq891lV`$N$A05`dr~a-FQ~tf3tU zZFHy0mEa~GS1BNBHi&oya5>Ys9M2~J*ah=|mC}{n`ASnhAUn&qiW1=N@+ujs3c}k_ zF1UKBb${cztg2n|N`e+SF_Rat(*8V6_Kbe15KC9sNa83_INdB9zs%69NE9YEk z^cV2LA-73Da|z$}3M2RdMPdjjY>d@!cs&4g>1<_>++MbmKQH=z)Ju(4r4DinfR^_N zEs$iR&mmoSR&sWAjUd_dz_BaL71qjL*?STD=w{&!mu-kdF~dIw>@)z{=)+!z>DK+T zN6sanoa+33%SsfH1~&r%`#D1akpAHz1!~)g-TXshuj)91bOPs{qH5r|%mDIup0iN} z_!Rb**#MqiWdm$H^G+)-!y_WzvYFxj{{5Rxzqz^jcAdRx3HXHc4;P#J64*mP`rP4h zFXIVt>`ao1oB2(lq{OTXS-9(X?VF17ky z-5q!i0`dRVj`l+jZApC#Jnad@qY=3sBEsWVK(qnec?7b%Fu+?a#Xi?Iki-p~Ip08w z_BfjY5Cems2cG)r^^EWvNLu2#T=XFbhBgdt#W-2I05jbOP+1SoN^6Jx#EtPWe~{Ii z*7zDo(7-bZs5ZbLs4J&8)=d`U)Io~z0rmmLI=Q-BD+lYxKV#z41avWlMnAhNy`nkz zEA4u}cYpZ)5y>yLr=5>{A7AD!PFktKR@~y2Bs;9DJ7tE^xVMx>)R; zIsi>tmDYSeFSV6&Hj!TJq5-7`Fw!6bc#?Ui8Rx_1HplUvIChgAHu&+c^7z9*CIir6 zF8&|biUW*^DcFK6^Wll`fIIBH`hR07e=r1AS#9Gt*{|88EpDEzcla{_OAtr(1E%TE zxLCOpxN{uvkZacqW|rMW-1dI+;)_v1{xTm=vwoQK0?dVHFGuI55*cS-y1rw%2~n-5dm z2Zy;myGNcB-Fh%r@}E!Osq`))bw5aYkg0^QCdS$!PzyN~PbxOE1bcVxpU&aWT_QVgapN){5TVB3KT%)M?%HP!VKVLJ^BeTF-zKpcf!Oq>us;G)MOzaM z@UJ9Sg?zj#J2;eed4-qI6TNn_#i@r)m^|-rk>}>EcktfOjcH|Zb!XJU*obBB>eh8W}d6YpqQZS6r|two@w)&YkNNFs{}5BILF zW(N_zz-q^&=U+MQGGY$QhAX#MCm^ROz7x35so)Ns^mOmV#cv5KUDm5zuRxn1sCZ=x zss7%I9(9_%BzXlw+pn0gRo*$$iOsnP5ALJ?I>`w1)Y*0cql=Sq-mX_oX#fy|} zw@0Z7JubhisxxTRELwS}x!%)P&$iqgGz~7d2Uy$Mk^-wD+*k))xI>Eo+D|&ZSQ)QW{!4-Wp<`0qa-jy!d;a!5OZA+KY|v~%*B+#&pm13OEy`u4Yk`KYmGZGK4dlj}lkzM9;eBoVlkVpz48_ao`q|`7r?DM#*|Wu|dd==(Do`-W|m> zy4@LJ)zG>_tqG6o`BZ_jJ$7x6VrYqfWI<*nz<2gf6FFd=%5U^WkU`QChqQ%jXO^kO zV05&i1th8=n8wFkNq9nWb?P*2HzHxOY5%}zho*L~B;n&`mD|I>USRCm>xN$oQ|UCO zUZ21(bNZccf@?yDB`=S=C@xn{e+TCCC+0G+O(^H(nf$MQjXy2@1W}eBaM0XZLe*2E zqdzmf?SJ}+`TmxdW&z_5)A?{}Ub#4MCv+yH2i{?6^K|`m z{xM#8_$lw0l*HqMIHRXdcn9}rHFflL%vw@9%LUo@vb+8nooh*A_X%;9F>8f zViJ$%S{`Wz?xwUT2)T4Te##2QD$&}abd3U<#kkqTbrVJ&Cl{K9t{xn5eog5Im(Svp zbnD6^>(=7zdr`~mf667TMpr1<}c#)1WUl^#Dp!lb3tq@?uTy( zAkh|togIPTz>f~QU;S)$Ke}C7A>xS_;ncJ9@d@Qrkd;7+Y|CE#(&K5kd5xqmF&! zqU33&9--yK^Bxq~mThZ8pH_KF?oYYho7)$kq1hi!x|84s8zrRvrRbc|d7*pYD_bp! zvkv|b-=FC?Fw64*F2b|*;Ztp}QX|%zWqUiF``sJQ^VO!WB-Tb2%CgPByCWLx$PEg+?IWMm(qkOY|E@WJol8v!RcKK#Ohp>sdu~~jsLNoFE ze0D*J@Y=gT$4@^sp7@_PuX?u(7n6Nq2$D>>W^+RTF2r;>H;l;8n@8WVfOvnM6i zX+fOC6*XdRW0TOPgR-P5g!9;1p!2gG{(nA-=hI#wD0U!`QxNQOh#;f^EMKwQ`5fsW zx)Q|Cf+T0$k2+6?>6gH(Aq0YO1MHAdP%`rK{{Yxy7=-&EATX>(vpn*;03M`%(rj5 z(}e=M1_$99dXPKu(R%qy&fcTKa4)|?(pszu)xev0vsye- zGR#hI?y;2>0}mwRsb6qvVc|%;)t)h$43IWym{!2*f)S*Lc3A?tG=D?)i`9 zzQ+y)%Zl?}Xa)0jYB!o)tDzC^rgUQq-68o(fP>aI0sS9Se?$#wb&`@WMXtM)1lZc6 zO!vDyS83?nA7>2ju&nFO@hF-blw|ZQW^){;ptg>1Bb=?F)}2QG85wPVyS`Dj^Lsm7qNbMiMc^j2 zD}lRrI!G8%hbF(_B`JT@7t3(Sh_@iSnT?x|Fey3gkC>?w9+11!#PH~>H!pIn^GjEqXT z8n+<(b5Kl>G3oXAS>Fs8NB)Av<0ljfowHuWWii4)L_~zgP=$xTwz0Ln+Ab&oreb?4 zOR#%^_>M9Fnj(Oh8vrwmj)_I7fuN~!Ht1&!4SWz5kT(Vq=6)BGVq@TO>e8S@N!WWZ zkce(|($5Yec?fUs?&R_mf#Es{Y+4wvmRyvA^(ixbo}n{=h66B9flApg8N=V0;=r@7 zr>~zjW4Nrwd5u1*0M;N9kDJRn085~+n+T`@} zncsvBD7JBNQwE<}XCcGDWBG^vo96d8XFcA6hw0W^&fC2Ja|1?>jf)_T6~Vj+LU53z zW%I}=v;Ws+=#`og&S8T%McE{>hUxDI3z*Nq4);74ar1%3hk)od!JHzHa0K$ zPwQN^N81r_gSY~blCGT4qZs4!U!T6j15be7S|?dhYwJh?3O#BbKk-)s+jcKs8*g@l4;KY*o}#P^btiT2MUs=!+45CqfF=0wfV^Xr9VM5GZbVePW-w1zW2>6iR zGbdBzPf$r>A91>_2%q8quJ+`(;d4!dC1NVZ=-aMBV_pRAl0ygMT)SQkT*hX}sOfyz z{IFegxA2w-$4=wRa_A?kBzeu~ey}VYZG|K56^RGbxNUv7ncy|H)pi!(T4?0+O)A*8 zJi46W*I0!S4Q5xK-I|!vYVhUIuQ!JeEHVqdz2UrX<)2Z134d!aL41|CnAi(+o z;KT@)1Nigq`QQOkN#UjIfZ2UkT3cit2y*mGfny$2V@nwrP=Kl0f0xtd^6Cm+62qWX z-vx4>osQaZ`XvlF!*K`+2QX!Ln&Ii>V9-|u=3Z7-RUZt02$^0muJNw_x)8;6ealKGq$?}`N-<%NGtzmyc@&|Q#eMoGvK}aa>?>nHMSP=c}Rz^eFcJ=@PE2dXpQ#tO4tu;leOwE_-gRP+f+oo zQyvF;To@6&$c?kecK&d94dKMee&F9&ich|l+?Lk=$m$WWoJZj!p4L-vE{8$;}j z7;~nm?Q#4Hk+mt?FuL+!%gn~Q$UvVIiO!3pKHn7nrNe5*#Whpc+CyPCpSlkYOHEx| zjb4^o34IXs{p>VpDg7l*u);nHWpQ~wMcHV0M~m6TRTlQQ>xsCnjI5IfI%f{MLUM}q zdAAgn*5r=tLiY6*%UJ(uiroSY_ zxMwtK?Xq!$f4%-Rykl0d&3>pM>mnD*(RlSz+RP(@*OW*w%}V!>9@g~TW@31RJM{O3 zhp3PMR|?NuNYcX{Z&`N)Vi)Jx z_IL}bY-6)CqllHP+g2Ep2%$9xUv;W9u&-5n83z^xCP)0>g41K&Wp~=VBD&Qb70Tna zfQ;Y%M1g)e)w_I#`|k~{R&}M^UlX5nslePr%Tf{*_+zWNS5~}(1HR@<64yu{p$C!j zcwjgiIzXyv=tRt`Q<@I^Kkn)upsoo`jQ z63pFq-IvH2VLXx@*W`IqWKX-#YC2w%>37(_-Z)iNplF>pZ1ntj=|0xTRA@nHrPA2O z`o36F9d62BQE>SvNmxd7`*#}+_xI?9L*fFJm8^Bwn|}AO`=8Dg;PT9M$Gk;;s=Izi zl(3M{yC3qavUjVi1}T$NrrIMWN(gsRF&zCg7zGlbsmZkN zw6Qs#sj4iiL0>;#UugBG>w-v05h?f;qt;znGoiaLwI%Lo#A7a`8mYSH_u6!U3&v~Y zz9sanjDp)yYArIX{E^Cn>;{b0ah0D~yLM|o$7CJJ{5vB@F)E~zn~Fwm+;Q;X_QleX z4}2l^vGDNbO}Y0it?|0_bEx3-3+l~y0hZK+@7~*=sRj{b_@D2;zpIAex{;=BaztwX zh;$D2vxz#Eq~dr&Z9C&(7J7>Vuif1e_Rx+5cmT83w?_C3oXN5?44 zo)@QRdIQYQhQ^iBkHePn?i^Su`7>uepFp}yip>d#c~Q3M6O zFZ?$JH1*%}d4bV0)1rOuT1vOM*YHCes?(M4tAz*bTW{S(agkv-=gpc->YlJYq4*FQ z+cJ-ct}z3o2fSj; zDHBBtl?HskqFcnR&3R1yBlF`0#)KsvMMT)>yNAU}sWeT6uZPEPxAPe?WNU_PyXXq; zY*vIX@cQfZbMk0ve`;F=MjdqT+1jCV`j8TtZbu;SK3k9mGcWtQ-hZy_wz1dGxjs@v zywYsI`deH=-ELH=<^4IW^vJJSuiT{9kTV*htVWn2pfFaLJ~DhS4CbVMwMO-n0*4l+ z7gF}d73OEG`Tz%sx!+{XV%flD)t~Bz>};C?#$=}Ouv9;$|EkK?jP#5(OBvC`-RBoU zfycz|Q{NS9H8%95IYX14lUxNHIfXDr!|YVd40f*S$lwAjLN6Hegx)5a#L}zMBbk6y zpCypVS8Xw;miTEzG=@P_jrSM1cviWp&aaB&`uch>3b*(72l@Lyx786QHUEAB0tNbB zunY`MUs>BV>ccRG(lg(O)>(o>1Rlt2+mzKWb!ObVgWkfPkSGH}=w4w$D{j?e3O`?Y=9KHUtK7~h@#P|I z_PUy0F~*>5zxMmC>J4ru+Z_>D|6fMQU^EI0gPAVe-3Bv$`}M$qHm!OPrC~~u$yj({ zM&jf(8^W{3ThHCE&P3eG^PL^+mTLhUA{cgAZ@9WtvU`-i^lXievKel)h4FoBg1>*& zJp6N6rt_@M;b!)XHCnY(*ymgdZ_SLWJw@4}e0E2h6SueRBkN>osk!q;rnHmgI(+1+ zA_+ljxjky&HrB|Z!8vaL#c>$JIBulGjzqhzFKHOOA>z|2)?3qEju!|akh>{kVQq9u zWkJmot5k(ey7@b83EmRQ#Gvl(c87N?CZ{j^F&WkH(0{ETDHyJ5@~ZF|(BN1`WstVz z5wzPUY;T#FjlXJg*s=1M6jK(wZC`vSCcw;U zHr~saS)kg4AD!SZc+3ARY+i#N&hUTpdWZi2-LnQ6k{f_U*q9F%C4 zf7$1%b9PcAe_88YC=)07?a{&_?(Juty})np*d57{*&W?{()-()ivxGo*9Bzt7!xM6 zEmAUEyHt0tVtG?4{Yc@{Di%dVpZCcluSJ}-ypYjIMa~KHmEHNV#K~IK zQ(PNvii|KY24xExt64}j{;N60FTeP$F&N{^0SPQ@o?)+6q046k4x1= zHYPW&idd7{E*Up})%&Az5Uvaz%Fld!>0C$$>-XB$*@5^od)tP>@S@nDnbuH$ubj2X zrc)VPdvUU3;`z>aN~xRm==Kr47@i?XM`77pdQk~5(>-VG*YM{hz( zq3*ej3$mQ=X|P<^cH|G|Mp;7Kr-RZC9eEM>gW=e=lfdy146jM>5`c!WDq#1>VND(@DwOQ0EV)=uR;?A1OSIPqq+8G3ylOI2=5o_ zTNoW;Ch1aNJtYN&4QS3`GM{FF1NB(aPnwIP81|MP6DXAko0ynfg1$ykQPEVDlIWPf z=x>>xXfKSbyk=jU5yWF7C=#(Wf{M8I=JUA=Y8E`o7S5PAP)aPowNo120_3dwSpDpQIx85dg^DkLdq<>F+fgq#8=Bo&s$I!#wLqLjN&$J)0hW(XWCcJJi> zR$OYw`g}&-H7P4^uIOlPd?4-9&^Qk}dnm(ude5@CxUUtK)G35cPm`9e3(|9`f40&R zJEMKc{CYsk_kvYu$QF5(=tscJ(yyFpk-_Njif03sKP+^Kt$&$rm=t893C>Y!zMGr& zM#o8_U?@CbeS33%(WA*V9~C|0kNJP7WIi+Z2 z^qT}zj_|4S)lyS0EftyJC~s8t8rNKZY5Wru6EcL$!!%Qs$;Iu3^k7k-4v~pLCAMzk z5$T_8ujSGoQ+V`Q+%d?5pES(r|;|W!ugws$7+l@6GaY-1*$px4Ft6F3A z+O@%Vh(n{IMJQ{#<$ZPzc7=Yh1p3~Mk6VpO;B$VBAJMmdu@2k#C3IT5q{Tp}Dx+8; zhnjq!DHvySvgp6lYzW`8Ft9DPY(5cNwFMJ!$ASn+&_VT3LSg)zn1<#LsPj3TwH*X~ zR2uN)IM7EW0qCJ=^{Sot!^1<o7og#?fm zAc@;63f9E$hsx(=R#rwTZPUQ~{yn$)S~iEZ0toIXuLnvEL5E&j0GoccH` z$P=wnX>se|nmc18<@2YBbumGNu)J^rg!4bpy`C!Fl(AW(zbk*}U$TPky#C-ac2Cip z*{E+h&g`+NyZCLv;je$VNJj)$3klLwH53Qy4>jk75Z8zmdu1gX@Up<1_ob9^Z932z zlwk^K2#%eceFWGlx;DcN!Vw9L{U!;3-&tt*m=p$}{`4E!@XqDeoZgH!)h6(>oPDedEF4I-fsh8TKvNjR1p38RO`qR(#`SQ0p|5jJo*1H?mkC}#@ zs(exza;3fBnsy>`db--ECn$c46C1st$na`8ajjV@u13gHw-uHAvxYc2F)b5pqcRO3C9(8@lk;nv5jODaY*Ov~hYklS-Gr9S5ChX}&WCt| zIvA}e8@B(|<9*pBl09N3Tc%LlvqH6HSEp+$&Ks&3mHX)L%rQ)6>&((q`oCw(rt6Ra zaFkY-hhVqI9Ohf1zqmEWvP{Mw4A`fnXNH@*d@K8DI&Hi9diZK0Ap*=L300X-Cw{>( zL)&#pc!ksbS&3&=HCGb{*sbc%#?|5VxIm2M4?7Jbmm&8EuHl4fCXM`veyhqgE1 zk08~^=F*aqy;`3h!tFAh4@B#}!sN~#aoOp_e;QJSU$l7)S^2B!rw+=BUy+}9qkS6w z*fse??s2o;&t*(`Sl1!H_eE5cdbvj=gu3CqA>(NRy1P0U24%=VDD>#iW^K`6!wC?QSiZS(T(W62FY!MOt>aR{;*Y>Nj@U=zHTei^({7wzJ`GFgP*B4c(VCK4=l z5x8ws;>uf_w!phr^z+jq3mBM|fsDej3G7QR1T_z~4~#UtQb~u0@52Ftql_`*_!`h? zzai2=p1FIv4n@wf^Q1T!<3;>cZ&Zk|;u(G~?WcV%8R4jE%I3i_m*Rw9k+%Ik(R9_{ z0=QtvaJY2qnD)YD1WeL8u z>y1E-J*M8@q1UCT-*2dh-9-*_?xK7f1TE;Zc{`a`9zYXpL!jmQgP6ckAKM) z?-pPcg4Oa;G?zX6ojQ|0?my&jZZ{9DQV_>y+J1kBf_t4B$+5EVH26UTCcyAEH>@`Y z5%W@ri)R#>vo>~j28UI)yo3i6i63Db|M}Jn`#Y3|~_${EYs zrAcwoIw|qLe+ZtsYWr3Wratfn?+q!7{Z2EXr4`r?+*bA3*nR)*P+)L4u#a0KgA+dStl zJD?MUN1F3oyJO%z)a-<(eD|Ii{2lSx{u2mb zYd+VJ+1`w}iY6UD3pV>IEIo}Kvm4GmPDzCfl6kYHI{R<_3%A7U9OmJWqP&PBdVt0< zi0QWb#QkN!VbszCr39z@a|tDl*T7L0tZ+A?<>cga*vWq%251l_ms2Bn;t$Y=b`1rb7Yilt2J?0no7&qDjOPm@Qjxht9{ zA+J9^rrT3&hk4utGh?Y_5A;Oi*<*358m*}NR6f(RGiILlTZM~Qi5t>7hna7)xQdtO zBVQt|-hp zq0SaCSqX=7i&fz8{!sU@qNe-wfCNAh(kkR!t{#75+5CWKhX9b$w2^Tgrnh+|)EViA zaGiv`$(EZ>F(ROk2z&LI;s@<3`SUkK!KgZQF$IpX#MC;v1k!~D$!~g$CuK+trmxU4 zj`H_EimekmV0L#Ve~#{-e0?`gGVkk~!s@ zAipiED;AISD=b`@PHUQdFJib-z_(>@`)j;7H8rIJsvQ(@nNoDl)_Xav@z~^1SW!qZ zwi`*Nb-sQyONDQuhRFF;x+*5xvlE>Ky7f=?&QvL)iZh6{s ze{!#lM9?oE8f@+5UqtlOHTvfaG z;E9X_ov!(&kbXiHcEBxUfNMl}B5A;) z)4k6D_-%70^rR_6pc)ySh)gRg`n2|L7iN#6@t~-z%mgCffx0Gv-I9WeDz`ytyA)3O zV^T^V!lT)l$F4Dr^pZJ~j6~^2q?2M4rM<(WEmuMM%V{n9E=gIQZ;$M; zf1ZUwoUg@_e!3-ny_Qm;wGYF)GOVf5EN?GC`FUY&^O_469MLg4Hs{NB5&P=xP+$K31?t` z&->dpNQyuF9I=W%_O=7&VM-u>iane`SLdBylkn^2xqV8yQEwxqXZ~RIO83A6C#xsM z+ZH+n04(t5l7J{8NZBRJ;-s8xJg#m-ukl@KaxU)gFh}QVIiv5Hl#%Q3K$5(%Em&hu z{}3mc#KEscT+`^ZP0C8Hgw**=>-*eE>lXJt;_|f=K<}1uUhf>@n`@HO5N+w#HKw7V z%cNlM%wT26$tZP`1I%~YZdMr3zyA{;HWL!Zx3X9e0e6zNg{wwBA2{^@KrpJLDV%22 zN;$-3viL{SrW5b%<-g!k}~p#LmKQJmkvJ~PnfDnC?l+iG*{NA7z=D0%)S={r7! zRO9vM78L0AL{bCx5zfaiFUKz!KAM4RNPtZu5)`E+bK0&Sf~H1{w_9IM72!_~fwv{P z@uXcPVS@nAGzxf-{<01Bzs!{I-#LmH=!$ojxH|nyyP2plvoi$67`@v*R@h3B=%&j< zN!!HDEb%ED{Lzg-$sZnWem(!5yd3|oI&A#eCL`2s z)aDyW4-k)HX0|0GjYi7gs+pKGTZB; zmzo2?`5Jkq@*%YLY$D2{1c@XX8qO!JLOH)tc6O%4q-`Et*BDYpl&xn0hX@X@X*w+` z9Qarx*H=leJF)jF$3je_x(W<4d`(qlTg|+@syt(ZYbQ^<2R=#MV{0DVo*oemo9;}L zm947v&~)>4EWKp39wF5}41T=-A1y#^wflJ=F_NTfp%kVc0^6M_+xw61-0sU5l@DjE zae;2fcKqvno~Z2TGBKT%XY68hN)#A&29gvXyezE(NB9-rVSf6-CbMsCdqPZAKEW!6 z_Xu2n6d#xn0SLOV7>msth-gQ|@mMCn*~(TW-O9F;ovKb1hEZb>Gh1dsnCw7g5U*U* z6*Q9Xyt&E;X92PMMFS?Nw{6p4C)&9%XPtBXy;pX?2PgR_MZDuy!`r=w zVrOq_5z0Kr>LV?pPhe=c4r^IR@C$2dIoZA=)|_eD=t`TN?&-p ziqFt83OG|JZb&>RZG2K{jHFUjc@!ff)*JGMFskK4t!rjx+$c1)5gD!i>CFTBBPeGI z%M8=ISo;idinksHR` zH3g{)kHqF>7+bcgFyigbE=$R%I8fgveA2coq7;4cDQjc#))AIChNUHSY10v$$SWVN zF#Pcl`Iop^M^h`2<7D|E35`UJaZ`XxSqSHRdhTF9jfBg( zk9DjWkk4(eP5^`_EeX3+z7yD^;$SWTh(Hp|5YKohx0|c+sIKb^b|nFlj~6iJ1^{;l zd`=1v564d-EA0kjbS#VU>yn0Zyb%6-4!D`>Yoi-yt6y(*2{!!Z`-=@%01Uf}x)uz7 zKm2blSqsMoUoMAX`F1en!?$hSJrZpd?I8Iz+MB`&x%GT%#h~ATQZt_`|vw^;P%Cg3CU^ zl~*^hJ%dRu5*7yQ5MuHQf=jgh# za|h|C$JLwzyW}@70wqJo3d%1Zb+R=If33a;gRX#L3l-A*smdpDwlYfe%qIyADfdzS zm(81%RjVm;LSJTy{n)tE(-%?w*z3Qj&Qq^9TD7DVf>8I2bmISyulJ7U@_qZqUy+E+ ztjx?xMwF~(Z@BMvz@89c>_oLo= zIj`$HkMo$%<9YmAb^C=mCiA$BcyrhH^D21PcLfx5HCvm$+NQ17J@iCRD|6Ur_HX=v zX74y60DV(RPcdJYERO?h79CKTPP{=eP{;uGFCX!?2Fyjy1)eu1v__}pAIaT*8a#+w z_W)ndY}{OtVBCkF!K|iXs49oAU|(K^nf=515zQAxTd`Tnx;Krqggw7HBifkt@CUv| z4!5BZ+pg{fIJ>kxF((KSM-#o40sq*xR92_HwDRhUSL9@e(Q0DCP}CwbdylAe-B1nE9p3htz_PBz`_EcV6`;qO+uUh+4f#8oG88q9Rc6ib(OA{z2am;I!IEn~#}gf{fhWIj$AvExyFht>@tv2Sy;C8c zo$32g2_$i{QpltEB)=eBfvrsHckAm->x9j)?PKPT5o}M{wy$_#8Jx~~>aVva7g-Sf zdTl~0OKdwq*;CFbB18Ho%$Bmu#_~NAhE#I-#L}LO!TQCh^1UKwyiw@d$K{@q+htxO zz1M&DL^W;6EvF=5|M<t(J`w6=1xhu`ltnL3P3ShgS~P3wb79=D3cvj*KqcFs1$Th5J=y zPiD_OKAf-xd6NIbdqbOXJher%(@fU^Q`WCyi;l&J5s-czBQqvvWrl(Jc8)i1(;YfW zV$Ephn=t#8)Ez@;HHBOLyM-qaZhC`X>`&$WKqdQ=Yfvbbg$(Z(r-fNpZXuI93%nKP z+&^g!64%`ps}u|+@FBFq{28qv0<9sA;F8XDiv0gpUHHO#^f=(otd~AJ@89@!@ph`) zFfo*B9FFa5?MQSGn8Zc#`J%5BzP&%T%B3k%jXRc$Q`rj5Fa|Jv4oAkds@%B^e2%$c zJde0Xj+1`m+qW$+=vWIz{vtn?mXn)-KEb(@!!@a%*79h8c|7|T4}75wFjXYGJudNA zMLb4+B8Fbhjw~c_praHYT%;>LFv(1;TqWMg@7-zHdrH#EfVOLy+Qo15)HP*uzA*lJ znBM$qg!9S^J^lk|=VY<;m%&ZqT5_~l_e?R1y`#?L&ZAzQ z30jKgR-3ibI|Dnvol5FHU*9ypkN<9^yZS@ReyZR*9i3JdpRS?Zv90eVSnwbn_6o<+huQnU6@3>dqmSkA2I*ioCf&M>*mw(IiD z#`!|-Z||rFG8Pwu_XCIzqKU{chboK)oCwHoy6|Reitk=j`N(K~>q<(=U@>Es0fRWv z@U7|P_=#5B<5f#LrpMipTYt{~zSekYS+GLh)P<^oZ86hbpDxAR!}=-!2Q2eZ}AYfX^z#1kB=_enW!Y`F5 z*MwzsG`D<-TRs$d`UFP?D4_tVrrUVkj<;Y|-m1;XH1@M|x~_S7^$RFil5=`oxf0ah zW8D3HPSTl8gb@#sM3Jit&i8;k0wz#XdLC^wk9s=I%ccKb01o@r>O))Gs%?!VuN`e< z@*Fb2d(2}^P(_7bvzZG?4(l-i>h|l=QwCIgJXf-5pZD;v43y^IMpbyBr7iF|--Qa} zxlh>{Guh=(-J>Xnr>zpI5wP)N}aV)A3rf_Z}vs+vR_}mHgr~W5rGD3x$_lv#5mI z0d*aD`guR%Lo4`QBISLSpy@^L-j}4zhiT;Zjvt@^eE)s1ET+P?Q;pnenPp=OTO`Ha zseG7lW({5Leg%JV=Ig#%!E5saC39aH58v*47iL5#D%}~caY<0!)n1yBLfrrRRh^^f znn#5F^1PT!u3Jj)9TabZ@HR1brs!IH>F~P$Jo26JZ}W~n`PW<6=E8p6#KQVL_)dpk zuqGgsi`!hmjDYlt*sg!xb-{NQxXuAxr<>HLUZ*%G`{PWE+smUIEA{A)MszXGGVhT5 zm@TugZbL%zgc@rblDxaWG~%7800Nhnf(P~>j#g=TlMz#RULnRcRRy-uOFo#-0q{mQtMuz#uh zi&aha^xAxTY?G3*Tg=1)BOI%LdXHfS;Y}O1{6yb*W`kyFz2|9h% z@8`J6Sa?y2??wFRFMpp8Y{rE)KT&Bp1JvJkkd{fRtV;BEd2`n3tZQ!`bL%3#A1s1= z6?!S45owZy?jE<2=6x?tTb|3TyLH&G+kpRe6;vQ^IlhUDW5MgbNx^H=19#`Yw*Ih? z-*(s*q6E)v|Df*yV1=>5Ph~SmZ`b}BC`GgtArklnRbqv8K4D1x;Veb zbBAS&voi4wJ@Jc7UWwz&Hl2UrKFMS9o_&6?@zij4_19GV*`2kgo}eb66T~s0=5+np z3;KfW9na}QR|%7dNkcA&{V7qWAOpKorF-|hutHaV(N}r?cY}v#%-;r&pg)l9d<2=s zwn4jXIg7epv%5UtAV)>d%G5Rk1~u~O0#4iJ&j%F7HOsm#txTh%(SQj_2M<_R z3@L!*IV=u-otvJS`&@9-4mQ&rulgOh%>l32Tm4-s4yZmTl^Wey$TdljW41Px>)6Ez zbak~@-gfk2+ux`OyTZR2XU6$4hQ3YpObrn@QwW{x86(qaAA0Yb(zqqNEQjLg8N;Mx zm{T4BW5NGG<4+Vs%$H9~R_UBKzC}Kk0&Fw1YcXM_v+#;w-`75$NUZgK zdCvCNInl}0XRQ|Yndb76G|`gtE8a!LvmIL{pUkWonJwv2V86dO&9$&=zKWWbmQq{; zvK$i}&ADOq!$*fQqRMbLeA{F3fRe5u#Y^6yiEQQIby)PLyfLSeqv6*dRz?z%)|R|T zhl^?T59Ma|=6s+)aHCzol;pb$#^mxq=K#h_OA8A_n05)M`2xdQv_L#+8FzR7_dX|O z(jtqDFrN!(HKd?rs|?h4nKKM8%V9iAo+d|2{4f0p$Pl}RJH=s?GRncstY{W3cAa0I$qwQZ~>6x14Ya) zdQ8_@BBMseEK7cwR37|(<7$QpD9-STpwK@@cbtcHfLjg_k$}CH1Q@=8KC3_w>i%=Q zC{aboHg8b~#pbS!OTH@~WNp57EA)q+W$PjIvO&wzLJ_xyyXF7cnDI7d+P$LsZ_tLkdB(+K%mA9n) z+T{&kbtWK6EGoQD9UHS}16k6Sr|VtTnSI5^(1FIPQxuHMAp}x}RDf)$PtDCW0Rc-# znbUmfY>Y0Vx1z2o&cQs_mE3ql&m}Sfy!)$gRZ#B@AEX~@Cf%kWJKPFsIQZT6LuzLM z^f(uuHv)rOjN$5Ab%;^de*qbIB{K6Ot&-b!G-_YOZ?Y&~WP9vlkHIHc!K|3Nn;Gy# zn2xg}cCYA@+3ohvnPBG%ONwL_UNTTGTem$vP_=ew6A~Z^1mvt*HJv?^!~IV1%=D*A z5}l;Ji-Q5Oe1259oQS+3&0R=dxlKmUFo}0raC0_PCxGq-Epb4c5^?oxcz>-F~crtAF zWtdPMji#__DjRe@-tqqY|Lhhx>}$%)Tu!3xOtE_iP0i$?w|zcbcdGeKHJ5ns3}h1f z_6{Nn{zk4!y4v4%?YbCui?%$Y|Chdq2<@*(duX*a)3vYF@{*H$NcrQ2K>pX|oZOuB z>JOjf$5%ojk%T51#PnZSe?FnXi}dCAbg750tm$(Y56N+dDc-P*_h$~;_GX3go^D>d z^!7k2s0V2oI5)YmlC3E9k;$8K$cY!JyY#k3Ogu5o?eF{sJR4e!1Nd~3kZ9sqnO~gZ@6W^L>TIUUecY2{ zyO8K@x%YCd24~q`b`xix9OU})an7w>nq~-yB+)4pY5Ww=SpU8Xf+Q#+m+8%!>0DSygxeJv?b-`;sINr6K zb5mFUFJS!Z+<~9lxL9lFd=+$`xA6>SJpCMW2;Nz2Nvky4v*ftAg~VgQok?XutIH`!8Be9{1nZU8RzOlHb%^UeSI~TT*4te9Yur z9wUdB0JQEwUTmq`%)DDIHdRgg)ObZY<~Gbrlz4b>_u!>nwX;gtT&+oJbqN*hCR7fu zD^1L?&$?4==|Gy+O-m04Jl%)7VHH6i8N2E)2f&~o$Ab&Fy24rrU4TAOv(}1r>pg*t zu(Nbf4lQNLRtpq9g`V{^FuoAi)eK2U@CftX3-*{{0Y@5!&(LmBaOO)2GkdDr%E=s? zUKWR;?VZ4E_5IBaRU}%swM{j8Bt^&0{t`GY-a}^#MDb1FZ9I^ZW2B=?sZs}*)XxBS z9(&7#c!`sLpS<9>UJ~X-_NWwC5SE-TG(zi#qD z_Y=DTzg(MtD5U~%@PJjMLW9VkI}I3#W4Ad>^osw`m`$Wi`|Z{Lch@bRF55R z@v%Nqo?D5pYpgdQq8N!dSW@}n>Lm@iJ;(xq5A@)41Dz#|gMd8J7t$LaT|Xt?6GjmE z5U^oI(Du>`iXPxT0q`{77ADE4#4R2Rr(VAA@H@x{RKCcAe!^@ScCJ4!H36z_5909d zcFimDiYGVJt2<^|=&oVD>MKytZ#Z#Lyt{dg7@Ojb6=Y;6^}PVEE}Fjf#5=D7|7~rC z@%V5N2QPofmj3C7>^nG7J<^bl0^EZkBq!3;_U)f^`2cSL{m0+d?((2MOP0eNogV7P z*zD322&{2=ueIbK`&H<4*Z~w!L3h-So8)Q7R%DcUI}fGu{`r)xKMd?H@v7eJp2xA9 zE}C(#rUGhqw-2e*RaNU@Br&2$2a7B(Lyi)eS@r$B@Oxj>Nc&}Me%k8l>d_}7HmnBK ziO3*yF!xi7Lr<|&&%D&qq#=9h=|6nf0hGX=@nrlNZy2Oy`i!-p^u%+mp_HYoLq8xcFY^`ay&CJ|{PgX>WitppsZtFqn{_^s&=~=SSig#$v?XGV+Vl1BA3UYLF zb5Dq}y;p_)>2=@_pQBg7dvqYg(763sa@v4nV8EhV`L$Q?oQI|P0?}0GtMkj&Ik)0; zN_k763)Cs;KwADmbnV77&Fk#~jd8znu&~w?Y=`fbpY?6?$IyY`svYZuAWo$D7g z{bH{Q@)70xkSH7JMqcBY97Ke#i*6Mf{j9R}ncSr1NWx&?~<^eaVseIbH+2^Ov zjDse-Z*xhF&Kg9`s ze}Ytsxydu5wY5O?oTO6Mr?l+9b$#;~=2Pn@7Nsjm{5EU$>dQ7Qw&FjZ=k!@^cwwAl z^mr1BGWOxZ9cNO<_e`4Bi8tHOP&|sCg7ji=1<_R{-VFuTs+N2!-sWV9O_!0pPxEVj zH($>WEF8H+7JjN2^8M5NN#jsmLBP~h?FLDsB#CL|`_P#$GHmVoF<%b8t_deu2wTL@ z;fWjL1l2fwxc27cBsb`_ovw_xY6@IXQQlZfc z$h9^&pMORDQG$HJ*q+yl#a2?OoN8}@orB`rk&?!4OVLJ~H;zevLUG@OiXFK=FsQue zf(e2^$2UhTcDL%~gZ9)EbBmYaIf1bw57(C>Eq)rK4db%1J41WJt+!hIM(YB)DXc6F zYu5K;hvq{il177dKk`_|XmjM}X3Hp+hgeH#e6v1C(xC`aCXn5}HS^A{l9@BbJcO>U;>y7g$g#Dqe8x4IV z-VO&fY9Q9L+hIWtb^YN`b1$jaNih-1-tCvxVCjzNZqNHZx5V~#`mU~qr2Uo9=2}x9 zV%z^<0b0=L5>7D0Rdu)C7p(?Rq3oTHbCj~)xIJCMTcFgP`bxr4->z8cCQo@UyJvnsE_Xj5=koLvWM=swUq+10=lF%osAn|$;cyOiv`R?f zM?7nq#g&QP3wbm?WZx}*@(SfcFWA#J=P4_e#E`_EtEGhGjOME-HzQr0Dcp3XUlLA1o$*d3j|Iqk z%uB>$qOj4UNHdZ?-osxzIv1^yl4W0HCve^_w-QtTxfw}G?DiI*w(y%LZupR`Y7M&j zip8L#+$dbLMujwI_Dz?QMk|zTb>kw|l9gh#=gPv_s0>ZaFq8Kpl@+JhQwFSMtxTyd z$?1p;bQ7EPvv>29oJSSeFNM}snt!$!qCs_!Rx{X|2=;hZsg0k`w6yURy-7v2A7`JcVrs8w-mlVfs zfy`Ps@Szz4X*NPhh)2ci3wk64x~{~e80f8vD2#hvm5j0Vzq-@J`KJ8~UHb#^Cre%; zxp^9Np8D1c(==XB1lUgw_~cmMt+!Q9GwoPfj~8)k%HQ$dEhm8GK3o1|h8Anm^78Wa z&CPm<7cSi{ToSzSj3Q6r9seY#BOrOL10Gg{E3tAt^9eoZUg1;EnaG_U$g4)~CE-_{lHeC@k*nyXzj}uTC#`zes)^MjGF6=KjyxI3BQdXWu~-d z-BYRHyp{S;jw)Y~&lSSvfs|XqILtAoG#c4(TBctThqmcPJru>9nmb!OGovK)u^|OU#HXk2|9uOiSV0MGHbhiNubQ42EUteF8 zT++QOg=QUMrzgjpK&=A&FW4Fy!>-L}gv#RmX)oA+f2ZtXA@YfAmEcYL&f!#(mxL`I zXt{>LX45^`^mz}jUe)5X!wlv7T-7r~;8L-qIPI?A3GG$K$N0{RJ(wz%tzoCb!#p+} z>iRAl4|#a<_RT%$1icQ3tq1ZNp-l+q^5x5{TAxwy2!1I>D?-DsDPqQ|Jf?w5bA4wg zFe~du_3@5w3IieX;nrfMqPO~H!j~oOWv{*|oklNt?n_dG#=+CT{#?Ox#S}Mo>nFR7 z$WhVbemY_ zCuuGU1&Ud%E%kL!>_&Q<&XswtFZVo%pHGk1oO|z^^JB{1Ub0k?;du`z=)WA-^RGBPSbcVb{Meaq*>eDB^pgy;0p z-1j(wFv@Y-vXEeZLvuP?wTSoo34bq8H7DySp14g;=9q7<%o0~E3-o2~!+3;C+WH9of zNDuU?xTt*D-0%n5yiZ(EQ3KXY`n8FrwRS_R6>OAJjylJu?|-^%=APIXS*`e`FI-y_< zL$hg(GzWGL*{1sI;L9d!`5+nX^L?AgfjXNM8tJLK zvZ}{4tq(kWXWpvnXy0LsZRa$qJKxaIFtN8WZU5v6DL+vk5zxg-NJ&knMF`bZKHZ#H zTnt%Xw@)!X6V^!5(1?g;V0@fhS_%akX`}r=v!zb+ct=M^T6ZKk+_w8P3lMI|ll^(E zueR^H9sX`Uql1Wuh;KJtaOPlZLO=@#s~5@JABcV*#PP6S?sYA7V#iv+tj3f*#6x`F z5hKx-4rxEh_MKY=&a5t!sKN5B+HGU&SF!t8S@?PM0^36Fhpa);>8f)BZ=_iJq?`_4 z2J=-=^N97+Go4`bU-G8CZ&pH5@-fHG&rBni(7}_M$d*P_MeX{`m&Ya_o9cVBxxcRr z$AE`3lP)MS)4KL*;}&*Dyg>a2`FzI_uHx+BO}h7^0ug)5LETT^8oX$pba+gj+Vxmc z^x*~YrbJ_+0vCi!u5K>sztt%dNwo$isagt-Vc|-AN`MoO#QR?_e-~jY<*2!N@?5eE zAzV1jx4YVR^I?f@wz>bZRCVq1;CcdCXJy7%x@l$N?>3`Gj~21YSaEp7YXVZQQreW) zgpzjt%I5Aw5qO#D#%YJM=}eszKM%fFM)4`N zf%-{#C?x+8t@%;${e26I>-;W1s+$#*Iu@3e9sw1&+ibKZ0T2~}YQ5*ag#}DHzSZ6< zH6PDTH`6F2G_(#9*PLDl&gmaN8Uu8Hu*~V&!PX*rh(FG}>X7@^!a03?{k_A(`qtKq z`sL1q{6vU2DL8M0*EUfm%u=SEF{YZZg0abf##ohS+#1pX2SSXx z_s>8y++|~UV_@&)fexrpU>56N+JA7E*=O~8xEKejlmS|-O`#+=*ZXztM7Kt}7{Pwi z(_2x{GcasG(rDu2dvCv>AWU!!gC0aNZ)`NFnVy`SXjMF6+gTfr;52T+q7Fi~JF|8o ztu2^>mzw(G_fPuPdfyFyjF$Cd)1ySBQgzKlB_vlKIOBp&LyMHg1P{sJ`b<`?kmiTn zHmklq%JS2j{!bsuH>Jq*T8ZG2$9-ijB$oiCcF@#u4%I}u!xS2bs#N-AF;8JK!jj;FLBqmZvlN6WtmuB<>?&#IgGIRiK$;EMD z0NnLHFv4{A{1uO+(NYI=At9lK(K3h^=|2N@5y&CF4Gchhqs9i@&drc8o0y({e%rkB zzh9CfUqVM>giPnU3h_kiFDKJgGTAM|<^Ft{%OpPo^~x`NuwUN3@H$N~HKRG%itMU7 z5(R53P<&BcBO_bs?V-%#nm!sx>noy@RrTVCk@_2eP4am=6n80)a4f!NlKpJe#{!g^ z=xI_BdB38f`fu~_NEsSl1s*oo?Mu#!KQN%3?Hl|cI?5!Ii z|D@*V4-Ue6Ln58kBtcJDeYh$B%x%!gRRAi{{mPgOEv2|am+dW1lf6B6IW@Ti#~Z|sGbW~Wsb%U_MITjI9Cmt*GSwO*N}cSj&^03z zTz+UsPP0Zz(?u>>Ns?BR$?nc56FvTIRr2H2vplR7>Wt#o^U!)%k4fw4TWmcrH60ZAR{T0{gc`|EDYcdHP`&FEe9Nhn*de)dMXpa*a<~&!Bgj8lsT^IA53$ z6Yx^<#VfItZ$R4Z2ZuEMd#KQ2q$KyBJuRZZLBuh0>=+37k;3~rPyrd$`eBGQ)3N=T zX}t_A<@gn@YfTG1;3XWp^9l&y{97;k1}p2OFjBU<#h)L0fNA{v`SXSg-6>+tsrT81 zg=rb?hkpZzDf&*^3vrQ1-V!*s>h0 z@u3A`V1y1BDoX(`@1K1!I$a}&kc#S(qM{;#9YdG@9BVl7_e58HEf0XXEs-uDnX_D{NB6&85Y8?7ot=9tU&oU_e!K?DCWGJ+Qd7SGBr`dvKM)>Fpl7`L_YS2p zOR>i?z?yK<^&sasaIWCH7_N;~K|?8qeg~8iz9?NA&cf4volWXRAZ9 z8k(^roSp9=1(8&`Y$upM125J9po?TRmY!T)9-s=O6A;i{ut1iRz*PYd0vZ|`jOg$W zz#*FgakwughK7cYu6;-1MP2%XsL!B5ko+U`e39}40D_P(GP!gLdDT9OXqf;om`H%k z>#{_Arg0gq9sz&Dla=8BgicT;ix~7*P=0=Xcfr|pq44kRRfFCP!sY(l=Mwa_&@qp& zz}A2NE(cHKf=o0K14Xj)d+0fElIbs;sRIc=!^yJ+v5R$H0OPD77y`(UHbIUDj#6Ih z{{0K291p``M2R6_Oa@CG7=}x1ZvIF4zX7^+pe8effhxDSxatrE4a9@>@EpjBs}QnC zg6Tn$3O#93IR7mDSb;tAyjG1cK?Qs{jmcO8?^^5pDrVSm6r#ouQp3?|FG|Et!C@Ey zq1t~IeD(HiFf>#e!z&^x->fU?1@x!X!tgLyaQi+uE5k*WgD@=xh%*8q;d_>U0)77Q z-R1+v6S$6Nq*3VlATfK?eSXzkQU{Dd@1V%Jn;7t{%arYZY6Ogau09 zgjtOsCzCrXBMT#6IqpZ$;38U&krC^!*2{d@*w|H@E% zH$9~B(eJS;O0R>h+F(Kk`@bXp7vf%lB7t{Qk5gkoEIcsEPE1Xq!9(ut?M=X$AZaY*{uTgl3XJ8T)USBb z2xqwgkv#kW4c?j+9CcqvUVzF1!*mO{#)0r&Zb2G(MG2SCfU^~uA|oTo0j>|&qEKpq zCn8coH3~}gedR9JR6?HQU`E8;+;|}g@IS2y3l0v>bC^c}$N4-w{1VkYH-dqDgXV^i z%XEkdli|EakjvpZ#Y%voHTOo-$AO*6ASUfSeq7yHhlhts*qaK(UjnSl=&xS|rtPEF8inhh%nwqX4rbreMDikwkRSB``+dEc`QH+{!G`Xa2xg zl>j&Zm{4TVtMX79SZAAooOT_s0%<@^4sS}7`10k;xeZg}rtsPk zyP6lkw~1`_-+P*RUxGc>xIKo=-ofF_DFF|Yj-Q_baY|fW$zXS*b|-^qA5GQ;K*8<; zu;||WYo}8wjL+;?l_AixBL)BoFM&H3n>t832afg;+!7cZD7?P4sOr2jOagLz{rYu+ zza9yuAy0k0ZI3XK^gt?R84na6@rd0?d zb#gUusQo~ii<-#{JfF?B$4;M~texHhT6Q>hOYQ)%XGmcV9vJjk)4}#K=c5L!zxPxb z{WUm3aG=JJZfa?5t%Wo=cpmry0so2;3j7QP(!$ROtEmu0Teh(GLSB8C<}>Hv0!X+-+p)1Nc1<@vW7+5V@?>#yMG5aWIHbeoGE$vQFswfpz)A<$4>&`5HT#4=CC#<2$*9WpdosD?HG^a zmxe&T3!bd#cpk2Ny~W8{o5<&M%etQxf-r1kHD&Msfu7kHT#Q6P57Perex@CO5$+O% zHM)VZJTG%*WYqZ26a%*r&{EcQr-*afj`ALXuy*(KKt@S9?J~q(_`*j7Wo2c1pjJ46 zAt|_V%CY7?j6*#{6lvx&S!wBSz#;n?^dndlBe(-^@7hp61mF)bqst6TnSN5yKe;K@JP}tj5v5H z7!28?M~~K#3o=&u6to>EE4R4j`T2Qc(74hM9%MDYIa9E@tK&5hV0-KP`bfYu)**?7 z`A%w3XayF*nURHsh2oHmOA_)5)im%T;flM2q=aBf9tb=*{6V0MQ;g3tY0=+m2;dLg zq7DuYS}MnbS8Qm zWOoqz0~ZGZv2TdT*U%hYB@HWp6w9;Af1j`cxfrR;bFjsT1*@tOgi&HGID-<~nc#&X z1%m>oc?BwP%4le4u&}Xz=t;Z`3F*<3z{AIHhN)rKP4o~EWR}m>K#Vz3YWZT?-gb|j zi;D=H6C^SQ>|G#e35L6ONnvi{v^<4`{F{UXN@O#@hIGseqLf&ok-Q8f-7w^&&W_-3 z;2r-8(5gUoF3J);1qjF>n7am+H=Zg|`aGC!$ZcXm0t+$8Fp)4EAgq=N<4RJJucvAFZRq5I5Q1H4f7kV8lgtnUgszh=f%jKEB`Hq3f4`l=Om>loaC5 z`hu?pgkD15a&^Bdsi|$%c~etU`v(R-0x?5NNBlXfc)&MAklfU;(7=wA$#^T|#Se~W z1ZW>5b-#DKJC0aTB({RtO5Mc1mz94;$Hj%f$fXIGyErT4uA``kk54NEj*O|`hcge6 z<*zRik1Er9Szz2e1<%XtvBL^p2NLvlwYIdt7}Lv0+}LH%<>KrNVRm?qW`12`qhzu_ zvgh*1jROAoKV;q2o{Eey7|QaU;*GoXP^qmEFbS5M#eEUSYQm!>JKp_R1p=e#qmi*Lq*GA z#K{Fh*iV1+rmU~?-vD>_F zN0dV9>oZH!EA6#E8;ivAaNTY>&Pc<8$~R!t5EAovczAT&1r@Wf@aDw2TqdIq!qNiQ zwXuUxM1l7%AYa`(SkAwx|Gmog7eB-gpJ-k~QP%v?BQzi*h3IYqCYL@_W9j=OlCF|v zzd0wLDB!9vai%VNdqaAo_a)@uH{rIyG_x}W3+@VHArL1n`c+I!Ak?aW@*in{DRo{X zf_X|QX=&(!f`Tn3Tqs{iRp-Iji1)$~Fbw-*Vmx9JjC8?cfzVygs0RirKht8pudGZ6 z+X4YuDG?)~x;CUDz>xX>s&Eyjj}%E!GK75gV2w}B-}F%C#WR0OnW4~Q*Y*gS@0&o0 zZvay&I8?z_h^9oI14#ptk_Lh!N=!m>4)xf^#^LzDMN3x~C-L>!Lma@S6u_JURAT^w z2Eh&xD>Q(tAH<_D_7{A-XAp`cCMHfyOrW5iieyvYBnDHIzkN%N7<|O|Lr4bmnw#I> zKqQ-y{I8{?N305@3@*UtdcxpIaK}=0m}A?K)jQfGh(gXoN+mEaFYoWmP`m-y?juN2 zd@d*u1s`v6X6F30Yu9-B`Ri(H&p|$qwVN3-hO=!X$f^s21q>RwI!u2ZORLm>;*rSj zf(^cQ6J+%fP(#YJ61Dc8Dru4lOTbI;s$V3&h$An=WSIBK7k& z;BLi`K3?U!u=O9}~pARr2v!Hz({?TLyzO3IsB{3=TV- zk_QiX##rt?9=z&Il`Sq4-F*>G^+smIexMTt;l&V1@!^Qg^W03J5UdiN_cXOYS6t;a zg^R##50(vyRo!=2UqC=07W7{F%%_4if`iXzFc4j&eg?lwWiM6|aei1iISC;;^9Pdx zPBT7KwEm?O5S4^{fFbeB`(yi{kpt74m6odCydegwQd?Jt7KBe57#XQ7`0-4KBKHaT zqy~ncc~m;T!BONH!Bj5%W7Qph6`4pnUVK zzFvGG7!kn#`t076kZm^b{>8xNH4 z9Ns&lzVd5HP5ORLWOgP(AqX^Qed~m&h;p4>PY~!#;zDQk-3T1Wm2%qeH6_Q9K>a;? zleJI1r&Pun_q>9%MDJ(&>TJryd`O<*&u5p{mW9HDOCNql@@djIUf@_NWvOvI1~z1v z4Wx#%`m{J7MbbF z9Fe@$uBdDHku}D(M5&!Bt&9@bJ!ik9_GdmOBmljkuQX?Ca^<$gBB#=(4^%e4B;LvF zV+od+qA<@}D(w&S*$D~Gcf#f-+iExei} zn$j$;V>?bN$y5L`(s1y5xy*c6#UF!oW<3rEy3(itsfC$sCn)~J%5(8WRv&_nE0(z^DT?R# zgXXA8HbX+A%?pZgIT<7~AHwJkfTH*Y`XTMSVmj`8lPxXMF)1wZXh zbM(NqVx53bZw{F{Z^oLQ{t_<69V4{_>>`5}g~6%N3!YyrUrT?fB-Q zkWNlw>;{Qn8bT zJ*Ev*s7BYR_!0MSgLO1k#n=eQb!I`8X%$uFv0<*a?{%Y>g=tLB5vPF6yRMkwW@JL7 zzozi%Wzr`r_NT*kr5=l9Ae#58J!pus&dp%(m0l^Qxq+W&_~Xk6AQ#nGRJFZ2+db80 z9WZ=bqA2NNP3!Bb(P^3z1GQ4a#xBQN?-&g7(7Fej-72yF2BcVq@aE`a!|P)2ot+t5 z+CBYm*2<>XnLHb)<_%gOCuNxHdUuQKYrQ{5Cj-+7SLgB3jUQ1A8*P=BEhc-5Rr32* zKGQm^w8)^W!v6>azbzDawa-Yp*!p#X+l%azZjIX5$cy02VO|4=>M2i2iQ!ND!m50l z4sb?DedPs)CQ>o^L67KBHJv}JH$x=Q0BOjoUrxNSv4O;+Ah6Qn87yKr^S04KLN{25 z*#s|$u=f0XT;b$RMl&uLq#$lyTfIW?cBGiiA=ct(TfCI4nk*^bD?sDd!)LwU&JSg6 z*dL8k=K&JgHzkgZYS@Era*lI>;*NMBX)eH(2~f$mgfA;jbHFNfS=4J&v68>+AJPV+st z3LV6qf)sAuvV52&H@nRT$TD@B0og;csn#l-1)+o6MN3n-T^nJ9mvTzY&Ys{}Y5(9bOKQqjr@bUBv{y?}3=%=8MyY-xa zH-?yNe)U`KLh+x4T|4r)p}Owg3zi`~-5yh1;fdP@3&BjKUaQSAyRpHU+5guG;AVgB zO3Xn_8pVY(|Hv`~6QAZPq(-qNH~ut1p$K%>-b|F@t5>g3;4v*MFC+e0kuuK5Hhq6} zK&DVRQS7V)T9q^!2m~)nX{HS{n4)|Eay9*AFk)e~3Wa(_r{BrtixBF%8 zbk;OGvnx(pj!O6Wh>`H4V-334Lqd~71 zr6;_S#+~@#l=?vs@ST9c(aSm^B2*_sbaS*ygkTJWzCbG+lJ3TkBe})HLk1~EOFpNHl4ySR*%Q+iQ|~R^bvI1wd&z-%kVqmzXB>g@nZbBuR>7(CC=efw5oF{a;C+icG$qSR9sC8(#h~w zp%YI?y8O_BXHnxiVxb)t^(#dg#g_B(Md;bIFU7%ef-c(ER_w7{_%vnHbIovGh=8By z*Hp=>zDVRfT0H8LYJx<7HiHfLmU28!w$k3FX7pa!lguuoSv|KY_h-UnzXy>st{iv5 zW?@pYbP~Sm@?8|l7{|kz{7A_5-2vWQ35^Ah{nEI$?4qhl@5O}$X+sM$9Gr?L*S~uN z7Wq@&DzJwuuzX6H5cSz{Re98w$slLu?N3A?Hrndu%ag_We^z|9@Ia`&A)zw-{e`%N9XFbYnU(@6RB(#S^k6+P6P~8f_zdiOU4)1+su;h z5Mve2_WK-4ahjcuW0P|RV@O)IJf#0uQ?2!ZZHMHTRDlou%~>Ixa{TT@(0|x8V|=Pp zVvogUI6*+{mj(9&?)F)c0Qe>)qxl<=>|VtVOSOnD7zjWep0<-=7pUQ{V9LWq|GH2= zVlJy!q)<+ReVdX8Fxr9x`AQ2EZ|mC1qypktmTsf8_+0b1Nd% z8*qyV!cXUBtQBunT#fHA|*mG9g4Jv}*Xa=!f!?iiA$>p1C{k3_k*y_38=pA^D+J+y5 z+BY0NJFP_w;t1Df{lt>q3SZwF!`O-|z4W!-TO=nh|ElnzWgN(Hp+q)5G*Lv;Xx5vt zUG3o(87q{!#Z`!o(&O9Wz9er0jWX0IUqFclLE{AhAlb~OFEHE|&?@%6h*EkRyCL?T zi>6UT`BfNPLK2?68UaIH7fQ^mBtq20#=FAq+jpMpWJo;f-H@r$fRlqWlRZiS3wa;z zzzZ@kBy@z?{z9& zmTe}QZ*7$p1L!UG=ItKvT|gN_+}gP+ksl(P3{7+Z$5tX~C3H0vK2XH=2mi$OJq`=^ zWnb(=y*`I%=xc%Y5&{>qn*j5C6_tb){RInY(R-9d17T!~Oi2CWyPp$(UgN`$p`V1e zdZLRhoJZ_O!^v@7)R^iZ?Gh?hB9Hk)$ zk$KDk0Po7Hlwb_qC#^$?G2q#(Vlp&|XGAhs{gNV|{&Jq;3-zPQRBM}>-8sFsHY85| zR!3Y)O65^PWZW;DV;04yUMC+zn@CW}8VuJM2$^FPnC{*r3Ap}xUK~1cz>5U5t>+|F z#&#CHWGGt8=4~SjE7eE3PxJdy)a#+0?V@1iJoE-#P_>RFBHIc{8c2;Jm%WzIZ%LW> zGoBqWRlEku{~v8{9aiPm?F}zX6a^I(r4;GzE(HZ?k?xW%=@L*;k(QJOrCYj7x<$IX zJEhk*Zufr9Ip2BTf8TvwZued+R?d6QF@81ld*{@5sf4{4-8<8RZRBQZO1+WRE&ckf zTujpPB|S5l^WPFc0ut&&`&Zj@ll|5uiVk)>4hcQ8sTa%ku6h!1d54wBJnHj&nx1o5 zEkBWHK#~z(P~_XLrf8z}taW8aP=PHQYMaH6SR<&1VareG`p%=mRST*2Br<}v;P+-r zu|^`z^(z!FmM($M;=0DCu1{bM+V!PNAEme{YYt7W6Y^qj1~S2^O8lQIXEXN#0ulo1 z5hzjO1cLmPVWmkjDB|^Jps@ejgFcGq7mppI+hK-(KPG zJ^$-pChz~D{NQE$_dmTCwqO%}s`?PfM`~(!L0q**fi+`eL;!J-`{x%Id;0ibogK{J zbZ`K70QBKN>M6(?fGd~={1-_n09oPLPiBB+0I6z(0gZtmS%O4lV%^-5-W?crJO%9| zaAR=>5Wpj>tUQR-6d4s&H#Bq~L?SsaiOoaf;t*OPbkM-e?3$XI8iG;cia#708Ug_H zrI$HydH`_aq8@_!lO-av{_KgzC7@fvoH{?9jKiz`?|*)Cs9Pa8O-V_~By{x3FfrC* zwB#LwMp+FAi;9Yh5KkCK}jS z;m~a(T47<~!J#39FhM5F0tc9_S?P`Fw}6NGtEkN61WBO>NEi`r1t8R)AOHa(YG8Gv zF9Q!adrxwSFyyU(kjb+2negK}H%mlI_Fw-P6J&$PEb*eRukWuU2|Pkx`)hTcIG&}Y z+^8C$1{)h2ftsevRYj)l8gxV=e08ttC*YwFWVXM*s9g`F5I6DgK)ABO5^x0wGtej^ z1byX?E`X3hUO>cSTl3)xE((RnYe8N48SqX-op6uk)$^nsqYTh_!G{Pt4=(6f8YgQ# zxuvHZe^!)ROYtY>6|2^0#z{>ZQ~@_i6!0nhNcK^Lfo>(Duc@)!!cS-z-C zQlt*NeaE}^^1#D3DUS$0UR5r;cS*vApPxSB^S|zq{q269+%(vXaxZ|~5!^RR?RpI)!ObcwTrf%0-|vNTt%{`~F&x6?%^Ozqdt z>rB`)fgcg2R_t~sZqnUk#{uWjtuT%*33Ppzq7>c&BP>M|6XY68B!`ma66!~OevjEm zp(!5BCII>pr=tke0f%83kwT~u;g@)wP>4Q8olvVPnuv+wFcmn8NMa}LlS8Y1jA+2iJ;3Lq6Z409IsC} zmntbA3mHL14%u&?M?|>~Qy)H>R_*_pUS6S=$w-^AGTb(dbwEQC{|NIrhR`HTzR~o1=Uv z<5eHyvvccZRNiKkbEX}KZMAW_H*%Kn_M8=UPvu4K3?-26N8G4(SmS5xqnyZ66%l>I z7Q{ zALdLbGQ}KMRPcG~{pjllid2{BUWlF@k4C~h+*`K*48Pl@52OLUU!&Rk&`L)-KfmE& zRahmdSy>9hnSCboVbo9M((?Utr^ZH7sag#d3l_ppng^Z+L<=vBCwNusU~rx~vCrZ6 ze0Z#c^FZj)hy_+XVe#^9=wW6~1z&WhT4rFQ&Ru)NiPW zwn#jLFI`*|d?Ek&(lfcpkT3no6O4E7-U0dXZD2(OLbQQgoPo`cl8o#ElhjW{jUK~e z_fqo@&}}beWuE}NJXGy22=rMihYk?Dh)D3Mh{!f%8Pnt(u4tjf;VW>Ok1#~_JjHWx zaL}KN;{l}rTxXuJcUK+G6M*`*5m;aP#%dU+4$7o-N%6E1i>xXzIr7*ozbaZ&1zHD@ z5)5d%&;vNgF*5`z9w36@@X7 zKypii+K`YZxf8Z|*p!|=dzK4+5N{tJCs2PNzX%m5@H3x4p`8b^UL=+ieD7^w{|m8) z!)F?BuyDou&cK^^1q2xOXQ~*O=PAm>fWSC7I=UU0Zz~&{8TjjDjuA$LoPo>X5VTlg z&!0~g4ruBfY)+xT5aR*zW-DzDRj?zR=7!) zA%hO~S2aQ$py4kX6*zy%5-{fCfJ&ta9>fcR4&fVsgOL4|fk9AgY-jad+^75h(E^}P zEp_$u2>NJ0B(QN)4sA}{@0Aa|!L5C3i<8dCR`T(J(NVx@!ghXZ%kGwHLue)I4=&Eo zdIhXnBeIH(d(PKOv$~lXEHowEW@-DY&8x;<IQl&$MH1mxkcHVp%e#QHvDEmhtJIzUll{W z<4z12l23!hb_X6yexAti5BWM4Eun=aq^zFNMX=t&s zlyl#YSd{z0JZ%(^dTFVt+93NgPz!N|U~Cv|sya6X z3_yfE3skYKK;FM=#Py`1rR8=z;nLC3L6l^mjg^iQ=l}&+1iR_oKchA{=@Vg-g}1w) zE*Q+y$3lD;uyaD~5Co?rc`S$;^9(xho%fa-Kr#nw4hvKnx@RYcttQ<5gy#`yKN#E_ zAWF-jrr_f+s7XRuI4nk=gP7fAe-)g(;4{M1FHD@C)&-mV;zYIJM%6I`XfZ`I`nCb9 zr5Oq3eu+~9N_{C%v@up}0=4KZBX}yW64Nq%7~thK1((4q5aEKr^+g018)(LmD^EWu ze!gH2#CXYC)ow^uCaCME7m%v2_0>aEp{f)p(m+8q4_;*pHVe>1AhwpF{WtqZiBp3J zMh{^CP1;Off`WeH%J5;-fNb^YxM~T6**4AceL8Q8DC-v`J)k%qy*VZ*LY}W(>H9e#@dgdar5?7D$ z6UJ>hSKe*~yp*+lHybBN!ljEkPs!g|wGsCuhc&C<4*#}AhLz*dC+m*hYM$OR>yC@k z>#C9}Iuup4V@r2ALpx=|l#*%bx!Q8gH)IteWs2W%-hkhcm+r(a?24S(fsp zcN3Lfws=pfo7ShmJUgF4-J`C(bJ^i#x&T(qyFx|~Bz`7##YsD^!bn*1@4}dQFts{W zsLqv36gT;Nnu7nG%nPNL`)(bFGf|t^zS@%?4i7%Y;NT;yZ)2BlaxPh^k5*8% zbp04~@UV2kr=-Nom=UC$!?S*APd!)ebl6jfe%eW_>d_rfSpUPiPie7Yw>F28MlWqq(MZ~Ru06*$^kFgiQGBqOCjJtBB~UO0s@5gmT{ zwY62<81I*x#nqT^DUL7PzpSLSTpkrmM!BYB-6J_cJ6h>+k84ZDueE4@s7_VdyUL!} z_)6QF|1+1FvGE-t%r>5vnn4?iLDgjLS4ckGm^L9(3%x?}lox~mh~)OEL^#cK1VbL)$Lr`ymmL9|`!I6!e$+@a_SEeMX*o2`qWFHL+2@@Nha>+Y_N4A8CT<*^`JDm=mEaEiyJ z<>j=roxR+Sn-6(n{6&eKK5Wf2^;Ehz5Ias{fCl$0z-ecmdQaJV0hH*7w2kk0HDCPL z$H!-Dds`RmEU1vLU*T1V!!-#H0GEC+C~Z7FJ@bABk~Xc5mLgM^XmDRZr_)qsx8gYY z?lP*!UY(kn8mw#{>FG3}xNZX@;3uc#O`i(+xvQpP8+Tj(7di)jgF z)Hu0{iOJ+6^*Q;s!q;G@H^JLBFO*h-e~t2;wyz7BrIMkqWoT8!T1(xXSwH>qbM;k! z1xLhiq&Vv3AJ@8NrAA!-WsAnKR$Ah`EPy8*>C{$d0c1elz>sLD?ghMABLn-!~ zJtM_mVt0u|i>pk_aJN_8k_0BctaFU?yBx&WkL0vS&o?PiT2J+M`5xCbIbO7#N-4IS zYJc|tpC}`PVPP>0eXHN*UgT=<$#%!NTS}*LPUD)#bjB8F-dlg>aW?b*AL81&r=i5~`wUF1xcxT`lZ)ppoZja(CRdLx~^W^Skiz59J@pb8b4a zwgFKl`DP>^^ogiF**!@&_VhnSWV-6nJmXF&aT`C59cqTzcpU zG8D5Oad0R)jR9Uj#mK1SpO&4CoEHY*)+s5ED!RgS?;3cJqCiYZh3l|faX23ZNBZ`( z4yOw3xcDzJyNY<<|y#w8-Sn_b`M1Y z5S|IbkHL`$u47cVV#<9!#~*n-ewBJArlw9%phbZ8nwy&&5qrJaA2O^sJ6iF5AV~Zc zR3q^ND-g}0^EGN+_Uog@_P&+Q@WDVasNWvW44P%C93Ovw z3L2W$sU4hOuwQ_3F6X2IgnN)|+5gD=`jsnB61u4bEg{zxJ_8!T4X}jQ)YOOschs=e zrk@SklEr?~OIVM_zjlcjCW_B7d(=KwR19ly{`gux?TAjKE-AG6T=}l4y~=TwOJr*h z-y^-0x8l!c--?CYF|gKMFhmiK@7}#s>F;Cg@_KKR&%2gYjHRNTrs| z!uRv_6F=U5>xoS&n9Lk{IbT)FA4y~yQ#rveY*!jdyu~@Sx-8xMWu(UF)qqlfT#$R? zsxlrYV`ICk=VGAEJ?pj}6dC%2`6He`?`YMh$Px7ZG=p3mDJ2A|zb9I|K zbbOEEucWR*Sky|b%dFPe-3gKo?njrjjy#^ASJ2JKA#dPIt%P?{^yc)(64sK-S|uvA z>%kMP3=fxYj?BakA5MVqA-=`tmt^tF`OSv!T@!YXQ@Vl6T(I(Gq(X zI1lP7#9^1<%$OTKTGh$uTJ`&1=b3*K{h`G6SEx%#+_YYqJ0KU2xVZSQC0huQ-WsSr zy8{-o$=~(g0KV9PrA^b6l9>2HUA-OJ5<|sKz)w&i=J~LFFAe2WLicn|8=9(n*DmF+ zH6le-cY>#NJ9I&C{TM=z(8>(CE>loTwa4%dWL80g!D{@QET0QR%$B)+P`=hTHO(w7 z8Rs+NH`;&&AI!lu09J+SNyqZFKs6h>mbu*O0L_R$?>b5{V-9M*FM_8_GT0AnP7bU< zHV>UOn1ES8TfAPnK%9R7S0Nm8Se)aIdI^KqFF{8_I0;frC1L_zdpe|)g)0U+5ng#2 zXpf<_Z*?+j?%u&kZsCXjLBT^!FD;2dbH(-MU{k;Fj^s!;^ik)a>k?H^xC7X$fh#Xy zm&gTS8(Udf>E+{NlPa^UDd%ohlVqh(ynQ>If_%xACtplbh)v-XD+4v$`e?NBT%@{x z(f7|-DfX!3a!z(`%5H^F3@V8ln64z+NvtVh^ykT9!5#UpQErB&rs)iK63Yt8#Cv~4 zI379}3}#_rP|;Sfao>2XrDncwqcY`W+n400yK`mvQ&fspLQ~t-uHYyORn0NpUj?D@ zQC|g7pN8=nlF!m5cTq3;j)`*IZsB;UKAxBV z)a4jk(&Elx>On5ON0HWBIM%TDyIvYC?J5~is?lntkaT!(A%eo1=l5lrQ0hx~4vZD& z%TPD^dkR!zYF|j44V_Pw?}U?z&8MTUuDI{0O^~kD?7j5ZMMouvp2WV$W$P$AE|#;H zXpQ>`yjn-PF@PXH1`&8@6W} z9jyrWEt$GpSqJHjvK59o<%I5LkVZ!cxR$YaiG7~myuPGU#%0KM?uFuO?CLMEQVc0) zM2SNwZjFp|R~_QCMLJJ#Vg-^F26QRgDGl1sBb&5KwF`bix2?{A5t}j{YrLH0jbb zLWb(&%Ju6YD}JAuNe93oLX?2h6Obn8VV*#aB5aq40lYQL#4bG}LpGzY)mzLC4Aj`# zMKr$TVbfq-`UVITK$NYmt;!(D2Xca(g(b+_`zly);l#NLk1*=Ik|nMJK2GE({{RAn zJO<#G2C^yNdQLn&L&_m^Zf*{I6)frL>4^3dykOu`>(f0U;4nkQE9E%51RWpSbg&Qn zaN03QPnUEM9Lh+sXov^sOof_~kukt-rC)~)_!6`oB*9?7D81653sG(6w2)whA}1%$ z)U1r;T`#FK)BjdBsHdxoU%3ua?U0a=aDGEZVhKG`cJ@#(1?Ar_Ifcu>r z_Vh)3)+dLhi_=R6p>hrmq~YtDzC`HH+l;Wc$_;U+D4%XCvtVb>e>!Xn<)zNr+O&9M zm1EOOHHVhKYX7S72irG(qVOw&h|AH(ThMy=IMkmjandY%tHSxDJ{}Zz>Fx`L!g~Q3 z<$8H(Yaa7^)d^NO)#f)zE!;6E4SP7k46#pYpgms;bLWoixvVX~+|@7AQQb!t~T86#VUWcJ&U-eZse9IrNi!Rwoo6zfd{w$W5Sg-GBYGF4xGi zf|ESu3Q4ieEkU?Yw43uWbIfKuMY#T|aU1iK`(hgBj?;3(M{ z)C)kIWcI6rwP5-BwXz4rF}k*+<2tHRGXM;fh!ry;A_CdX!1RoK@z%4LfR?t_2SaQE zvwrJs_#P0B6RLZ@?PgNMgosQjFk-`J!@vIV<45pjv$~(X0geVdd?~kjz-sHb)quwg zoCq1&CYYq4`E7*}vBXC6qn(n7|fSF22NnM9k63yon zba3E^R5;*Et8~#STcP0O{2CN=3syIT{6UC>dc9-@JJxCbKA^LW8V+O6 zV5I@>Nlr!8oOz8YtF_=&%PsiPB_!h^RN);8gh`^{QE@+P(?ZO|W6t0%iQsi$pjFJA z3=}1v0?c&=U{W2xX@NrJvOQY~_y&1Y@WulsmzUG|#z%|#@owKnd<@8kl>QWA6cIlM zl5z4DK15z$cM!8HIax8hm6)A9ggDvca%*Gj>ipr{h- z(j`E}o`{vKX7_C!SBHQ&Hmf@y@-D|YUO`6>Yx+y zLkZ|lZzz!trAuOx48KE~Mm3MVKY(y@L}I=)1V7lQbsPQc{5*@!&krJ9a9!ksw|8`O zbaS7>b*OqF)&(*5)z&7L%YmPz15}n0%F5w+7hXF$mgKeiK!t#v0716#FVjLoKNz%! zcc(%O-DS>U-K!6Icp|~v%=`QL-I*m=uCR{c^YUIsMCZYbm|f>emhNTP%S_p7O(5S1 z>J|M4B2j+~$IaTy5fJDI6*XW~QAF;rm~G$>r#CMjUo<3~e1Shdx@}O!tUV}&k!cfv)+X@Xy??*uJPx0B zk+}*Hbjd!hQ_uOr8b!wXZIA&^a2i0?Sc6#~DG7tpi>Gw(g|{_2Sf&8~2d!VnBCi&6 z`SEu9S!g0fw)Tl@94fvi>^yY9zXnXK?5!yC&}8Dc$Xn#UFn@l;0*N;{G zOEbi{^L%p4t+`0L?JnXMtu*aCBClT&9;s%%OsRcs9I?*>$ZGg*6I$;$=rUC^Upt(~ z%m>MoL?(uH;TmI=_W{MkHh1)!9+gMIQ=m3+e7+BS8NsjARQpyt#`_r%6BI&CI%r?$ zoBIeL?8|EQLZkvoP7nDI+SSc&a4yE#PkXXnFmQLK8WX54luR{K(kcK^hY_Bi@vV8; z`{r6_*!%R8l}$|<_G&G=2KWt~+jr5!-j6(w9y@6$+y@v3=~dOaj8$_Pxmf(AD;dl^ zjKxfMl}?NL8boT6nB_9)IW>MMre*HOWNkeFkm;V^>f!!_Yh_yx7VSc#WyXEK6@5xn z=wjXa#%LCcNAkfApqqDx$A$_K!*rb|`IiUtrytZyIgft(!$4`Mq}wFe8rWf(kVU0? zJbmmHwR`VQ1D=(&eUi(lUrAIH5ytV(<=H`!~9Qp=Leqb>;;))&4YS~np`b$kM)NHJ+k!Tps zFRUj)j* zHlRGPL@WUJ*HFR5?KllAKQ^@TmSgtt}QM#SooA^RJx|w1bij}euTs*lxC-by= zEBa*4hDO4gyK;f{=vrLE=Mha*XzRCq1tlZ8#$UZ>mscCJUUJ*K899DMs47)Df6fr+ z?0LYG;#&alzevOMCxl52Ga+eRR#UU~a2WV?$1l{BeNClnxfq|E_u-4h7Sth;*3t!c z@XwV!wRt_(CjT|VomXZKKt=Bi&ww!jOn+a}oxw|28Odgrr#!^x>I3~OU(Zj{03*P< z1oL`#&G~9!kaPy=sRD4(wR?BgESC?kOTGKA<4CI* zHEGqb8l;W#6Eyl*#|3wu-CjtV#>1cc^%OgQK=H1eY>3ngNB6m(+A)ButB*2Bt+Ms@ zzZKVaSaMMVp7r)Z^3?3~r($$baDq`h4c=+PNVbWPhs?zPtC=iKc#{VN>$ zBJ8`OohpvmK+Z*sEs)% zQ^)bsLGt9jwW7o<+f;ae`!jBQ{;r%K6&k@MEdRZ`dCgl}DO$~F<5&>Q8>6+MAozYA zL9FW)WS~f%3I|Q~Cb09&5S;-5$~_dcC-?kBkVXU8o{y?o^C0=spRV_U@DYtIWite< z_?&FwXr=bKhyvI1!;PS*r)t5-jq_hl$cJ$w5Y@x?1f$^sM|dV7^+F`c5>#TtY?pvg zhQP-Nei!?wM)(=MR7w`=aZWHjE3)I_1VzDLwom`*EJ-3e)3VMZ03qD?IYUKp`>u7* zpYJb0M4@2gI747W%Vtg#hWsdemICfW6gbQH_pbASci=Vs{k`wkpEXMBtkY5>OH2s! z+m}(~m65{2MDEbdmpA?8-zWI{EdTW{C6d4I;h*RJ_tv=QtWN*Y0{ngWdWF9o#=lSX zKksXG=P%Wcyqf=d$bbGz{Ub2B|HrM!o&Il6`Ty=|eo9(dF$3R^NX?8ww*jFqM%tuXhe|n4fcO4P?I9+G3<;cVP`M2^FTVQ|M{-I6MaFDE0T8TdE5@?@Bqo5 zpqXQYp>&{;gq$PQq?3L{Rn_5s64ck}Uq)o8woYM%xM5J>^?BQ=?b zWKD+nDhQ>!&J&Xz`u!HieLthTV6pM7n@eI7va%t5Rf-Zi{mi>O^u||c5eh1cSOhlT z6t~0ZI)aIZv`$#gF?a3yncq@0$=YtQ0W{>@o zo$pRdRH(ZOWl@nMQPJ~t7V1u^xr2Qiu2PpPk*l~Nvxf0mRMv}yUw4L{V3OS49&7cT zrNnKK`TIt{|Fgt8B`1Iz>~Jcuql zS_VAeg_@dAaPZu&c3OuN2+NIMGz;Kjr=0L2d?N z%FS*|zVnUz*J>gMD6DiBC{a@WhfAFtPy(hQf8liP7bIO@%(c_`YkMD!pt08 zR)k6FL;J$G=|P9Eydyfa-90uNBbErlF0~45H8O|VAz@QwhrQt7N1EAmLwfZjB$UxN zK6yCzjwI3P>aW;gx(`NLAb8OWiX#(5h;m@g)rWadBp()ye)ses3Lx;{KO`Y}2OKpk zgdhP%)Ctm{`+&zok55KHVGVH)c>vzzHzC{|fHa4z`CXu|!vTVvl!@sJBq`$qh3+%= z2Eryljy3GN0`jOg(9Z)m{uRL0>6w|*KjSVKJ@r_odl(SNumv$A5ZNybkUjVT6G0GS zKXL-Y83DS|VNbT2X++d~a|@6*&}(AnQ(tL1z#wqCD<|TI{}J*s;Auf-w*&ba5ZBoT z`9qIEI)Y5AhX|}WcrnvamQ^~iTO*SsAcAdjVWCNav9kUx#(5-;3f>GcyckAs&%Xjh zwqmD~7hu{?;LVSwS1bAg0>E1B$0)rk)qqqvH8r&c#4!MHAh{8s zc%pB_NEQ>32&2;hn?3TbfIaU{lcOxp9ptH2nhDRAd+`F2S%T|asZ>8vERaPBlmxFV zoP7mdC&nb!2U{OXGM3oyJ}Fz**QJdDYSp>+Y%=O!C`5KO{;^mX9?HSJ$*SqZ$6|lA ziiH39(Uw+nN#s3I$BC7#-Rq``l3~l%i8%~_)H9@AX)B%ogf7jrRuwlbE|!)kDzDu8 zc4NBLWFa#V zunT)Ft3&AXenQsHjb?`op0%|~)$QQF`|^*ciiEd>K2tc)_;ET;dr^k78e$`QJ&41J z&&>1%J`x$h2YD|Ch{8$JWsMyepIDIqyX9Ul_*NpLEXuqf$8!?~soQ{4TGMIn4$5Z^ zGMyU?B-z>75iJJ5o1P##uz}AWR*x32TE4Z~KU5ynKy(WtLV!%xsdtx&YbGYNoTO8F zRLpl`9L8H9%+q{N>r_k_1#%3KTO~f5CWgfe!a}ghGeJf=vTPw<(s3ciVR5XSGtTXZ z8Zw6jA!_RKWSE)-0)s-J!%jV}%qDz=QvkRi!LPO2+91>g!9EQw8ge(i1zeA)XvYvl z6ynE1NrWN!qz(t+#tM-oB4KPy4Khyyz<_`&h$7~9MzUUgtN_2oNH(8D5|jZV5`!Qu zkJY|m#3!fU7B=@w@_?E=|G?3%bcsR8 zT%XxFM$t)JE904(idk+a0Pwzz$vM(RJ3faWo;FhBnL>z>BhUD|DO9R_SeH+qb5=oD zg{5T1SM%dlfj1uIQ5u8UxWBj~s}kmE1l4>JlG8s7N4AOtWXOLNa8?Sv!$#fz$&Pzi zXZ@R7}?TlsSY9~zC^(BWkL9KZ2+P;#QY1;nqk?W7a z^$9jR$q^a}%(AYik`4Plkcd9~KlO1PadX?r!l27y_%ex7-I;=FNNejB*Lp zAphz)$aEp1RJK(OvV|b|$bJQqc_AJy0&;L^y5KsF^1j;h%pWqQ)y(q)0s=bBQ$QE` z6hgtYhgp_kXanE=pdS4#2LSXTpbAkgMBM(Jqa_F^<7aR0bMZ290tU2%;88$!u%ADF z0_U#>_C`9jB3~#TAh!6o5ihM;u!z~7gqc}p-vBp$8==U#;R-Wh1cPGC? zju)}L$kNJ=$F;T7blV_q5;mXijk04DRmJOQxpKiK#sW$>%e!qhZI86j51WeJpUZZN zWiam(+S2Oqdwy@>uC2M^p69GS(Y-?_V3DP%w#I8Sc^Ny?)hpJ+A_>%vNs-A!Lo^*yQAAOn6RrsFE#^n;{1DYlyS|1hk#FDz?h)1zI z9);l1b!e?P^vs{DeX}abS#7Yj-QflC&NnvnwUj?}`s=hQViM|4K;|amfgx;u9q=OV zqP0p2zl)~k+<+>Ia#jnkeh@7UKcbCj;sEJ;eTZl^MdkvNkGXN$eq`rib=H{xo0-FC zBFIY0w5`naiAS0d!JnE+`);+Rh*pMvol7w*Cb&DGE;B(7rWc={jcb2WmX1M*M zzh#ClqZ0I5R*t8pu&*zG!{2tDKk^CZ*_eUkbq(`UtaxZaxpH^pXuKJiO!{d-oRD~2 zLoiuv{;B7Wdlx*H{x3gwN`S=x32Gm=jQcKn(%~C@_#05t?V)cvQI+Q(aaEmqh|GX- zRNqc=2;Wi&(`H{l;{7bip#}M&*gt#p(@E-#zAYm6|f3G!53Zv;@}X zg&{G8#qXKX(nZub##G|!AwH7^8UK%c@=Ma;T{VD|3??yx#Q-B2t24Gr2lOJhSm)gg z7)C`w7e54&bSQ-M8+!y<59U+2%H}j`Yz=2~+Ri)!^ED|fw&O}c1S)o-LjsV(CFv8~ zfi9PcZUlN>y_nfUdU*&NaT2M$%c7Nsc`~*MeYGQcKf>-6aE%9 zrlovW#3}92>0TWC!6lqH(@9wHyTl(QSm9HZu<;GOhr_aFNkCQR=&d2~fR$G|#_2-~ zj(dYIW%11NQX8O`!~A&H|L(NufS<3xZCti_!tsPuu8zyR`aPB}n#h6*tJt)AmKKSJusM2-n${m$;}9 zsg2E8yc%_VkdTumWV3bK>Hcx)em3Vni}%&yUSncgBE@!>y21p-d2HGd) zcTy~JId2eh|L9Ja?ib)?GqXYG;&9+!*2K`r^ru#vk;3c_uj~p6@|-OXou&M@$|s8W zYXOjwmzS>x#qvESZ4?S5(K`!Ww6qC>$RuPCMnOK@i=u6i4MNV52OOzvw8=n~ic3g{ ziHVUwe%xEoXaiHZ+W!^gk38t|8La~@r@6UV8xZ}k zL=HB6ac|}RpyAL(f$xAl^0l7%PyZ}8D_c5cpE+p35h*6{TAUCgl?!#}WwilY`fmS; zp7896`LCMJUckjDtFUJzSnusZ!To~o&3g>YWqgTeR@kWZ@h6hUE3mD4Gy|srYS+$e z;#Si!z_}KC)tt;hL}Enijp@y_r}li{9U*ng#fKY`kIEv&rO`(hQO+9d@U10sao%x| zaW7ElXWTx#@a%h!s#azDU9~;?W%f~nWA!mt%oXMfN;q1Nj{HdJbuOZkmTml&z3@4L zcTXpRT`1nIEL4pw9{$8?k~JhEC1cTaqI+b(N9jQSEj<$@Gx2MJn7}hCYsJ39kB#6rj@DX2r>MZ8?7}F8A{k>zQ$3X0q=^7jvt!1{7C>Aa zFN^#FeHNg2*nrnpoR+`H$av{*XKiJfyYGDTY52s|sCj&FnUFo`APrqtwGo@VQMj`x zsJQ<2&i6twX&b&2?$&V^!zc43fN$1TXHEVB_k3~A) zc!8HGcVWc+H6WSMf<^C)-A5AZ6RoWk6&+EptxeuUbPgL{#=~+Qdrdf-xLU-M4DfB# z-_`cdrnq$L-?diF_-_dTr#2E6E+!>42OSPV!9lxnF1h6aJNvxLDCe6@kmtcILE+)4 zd|_c>jeeZtsb+rqX@qJ>3?&@W58O|fFJ8O|6Gsq!6jCkM`Z>YD1@YR06;7-uuz~;; zO+zc?Kmb|kLuNK|wj1Ly5C&QBd=yn!SZILj>MNp`5a%b7FqF=2M>~lEO&2o=uJp;H zKpOc{P7b5Ft&J4&5|=KcaBy(Ey}eVjvy*|F{5r<`fn^!nMN%12u+- z6?DJAv=9`Q7xkZ2?Q5e?G_&-0{t8&rUpQ8e1b zS-Jj}g11y`EngvLY@dBGs^;?<>h>$*Jms$`mJpo!%>eJk3P?U`jo8A+((ZR#o24d=h68^gyF$p_SA%|q0;0#Qnvxc=Zlfn(*>4*V%^W|g<0?J2$*|+lr(;W^M+Kgz zI2WHqH`QL-M|bMNI5+XG5N(mW|6Z>e$Byv6nicK?(G>a=b(>lPGojC6B-|Za(eqR; z8!`IJJBtOO2B+$r#?6|NdvNe(FlfrD3^1K;sNLh<5d`4j^=8Uf^Zj@9VFJA2g=w{1 zKe)q)?jeWizuQyWf6C4`|Ew8cJ$#f4jBY}k$pn%Oq)P#vCNlg3qHKjVHHjg4Z$8pA zJNH0Y<36N=&LU&HMn2o{=W&~%1wulC{LMEwFtf>O@LPup!lfR()xry1L^Yq_n@1RO52c*VjkD8C6y9xHzqZ z12;x*Yw6s%8E!b>9|A!FD1XtAzSGgi2t^8@X@11kp;G%4 zV((4OF`*5l4d&wSfoap$tDV!ctKRO)^1+?YU@ykr3#|-KZ^OEBb)##o>$DXPX6x5u z?wH<-GC)V0?FaK?7bcAtu9w{zI1zTaHJFrRol8*D(1C@g)OFX`Qf>%e&5qU*blP`= zi8WjMW!AqP*QD(d@>RC%VUnnRnk`6f5j*_&i`ZkW$|3CbtN5&6@tu4^(CDM!6i8)Y ztdAcMTh9wBNBM6Yz-AlE$)Ec2ChytJ?caZ7ZJD2OD<)b0jOUEov^4dZK8hnE)G?Lh z4qEtd!#|ksl{84K-SVFOTlF22B3ScxFThz;z^M%maLAgc4!(|jZ;-v*?q9fj@3Fl6 zZGbgNVONNcf0%y-t6x*E3ub8`!yilvBf;y8l3x(&j?!_7~NsO9eC_&TUuHS zqM|_LAwG0>)p~{)`fx~><={O7nFi5zLIRn4@H^B{shCaMYt=r>e#gT9GJmNRQWcJYuvLigJ$MN`EtxVJ8H z@4aA`5~o_#XpPaVPwImHHJkSkbHK_h$DB|e&&s{-g!yp#6^qQ`bHg9yc)`!Y4EH4B z!z-iM3w3ym7sVWUCl+ZJu0B;uyhV$JysH5&kHQ?BvKLGO)bB&XlqP6x;<_7=vd~Z+y3^3FV9Nq z61UV{;9mTSdUE%NYF|bX_@7tPYh^4LnDetC$rk!&Z%uL55qJBGlOJeUX%+yXT!amX z?=U!Nit0vq`mC(2kvw9&uWeE8ODiibL;Af7tE-ukY{n+83=9kq&JJUjV4kN%f$wXH z0&YIOXc(RaVxy3|KIPO9e=a2{c@0J+HZ(OgO)~?%+)8%q!Gk!F(_c*f^ZPytxyl*E z)vvSk*bM>A9kaWk{o zUBDGaDBk~!|D^F7JCyqvpz4M$gM6k2=YlA9Vwq$|i$$jMlUtAE9U>=2qiVW7G;ulPR9T(}`rj+3XHBlF@z-+n0Q_KyaV z;4YZn_u?h@H#e_5a_%L(%7SBMJ)qlqm9<;(ZlKj`_KOSH-5bL$@Cr&~32Ot-Fa365 z^W?0226Zd^=%wnH+EiYxCrK<)${AT{WQPj@-7D#0GDmj}@i@WO`?=nGldT7*mFv7-s# z-&al$BcpE!+_^(UG-jb|?33H0Ig>7@soBX`eIf*v0!WSnPVtms`f>vt2dZ2w!T(Um zK*Lh}QUov79aK0&O+UTPI3Y0j;1l1v;#-nw4Kxw?MMKcqI)4QgKZun=2&WL$*c=ZKV<=qYjH>JibLx*UR^~-hT zEIBo~k3LZ;V@FxJ{b3tg_iEo-;efM3-dE(jz>`2Jn&Q$mJNY_$ts83-EINHc-<`Piic^k@bz;M%G`XYll``wL-l`xWC1LwngT; znA6tMtfZ2dKB22*X zf!_Vl<+3kl-)$M>Elz~w$!y8rmd)pVgs28Ghf38x4i{Dp zeJ50(Q1=zt-J@^q=vecX!avtzuLL8jN*>u2rtI{^>ZavXHY%j>%i!Poo{*77lawwg zW&GsQJ-<9xu$_Fim$63v+JF8p?r$Wx@%(S9kC3P8zsS77WxGNO^JlVA{c(1>E9hc} zg>KnUWBi)9bor#b4O%hGcMsput$Io!B+DOSM5Az&=p!ra_& zxZ7TJNzp7|q#z+$R=xJZ2Mql?dFMWn6MXp6sw%c-w{ar-MLwupUO(gGf`fGDyRzbC zm+Flw%kj~uvO8o3lEGud&rR70V^?^CA_+I_wE17e>&OroRV;tn8wxmWZnwL7 zdsVnUZ<9*>xkDk{$^CPPp_Cw#kl*= zf~3#BQUqUf8@)?c9!amd)LG8(W>PF(@Ba0%*ia0Gy2&N>^ohJt-K#%WLJINyYyU5= zVX4t=uCiP6@;uMQtNSDqn}#i0O`3E3@EZ94c@3%mz6PP_y5aMleHT2l9GW?7l(3%4 z-rEePy82_U=sapQj3K8fH{4g4IDh{hNeN-lv4mfifwtM$jcEI{80~eFz&E4AGgUsF z2J0W%bXG=Yt%tQ)9sE_JV^_m0TG)RXB{Jp>(`&pQ?znaQ2fb*)Tqxc|#_CX-+e<|x zSjzS88}~wi+K-hz_YZA=RM+tkv+UqL!@xF`ac_Tb(=4!eCyuoEmEZEoY`-`M&TU$sF6`yzPX}1G<9qT&ovuAqNqRsJQtd~AweA6a(tv@0K>Ithn9k&eWPjITy@J8ki@DY|w&6&ct-6WO^C%uQ6RXvpg)b~t z6p_-aLLz5E?V39_4Y_?KdM;Ok7sf8h-gvz}f}>Mxt2Z{2^jV_iJW4*K>Oy%E!KY?N z`3)TMt5JJ%aX)oUo`nmX8&I#t!1YnW zaf&T$`ds(m6uX6+oXf_M;E|r(W~B@In(I@u2>}ipN�ZqDa#}q&xz+w47BQACa9L7H)4s;j)kqkatpv7-CF1PV6Z zdpDH#Ze$MjoDB3_l52BK`nx(VT36%ymUe2+dbxgHP^`P@{mQ*8R|=YQV+V0 zN8fMsE1!}lYdYY~XP=T=8;)P7arNx0a&Y%v*>Jo>PWzxXvrn+D)?DVN!Fqj&Q!(iy zj{6;j$FJ*7-D{VnHuTn|WVE+O)kv-~)RXC-M}41WWzs)$el^SZc>2RqbF&so_V!rL z#t)qZT7nmO+d8*%20u*SiP~H=9 z4pdG5h(EFpx3=Adw!EdDw?}{4sB*%4d;H$!l^OmpW3Tp6&~ffrizR%+H?+`QGtWC2 ze$vaVHbzGgiyn3gre(`+`JsK2{+xVW9SGI>5w`ILV=B<9nO?=CRPf*;eul*V*VdVb zL*2D;d@8bU*&=K8Sj!e!$8Lm7$TFc2Wl4$bj1gfo6SjB>q%OH#u1&J-( z^95-G-LJsNk`GeK05lX)(Lij@CK_EPC*fcI=nmsvru1+=$!hFMoU*N8+nO>qlEBM` zBpruvuZlii0sIjpUVlUV@{1E)v!GNp$Po!` zBjmtO>-nCM$v)!uH&ON^qL0qzExgLS{S2AvqMfJXvEjMQB7dz%iU#!7h4;ghpSd4O zE#tD$N^!yeQ+NVqExS8-BIJo<)y!@o3>Xk#G-t@3jD>Ad- z@#Ap?;4g~aTe#i_+Xkh3^vwCftVkP7`HL7HjEsh{0_p9ZkH#nw6NfZ_4jJo<-=|V9 zku>vSAlY`OO8F#crC002+gr*-1733Z8fGY?T=eTge7^36$vdo}sd2}MZNMnTHnWjP zax0NEu<3ONwG?4zH|q69&i&unQgVTxDsc$9`>v8VD8bHTS2WvBlA+_^9(Egny$hy+ z{^IzVCZN6^FmcbOca{y^9+b2kW{~pkZ?1+*!B$%N1wD0{Z|Ssh1wVe?!+ zEObXft}OYTxxz$6hsUmGlthiAJRb*l&QSI3;`L*u8ZqZn0$0C>tCzK1SOjVNc`8LZ zGmY>?PkqIaE|Ue_B{^MBrff3OfLKmz27K#)n5MGk&RL);F?rqaS9Zi+{3I(V71qFS z`Z*s2vh$(?Lh1GFkc_2hKbdvDMcaDr`DXQOU_Ea`h*uWH(dMST882czp%)lL~O;rn7N^GXsJoj6nW`ZqQxK? z$CFqY`w9$KMQ;WQZb6Av$~j-V(~-wu+*iE1IQ z#A|Ub!gT^y21_qS-KA96>^Ix|`U)_lx(u_w++w-f62$si9ySwVsKIWzv)NGZ2UP!K zek%|+9!w84Q8HPj3H;Jr4#kfr^i<%>;7rvD7S7lv*?I>{-P4|p>vDME&5%C)WS&~UFSX(@rV1oT zPw{?`{bc>N{PtE+5RlY-V9%nlZ>lL)Y;JwM?Wj0r|FEQ7E_3UC>5=4sz)Un}2vC@N zo-ya6GnfVfrcvLmn&(6P0}qDXV(+tF7peTXJ@a`yb_t&Vza}_Xs*4GmD28}xWZTu! zKKZ3c{@;qUg8$%M-r-2C-nHpUtz*yaje04`#Lk!T0y`VR{4v@mm9XNyljzExqsa{t zd2!MnIvGFKbNLSHTOp0*`b-4FNHX)d7(FY!3>`@10m0&IE~oc51R`=~fN9x76}1A! zp4S9B0P2*95sc`}a>|w1K~07=@w3{=>YIn-Ff0J7=Y3&L8y?=B%RbtVRp~TrxDJll z%zd@Q7%!kXL9C(QytbreV-ZC7M;emyrJWqkJ49CQrfC#Yq3 z`gpS-T>-dIDs+H^WvU-Bi1i;lwfTOo!P+?J4Ns!IV7Ga%YW`G;y@S)7ys$tVA<#lK zQFCAIt!WdFp%x`_O|aAl#`e^ltrZRKM}YfN_^oWO;KdKE-jJoK@)e-UcLgCcSQ^cU z1IVy4n?tfLp#!3~8RvVT5KR9OE7hhE*>Ka^DRP2H>C{bW3>Fr!=Dbv3QnvfviP&Sv zQJ^fM6mYfakSJ)m9!!hbZGPUi2}UlhomaG6Z|R16Q8{9CD++0vJx;deNAW~_h<^RN zGCo-uyXl=+&YE-&`-T##v|u47>Nji;Ab7ETrc|YAQOo=56bILI8OIPq8vRIAFS@j# z+(X>s$V(ddc?%!oPY+A<`m=3@MrM#e>L0K9MJM@V%%i=B#xh zhf>I$C|tE5kdT$7zAW5d!7h6i8HCzu`p%md5^%KZq+(!sXhV*ET+32)g?Zl@GTTx` zdmFM%e- zpB+64SVt;$R@4E<_x)E8u9$r~BdW2I+Z1JcU8c&vel(!rI+wj%fI|c%&%iSDApBv( zoPNNnYWv0eI=max25gvVX1A(OUq8#vF+tUX>(hbFp1SX(+{fMI{;3JF{4}&aNFS@U zreeSmQ>_)1ki@3PWnY$74{Wg@@O{^=hWpPKqI3YEz4CTXSY&{z*P;B7&{Pmyzb}3r z0AAFhI4@?-r$%pK0*$<$WbcFyr5OW%R5jFV-Zkay++u@m);xz(t0XUKCyy)!rkQ@XU)_yIJuDyf!*bSaoaJY(9VVRtdRkn>TU7eTVZ2(l9W4R~lBiGs_fb%Apvj!8 zGCPNP{J;0p5!X`jvm7s3FdtsT;tuas$9!c5rf*9HqNv~=^xdp>^Fp-?SFko3lZh4s_IY z`m>G``=?-Ri>`{RP8tU+A^hD89ZD|E{2>?CZH`jy-h5O#(~6JPH81?ajYt;ITC;MF zBU!gPSFPxwA78!7U{#|X= zGOYSwX@p+cDDZG($Zg^8ha*&t{L|j){%irvrT)9+7PJ4Io&2Y2H1Nrnd-z1)?5xgz g6(pusCLY>5K-jUCo|QD-E&u_|$N;MUPS-KwUvs9J{r~^~ literal 153581 zcmd422~bm6*EWi+EibJ?x4udX0E+h6%!NB6%*U;^{<`aF99bswt*izZ&;fDDJF#esKW1YCE6Vaps3d7p((*5XObI zu614-Bjx=LHoW;s4JR25wQqmEse9;j`r{9=jKLwPlGVS(Qi?IK}lIAtA% zRk=^{DkI={4RH*?I9q_IUAx>qT&|Q@2`@Ldf@6NcdOcNVcI@A%aZO-JG zG&l~Hq&$G%4epq*vi{c|F|k9zYAF_FmSLR-O`{^qETLy5e<9z8lmxCEA7~iSbtV31 zneU%sihucE33VPC4!TYc{3{pIF1TLH96tH|lbHR{|K35D3f5P%g+>l8f#>Gu=WQJv z(u4w*kTTPdq+%1rZ|c-)F>2wBvo_}4rrP2=(^|G>Lb9WUe0E`Zxh5fEy+cAJ^J(Bz zTR!;J6(3A|8#tvMvM>}(?^8mdP>waXzPJti07MV?V;?kGf2TCJ2=8VgpVcDZGvGq5 zCW$~V$mpv@3@Q@!S~%UAD6%6ORdF=o)R8R1P(L<@F<3zw_R7xsao2(AbT1t7Xrd8T z@t}T?hkW?-vy184N~^QoopWDaRr`(O3B}NYPy9u`#DLyOc?d*Ogjt*N*TztTuHl@S zH00OI=C%4>lOG;9*4=iLG~HTiTKcf-;HiKKH!7{&RIu!p)e^<$MshmgQO28;bQ27B z8kx;=Ay>d#2G^k_I8+)8O(gEVDX-ep5?p>w%WZNAR+*=cXYcxNF+zE ztdw7lp7;3lX#en=>t+IykYmdET4<6I+Ps>jFWg!^ftvq1SV8R%1k%TBw-OopUW4Gd zr>2}FQ{qT1VwLG1&0FU~CWGtLY&^EU-Y8h5ZCBVljf)&+TuF$$$x_RjV zp%@L8m_AhLu56w8+_C!R4B6SgTgZhA)qz@geM3XfP5J$%-AZXLSXLy>Fnnvd-3|`V zUhOf|DsiZ=#v03u1MyGw&VwDAPd*1eD-xOYRGfN6lQx>?W#Q`T3ck5o?vj4JH8ww# zMM>93-jtD%Suu}ZGv^R(qOcSKnl|K~*u6`u=}qe$0jPHb3 zPv-5BnxbywwkHRZy!#83V9*C?cw}YwwR=1FL=e#74k$mvwz|56`rE@*Ym4KCuoW=m z%vU>`ar(8;ag+m>&1xB)QrLVa9(Q47V>UxRpnQB+bg zdL7Q95UOu|d5I~;Fv3R3+|8*(8nl26yLabUn1lszuu+4-6j@e){!lsXBRX# zn?N%T>bKIHu@Ow$Y=m`BC7R+Y-P>=1w{kLCI2pk#3SaCB-pevgv%4$(1hf_95^8H| z7M4#zGHXD7EJm-k>^g%?dX-?HChZ!0Sst_Yr7J^Et6eU1j6qxUdBH+d5Ol4qtipvn zD)nZmlkAC`7s+MLX%!eI!gs?aLsvs@Jh)%}ze=cAE3%;j8cxaY?}@9Z_9Lj_v@FgR z&6GMj23(3VO!xNC)1EBDmgea9cYk!O^|4~8oC~*1iM=1 zw9eHrbY_RI&kw+`-5Gj?xw*`2XJ;0nx_rjB-MKNu7ms43DmF}GEwz2VzTO(A@?B?p zvNDh)W4-=NS$Py=?lfrje@vwgN9NDrcA zh0gj5H~d%oEVX7nNyEEx&fE+7_=~y6^yg>k1}LBAm6VD+;8UT21KSv9){NO>Nzq&F(OvyErdcWK4mZEN zJV*cX%KUu7p>!03JW~Sa`$P#=vsGZJ#~iVft#MwxIcL0Y-TEA7vX#lw~YWm32n6e0!w6F>e6$5W^g>57AMO17USr2#;A$>rk&4o2eOI zFr8{owCR&M51HVCI^zEau@ML&_P-Ty_ta{FC;md$Q=`xj7)S>pEOw9VRfabBbBtLG z6#7rixrEQ8)M`#@&{sOODo_&Ot9OTU%596T__zY_@-82V6ew223)BhX3vhsMEOAu^N@qc+)&hd;Ff7i9$IP3H2I@JRe$wE=xlCU^i@U>Wp9ts>?5Z%=+z7Np>Q|xGn*Zn zK)RyiAkBx6{;LWqxu+2PSUI708%y&c>vrjdA?u@X!La~e)=IY$*mRP`Y-U; z)4u7@TIX2A;+z=JgvESpRQ?|}td3|NH+0J{l8;%C38}lI%=>za$ReZ|w-?g+C8Rps z>gHJ1G0buAxy;=LszoPNQ0v6Y(u(n}2-nFw)f2?&8KH%4=>_Zbr)vktBW|}onoi+i z8xj@o*;t>C{*C?>$zoLoqO_-Q9{ehgP5M9yaJyo^9hcJsi2Ua{9ixMhw!`vK5kU){ z#K5T}O$?T%GEi5y-FHcq_zNwS>7Y_?Oy<1tm>!0?*H8O8EI5m0DH_KCXb+>lqFyV5 zW@;!(NF;w!rzMl3+G`dWCkz~Q3A*cF`yM%9Ddvh5#&CRgeQi*P_T0z3^48`=>R57V zgbv*>f<%K>Y(Zqg0hg|EZTota=sGV^RIVqF!sOkwFH%InEfbng71b!N%KM@thu1tN zmi-sx)o&_mbo&-^A!PLWfGASv)JJ(&`N1R{7YEi!e+_ zVba%Hc{tmtYO`VQUwUO4?-w7k>*V2$ryPxx=tHkc&5WnzU@h)R1t{W6FD$*qqGz*2 zn~B0UEv;51tVj$lHpK4fOd6I_-i5o+#wU5ucM&^VtYZ_@b5}}|l1>P!#tdP&&9o}a z*1!y}xB-@U*t27y^}I4t!7AaDRuQ$2(-hwalZ#FI=4k5e5RQ^^|(-3Ys*}F>xsu)Blf89_jGR3-kC!sCxb0y8dVUpDwqUKgpriK(m~7_eO(&6%ssyOHA-zo(NVh$ zRW>{6rI>LwEk|#r=m*Io@s~G-^nMpl764^ZINHYQPja4PNN~e74yQG zdjpG~P9`a05-hHEson7r*4G;Q_rLI%PsDzaRxYw}6WD9tc1dqDgprS3yh+J;(vYX~ zn%Spvkey#ehzggePb8Gye-D$uWspHF&COnL{acp4+j57`eTJwBf z*CgwtWssG&*X{a}6vQ0)h;aQ;4YNlJARUJ}N-%#5x8a*CnNpwRL4>mx_lY8$y{EVd`#IgI|;&{~|};UrNk z+oV=&f6BEFQ(0w&kwc&J%-kiC2emA9D{Symn(e90y>({#s&d5jJ)S?YX07t;HcUuk z<`(9hy8cj7)NlH?|8!K~t|K;_8bk_GMU7)7px!U9Gd5-7&l5blS+At3fT-69`_nRXl9QHnXAwiGJZSH_cRO!J!#PfTIFAS+id zYW2IRcrvH0jgtm({)C&%m*nFHD6Rfry)tSLD|I@*5qmtXF6)t@>U$PGU+H%W{y;Dq z2#D{-B>K6&3ipbTRNscCQDF7kJgEgbL~I%s*BWXhTsqOg=gN)ZD~w6~eOGX~`KsZl zAc<62gS1PS_eq{z-)-?7<-cSPF?`w`X%)|&J{mjn+qODyls41LbNpN0MV)cvt-f44 zP`5eT`=d>&Y6DNs&LFsP-3E#qQOd(_v=4?~?Hej{fjc-9;BnzL5-%OPEY!L^4dy*8 z#aAXgdbWEm%$%@jN3o8EmX>*2N%)vI)iVXg18>63R=!0mA0=5w>>ggP_IGhDV9KNI z4{H$Z&-)boJ&@M^lu1){q3wwNdSib&F5!Ltxi~me#P&uI}RpQMw2%~xDqo)jiVPy zj^O4~zlvh(gqV|2ZSd_~IUxGSnAw|^?Sj7hs*(My3*A)u<9Khw#S92`1-#x1Wey8o zd$N*J3#vAPsO~CnN+K*oir8(H&{9Aa!Hz?}{;z9vq6C;wHz7q_O~R&j&!7hd z#G+^?vI)h9;!a$kDuKX+m%7;I@?y=TDuSIYD4AaBPkQF%;MK+Sb;=4}_|lA&wt?Lg zC_5Urpy2faSp6B#%+!KBY9R5AU6M6n!-fE45)ZX*ggnJU(w%ny;n(U46~<{zE2DL^V7i@&p~BU1v_jNP zi4gNF_;_HF$7<|!5lh*Mv9XB9bMq?E3^rF|)p}r{HU#1CR6S(~h3ivaMX)x^EFluE zJ+)Y6Jhix2l5HH(`5wFh)xzhg*xJV%OfKHl$iL9HVBM`cfZ7Jd>#%B3 zDc1k<>s4&+uA~Pf#S{zenK+=`)L{DfMw5l5Htl^C4oPz(7NB6O1s=T;#D~>bt|al1 z;|zC?dWVjAvzGq1Opj$GahDKxNLLMbo|Qh=vMHP}(U4pdc{5$6kvBnT6m|*+bYr46 zg&Mis(eewnu$!jOkA)wm2VJWQv~r|H@MvS{C`;%1#yvwD`3vD);fblCqYVz>rrRmF zL+gUPapHmHr-dDssv#rEd!YT0QjKk; zI^$>$veU#&RfREs%=T5eZLYzU7->rF@T_2k8X6laO&^lE*bWw?>AHWTHeJ8;wqBVf zjvpm)xL$|vpk(A`Y^pygikS%MvK&Lm17@_JL{3sun3sfyxP11Z&~p-H3N5PM zek1%w?_rn4X8=Sd9qmCF*A*Tw6r2hdBJJlVRFvDJ-fo$_ zQ*W`7=h1?w8%-pxWMjqDoRo4_gzqYP3sn`4sq*&K7XEEJ`izAzcB4KIW;&duX%dpA zG^J02jrh)4RPYXKotI78S7BqYevInSZCSuCW$J@iNdnIOU(DVi{LQtOUd|-h2%o-O z_hFncjN`)b=|f*>u<474bS91Cy56dIk37vQ-;oPz7?c>S6ABEg{a`Ee(^Z7pqy|Jw zAHT7-jcJT_UYTxD7V_)!?ZSKiCVC5x(#b6tcTJoVzAnk*-DrnbMQf)Q#;j_oh>S-o z3`8_FR~j+MIT1FjYGV?)w`jc~HtR*^R#D$&%tBme^I_I)LJ0k_rzS1ADxkf!xgVzUY?O->)oC@cDH@}}`}9I!JF~9T z!O@!DPR<2+^4#)qYBX`zOm(>XD9HkuZjC3fspIP*B6D0S4jv$ zdz*dPVGO#>#VCJ$EMdHp_PH9%-m=nOSy=I_Gj(%-pWRRlXL2;$7bh``%V02pja}ij4@|zjRVoe;&erL*}k8#H2rqjQ--b>zHI88h+@L= zK{TUl32ftni@c^2W>m+!eW|lmv&(JvGu&~IC(!4{n{s#LjFvOU5FaVy(P-J!dOy=m zDc{60c-1PxfUTDG0a#75R(3k@$U0l&{m)Y@80>=evNK4UhMl{AV^1(&H+mQ~)Thzx zmw^vqo3J;A=R=k&y0*8aiZyw=RxL>pV~=86ZK#|EAnChYQNj7jz(i7#&aNa!c3Lm8 z1bk5O*F;EUZ~mPptRz;^4HaGuKGY_x0z8#Pt9Nan@e&$N(hUnreYfV~m5wnZuW3)q z5nr#e7X_oEAy(6&QMr7(i&9314;pDWE_rZF_~k*=1mg{(*?y{}cKz)N$ERz<tdP8dRzR4uh# z2^m9u{ShXd8d*eh29?CDK@N1gAy{S5ueR3xZLXd6(x!1*<@NBYIl9NxqiN<W0+8 zO8B%w%IOGyR(7&?v0fR7xG-CX4d1K{bcwHFLgmzbb129_yCdw8c3+MRuxd){88NhDx>n@%!VSSly7sOgA7{Q8H&P6B?<82@=Im7ug`?MMyp@FjjL%5UAOrFHOzWln0L8zRdi zYMU|^?*Z@R%j*eQH(_6C-(dMMkj#th_b}3=XUCF>Ig4uqW;M}Eo{W|Cdz&jN>+?w4 zwX8cb^GObVf4Zg8vSrWx2e+QzGo94tZu;}VFUPbA@5 zvHPo&0LF7`bv7GRr1z>i>QrP7R+=*e`cle|apSY+Q?%{Z7sM@$Q)WHh@AJgW=}V=a zuH{Vte=-s(^xK}azZyFm?^)`uX)S|SfUTm}XlwqMPJ72T|+h*BCWtO7LYD+(n zlx43fV-hv{?>abj;Co?JYoAt{W3!tX#{u+zU#Qq^r8MSNowMT|Khbh$)}^+CVK@4E z8=4Y9aQQ?^(WF%>Sk23h3QT}flEzI(Ekjcx>Yb|J++P_@tYorYA*gwz%Z;bp&J8y4 zV)@ZfM)Oz2fV~>}MGU}NVJCPz!*<&Hw8ht`gS>J4AlBQI$}u3ha+STd2JTeQ%We&f z=YT=v;^jJe> z--{l#$`C%2lu&U=>uOR77kEL*t=(BDBQ+=|56I!q!!O}`^~yAJg*iz+u22c>65{)b zS}!6js80pq`pKDe-8@+Vd=pbPk8lM)Mb~%Z7k&J1JU)H#z0%ZFYwv{h)KURu5vVNF z?d)uc)D8{e7~S^ZK&O5~&QQfF=0(vJtiz(EV2SC`KjP%jPcCjCE{J1Q{H<}EC|{pj zPH9FFQ+FB$xids}VP^2cvnNKDqB`P&p{N#g0)+xz%*XXpf|`a>n0$y+(25tfmGoL* ze82`q))?mN1HhZhDi#px2b)yGSKuI(RK90DCS*hPbV*-GQ8{(7r->FG&Acq z<>?d7CHfyY-mR+nfuP73`nPbwh6nH|?}j|OlwcTlM&$z=m5i$@j8tXw=s)Pk z71M=(YO^Y*KeLtkqf>(ES(yRjxa`V?q8$}-jY=ibidpCsT1kn`)gIV^t=vq#RZ5;& z`^r|Mt@kiW&akAB_Qqp|70AaNFpP`YnAcu~7iZbWa+uhf7r3Y=s4_6n2`*H*LY0Xi-sgv|j?C)S557 z`H>rjnlM)hLv;;efj!JjnC0?jJa`1Ci561{y|K^Xsh<oJ?+a}=m^G<-jF+w<6B-#wdG3ki{t%9Q-IKw5_{xG*Qhjuu&b0h8 zWu@8>AQ7B1_1X^$M|-T?IKFf@=)iZ#88Z35>gVgavTNdI9*3HqZ%v@8caLU&#SbH| z0pL39*7!DfXAA#mW5av5uH~9QR6{7zjuA|C<$>BwZS<3kuV2dXp-BG5#!1RhqO#36 z_M)J0db1>{*}R^WniY{s4YWiucyq^(c{|lhqo9p;TU3}?$j~SXo{7)vZ|v>MT>I6j z4isb_7bg2H3~pbxs0z8{() z@40S>Woq+tuv3n0nhn=`qa=btWi0#;R_8bDc;`L5oZK->W`45ka3aFe$>>=E@vDN$ zQIe*67y9HulpBK(GFMEA$8$aA-hv`!+2OT5I&qRUTrgHZCY6o9Z>+912yqCt{jh|x z#De|g&dxGzCx_a4Q&z*O6@F)&N#tBg$2T?G?{K+bUETpS43 zlfZL=-xf@znog-AQ%$Igt2Art)TT=xzTjFd^q5t2r6){`heRMyo0iaFW#p^JXTzlZ z6^eVZ>NABr54xqN@mx8kv!(|^Ve24g$PH%pME&NduR`zhvXu6Bb!3Hg->qsPJ@eF< z&nvw==6f0-evh7e`KzH{!q z;u^0vQwQ=!4lU-4iW0%Rmgj(zzt&4a_&39NhF|L01`LLzY$3b3E3 zRDBbv=3w)(&Y0px8i}tDl{mzY_6GvPic3ZdZw$6a#9yGSw~Mzw2j7UrsX>t;;DWwT zfqKXtLV1UZ|2w1JKlG>t0J=e_hYFc%GPtIxT`){s&~1LzbP82@Ro-f+eD)IqQ@Y75 zDr=xdlhazCWY=;nYh={D`|k7%T&2Rwa_18(8ABB-S*#|eWA$XPK|n1eeNCD*#D=jd z;Z1-o)wu!U;aa0pB8r}Lh<~RFWM9;4;IKgy)FRy7Z`X!dRQVBcB!N~94HQA8^PCY8S1ZHWm2+zTF2Kh5>JcTenlsgvi2Z(c*}Dyy@rl*nQam~m zu@?ClTIdk0el;fv>v@6_rU41WyC%nTS)*Ln!}TiMQJ+f8xA)eKDe6OM=)f6@fawX+004mxP~~OxGURQx6GQX zVU-~Gs}DIu88lv50HJ7_0|Tc6u)!!pTy-^`r{HXmRJip!eZ*9sJ_Vu^bo?OAx@e7i z3fyTH$JAX(mDMq+MoJ< zK0Lq8m+AN997!1=t+c*}*r7jzGmcGm@3tbA@+>vJ$4e^8m5-xZvhNtS_$MAFZmD2F z00f1VbU{g;B`c3KH~mR?QPS{;{^H7tp%eE8Co5|!J=6-XlwPkFJVfr#0=IZKLAGW^bF_W6Z0re^~8!KFc z4!!rdz9<@E)7f9qxXzu&na7@9Q=7Uax z<1p=&uIYg|Y<@q8MQMwZN2%0^CilcTwvYEnRXI|Le!ON!b9Y7(x6PP}aBf74kA|2* ziTRe*unE62zZGxn-V_9v5Y)?{?ThqbYTd-9c1w1M?T3x)g{gmqPdlQcv>KaOAIKx( zS(glo8vP{F6Hgh2Z!$dhuz-uMUnip>cOJJ>lvO&ToM&xDLL{boFjxnbv^TY&R%Odt z;l|3fIMfAm%3WOyJg9tC~JLm%S5+av*qz@ z!AcWM;;~-2kFi%ME8n%&Ur%_I{oZqaV_2Bg#4p}U(F+;nSF^fi_YfcLSBLmMO#UYz z{<|nqNqEB|UnzX6VESWXT2aNICWT!o)0k>KWYMX6Jv6@*-n5oqCAnG-kgKD6m{&xi znw^IYZVB!66;g=H-_Y6RWH_MSZD<`&C}CIW)%qi*^@&M(Dwsso zJ8R9)c^9;&6=J6WSAq@S z)Ci=GUX87Dt*aQ-cC%bfeG`(gEdE4;VP?Y*bgXy_umI^*4?-9`CY$QdaruJx3$!(e zb0GQesS0%njcWsOEL|Qy_%LXEl88|E-6l%u>!W*rWy`siGlzUTod(y5y@9~s zoXqC(`#bUE(UAf4@Hj?&^dg5qpqM9@&pWbJ3i%vdbi3h++b%0KX(4qif>9=-LB2{f zG05Khs1n3qAM~1dcZa9@J5a=>{c;ejkQFg#-UyABzU6f}aw8i_*@g|lJ-Q*PlT+Z7 z*0aC!WEa?KJaC@46gaTpF;@hgp<<_2pA-iKjJ-a_>Q;HirnKSbDM$1#i*v~yUoy6YI6uw~zdbrb> z{D#ukJvLNpfYaL*M}_hFk5Ha+ZZk`~)k5^$|Yd1v!=e zx^YeQeL(#-!)S5DffTXu?w5Q23Z>iqz=~=I;Y5|aNNx$%XZbt(=4y6dC9j7ynjadj*XflU?K5Zc#-*i)6$%eDkjg=%ikW!(Dm)G(i=~X-i(X>d{4^cIbhIEKX*@nVK980IOO_^ ziy@}cMkMfaOE=g53uQuo7w*`dU}1dW-`Hlth~9ii+l5UL$q#*r77F@dD) zdOk7)Fo_!gJ@Z81w~u3h_Igm;<3f2ecRq5XI=lPxv!m2&kZqrChF&ZyG2AS}!3%aoAKkXr6FmP_6|l!hfZUe>h&+cK;22ahU@gyn zKAPCYp=DgY)MdPDBf~#xU%0`gmh#Iexx)H=v5cx4ub3ELpxY7+9?7f#|GC zGO%E3_OB{$RNs(sQ3-m=-Pcr(jf2>Z_2VJVe$AZOt`|D$g_%JX$`_wMEvaZWaBU13 z2Otod^&BMJL=5007;IZ>{?#D(mS9CosD0vQ*Jo&YmtUQqNfd4-p78kmG;;PtHqp+; z*goR}cy!`t5ffuVBOg#UA)1h13x5O9F;${@_0bu`Bo*3pl1+~xWjSFiY%1QdIWoMg z6P!rI=!pmzO9ho7fj7<^F7^hTKF&Akmgf*@_iq*4XVt4A@DS63Kl7GeT|%Q`22TWZn7)xg_a z8-hHexc%9)vl;$9K=2g6U7hAKDo83O%YU!2sL?HBP|-?KNmSO!ssHQ!-OP{?Z~d*M zRwRqSE&!b1TFt-fAF5%B&r{ z`Qg6AK^>nfWu0Kh#k>%;35e%IL|9ITLo*f_^GsEzW(i9FjdMja*C%T2mBNfOm3vjh zM(xp88FWEfwIwQKgU$OD57kLe<$P~r@B)Nl&S!HIEW{0k7Wo<@C};ddMg|fv`n@1+ z0LD6QalDcCNWJ_s#J)Zhy|w(0HvT2bHZDPw(jWncMyt-|-)>%x_y3ANG~~7Gz_HI| z^^_N2CO2oh(gCa6PW$?Y`!1*fdx%Q*eI|SnVert&n_bVJ0TpNz;v#$mQ>KEWat6V# zQLv?0z!{#dZ{hp;5!T6Lf$ehMw{Lfuo2)!@L3ZotPdz!|<0=nkb0tf}qx}7tW0fK+ zirv@`Xx>|ZOK(~4H}2!Q_saOnOy>!}l8;=?pmtT0Ofset3^fPc(7qgZc8AwVv%@Z($!#5}6P6SN6b4uI68;9ug(89!-Ze0f|T754S^~XNti=P3F zHv^ByJEcKY2A=46_3IVT2mooE%3lmkHwq6*(4Tz{1`+>SY+tgHl)a@`Pl-T80cJC8 z?p0zBWbKh#QwpS*ZQH+3X+cL+$=dr(^u@{uOIVbV>&IR37X5KEClK59jCI$eT@N*ty7<&B!z+^>Z}pgCheWUpc0S2*Wp_lp$JTr!iFWZj_!cI?TM zC%@tq!}`9Rggq9uoQQXIq^Kj?4tgoV zAbuxcLYK7df1lwDRxFA)O1%kLJ>*b>nIk$5ZsDFlccht*`)o>4;b4%abE5sb{RSXn zH-J`=)epP0rYGYRdX^>u_iyhZ+XI>|&sotz9;YX?IVlYu#aUmRO9VR-;!TUJenR6< z(FuHLiiOgkYpAPW)l_%_aIsHYpPIZ6Y$UGcKiUtn^6jEPf6DCEDyagczm!^e*cfq$V;>CpWGtBh2U4(mavItFhx^2)}9 zK>plPi*Rz!9>A&w?l?wIRkTM?Q0EHNW&}9+qGv!Hb)T`Yj$kdejHtONnP^ zs`vcYqW_HX+xIcv-q31Vx(jp`#cz+^iUX}(zW_mcB|+;(A!t0H7Zu|AKvYV>VqezO zoWxAYQhVRs*`6f{MQO2#->`r~BPLe<8O20}U>kg{=^%6{|V%eGJXfW(@BndgC_e|FD5%8uP2~KfEpA zlDBsei1$C1In`PihAdnP3aV<}sI8zQ;Jg<%+};0?q}TeN=^O+7KwnB7t4{_@oF)LI z3w%x*7-sJD#^QJh@aEPeqtz!J9UV0RlV>qA>hLe1EhP8Nn?L@M#^szML=F}^$pFx^ zZ*zHSpwK4!e5bm)I%>6Bj{z{^D-apa|27~=$7jMu0Gw>Rp6%DsB;pF-F`21U5zWnp&3nG1;AQ`;^4LKs(YJaEJ_gVfNLisAgb!1pt!GcftkQ$ZlwfPph2U3&Fy7O2s85Iv$^Y-Y+c; zcbN@oRDuC#978U3oVs#L4F8(Tjqn|*fq^JX2Ee=+U>C&lw@+MheRDp5(DmWb@`>h} zX$-YLMKteQ@uPGwsF+x=krrVMYhhs_qft^(;ef#qfN1&}@Maey(oer712Y0DE(9X0 znVP~o)3gSGQcwWu`Eb|h(CPtWxI5y2Le)Z=o}tm;Gp`{F5WCY0Rg{3#093sybFME2 zy&)43^`m7xRtubD!Ye&;^ysL*f!O$i_Ng!83XwUGbphTzYyW`*1)vkh+1uOu1&Ef_ zRM5aw2HJLBK7alzfis)&Lf6;H@H}J|V*gmjv&_sx@d~CUuW>z4C*vCE^*nd|`gP{d z2V)jX-@d&Dxc>tHHzF`AL>17U)+8UfbjEnC*X+^Xe|y(3yY;B0Yzo>2`|n?V$pv`) zGU#bb+jm{0`udLnW6+Ca!e`UHz%o)6B3NU+psTOHMaXMOirLw#32;CKSTG-2Pu57C zZw5fJCE0?tLYdjRB@<{(s7WF3X5 zU@?pLCPC+cn3xOn8u%eU=c;MswQJ9txdRnyT3R-V#v8v%+!B-P0~@Af)W3x=yrV`D zn)i4pb>PXt6Txe9UqYS$^d}~Um;Ua*6k*}v;Sm7LgZYOB;%NHFS(gRZQ(;Sg#U0%d zlM38d@jz}J0)aqHyxRuAm=$nlw+cT)L*$?ji@d~XtdhTxe4>kH8WxLP1HG1@ozV)~ z&;7aEPM28YjEeNAk#@DUwPk+J&dwz-Umoek89PUVwy@E|2GBrrZqFf`&3PRD&E|2Y zf@#Y>+{zH62H%+I751w~pHuYzVsHgaz#i(Js%P zJqv1B5X>xxO)rOCad0T)a=9^7WaBvAo$lcpjkZO{?sD0$+In*yJdQMgy0A}cBwhxo zeT=mia?#Q{F2;Ip&Ch#chxeLq-vf#Q<6cu@mSj;s_u|SCm}2gojno$}iVL%&oRpN5 zz=paS9^Rm)u5NE{pAWD_NnPDl&{}72WflME@nbDNWOLIMf5DuBAVnyTHn~ADswqK7E{}=-H@D;SYF^lo~B7go_ZZ;TN zcyP_BeGe7ie-k?!s|b#A{&W52@qhc}hb+;W&%G{wlwXx(>-p?tP-_1d@No2!OcIDQ`a1r#+H;evo2r|Dg7_~m13`rh*K;&S152s{3mGn!t#vFNI z4l`4>thL7)x>#hYtUp@zb$+hSL_6XIzo=IE&)xXlSlP2hZT;Xk#8|VF=fJ=PamrI4 zwLGp&(Oe8cffueSXzNYcE*9WMysXO7DEgy){_R`U)Zb7I`CsZSe<7HKAn*Q%3y_(x zH2*bJ+9LmMV%~Ot*vf_Nd-GolY*FcabyJN!7Lq1+WMAW&Jsb&2dF-t-GRIfvm2zGE zN-CsU)c0hBpgJHm8SE1o{M=LS?v!uJ&U+(1Ui9vgt81EzSzE5|TWHthCls309RFyY zyurULbBa5kmXhK5_xg0>0uq&8Gm~c9@+?wK%}u?(dgb4fJ;pI%UMJ41lxdAh3~x{F8ea>;)(`C?`-iY#2$j%y*3ME)bHyL zC4D*jy-JUV$H3iJ2Gkf|HH)H~SV#{A?+e9W{lji`ZW9aMtz^ESqdZ)Hd*WBij|P(; zL+D+gSG~lZnv#_~k0@)ej{d<38zJ>W>LJG)Y}W!oG4p zeIU(guhSxPmAm>Ss)#0LX@pLhw*197U;gl+pBnXPk`|N3BPzcfqL>+QU{jt)Z(3Y8 zF86D|MKCx!#cshLG}wmOsE)9<<#ilkXpB*M7LrUbMVN@C1G7UV(JTD3MFZx>T-f%J zr|nSZOYlK;;K6!gY?={{+QIe!@avNr{Z_1DPc8lR%ak}#-Wd7vfD0OFpqwdV7xzUB| z6?Msjec{P@FO5_eozQUjQD3;{I&bM+zo|_i1n$dUGhMXGX^j9{E`> z(<`Sc;?q!X(WkgF73cT5-hB?GgLWv#sVVQW(qB&GBW6c*+v|3ksFX2ZRb3jXZIc-> zANy<7C+$$>uj7*k+^rh?PxWz~WOqhRJfGx_p-%xfHX3F(`EIyvZ^6?y|bCI3ldJgI%$ z*UViiOSxP4AhV=?Z7Q`t71KygcnQDgZ2Lju zsxG9|@uv_DI30K8IidooP=9_|R%ri1V5RC8G{v+?ggwLLM_EPeLCX@s>?<_WbhHNt zhiLQK-Xx)g`{L8-RLLg4(O7oPy1kO_v0`Cw-klCL!^7)`JSt%Ij)|||Tu|-vKQ%z^ zSg~mClv%5WSGsiyoIsnA+X%-Hv9KXI6OsFN`OtG(qMjgf){b#~kr{vBqW=3s{=+c( zM1=R)S-4FNZhO9L^Jv}bHZfQG>j{c!CwQrgwGOujT6i*a`x>H1O0bW_v@}Tm6udb2ZklDpJsoxTwl*MOgty97Hr5-+2rMQ;zvsrm_ddy#m@T`~0e`cI37T{2AsC-qM1+XrNx8rvp5t-daC ziwy{DvMR|0vp_T&9N0eN#@Fl&3omW2HFTLbRoe`@t4|p_#(rD@4)&g7a>{4O%OEc)&qdksfcWmHr=y(|Sa%~uwmuHw8$a5dONy{W31A z`WL+m?Lt3K2$+l?6cr|dPf>8T+s*5nvOI|7Gw%8GLDVXwc}ry< z#ckfR>SK52<*xR(ynnly1Lxr0dG4QaOsv~%XlA9zS5I0H{=QG{P#dA13V{VZaP*&g zX!4%&q7~m5ojv=v+|&bGL-VpWnXYAA{b3ulq)+5U zd7CAgycoXfLoEHsPR@9CoK-!Kkxpp#EF0H)ETy|haIw>rqj(U|;>yDUU?1qIzYlsz z1%%JvcFe)sSM6ARU|Ul7ifj30aEEk>qJ3rxh#Zu_+FqIcU4h~C2qzmo*Q=4A6QUnd zugH6`hwr&9XG@HSm#WpdKh99w)96-QRu^%tY8A>igU$ajlQ5duqF&Vuv$!+w#ZQPs znx-?(i&i(x_10<(mI{(jQ6mHvsbhN*u?f+)_I%cv>6;9_4aZ)wQ%%XLlfQH>oE&rL zb?JvgMK&%|=jm1Z$lFU4P2W}lH^_5a>9%JUrL9n~=f@Wq#DNhLBNWz1SHaW1GI(N7 zQD~`B6+z>*5mJ@03wDi69^YJNtvBdL zY5!|^N|jPg-mOm)8^(LC|H*2j%>X>Nbs6Czm58-oeB<$9jx@a0QoWeB;GVy; zJ7)R1C044%v~Wz2`pP3=b@5i)P}6z>XAm5 z)HS2Z@$;zWQyYl-s8#R7$dec2$yeaG4qT+BsS251j_JdXP$J@Y8 zu|6FOlgj>DH!8?CjH?_CYKZg2BfC;xGmRCO!XcfL`?sY&U?;0tJKx2BdqPk^noosi znFY!x-mYWJ@yAS?b9*$N?xod^tr~v)CZ0dnHvNg|@Eg!}@9wnrDbs&J2YUvM&e6jJ zmBF%8>XE1Bp4mKXy0RVTF^IlSzYAmm;KL975?GyXhD75 z`{rxA@Apjj9Dy?37|p3Uab1;}Uhlplo6P@%wfBr_@`>I>K~!vj4GUG86s4#XDFGCe zrhp(Iy-N+f2qA!qAR-`L=_o}y(rW-wkq)6JkRTl)AT0qxIrE0!|E_cIT6diw@pyN%C zHzJo5`CU;f?rC?`css zf}HW*j|71(DmcjTv*bIzW4`U%_mqN142%e->RNt64qLeEp&WEmNuEmIxzO`}@{7n*9zYe&|PZ4A`(NSIE!p=|2 zpBkGtyqUVLwkn}7JUQ7y+{?2dtD_6GzIUM)8nlS)S^J?{2QTBxo<NP$bi_0y)IG;Gq~v0pFqG6BQ{wLOR&eJiktnb za^)L^sj3Zx=GX|HyDPeKN)HUj&r0_Nr+U2^B}MLc{mle8yxm=^@sGGckhDy-l;kFL z8^K97V(cdW0nAiJ!de+ItiltL8ngEf=EyUu;5dacV{j(~80X!LzK$Htt~rru zmK3gdzOTdgJ*{@5QBi+g7C5gf*qee^FQ>l7=sph{{u27G4BaQ_CB&V3z?Vc1#k=`; zhZ#2Y<7b?k%;qZ&0-45*>tcz%gn;qr*16M;`%`uuH_d$}9xwEJRz5y>g8n^ zqbpOmuCL(y7bz}bmHww;(E;Aw*|?|0^x@jzu-an41o`r#?F*O4v)1vMpYS9eU-x~h z@CAkID*R!EPqx40WY#j_iLZH;&Ce0{mvV+g1oc}sGKI;(J2%_o{yG#y)uM(Zo>p0{ zKahZ-;wRU`?Dc{j}EX5lYW8PO#mBI7e* z0VT9C7Q68Dlv~@AB)!q`4-<5v3~RUwEgV+saU6Go7*17pXu5o& zgW(63S!HeW{vxAgL&h$1QwyiyIYAY%ICPE7;=NfneFZni78#7E7|8sYOA#*ZSu@9^ zd)&1x<%GjOE~wEbOiMHpituV!J(ZRH5#Q#Y#y7flQ;X-EMOs<<`l}il*Y_%fD*4w7>3ueQa!NKhZqoR77Q_eD($vvC zC1YQwydErU`?cwouO`A+#TcKs#au{RM!FZ6=*Dc#_3^f09ox&;v`Y6E<8rDrt@C-0 zU78!PcdofRVw((k84?TZN0N z18|rpvTigeA!JZJVsWS+Hcwk%n1EEfgVbsqKaarf^19$)8@%v_QJ07F+s740Up#)} z;TG~V?wau(>3@|%RdH!|H3X#lUKk?=gwOeN*$%|g>OJ4KYg{>6&Gr~>3WuTGOA9WS zYX?9=G*pB)l#+vim`C1IFD2f8 z)Ssb!Yk&hjIWcx~Vdc}1GV37Tmz}rU*>L;uHm`0mxwWa~wQo&J!L7Zm5G|e1ixPvu zbFthtnHl{{AM<)7&J-`CbHrq2kTWk}3G4fESf9`(Y^5b}4&Q&%-fRM1G;MG?u@3_AhV&u$kv;5vo;x}>1^vdtZg~n_ zA4g2wkaS3Qa@dZhyJdjH&AJo2f6lYUkLGjAYZQkmxYarCs|B=VZ{u3CEB%cGf9ebm zWjvr^S*aG@3hph+jdk0%S|PXQKW<%uCCu3PbsUeNXZbZ_bULR3@)|cTeMgjge|2b^ z6(s5z3;ldgLKfxP^5Lcs_;PyZB6TMRSGu2GNW4L0pZK{*XK~fjHfF&4E1i;nzJg1)gShAduHxk!j7Wkv7KMnVki1Gb1|oMHt;x1ON75&XnZq;4F+5=Qt)^l=owH)sbM3j2YbdHW+L8#ZLsQ zliILRe`)3zX}o#L@Bq1KzgBXuL^h^g`HRJMBU}P?dEM^!223(pOPQo!F1JClO~7Uc zd2zOVj3ftHr(XG64rFnVHWGGuNS;QHEVkgR)Nzfu5_I0VnXu}B!LihF!jz$4@Fc++Q* zW-5sXr)?~2Fd#8lTsQT&rEqwRHS|e?N274_8Ng2pA-c)mIHW_=-KA=a+5(oR-`!85t<9e# z9iz%fAjQ*JBYh+3%vndV3vZz(xcl<35?#>7ph}C6mqm`whHcQ#NjfHq?jFzivgk`+ zl#tiGExU3M7VDAU6*O*pO zR|Sk8gTh?H{z)R_gXKxHUX+7z=ndc{KYWiefWx1t&fccrm;ZjE;y4`L|E+%v6zbL% zW+Wuo3#5d9DOHxL{W*FCKmwKi+V+F8920@gID3KnM$a=mtjeAuWy{G>>X3YK*#r81 zd69N?P!Uni@lxsI%33(!t7&mGwvO_!jq%uBL4Q!un)J)n7@JAZ(dHn$c$gT)mN@d- zb&GYODJlBKqr?}*7w?#~2k5mU)J`pO@Zfpq>eSt8GNb+Y$&4yOcDpdG#&ZB3jFSoi z;yHayYEer;pu)J&Da$Xe^X_f5eI7`j2u8uA>b0qSf%r9iOoacn@MO;!vP1ZV;j>gy ziNxwgZ|)qg(N*2#xM1~|@0^0JM*4hlY%yAwM)4=R>zj+^=m;Zbm_17T_?7_hJ%=s76>=!N> z9+A@Q+@ArM*=-aVtQuN{A-CCSwOb%I2hRpx97G*#`l^g3RLq2n5lhS z)R|9Kq0igc=9vy2@Xx5B%dOEBre!Fc)2 z-y=}QQfsKq7i*`S=l?LjOH~o7+I&%~^)n=M98le4n&EPPuVX9ClAQH-ZMZdzr>s+b zbF;^yPrtN4Wg6)%T8A8)r@JiiK%o7!5HY=c>Ol6sCmnTqnL`2@L5nuhn4~_5o>;xN zlx}A{b0GP4XQR}pa1V+I^b~jz=(IGVOO}}RLckJuf8zOg#wM||)2-qx)-Pf`mOqFY zwZ4x5h-Le9tG@|2M@3=J{XcgBg5MSuM*kXztDr3d5>z8GJJtM^#ibX}Z7Je&<_|JN zyrt{J1n+>?YC{a$X?O6|P7IEoFHg)gvdyo=i5 z9jUnD8N;1G7-kh>#oM2>Q;`DcTkMjwZe)&Y=gaoE0vivf_@{1L=tY*_+f!ctyT{%K zR2#3niYzGLg8Z1)!IL4HLM4xhJqd4|0ok~+61A{>V%8gn5j##*+-=~!b9!eVr`err zthLRbAE_EK(tuhKG1Swu?3Yy}#&@TE`23k*R6SNWT!RcgDpa*1g4p^CFebVXy+53l zN|X80GBbI&py<(d^kC8(Ng}Cfz*=jiIf2c=I6Uqut|ge;d3on(Tsl!&FRdu9T>~rI zDi}L{5_Z{hQQfnKV{2iv2aJS9QDW>*@iU~NIU!b)vYKk1Fa$V|Mg0mMja?FR zMTrH2V)a{D(+Mmd)NWSInS<~6WQeih*PP>%9diq!%8xQzlCN0@mmf<&at$u5k z(v1L5HVgp_;yS#8>KC2Op7D)i9C69aWl;86gtN70x2qf6pJ_@$XV9UyghgeGsi%q) zj)#9czWI5t^57FbK`2%gF>GS+&|&y%1>V|WF)1~2sM49hL=)Hu*2!dOuR&cZ3C`sR zT)Abm8mNSm#>eDT_NEHEuLeX8>TIu!)(-t0n{5X>nI`6@imBhT#ErnNRT;N0U+vW@Ap~`e`xKBt)gi6$O=`T}_hNs2?Zy11!G@z-m3dMobnzw@bk(_NzAIIqe zbbfKGfiqS*<`AD@Eh{Z2xrf!PSt=~XoqFM@{po)fkVHLXZjq%+ttExsnv}twc z57iZs&Pw;R6jfz5uQsYQSc07AEiRnYH}>z#z6GzoB{8s1{0Hd`S`87ECJiFF*^13U z+2*vp+HQ+;2}d87uRf=B>m9A}H)L!kIYqS?^c`^TaESTXh)ZxhDydGK)<@lN@2W2(hu^3$i!% z2nWD*jEd)YliSxM4lWZ73}@8dsloHBlJ58g54Q9*Wc@JAR9I2AT(F_&wYezmPSUkGR7V;#4k%inuwpnxdDGc<0LY6kWyj{$v)D zPmH||ZdoX}iyI8z9|NcT9K)EMd54>QSBCDFy8gBT7ozA$S8-~pHLXPENBaA(Bx(P^ zZt4Tm*G8l1&$YJ&KD}_EvFG0BobLpx2unS=!5Ny!pfF{ig~MYmeCpClJecLM#Z96Jj=@W z8Z+;;#eZ;m{32F3m-+8b4yyZMuPvN1;#=M$qL&aRABvEg;n9#Tn!F7Kccn8sVAfl) z>+MPP1+va9%DTxFiWcTYg2jcW#$GGYk@Jfkl&7}|a^i!t)nn_lNvFS|x|w<|%pH@< zv>mJo9=5=bMMrNgOPNkMym#hbE;-T0_#Bq-d5VB|%-jL1K&}5dRaPV2vlQn`UxI6E zu<#277d`&=^$b1OaNK6uV*Y4rO_x*@MhEUFN&N78Ji%?(|8cK_Ze{QV^9l(<_RJkNIcTqbG@@vodvHMrqDidm^#*tW&IWw#~A z7u}-TT6FZBi^JhV)MMzKOM_O^ZxP3TH0i29J0|MvYWemK)4p z!Cyk`TJztQmKEhY2e~s-@Vp9NY-3UMjV2qhA~}tf_-H3M67Q;=x!ZVLHWFv)`9>`U zbrZfPhi(o}*hfN^b)a%nN{LSH}A+eoLVcSNk_Cz@zS zpT}>+&L+%aS>DdAWtK^TDgo-C&?=HEhv&dVOdO`ou;8vM*^q2PfN zY%{z^sqLKFQPHY~4*0sRgm-ug%^4nCbPu;M`s>G&aPoPo*6GX3gR^4^uW%^s!IYe$ z-F;j@>^N5>ykZj>g1zMfVsMJI)m-}L-sMj%H19>uf9(!mx==lqO0$&eC)BgNfD9fX z?STrGEX&7f?|R-Pgmq3P<}^|MN&ia4hQxhv5D>-S=c!|r_A8Birc7#TgY8EC^xHT& z7mr0UTV2!N#q7CnMVKO=K5D#Vt)_hkxCDw*z=*>XchfJ9f2_Z|1%YZRz0i)SlcE<` zz#paZ4FlRn!ZW-q>cnm`IQ_mcq^mlop&a*st|5*?#o&O(Zb*(cjb%akzE3#2=|9es z0Gjwn*cAH5SNvEI>3v8xO_-d!ZT~>qz13gkz-?G6rv>_k>BFQdoh!dEnphNLFHmTs z1&`Y-kxHNYPdWdINPC%dFvUb6av;rSlTiowkpj9sOmO!lOq4;$Y~2ABvO{Hz(x5^um{v%azGcp1G`@y zUI>Q90bc**e5|UE-;^JC<`!WVl#`$MKFZ7WkOH?p?uYFV+I{|JfuktZwUh|x0YEi6p1zygRU35&ekxHg&dr0pVL6ATAjO;(dvA$w!_NVGB&E$! ztc?`wDWU!#^RkQm-a#NEKY<=yZ!NDf3+p%c@ELH{TkdSTzt>R}kOi7|G0EALqc$d3 zYggSR_+(_3CdFTqBc8U4bl(CGk*q{XV>|5|68;1O*fH%jr;T|7x1+2fz~)^Ao5QkCtbh(YXQpd1H%pv zt|CUOoYR);*VVhy^Qy;?s%ZIhOu3yw+4JzV_4NwJ(c7@i0d0sY zfJURs5hSNW9t}6;zJ4Ihsne(9Qd5ft2A-zKA`JkKIJLC2H1@-X2@hx~Q@#UM0iY0M zfR;&i;MP9on`OxL$BCKX>b&iEttViMxC4d>FdfUoa|S2yH_-EEW^y;|u668y{ttx^ z;UZDmy9iv72mev^$&)9lYHIzdFhse}`g6J~BJyhSH=h8`5NI-#J2`2QqW~6BUgGd< znZSADh8iHR4+GX97YxwIFksyALdF7BNpdRS~4cOW^qRsDTprYK|>j;i_XQ17i~vNt!wvp7NOhm zBz%A=V1elP`PCne^mJcepQ?t&Fldgk`8U5f53rHI4foXv|+ikDS2=MW_9InMJ$^)J~56C!+LxtL^s_!7HLjpFowv$s4u!3o~nnRLOG&Bu> zel!n+1$+U$cN4VB5#Zps2Y4}{e^o;NA27w~VH65X;0B7Zda4LD(fb z(A5jr$uQVofSyG-v=c>2$>5sp=H@1}dq9(_FP)u__7)rW^SxGZh2U+HtPtPmJ~uzV z3S>BdO9jnr!yXZvC}RFUAp-!9k>~X)(Fd&Kt}Ha46?Y7AHPD{9KE0`O@-TxDkCG~;TB^#EJU_&u#dB_utKUK<)WJ&jOF9Iekz_18x#MRYRgG$Fwz$4F5?8El(eqrr5_qlFp z!>K-gJO~(Yn-EhEu=-S0R9q?hz(XrEG!)`f0rv}fyzQw%P8GCg`wGZ~fTgI$7TLOR z7Hlk+IEo9N4+iu-hzZKW%ex4g`3?32?7I^%6>2~ZBZ=Zk(!=JlRmH&T+5A;pwFI^@5WbX`+)vl4qb_2 zdAYd|s}UUAQBxeJ@l!xX0!}+FHZ~Jb%=Hhp(++YWO9sp2Ng1wu^u?=JbHVmq0PWn8 zD&g2{K*ywz^FX9{_%ImEOA5s^B~VJ=@|R=d;<5mzc~MDjCyLE~%N!an;5Wx%yV3%{ z7teqE&u#KaNaz7q=?gf2VirG6K${XYk)zNw1I5!BLBg1RdK5%Vr`m<%I+r`j103#u-UJMz0*)2W%Fedm-`xhY65Tp=IN0)6kfW2otf{G) z4rsy)Ko>;M+ByptaDXf{uG0m!diZHZpkTjayMWHZl-We${K@bK4<6V7+Oev-IsgdS zz{4C4wTrT0dqZ_}b?s-`;~>f+?!^=xL}?uajpZnmR0R+KZF~&lp^j@!dT+r2c87p4=^#+`T6;MCqsER0LzawIp!mj&_N+r2j*KW zjeKkG>>L2|yE(;v@T|Cg?cMqF=gZBSkHAMtnkoOQH;^(|-u3@O#7Q>>vM8qiIZn`j zFdgFC0YKEBqcIFPv`@9Qr##+*F^n@o*AD~LCxK&tum_+ALKXp*6*4G5WINmzP3OSN zpxib}c58wLim=ci0MF5*OKg~ri%S6z-zeK6(5Vg3?_>@$w^^O1Pv_fs(*`sGcC_hO zrJl+G*$B|tlQXB~{)yecdX4B$cWjsh4Qt%8{@b!*2KzwgVy%gqD!tzgFez7mUaokt z3UJRo375$qCm|NK25d7HOn5o?>%9qDIZb=}yhBXEO!16Te37kRK(A1hgAI*?Of*^x za_o_^J70Y_=Kpxuo`?c=js-0ya}4UU0bvtxP@mkp_wxJq@0eTQtmS?Pw`j5^Kr9eP z7>K&mK)mbGGMgJ<=R-Oe+jRg}PY75-XXAnNwg5taxr~SS=i^>jczau0AK07^kJN_M ztf0u;DwlB3TnaTEIf|^Mc>|hL^fPg9lAsP@>pf_kSHO+C`wrCzE38!RW;K1T$ zDXU_9iLxs6Kw^UnS`|PEAIQ;Q2R+3U@^uTf932b#GyVvClyuL2`2I@Yq&OJK<(NUR zoVL;l9a%tsfFC$hz{Rcw3MLz%TcZQ$@(JNB!1JcqczOqgv)M}xwlhCizP7fuoqsJ1 zn-Jy({<_m}_$T0GLyYMsii(P5*!L`wTEKFgTfc(us4W8OJAA;ownnlK1EGcs4L~jg zFqqL000Zuo0;1<{QxL=5uPBrWBohFdU2XyyAp!7ZbzTHCP!<4@g)j}oYqWtHLX#&j zuN}-V>Uu)QVD}R+Q6BLBAYz6>$j1LaM3m2Y2szFs4xorL5X-N<0Z_H^>B~a(cL5vD zDziT$gB5rT0WcL4wTX#Lg8HSIDO@0q&ddI9NB~<2hj^-xdO$dnm?~gd>j9gf#9I$l zidA9s0Xl^E#L(1=i|eun?0$oMI^aa-D7;nxxbX;m8_fLs(X7nOyJrEClPBGQV?+z} z%N{C4u=D}(p8_CFp$mc^w3X2N)Ohu3G<;p-q!fe2r)&SUa5WL%Sc}$W5=H^Q%OKtQ3_^!f%4spoS16 zU0Yj=1%43HCs0tJjfs!ZEd{} zG^~6yIyy>;7`=Zex3jBHm6nxx0);9l0x*f$#{&G317PR_B_)7*q`m@e89??{F6H(x zFi31U2L;Srpr&%;KU2M+A(H_bEE&U zo>Wl|EV12^32ycm#O=p@YK6^ z=}Vjrf$~RAa*$EN>*Oh``cDNHP8|JC-hR<(xx6<<7`w4`Wwuk2{oJ_)dC)QsYAyVp zRXQFFKz3)I3z*Z-iRRbR(xQ?r0D|2HS`tP=mz}DTK%!Myrf?ptebgn;Ff|4A0Sp6+ zXo4V!2?z*$lyGJP+0Ha@Ys@n|ojWInrNjRu|yHX*LMxw(OnY{5^4@9k!GN6aqWzOgFBR=XD0O|PJ+XfWYc^9NB~3;38ZbQ&tlkIWDj#BET7WprPblF9tran|-++~|gG~jg*yM0%K~toy6xRz4 zg4Y)8Y9o)n2au8!5LAf*+G}N2ZRdH?XM&Ce$*;Jcy;EDp1wD4ug~2*+XUIc?)__0o z2m9WDzy47i&NP=6AloB%AOoCh7n`1uQ77o7dU?5eiXLh~+s{$~O?2yj6P*Imglgby z0oc0@mcb9eo`PrJUcIED_42YsALBN$YqN#EOtS76EiGuJ%L!7GX3*>Kip&cUJP?Uc ze)MQMN{Nj_Sh&aG0Jw_yckfP7K|%@8a}E5^0*l$Lt9m~SeCO8J`ub!gHlHBSf%zX1 z>kQgC_xuCk_!f|$>85{N`yu^bcZ586gQ64$D1Ly3wa3V$6&oO50(7r}K)`VUt#eDf zS4=?Gxdmi0G>nZ|seqjU6@@jRrt#%xyB#zucRoc^CQ|lUg*_vX<(UPt4m_YwD+Bal zpucOiQ4#ny=xY?a&%dT+cn-o?W@hHUFw@;v03wMz@4N!m2!w@qdNc0eD}cwKnm0;I;*<6`of_t-a4EjQ7#xP1+>(C4W#JKUb*rcpf(?% zJQf-jwz$+wdF0Hne{v>-c4KtY&ti0cMbO-iV0;e^ej@wXKrn6 z4O-t`*agxi!mh5a^`L$OwbD*ujsJZ$r}V7q?TnkulRY7U6WtNYU_LH(#0xrTeY?ua z+66S4?t@@5yamL76dpb5TsWgK{eHa;zZVf0NChfFhGRM4yMc_~Ef6n;ij37j#YMxC z^8JJy?sBl+9zLKRa`f1-irPpl;W+@Lko4h2M#fc;JthOCj-&}Q>!I#TZ<=0Sne?L@`q@fHerS};1YH$bTNL^0dm{W5tk}cJF~@M1`-*65 ze5BJq+$Hpd<0fZb{t@wQKB|{v@jto%p*-o-wIrH^)4n{ZMg^Rl=*^o()n`kB^wop| z0s=t3-#g22>_KfUq>W~JJ)P#rkrVXv*ZKHP1OyyBClwbJT?gg@Or-?WsQRzwLHoMy zE5(7<764_hH$XBa4XhS~??DIEiHbb{W+2}-1-d1hff9}*9+d*}O;4?I^tn@!BZv(b zo169@b@o#oPSGn&U;B--9PHtMrNH0hp7my{PCRhx=dBpj^tib57`FZFfnufufWh>j z_BTBxT}n_QuVP6u*3+_#=$6o6$S~SEL#O4Wo`t zXjA}n&}bSMv;)-o3)IWL16?`bd~0Tr%bac`1^KU}%dRs%ye0%hrCVKwC^oNILY97k z+5ER&3c-igk!>#KiOY$<_6>$e;Fzek$YggQGqgV3xE}{9de2Fr5fQUM_DrTLDm2+A z_{`PsplPqV65mP6gvYvx;TTVybr1?T;_%PI(d%! z9z2exm={TF`)|frU)+jNdDP1@m&c1%bgQUd^mM7$eNBm^klLQ@voJL3Oy?LiEiU*I zg8|kd5P4AP6Wc0mFCF~OPuZCEs-fB6h7WZN^!v0s>c_lODn?Sb1C5!@I?~`iMtdtl z@6hRn><*vC-LGZBgYLOE7o*l{MCcxx%OUG_*rNkH z1RcPrkVvMjm!X;2wXjQq_TR=!-j+96rwP)uy!_Zr{}4EyOwYs%P#CWT1t=CMM!UM+ z0)Edlg7)Z9k$`E z(xo|5`kFo8#mr~-#h#aw{B?Lr7J04^#hMuCQSfyp+8_)uddkIC?0t2+%0TeL<^hCb zjSM~-%hl-AW>)e8NP6%fsCSQ~8=B?|5&7Cmd_E#Wsnhvbzx(QUEcPnT%bosivBYNC zDy3pw!tGj|L6`c|A90+jq1B+m4RhSEN1CdSD;bHbNy{AOkolFD*KCknH;yZ;M%M5G zbM~$_5(2_Oie_eJF>r7aksPqE(tVl(iY=TrqKAW3`!B5(%;Nt(8wu z5EdTQwxFr!pi@0QS(xH6c2w=C&9ZIn%FC((Yi}RfCBJ3^-NIDeFzvi|EDHAx)(mKvCqM$T%qb1`TeQOw!*X-J}v+4+hhdr z9r4%GI*!oLYy)kpL6vi%z+b-oz3}-kSe=9*0>FXxTGZnou!QTv!jS-2r2hIn?ZKz~ z5~G@PTjJV}yf^MKiIuOrM;$`{Hi=w8xFgpp{ktu^Sue793HT?uDB$j?Rr;p5vu`jh z!!BKBxMyr^oJ1ZP7$^bo5mbvc6s+88r-ynP#`5p2RrGA@a-=k1 zujbz@SN#*Tpqsm>QZO`l;FVE&#Xg^-Jb|=5?u01jD-Ck4dSPRz6RN|>YqE@dWcHCK z!<}Tv=m~gdKdHRln+Ecrlcv_nyzoC;3p`)62+VY{;(Dk7dk7)Jg0*V1WH4RMnGo4f zcB#xkp2`}HpZ6Lb?MOhJ2fInTC4NjOAq*&)LDGim5vqzmWLsvJL%u8$XwzA{2$kxJ zzywwatO5QIu1ldr0ykX*Xx&`{0=+AuG$Z{kUU26)s@7%rnF^Ws6)PHZM|7v#f zeW$8Ba&D2wPY!)GkKct={=9nneTn__#$zudPyWn;ippU#cV1fWkR@36t*lSolCQW5 z9(#NG>{Tq99VCfNGOg&2nT6s@jnpn8W?vC`j+gi(A$X+RMI~|&a%v?ZiuYd>gzLn~ zcl*z$_Ie!b-y!(+ai!b>gDt`=XB06-IFe<{XYfLpD2kGPZgG$nwAB}HP`&lv-q<|;{yNay-JgNZ$d>j zdEMEQF=uw=HpA{>qla6K*)FHD?|2^Lec$_4vc2A_dtL!o5Er-`Pd`y893(Z3s^3@& z2Hr=^_4}EX)k+J%aQ7PfQslgc1myytv z@w%d5jV($`xTkB@X*4ofP|i@&3x zDWUc`q9J#ipdjpty1Vw473-GdP-6eLP0rB=v2g-X!Smds18We*aqZ}=ESk6-7SU9l zR0x-le|F|kZNsKzA{kv!NDfW2Dh|#b$9gnYra~^M4*1v~;Edywl&8SSlU?PDXQPC2 z{=IEbV(|X;Ie3&ovFGA{aBGuo<@d-s{m4_XsMm(L96ip?T@`Wk4NIr+4FHGTNm!c}-?T9md;kY@_{Si#BD<=M=quoZHhc0y7csVG<{OiFzT| zzz0h3Q}B*W)`KZ&=_677H{`COB@D4mfoJF4{cV(hL*o6CXK!s2;)2;&I_W;!G?U<* zlV^{x33109J#NAP;L=>`no*Ka4(V?Gk>h+l-r3!D1rWF~Ncb|wO-^Qpq0e{e*EzN) z$j&KDGFBeo^fK+Orf%5s+xz##**(k!6o2^e zCP)i-MUL(Ddf%R2dcBvQp7%paY%}S(_Mc4TDS(zZOy4xSV}0ZxYq2;J7`1I@4LLWV773nI1?D1`9?_dy(Ykq3~B6g*Y4pimSpLzZF_E&+*%}I|H z$+$9-{Noz$wQ6pf`-oBU2em@`5xEnun4aF{ZE%vCU6L%>$M{s5#^{c*UO_mWuQn1V zZ3Lbc1m4^TDZRR*2r!k-6YrIN)c@l<pJ?kbH3OEqLT%)GV?#PzrHbT2cy_Z~3N8lmu!AbOA9SD}|3cdTDB#}m2 z5-1a3c(l9$DsBAE^)5f*W!?P8Zwq%!Ffz1U@2}E_T6%%gDc@3GFR5j%vG8?N#J_;i zHXp+~ko{=!FI!fm7uVSw{Fk1#jnanb8V&|24V*<3->kHcpe}33zwM`^(hdS9h=D~MRsQNTCUh7hk|a9-!%O4pM=C%6#@Ks@c@y&mzHt*`*`+Lbu8P>Rg&iJrQ?SJmJf zS*02o9;slbOYSyIJ$~g)%4tdLW%7tO(^ZY&6NMU(Ja%Ya^FzZr(j| z zip^SkHR6y?OCMc)C;f?+Y z&DL!fiZ?l|4XO7|qg>pP`Gfl}ii_8QnQz|94{YWnpA!^4lgCn;O?m`6^iv-+Scl%V(Fc zBe|2?w@=q&$(t#TD`Jc|olZC?OcHu931)O+jv5qqhK|m&7^ygO7~{o{$IFMOSqT=z z{5>dKS_}Cmac`|o_fzuDxiiUh-z<~eca9kx*=iEF;=(ae`gd+4TsPy)&}ZrAvEDcD zozrw1vkOnTi=Wg#_*zl7EZ312ai>zhj*wUy5ef53t{}^MkUK*2bw>D)Vn2OuJBEoDOED*asJlG_A8zc z>W6|Ql4;&3t3n!HAPDB@^tEy2-M1zV>-t$a&>j7M1@# z^{$6*{~lh7D$+S9r>f=4;veSXW)iLxF1O3jX?i@a;%wE${ckN~DGjIKR`F+8xcA;x z-rm1`^Zf6rQN3=-{X0IzD;?id3E<6}#m|h)NNZob&1dhFc+f1h1*-(SUf(}5=-Iv6 z^)u1n1gZY?lSp}kbGu09AF{_gyeg2!k)BFsMEQT-6|zH^JF7hO=OPo`?pBWKub3Qo z&xBnz!#8p)%UtmhJd^5BSSSHASD7H%E*jnXQh4mzv+vaixwkAw_p+tt-m+MoTw2~U z8>kTEO>dt4MdNVp?!^7O|0=sQ^!(2J3ZS_@Ztnho-H(=7Z$XYQnSjj!8%T22@ZX|w zpnIlmzTQXJ(<7(8fxHRyN|t^KVH~$tIGF7UqSU!Q z^$0^}$u}CGe@#p;Ru?PxLplmJJsj`K1cbXUVJ^O~;JVq!c3W+N*CD;+d-vv&7k2K~ z@pbiznF?flJ#zDSzDR1SnaW%z*~~V!;{3s$&A;C=YC^@;Y{C1~rK%auRYR8HCtiJY z8HutB-9`(1yoe`y!cOjb=KkAj!>x)-fcd)G`(^X4V$-ZQw&92yQPRD^hXqgn$#lfc z3YoOWwpS=sv-Oe3BE)DC>*)v6`|k03%v@!@z*xMv%rxCSbyp#tTd1S*)Xc9uHNjk? zcsl*M3`0}p`Xj#dLDMA1v?dX?M`W_${kof23ugB(&ZHw=>W%WsCh(p@kwKCrR0fA$ z(_^0xW5P!Fy`=cfJ?D|+pNo;-t9W1Vrc>|R2*y5@JZW3<&Mq+QI0o?`ydo7<-aLlZ z&vNO=FR?1pIU-kmeEBXux{wOolTm`z6g#hGUu-HYZcY=fQWTLd*8F{=$|r#u^*g9J zs^rcEf1g_eH5@W$Cz+p`h+n?ZL_Bll{7Ib(krLi97~^@ww%2$$=Ut--7|Gq;5)O+Q znmoID;!McB%Z6)J-5P(u?;a+{6V z=NrTrn%@2~I`>k{Wt>lK5?6g*X#RA-Zem$O2^wel9T~QbBTek|>8>uVZo8_TK;$Lk zVYZ=@HLp2-vwN|GtWP!--;-XNwJ6Lj`{7|CX$1Sc2l_4?{d}L`<0}f{$sIdE`g05k z>_I=DIV|C(>Z{^rq&n#40*J*LP4P2Z{;X*|Gp|sWM=Wq0zei5NXeHsb>-67OdpP_p z)`wRa%6+n1ECri!n$ON`q#Th%nD2cNmnctbTp?Y994_>7-9T|j*({7 z&yUt8EpdlX@0VZQcVO{g@cLD0-J~Y{XYx2BYK0}}^p3p8$2-I!|F>a*CgvqeQq>Oc zbW9NM-&c~Rc;Kyz$7S!H8ID|I3m^x^JQB(+CD*zH#)#nD&RpMImCdesCXub+%IHTr zvT_AkBlK+Y1(9mS%A2y}@snrmRF>Fdv z-6ImbO{K>F9!B$|HlNS!F(xdfj8kG<<_^bq5yI~y?3kuzEnTi%c49ic@IX_OdTJ_}pr7@xoo!@;)zCD_ zVs%VxaMY&bR<(69&k)R2G(xPGL6_Ii$drA7^|kQuu_W?#V^5W}M7+F{j8{Q5!3M3x z!YLSfvEmcnklvuGS!uwSirW^eHx@nirYsFS@?ivqRD*Ep z_Azp@BN7N)b|0ADbUhqN-yObkCEtpcitiln*ac#ywWjQ%^g0G(s* zpA|lr73TbucZWBAx_9iwiG+1gCmfDmxs~G;DxcJEp;+lyi!a6TYScFCx0@3=6^oA> z|836kOM|c6iAW6ldOOX_7H8i!+*r(MFK$NX);9EzGOa7`-9hJ5yAYb||IQ^_n(zK9 zb}a9ZovSqU=q`=G{@rwj9Tb+%lkE2Nr2_7@o8iKOri<-gaq|zt6nPxY6m%BaUTogd zmMvBE%aeXJ_5F9Vs}m#J*X#1CGpuDi{G2{ncUm=_SLTKqeL-G* zT$&U8uEDNTS%`#sf7uoqUu-O9SS%6OAwUEbO%&G6OPti^AfGJ{uZ?`NiE8 zydnnIsrF}PI?mXJGf0$59THv7me=@7K>c(dO9o{wOwM}MYB?QdwtYKUmEVKwTgMav zr8G2kq>bn~@3vi9OFb+r7*v!Q8oat4G{S@h>@Ks8o$E~~)nAM!zwheJQHyq@z05lq zP2NPyE0Q?TI4_JK5VGOWA1~D8u?`xf1{zPZee28%Hph9#T*hY{2^)_dt{w*C`)jIN zFUYA|vG;#`Jot9pb-RFL0Dr^ZhsL^?=+Re|j}@N^`V%D0Y+5Ro_Z$XKii@5n5GD#6 z1@`}bQ+N5&TvGvC{;pQoQGz1fll@oi%dTtGtEoHV%CWSYvl{qfp%!)R`ktc~GPKd@_&ti=&4WHo?yfG&OO{wFhTQ6SX|! zJtoD%s;}O}jkBXxv*;}RD1tU>mk8eSK;NJtnD>F&2L`7^_u+^Jj_PxPfor{q4~> z(@n~5<$8X&`u=WPe^Vpt{#c#x1lPTM(5z`hXcrpT&>?=N>UVS}y`IA`av06i((pcA!P7A-T($ot9 z``KIZ)P4a0og14Yr~BNu+9Dcc1y8%jHpn1d3wTpHHrvsKYan1)pp z-!UYo%la$F?(6iVNn5YhTnWA|+_^Vf0WuC8+A8UNn;YjT%@eH3DCLE{;%a#69G`wDQ6UWVT@bch5A_5W zEcx_|L_Axpi)E&lsRT{!?w1+%q^9X%5e%*u6ezX2_DWl~GK?Qq@6u4+(+~VzEihQt zY4Qm_>PLs=wRBqE)$E*49^R z7Gw{l)TrAS*cZJ;?BXpXtp=;V-pKQHhXS&&_9m^)H}6SW?5Ze{Z#+_e7@zo4cZz=Z zpQP1q?d5px`GZ4y3vJ%+6@v+{uu1DotFUJR`gI*ls+VoK1A+|^12xU6bT5`3tZkO1 zT1eTz4QP66gXH+>dXJrXKkv9G4Lj7`PtWAP(-Sd{Ptv8xKtzP*#yC=Z z7r6A=D}EZLyQ6YuyTZ=rNz?AVo9kV95h8Wm;&PA5_)sXF?9RmEHrXDTI0AWR>fOIBA!oVBujlSpYENEZw54{X_$xm3E*XDbJt#Tl#gJULNxcep`gEG_ zW{2!Bvz1&}cbenZYiQ^y;~*tf(LEY>VM}cfZAeJ@IbU*CTmo%b}S52EuF6(DE*VwOr!b`HY53PbdQcmj*53eypC9aMM673obvSaEMvvUfSrNMwmlY_jqbJ3V%PvmWxVR4=pE?mllJ5)8Ys>}thlXvMzp3@SY$J=68rIu1#J=dW&}%U^@O~h# ztRjw*F^txIFrhj8##-H}nVlJANp2OTEfv>N{Y%PDrZChyh4n4c1zRUxyBbZrsM`@L z6=)t7a8Zaxwe}LpGQ9A1N~2W5bWu}_p5@bXPG!7LDnKcJ zR@XFCY`^TCp;81!Z z44cd68Kglu)PH}MZye5Ds^hJw!<%i|(N;9DG$gIZa?{Ikq9kev|J_>^-QAs$_=4Su zvOgA{Mv1=amg@W&xq}fqMYc_W&XQ|i9uOZ8buTPg+EGw&NwxABI-RC}+ieE(xGUtJN;BUx-IS$$iPv%XJFpoD%$}F^q-xHYR}MbDb>rm>n2G?RTa4itiq5Nf^~sW}j?W8u1&x-Q`TcUGmhP z7wouVbt`0Np7(3u4QHR-(${DitUEIIJ+2rXZ*x1URaqJzo>1Bi42`yz^huYM?5dU+ zHgE3G@KdB6b(u7cX*@w}N$h{xlE*PQDS6X$C@N4X|H7hP=#XvG&HyJT&w!1)Tifu5 zt9u@&ojbvyWd(&?X6l;iW)`^~M|yj+9662rT$i4^UB<<|#?pGJda++so}9J8^>{n~ zWkF<1PNrAgF@6+VkyA9~;Uv0C-6WdJ>2}`o2XxFq2=Pm!IF~O+wd7_Ozn+tfoScnj zlhM+Zkt*8HY!3B5J!)1n-Th-Q=e#Z!JIBvEkYFJ43R$>_(J1|$jLcIM4beqCvU?WU zp&pj4<7?ynjFi`A(V@(I)7LRCKXc4yp(`iUqH`P_rRABe8CKZ;n=d4Bo?dp7VA!Sm zX-1A$z)Oms+BA;&$C~a$yxmm{FVt<${Z!zo$@>j-=k5iw80vTPHOp&QGVkm}!EGMe z4>bHLDIM)U_I7-5*kxMfmzXGs9tr}kiHg(H^{CI9aLi*Is0ll(2MU7IREePDS>gn` zI-idYiGXjjuOy^hS;C%qV%t5{5t1Y&(LUB*d3+0ny2vknasKY>p(b*BsHV~hWn~zj z&UN0(^OIlFU?zbNTI2B6}$tX zkg?=M0Cp^%^Nd9KfvJ(plQ-=nM@vPw9kMk~XQOkx_B&8HY^5BW>8UDxfK z!y}gaK)J5abWN|>Ja*3AwZg##14A>ku8vEsGo`qQBQ&?t>zZo z5=#6#j?i$QT{A0Fe7-C?BqAIkQx(LK}LoQC#xYUSB5V@c7eI^dFC_L;Q1HKNU3*5wEMdpHyt` zbMp_~OsYE^OS2PmRQ&a;4F^{q?UBqlgH&hEsg}Lp$2-^;?bO2BT6^d0h>4$~EdTLg z#QdKGa>_Ys%k8F#h|jl3`Ei_>TyD^Q*Y@~65(Jt)j9cvKRVdlU2@(uQQ_z-so}h1I~L&iwr6U5@Sh zKi56#Br3NgH5cmNsr7xgRzx^CU^j^s`RlaZZ?zU@;cL2(OnA||HVp4M2M1E=ibd^a z;iQQ>?_XkVB@V3*v<%}I@aL?O04!&6JSvIRU?SCR7U}MO=E3%_rR8@!V<}CT223ht z-h{r3sZ+(;#1u7l^N8#M-AUqv!Iyt@Nfs{23~2p!$YAw*jkZQu{LpD8EJVLQz~XWe6nPY^t76}I&vm}#t8ZS+gAUbWv-bpsJsA=Z}|xisfRPV#LD zm)iYmCj5O?sA-%1Qr5c6R|_@|>%GmiTd$}ru=GR#jJUhR<?+088n-WEebc^EGBVTS^v-GkXi?}#gg!Z_| z{CPRC@++;RqUF6gImL?x6=8g|mD{iM)UUabT&%c2P>r7)UR%d|Z+o?$c& z9_+%*0%%u8%KIlkqo$47S5}Ub_9%Y#)pu_bQQ%$=mky;Z!|vf7-i&va zZR<>S5gv)E#kq->{E-OF%OdtKat7jRC8wp8CZ zyhhRUk4+@ro3ysOKeIp$9@Gy-`Cw*U4WY)XiWb#z`v|&r@umUeb=?#jx~*{KwMX0KA{IsjS3J;l zoA2lSQVOo#&Wl>3c}cuAZ?*gx*u#d+VIjEP`Az@0^<>#2WXxLU{i^MXI~;VXC`%;8GMY$shgpcYYvwHS(ERN{~+a85V_8e;HXhd3hQL#{GNSgMpMsTOA>dZY`5}} zUG@pIuXK7+PY9Mg>m&&E8|7Lp80Df^7L|W8^W=Bt>2)#6Uh*>c5YM#5mEmtF{-Ci# z5$OuHXhV@Bda2yf3~J$>4AxS!0VULOZIfg{OP(dnacKT{lj*A?aX&=qEV8RHPpT`XM{KnC&It)yULK-Jq%Cup zq|=mlQyO;T8d@Ox+4rEVwv>tjQx%nS^{~ySoboaEb-LW+If50-QSg@pxobBx7!e;C7e7$ zvT$dm^3h_#>sd?>EVQQUyf_bTShyQ`X6j1K@Wj5&6*kh$VetHHRvA?FO|@efN0hx_ zcCdiwbUoML_L?qA{NNFVz(9pkWab~G@}s0x1&N6n`eZx8`=_e-jX4hEf_*(XChQ^o zQ+uq#duq(;1Tf;4;(sC*Sc@N(DvHz&D}#4 zRhN0ZMN9lNWSb}Va_Q3E5Z2lk#=X|7FZJ0kE;-4UvDglO>N_2~SBr0Y^IFNt>iq*o zDOa!dzPReEJi;c5<-a(?Jg`l(CR>^zuLp8ks+eX>TkkXNgBLOF(HE`FgBXOdI=w|# zMK`Lf_s|1q&WC$jBnFJ%-eF{xDO;p|iFYYYRPF+m`@|0aMxbV!G7z_;1Bc40<|4%X zf37A8OgLfs3+He5|LnU%D=uZ@|MOHB>du3^RxRTLN9!-{TAOEa)AVO;ZyK2Uz9nS) z{YzQZc0_sB$$@Hcleu;6SmnQ>j9ta(%CqhkIXLjFMSBVz!>mT}|6f9Nd%q|Pk5EfS zuFDIqlT~_3Mg2J?x83RfA2=eM0QyAPtQI-XF?yW-;7dmgza=J#9vvF|3wMV}Z@;=O zr+Gg4X@3FpwQ{&Vvt4>j-Eqjc7e7OmR*YV@$Gi8S0lyd`eUhRelsqRO(|L-7}I6ad5u|CsilTf{f*ZG3Jx$lidAedT)@qItbJv)CR7t@g% zZZ3RGDHXKziqE1)5Ah&S{3;iP7r2@1QWsg}KV^>{xJ6^Od@n}pzDZh1F}r|nPIc9G zfkjDQSRt8LV=^E51Lwga>wVR`>mAY8STPx0dvjyJ?hBa435aWA>nzKJlxpH?ar`vU zplz^ABH${fWS(fJ$n8J(vgA9Y;hstk}yKoGFt<6QVopQWCsBd)zM5 zdRJcMs~lf3>(Y>zz&1&2gr1RFE3K0^sa9U!A7n5Wm(B-n%C6LXhM*aH)@< z>Q#9@S2_+SopvVJ1^Q1$_H8FDj<1~OTT2`3Y%#me{Bd8{3|`&h3=6hg`MzB0@#Hla zl*9lDslBF=|F!h@iCPcf&$%Q|IhRlxjB-|+Ke^sW5PVfHC&liq*c+vM|?; zqVj2u&6YLa8regFf^ExnxhSKy7}Pa0^6ZlW$BWP!H~GM2|K=$Xm6~1~_e$AKi_rdD zyFE9lH!g2#a5Ai(E$8||d)Lupb;pXN2~w$Yg6fuUm>t0C-(NW|g=yq|UX}qg6z2KcgLxIJolyttscli_TXa zPLH{A;vK9Vfvfk)O^+DS1p3|KG$wz6P|0mHy&<$-y~^^TM%ymW+O7O;jxMuuhE&ST zoI)e+-KVP^MlM<<`!Q17*Q*^Dceg*0)qY#st{vf;wH&Ov9}}Z`0SC zh(u_Lh}M#km%jum06O2_vcywI1jId z*}g(19aTm1<VvRA42YvaV88 z?t0Upo6F4l1rGP;E?RbNR28&{C@IDllBJE!)hxH%n-|Po_^FO=G$PRLKVH^9k~2mQ z1yR;!p&+am=#If8p>1{Bhn9<-*edUKTFjQ4(PB`4vNGRE5)p?xY-m-#T%YP7cmU4% z8r+HoZ7}2#vp=nS%icQleA9eQ~Jl;6Rc7@He>>x{pPhD?bqnY(O&I?l5O7?DtC`916C^dGFCkv1l?%w~Vba<)I<#Y#n`!~*ma|3Fh zqp9Npx^uAZ&Kky9r7=Ll|8UOF-))@N!uvRb^Y+h(EOFlZ}x@x|KqCr+0s3_F>!qq)gQyN_Oo-e7BpOEkwB3mA8B6?H!$>OueL$EP<`mGd2S z`=ayKX2R}07s8p9qKD;)b&Ai*9JJnv?O6GDF}o0aUQD{(*D+L+Skh^^P&;zKJ+DR_R55UNS@?&m*p2D+PyjqZRbn+EgiK4nL_^czvRWfv=Y9<5D?D=NX%DV@ z$sfNCg6X%d!WYy}E<$thz2{FSiwVu8P14$ne)Ee@!v?&?q@;E1Sk5haSm<&4&5`p+ zv(a)f|4QS>^Ss%$v}qF)C#CM`-?P6gzMOyDo_7Le5+lA12kGVh+ies72ec<h5&T+g%VZF-(DY<3*6FbKv!%GYuWe(0&(8V8Df^ROPh;!jl@rkS6 zqhWHB7kB$ZIGL$1JByCnY_(5sGCwgnn0Smpn;8vTSO1cNkN|JIm8B(P_?LT$XE&MR zXSN5l=0Is`rm&4&4^-zaU}2THg-MW;@zU&^;5`m$+7k`}M>pKvKU^23zxH!HMf^N_z*SS6 z-hV>-d)w&cXUcl-elRpIhUT2&i!Z52wV*vD^hdW6nITeNB_lL&Dvhf^FLbyoeJxtQ z-V<+m_EslV+uh4y2L;?K{~pQR4Oj60%|`^g1hf_ejHtOo6_3! zWGEDMQIj9C%gYg*i24#zR8HrwR{c(F+wKw4;vW#_{nHC_y)VgU$*##x%Z<>r$iyQb zBnN}8ET_6!Hvmdr*~cK_+bfALPqMXaQ>_^QHP zAKc`Ax&nm--3i^$yTsR{X6X6rgfWv#uW_o5cQ!ZO;ODmcT|Gx+$CbG6URx3DW!cCu zZPREly&aMBsGGdLLgmkazhv8HkP?=-QA%)WP!=cc_NPdqngL_Z=b7VUhc&8q>Y~M+ zJgkh2tXxZmXsY9px7PPyY5kl?INLoW-y`HEYxpkiT&twXkpTpTLbl5Yeowd*+YUTB zEppSW(Ff<^6|OH!5_GDs*)ZH=&5J!co((e73$u$G@s(|M;0f?hYVhN6V$tMK?=D+f z`Nn5?+N`sk*#9v$SKo+V&Zebj>ns}-iShduHxMmLnbVRp@TR#!vwolWk$w8Yv0}I? za-?V`zpLtfh|OFMHqqoND%X3&l%h7)E)((RkJH{UWyb!!^0&OG_G#1xo_T!!n?-eh zZtKbW(EHyW0*or795K??%_1Qqljd=H0s;l=%ViTiS;`zmHv;wVdC*ia6N*nn~bM|H+br8=cexn(xza$y}bK2!(@he6V3dH)bw;& zSFNXnlEVo@>R9q$y#OOEe?|o7k4qfyyq;1{34Yo`(7~(AI5ue16Ca8=O#0(&S7EbJ zoN^Gvb9Hsi&`iM$`o{k8Vc;c0ap$DTNo`lgL;cKMUQSNp3GdqMxQd9cLFB!K22w>g z1f#geI*3R~zs$5o#@yCHOGrq#NF(qb^xSm2eTL}h_#cs3Ex}FShv&R|E9F&$8|sa{vK7Sq1U2$+d_3(wy9wI+b&l0 zl{`ldMJ>+Xl|uPnTBhH28lw|D>fZeltS3aHGgEtPQ@GvGS;wM$KIOJ%Zs7W01@qfo zPuZ&FVt2SMxk2zGacG$RZe>GeEaC6g*d^##r+40hKLs?H9 z!D_9lX|jnOZ5(w^Kx##`$WS_sIgWT)|A)!Q8 z?w-4Rd=#{_v|Q7(>oYU@2RqAcAdeXXk~#7BUT~p$NDhy8Ct^VA1vH2n8XC@PX=#B( zga@dGGOmt5^HZqw4diHYwSZEE$#5|XC|Bu%wChcz+5jJkQesLOD#w(6Q1PV`A!KX(Igb~=(ij%;y z%ty<^;lbdY#3}BYk|w%t;D7?K?$nn+!)8fGQ1~=}-$5np9tYOsetPU^I*=P&RfPfx z2__bn)};VCx(x~iq?ufjDN8vo4MYO(SdP9=^fhF6B6o8HR5z=<3Th)98 zsfxYzW?CBu2OgAC$kg0iGpG}OhkvCIbS@sU;d%%HNluG7WrG!VOz^%R?H78gLG8A@ zvT|y5wG-ql+e3iX3B50d-14%&4Vtjk)z$NZ1vjo=zYad58GQTSk1VT@P=d0S+q*y# zrc2;Z%5A3ei+T+VxT{Z34xxNJ@aF2>*Pz=LOU=}z!b%3RoMP72x3LJQl0b^`NrFHO z=(J9OgZUOrdG;$!l4SAVn`P%gE%l?z?#dC!#L$D*iMY5pylD&ilKKVlftYwYv%*jH zT1Asv4n=Ss9vHA*>x~)74?Gs%K_3c{`~kfrUX*+YuXg=8FE6h>Fx4wO<`g`!?Mo6@ zGUY!#enZI{l99n|_~U&8*qDu@V{?0ZFz8T%KIh%DJ$6$uA3A1*eT{haEtIwsi`KOs z)a=%GcX?4E0Rms(@P7lL#28@@p}g9I%pse?R6?OWPY_&+1Hmv*#kFvtLhQZuS}dQr>&Qx@W$U0n;!i5)?kY-_&T8^j&gKtyOZqkCbb%!=vSHBS(0 zdzvA4-FbJVUHEjr(|p%T;URri8@~}FvM2gQLoY#ol!8C1w9d_J#TV#4zBIAB+Q#PLUh za&tsn9GrvnG`K(il)zLO@QlNd0N8AR*4>gTS4Be*6nZu1bJepnWTzTSTA5=_9Tg*gE{fpO!@phFZA() z<~&Eo$4=A1yz>Kjw4liO>HaG;!{&%XoxJsoke?yesIc_~bvp3LA`%kV7Q@AeR}lCD0s+Q9 zGl)U;`o^6*q*x$nb;AG;gppppe5qYD1j|(a_3PKaCcbe2{QHC5l`$MVJiR|ZKX0v! zjerT=%qp9%9fLq%0?!9`(v9Fefq!XRl1Lk>bwg>n?=yf3>kX}1*RAD|XwcD`0?`+T zJK*WX&wO$ZGY?M`kHv8Qi$x_wi4Uz_}C3GSXx5_|l5`!-v%GZIWmF$)sjQOQB@G`9GrEfqOxcBq3bSgo#a@asu&=*78 z3TVG_!U?{ql>IUbSsekvGdG>u0QPP&Ud_)Wo1hOiRJ}J91b#Z)KVK~e{DCj1*nv#V zlUmpPA0cm-6*A;rfn~$lq`0l^Ib?%4xf#x*{kcTs=e~UXT42)4_<`5T(t+OT;>yZO zwq{in$c0WVEJ%WG_E7i}#p;(f5JdTGXRw8jw@5%gB^}wd9QA1A*lqt&M2?-l%h{s| zd;yoSzP46xS^{xHq{OuE2Y@z0ouZ-n-gLsc;~h#J9i6vq>itU+LrM^s{t6-mfUx6x zYA|cShM*UQXWWyD1LDZqpmV8^qt>@1v2g)}Z9BpAAs`Y0=FzCMZ-pHzDl1C|39D?i zlGh*{x(S*;w_mPl1KHCAigx_&N99ArV*kRqG};gs?wI}z0M+6mkn09fFCzzfVo7hX zDK3y72DzsDAo1HC5((FCoVh^b7~;94oLtyHD|X$ShY}7|b91vl*fW9-aLHJW9atr? zKrt6K3ZIJK)&~>;h)78E98#a8Ks|vS(u_|F zZ-?k!3xJ+3=xqAwetjK7E%~rV8z5SeMXjQgSW`AeF`BFl=GhZ`1pjO94*07Nn8aV z;*S8n0zGj=Gr4GbMuIHJx4!=V)jP(X(b42gGI6*6qKVObyE&QB(NVq^e@N9!%^TX< z;KWBXKvDrXr+Ivw#?jF+goHGKL zs>ZhNd{^?57%mJHD*mQep%=GN$K>qnSG!I@aXC36vLJ9r{85pSB;ct@*)=FQIAE0c z6mlpaKuv>4EEW7_u*GH&lKA{I#cwElhJ{77kRBw#7(7mns<(QisP5UfEJ?(ufzaLh z=H@g6GtjH^2l2(pm6ed#SV|B`odbtvC{9Y;%4Kh$2{0;u$Q*2D9Z^$56#6Vj`Oel0 z&Pp)Ic1}%B*25|2tGPyEZDVsCwrhUg7$T13 zx`yHr>DfRkW~-NlTw-`U2`F)8tg1ca?ZTLOA0h}3BF^86I)&O$tJR{gK$Nqz*>rig8&fb=sWbd1O#0;sSTVI%o0my8CE0{nro z`&knX2|XiY56C6L&wL*&(2L>J!vw%@*nBCH^rk`pU|M;Aa-b930Ivs5&tTNN&uwXt z^I&(ilXt>Z6pr2+Y#_+voo!(8-{)bwejS0{pm5a&8stu(A%+(HL-9bpy2X+rkyV11d1NGB~^v}-XvTZi_ z@8?dlmq9hP9q{wo#s;!00$u>rHh|NLMuRA3VvI95fKr?<}=)~ zLqNrMAN~Ws{X7vUqb9i>?!ewXp|={Z_VM%E04Ld%CQZp>H4borl}R~Q0}1tYCkH`m zYt{%D#G=i~YsF&pqh0~MRIyfLJ z4X(2ba+3aRRdAoIZDV8cfV4niOkyBcGX|7!a&vP*l0P&a<@kYG_Td)=#9K*(*uf?v z;PIb?1)KpA2*vZ=4jllc&G%)IpPua2!CINz`7cye^g9u71##;+e2wQmvB_E{(o=NC%iCZR)uK`9GGyq!7(5&Kt-8BU24^R*i z1O;CFeX2sEPMXoNF&le(dI5nrSXB64h-{z<>oogLd2MY?8vu!6bGW#6feQA;i>WYI z09_US8ym}`9R5Ou02hm_l5ODet!l3F|QzHoS@zmqvn zo3^#Z@^YYKUepG-V?LPw3X;vu@3->gN=y~e(9nQpc#Qqwt0hEEj8xR*42k};XqoHS5+Z0s5`3@q2QQl-S@5= ze1EI6HrW6;XLRW$9o-cfBxPwO1_KaV+^SU$Y+|oT&!8V#R^N9}qeH#d zX*W#Ks&hXA>328zH3Y~g1Y8J6n=*27MXc7HCV;E&D!0*tA9)X|-qlL3!HX^?e)5Au!xPB>8^sgcgxe~785o4V0HY(ufaq9De~8F^6nyn7Xoof?iFm&UZE8r5UW0r7hsEUqH2b0=;Qwr z#NsOXU-IB6eNlIJch`f3bYLfa;1oels&41#$OMvM=vV{@%>~&j;9bJQquDylc3p@fwJ?jC@`^(O0IU8LlB1B#rG zF^QMkFI)mFFynE0NDDZmzO5|?^3~o<#al%wfdK+s_&6lQ;pPmSoZ-CVFTEiZeO+NU zmwApYLJXj6D1@<|TuqeF{tQXcv;-z4%7L}Ew$^@SGzLbw{DsQ&&-k4-=%r(M4B(do z1b&QR>|_c7PZstVCgCS5UzmDt$X-2he$yy~xCzjPevTXhf<1+0cBr@}&(e9hR@caxnq0 z0JT3538VVb+8P)ZMubbw{s#OEq=tV9EY7}ar%f0Q#DJuZbaY-Dvu&}|lD5p?HXb~9 z0D|_6Fc*cMpC3*i|6_29F?Y?#U@S`tFwCy|v(b>TL?Jv92$vU42L_BrpLv8?7|-+p zUf2$%zrdP`r#uQq98l$Qu6WsYWNMT6BlTB0%OOR4Bk+ zLGug;Qj2g{%4USQ0(E(n3R?!S;xtiz0)*~EIM(MirU=J+#z(a_0(9{8_s4=?ste`` zq!lCx4{4C$4|@}*C*psZH()&8g9iBj1GqL6;_kh84ex`@Qh`x6B2cn~g|&?aq*VYj zwP3CR612f4J`9E1vZ7EZAg#WFDMMLP*cj4fTGzGnmv1U)1J&|SOe_YVjV<3;+XY3%KdghcpkD7Mw~%j~!&VVZXRy{u9>X z`tqN$XgWeg$oLRg34GDo*47NDBg64X0#e5HXuX*V$hg}> znCSTbM!*I5A4|21kP)>5$p^EV2oa{!ab;ANGbSK49auRS1r`dJ7IM71s1SX5u+y&t z1JOX_EE0eQByp?K|B^(9-^qHGP5@|i60#d4^@ITj5J~Z!HfE9`zAlZ|#DeWk&d*Cg z(hNKa!GEJ>+jD2D^$dwkkhv|5Rqf`!0E69H8j1wTL6u21n>bx z#i~|}4S}ubh9slGe+FR!1^-KqeaT55<{mHsvI8;QE^z1_iNcU1?^8ND?y7G-8pu=( z0#0!9&!5+Dtif?XGzvF=au%=^Ab)ub5C-_=Nod6Iv~etl{{w6wO``h&3xM_}-GcXV z3J+P?U;AOf>6aS5Qcs?UG+Y&1i#@emBA0a=+36=Fc@3#Td- zPgz+R2#SKTvStAJFsuf^@k+`AUtEOQ1&dh+`nw3yshi5VZ_3Jca~5ss=oUoImX9n?lc%cu=bm`0+7suKi2~(Y$UWHu!J$4G@R)!Kz+dH-v9=i4CW^T-U#~dgz~>3 znLq@{P*1O{$W++Q4puvH1LFj2fkfra|CD}joWsB+)dryO@X;g4z*=C+l+!O?a?6s{ z(jjw5a>H5w;#X43Qgj&XQ(N)_7%&nNQDDG~`!e4JE8tewV zAqJKd3g!vEgaQWL{e>Gn^gtqm062z~l@$Vq3v|E2=0#k8P0rB)p_KXQ#|tzxG;k<@ z(A*$`JQ&H~ATffj5}D)&zDU*r1f2o=s7j6!@_p(?ZiLuP>WAVUJ{UjPyM3;Z&|>f?|wTJJ2WB7iJkr^&c0>D5s8Lwb^4 z2}qPU`+RUn0zyOUR-J(cKL-?X3zT>EK?8le_+wxTNhNd^!A!SnfG>f@yPU)@rusi2 zTjdQcAXm72|2-vF@Qk8r9~z43>XHL4MFe~;(9^*{NpS)s@dQ@^B|S;-1rQ5op=YSP zuU4JcE}*66jL=NucU+-@E`stojZUyhK!}h6!@K?lF18xR@y)bFclxB#*$P8K-!w83 z3)2%&Q6uI&NOcq(1+qX;0cT`*yVUVNG2DRWDcSjx!-><4#k{%?VKVU8g|QhK8HX|q z7`NRH?4P^u8z7+y1|n_ot6Z4oK7`F#`1zRxaG?=wKdg8&3|n{zvmB6`89-8mF@gy$ z&&n({0Xg{gncfAYsZWPEzyK4#o~t+SkBp2&0?7zT(^q&j0DxNaJ)iJ)c6Jy)k%nU- zwIf6(9*{opIUD^ONCD|A#yrRXs1+#r<`wzBdI4}4nEs7pvx--TJQaq=anQPL5hH<; z{}Yn&zu<|*hl(+9&Q1fBFy9gr|LPaW>X0fCoDT-s1OdiW($=`8<>h_gRe{V(1MCbz z44Av4&qY`p`Z`zj`{`Repw>LT* zw70jEL!fTm1)Lfr(LaD}HR;NDdINzf@$uA<1RDZ}hlqniOyz`ufX+KhCJqlcMOp2M4mqNWsdv$GmCACxwR1 zL{5KT)0=^zbXoj}1Q6iM;j1@)`O`w>)XMUHYdGY5NTn14F2l{6f0R&sP)~=P_2uDm znY0X4Rq0f_A!2-nEC>>9$YLgeM+Jn$qF%}hm4h4X>>=RYrjaVOg5-_M$?baZUia*o zBN?UXZr=_ALrfc`6@SrHr8EaJwdla$0{VF5 zOd+QLOll2!8#bZ3^sLIk0y&&Oi&{H6*3E4~g{2{_H!oYwL+x`t^jibpiExYxfPuQ4Bu3Me@ib)* zrh*|>2UdIs2$CZBFYCW!tqLJ3BE>VOqJd92&9#hYoP+vAun9 z;DQ*v;F;r-jSsrT_nQ;t8z6wBo{$63l($1=T?{5;RY1n`>@frX5R9Ugh4H75oD6GX z%*RquQ^OF?@6TkAPCL~xc&+@Rsza{KKGRvig$TTd*h&%+sPFcFGauqyo?ms7;qZea zB>EfhAtIwgl-2zk@Zpes2YfFfDcN9JV!Jjea`~fJ;dulkL)|YNW>C&1kWX0}85uRh zae^s5Uyjn5R`djMx+UFry)n=i0NrU%5YJ@;+ zOvv)bNbH=Ezev3ds3XWb0TEuA|IIv)P|6Vez!YgSm2$qrW>`^C$s2{1sO3OKBLMma zp!?+t2}w{(oD3c zj7gRT)^N4T;_+i#_#UUf&zV&TF5699WP%+Sfxl&j`t-L?=noer>V%OZ5-5=)({~(; zO{135!TTeX6ktb?dDB#l& zPYaBhJ|NGxtg1aeJ`p7RDAY7`Yy5+*$%1ARPGuq^BZ0b(U^fLc&>|WPs0qSGBw(Eh z3(IlOA@H{wGu_qC=wv@ax#vfMU@T`+%ZXuf|}F{;8CQqAyZxfeJX1 z(Sp6X4RbOCfBg6{AAq}V!RW#C^fbD4Ggr`8FL<_A6FZ)N<5H^UImLVs_0B*_dh$Y{b&ozs!yqV)MyZ(fiu82Ys+9-{2F`BcDoZScUHCz$XaNoWtiskHviEx=H1ynoU+g$Gf8wZ= z^$wU*7`Mm`nGwtL>b+-=ndxL7K*s^SxD5-|r$1LGqRr6mKKC`Mx}VUPZ&X_`lu#T$n!-yQs?A2b@la(?OlCPURx)P!?bgEA62Cct0#>&OVI#xSthB$* z#dXQU!vpZ(GvFbpp`Aw?JR2VhHBng){O}J5{0I=Hql@W6h!b$*1!_5Ej|8FUpNL>} zu-_sW3kv5t9nGGsx5mYhm8=cDtN^$?@UOBg;Q|4`bO1xo#LD^x=`MmCT3%j$e!K<+ zkQ(C+TAIEl%5g;>Y9^4IKyAU=*0wSwsBc0wM+xe$U`klvHCa%EUd%LjT^U%_>EP_&l+}rk#CXJB2;xOz%!^-Q{y*?p}I%B~4BUbu;=$d1(9M zE|$??ErVj@K<4fAq0>FXsZdtDeGG619*h^0?PNKMQX~m_vOkm!5kt*uK_GsUo>9eV zF>&?0T)y@B>gO(jrSTtrseQh9&Lctfd`v23cE_#IGbB&(FYH=raS8NOF+o`mL<&pftKh3L-`)_)3KhIo0P~B4Sw~4TBG|O*;%!!L91ul z%{*g8k2L6NlWEf|4}jhLqdrP>+N%=u`N@X^<#JzYY0QNIjguy z&lVAu3W?X|n$O_V1@XVy>n6A%CMW{8EE;ww?)=hX{h2@B1{{2FYu{?>MOD@BTpbjM zZZ!K;!aFr4O(QERj89&Mfu ztGfUsp=Y5We?b+HkFAxyz8X}`g^?OpW(1ShZZuSyz+zOcEX<;}mkdLHAj{|2NiymZ znbJ`0dGFux1axfhN>4Oth%#O;XR@`9AAR=||0w9ec=4TU$a794@5A9gtOC*xa%wj8 zoc;@~uH5z{&O}Hd2J0!fo5~+IO8Usg3l6$@vih30NY!CiBP_+`1Bkh>!m$~HG4j_O zq$rl07*}2qMTGm5?jj~+!(){19MNe?OCime;Mm3|quc|dcfZ`?6RS$Q_?rqOqL{ZRGk|ls$)|Sw@FB&lyJ4AXQJW5pQ@af;-Ny_DHVgo5Gu^K9LdYK?ElzjEo3kw#th) zNZPng?3QF^XKBS!7M$TdQYFjRMr53;$bqkUqb7zJ_(@_o$bRHDtb9mI+FEEQJ}2an z)(o21T(*SN5_srE%K~8S`HPkYNa<5RqmqpLq-E(H0EPf{J}p7+*a|SL0xsaYHUKkA zOFjY0__JWjL=W_$>Yh=Ub7X?K*&ByPHEH3!IJYQ?(}niq)oYWKi5j>b>tTjjU0KB{ zm)pZPI_XZ>N$=D$iuzpgAM7zH^*KW^i#HA~P5JCDLulwAev0|^L!3YJ)b=EHOnn){ zv!yEcj#93iSw7H=2{38omg^N~n{tb3OIBX(*}N&51?k7bS9y387Y)>x-O&u!oCYG6 zkv(lp$HY2^IVuHp?Um0k?D>nN7{E$8<+H*`(9v`vpd%6gda(8XxY&SNWXO+wp9v%g zz`mf&kP;f2pZa|J%nU>@2GNUYT*#eC^McK;*H&N0iP>7>@uTdlMYH1dBVR!q8cxK(h!{!yJ0WdX z86jlAmF~b5^FMkjnSc|Z0H6XYo9mis-HeR|U{yR^ zZo0@i0OsnE{g<>}xtJY8sT&B4$l%9V0l(Q&{{P3H zppek!!9hfPJZP>3AT?3^tDJ&~%gTw&n$Kg6fQINg;5f|(gm?h~f#v#4K$HM-I5$;J zXy|gx^Btp^w=2G&fh=p8u-!+h-iy|=xuu$knZ0+O*4px#WpTPB$~)pEc463MM%abr zi|r0AO#5vQS=H@Oim_D8Yiw+EDoF)?b>FM5@(}Lzo+65BfZiiG!!%QZjCS! zcrgx}Fh8zt_SN)whKeDe46U@bmO{?FrEK%r<%iGmb)w8ZS9gUeN`G0PYEab>Zv_r; z0H2Un81kC5H|%*l_eMGz`*64&_zk-h<;J}6u)y^kHz1a7>&$Vy&6HEJYkuNRA5HPz zI>ZsUkm<9iF6gMfI)!81TtFgy$br-x+kXZa2jWvwUVezBmI69dO-ZmPd{Z0EqxRJD)R#rFbaQh5!W5ba#J{HG4T#bL#zgYs$&7{!c(0 zOYIr13P3lA;-jFvBVn$8zbK*4s!}2bU}m^vj-F3dZOCrRmo;UlYh^|qbmj(BIBBm@ z1d0tT@F5~9qM->>;&D=?a3kvKTIB*e)BrKKl(@W&<-NRpu%GZQb>G)bXT@WK$0{t@ zxhVJLad)rN>RlG>3Ap-hYMVF3H9L}iO>CtvPu_2T^=~yQ_g;)D^lrL((M2}GTMxoD zv&4G_8+3W|zIPsGV^+dGW)L*;_|KLuyvJB*;QJ0R-4jZBl-l@vD#y-AgNT@&#e$2T zOySQ9Z`r=C1Sq9ldpzD`+u>a2nH2AfEY*$sC0qQ!RD}SpcMgGjxU#^`m@@P(^K*+k zx=+8sv^89ey_ZGQmjTzLm14Z9ySBrkeqrC(J=kP}SJ}-L9c2Kw4U~^y7 z&@<(T8l$p|5Jd2iTo3k$9LL+E+IXFDhmBK?V5jmY?yQNLYxTwjn!$A?m1$(Xv{n$` z=f!7?zUAvXZo$;|o*d%OS$N5)%kLKrJz;h4+l|aS$Z>s$^uh)N7S};7fx6{J5`kVD zg;w)c4B)KH;~L>0)3clq_L@$>=b9C;6#!PmRlt}i4Rlt_fMx?0nZU1S^8{e60?w_#CgTW#I8?QQl+E; z6ovCHFk{$nES#pCnVXQ4r%BMCnVGLk*y{#Z`|VfjyVJ*Bu$mBZ<>I@(>?Pi}-Y|Du zA7d$Qe5>TRX$R3z@g%>W>RI=m*pKML_W0S^i|yZPW&GtY9+{{8Q=`PO3S2c|z?OR% zJS-y9dq*w^+;fqoOU1XY#ONKx4;y7Si=>WE_P7h(t#ouoy`6(3MItDSYO^;R?1qNg z9MFlTgdjDyC~DUx`r=(^UVBH@EliAG6niktEONieq%MWhSn-VB>t0~uaN)g;19jl!(rGOs>;#>FPL2Jy|B{H5`)Qa61UuiOeLu& zhEdXDzOZ%Nw;oBh$z!U`Y5j%=WEmO7$Ey*d2kjf13qf`N zF0gMgiu_+XjU*=T>f>z3K=A>|-!->gZ^bTKDgX+e)3#`kM25Q5)2w?YO&0Y6GXRv>q#v(Iqh zn}ZlYE>my%Xoa9ex%fk!f+)Oc)@y)A>X_}g@vQ!9{j^1JHdk|E%EqO;+53~x*etSziTe1{hlTm|wGx7%|OeAxTLtcow3Pj`sn^A;~Mp zc-#hNCET@BE(QHml2u6G^uaBD1;<10*i1YL*SVSAb*8oZAG>mY3kHB1TDeEE(%dyp z(6=c>B|EUO7tcRbu+m@EbLTx~ZMq=pTqvL&W2XaF znJ0vABSn}}%FtH)d6nxOMQt?TwNcL<=g($-Q=WXAbzh z<7BhuU8TdQ&gO>5mYr(ork#Y-a(ww0lDFDp_EH zISb&K7L4)}Yqed9u)=k|952`&G>(k-nN_*!onwOert2S!lPxL~Gb0S8R$rKGwZNKOA33v5*k7zKLN9tg9c?ZY`T>=f z`pkw5NV=9=EjiNx&>#qVbH;pqT;qkz^Va&oLKG_6ii=j%^8V~0a`Ymk)@KC^p^efg z({iOfS5DGViE=qqA0G2rR?ggK-V?_zE68>f?CFZ_`Mn)+kg1}#W9BQP>M(H*rV|?> z&I4AW-l`A$--9&dFa=qqoziJZeCuCp-{YYR$%R2*HW$11oF}hadg<=QvP0g0Z7UKV zX@aB8NVczOUiIkRgi3i3$U(Fbi}?wext{yl>zczX6@EJXeZNiWmlKH%%=1SXJc_cD zS~IF2Y;Jbxai!!z3G0q#xen!OzP;|lhUpQyAPlu2Ou!?-WnpL1n3pwC6h~JSmtsf; zp+DmIk9}mTyRNNOas(5sJz>>hz>zN1oF*WviWBdq{0xd@ zCvEWg+r-G$Pc5jQNYpYK{f^{az$@)qn$YFAI6LTN=gaVvjy+!-{S{Pp>-7>UcW^EDrJ)5{^xS76SeZNvxxm$ zvj7B@9kHomsUu_MZl&U;xN`K2`P#Ioi`AlPnCIaknLrba$a$AT;vqSts9TtJ;hA1g zFMNLFRw;!nFny{)v+W`nqqxNmF&MMUdO`$>EfCD9BY{|BLBrGi~dbGl;hY?jR%-4$j5iI*ZkpemgVTs$PncHmu$(h|3aYtP?eoja$$UPe9Iyt02w$W6vbL zvB(v}HOEaXH68RtQYV)uj^VBvF)YyY6Ld20tK*`tCA8 zx-vkPnd6E)Pib>lq#;Qj~8; z)96fr!^-NajrBkK0RQ0A64;_@#7p3Qp)5mCgkT`8ksTLQ>w{AgN zc;uE5@mAfLYzbk!1*-^5(!MJl$>WeQ1dVHsLCcJobY^{~q({rK_B!|#&oFa59^!O0 zsjC)OUgu{eh9WQGVhgD=h(`>)w?|}vRrKa9(E?G_Nahlm-Pf>rOZc>HvrMu%CZ*P# zh6Y6AwPRX0%L!Y7Q|h#FS)THJ@N?x%fcUJs0&&HjDXuVaUTk=INbVBbU;=pJjcAV# zsrKv0CC=nHIAPsZ#WUyjKx~bNHYnDh|4+;3cw_p}NiFX6^IOY{0Y7**FxuJg#hGWV zJ^I~~&7y1lua{ge^&`w2%*65yyfEXP=$`RIe1i#7g@H&fG{r2TVh42K1=CAP@`JJ% z?95)cK-oqn#3h(CN`&UvGa>caz^?PG&~4X`Q9gb^37qRceCL=0SH5WwwIiGT;R#^T zcKzW^4r2VPq>_CcVvmk2!MeTZS7Sxjl?(x~=NXF)-{h`@Ra+$d9&c`4hUU%{hV|J@ z>+-?(;y%0N6xtx(V~-i1%A{oreeg01yGamcD-i<~)sNRNf1JSR5GBNra`I1A+f-h^ ztNSZ)f*NGM>{D4|t~k%!B*`HVcj2Z`$u(=<0?yc@1n<3JteY)CUs|8(W#{8e#rlFF*}a zLQzmP_D_!2^4nl~Rg6z=X_!t0hEbYvgq8&G1tUFO2-HnK!s5G_cgKiE%-#$Ys%xE?7WGPuye763KC}VmWGEaHdj8Q6@G-eA{PL@pD zb9R}}n*yh-WmSX{UXP?!$k*Gv^Hj&30nk|sA!75*Rg89y&Yh7{p`dqp#U z)k~w$zAfe}9Bfj`ET(ige@k4pVo|T|>dPY8mo*2~F$(`tDsOP=f`EmJOm9Y7K8juP zLyK(kid`M}-@t1?xjG8%Xzxhb^ZpZch;r>4-7scH(JM#qK+6{8Vr@<#)A!eau93f^Ei ztwOL@u82JfmT<$ti#p}ddoA<8;u-hc7Um*ROBaT@Oe4g<8Z&KXuURT%i3E~o6m-+> z(v8(M2y6zY7{*MGYt&mtdRmvg~tO^}L*$Cfniw-96WSOtT+7knF& zXAIBH(4sYB8rrR^w42I|GG^c#OtBYLN;3qdZ;5I{Km1ieCkjSCcORIi;O@He9*UN| z->>3Y-(k;^Knj_cjs@`%HgOZOgy%BK1;l4JBjR!x10T9$Wh(tI)mAEK51DN3%wL8= zd)M6E_fCdBD*(-?t&{H-scW02hSMH%6>-D&;*h}86Yi$^0a=5v2%mqfjpeuunI%+t z|1Ca?xP|B|$)a_9Je*Krr|iI&5GYGHuMK)R$O+Z99A`N8%2WV|y2a_1YEy`l@n1F?^6=H<0y`gaKrE@>rS zrnYLxMNz(oga;FT*6k+za0{w-KR*q=fc)gzlL!E-s@}yd=h>cJqSM+;mqovK8G+&` z&|^f~Tb`9yE@h>+{Pbj@EAR2ovZ{@%lTVAV@PdbIZ0t#Df`qW^3xF`83g_`q{RKt| z^kd03U+jf#?i{0k@cPJ&Jwq3n;U3(5U1;Z>`D1~9zRZMeRP<9{ma=SyBf3+1a!V4h ze}u$D7WL8?$Cd|wfiQ(lO|%IMCR7Y16eNleYQs%KhU`e5Mz>l+Vp`A=$ZR~4_sjkOO0H%+I>J{zySbEfuTYFY&(r_eEkcOm69HVC=TRK+n zxxpw(zjpVIf_p@uq^MkW6?b#2+LuUcH|+I7q`X-(rdf3^5S5nQg}SNY-XFxXjE|Sv6sHJpc;TME3}zU!_jpudA4EMP9Jf-C2n(aD~-c*u`ujM zoi6d`pPGF$#+v0f*_Cda${bc<7#Z^d^J-Z_*cMes)^is!v=Wof!)=blBaP~hxkUpQ z=b7UR&5wssWavctS|P$+=5cHJ(ASc-jWg7O%Er~#X`qlYvHtBe)`uBssXh4;WlL4{ zG{xn{3!!Dwg}jQAUpqgUyEfUxut;s>2A5%UwUz#LH06wb5GYFf17)d8TB!vhkdK_5 zu3Tuxh-|IaIvC%UM98i^a7p&DzvJ}Pkuj=eIX>2E(i1NO=)OvR2fMz*~Xxe zJJkQP8&IhJC6;O@Yg_VtN2q!oJG?=GmQ)|wz&$m~Tv~urGdJi-z^6B4Tk?v3x@`l@ zol@3URb$4jRnPaWSaH$@BmZzmXz4=a!MsyTH!ZTXv)dq^fVR(BGPMOwFzt;;f#HrX zxkH2E^%Qe${={|Kkca%|$j@2J>I&37Z6K{%tTTzPx{>iT zM$}gqefkCx@~`KU6R~#rifUFWvZhGC)Voz5T(hRbd}-)`<}>D$9R8kAC3*J3-OAP!D(%xsl{cJEm7PKb8aLR z{VW+pYd-Ya3ai6qQfvDX=uHJKqAD#i@v;af@$xD9%LD3z3B^ht)BOU^ThxVoqI~<# zuXc1c({>1veOi+qej|~?6#pzL8O3Qe{>zQOz)0sFLm_*oO5U+lJW?AA3s7jPv@Oly z6Mx+_>`>(C^Dwynn8g8HU|`F#vpTeKY$4u`Ee+ZbG%wt;%S&FUuhS!sb1=2B@bg?f1nvum#1dM2$D(H13B;7*pWClNz@Cqlq;mz(sOx zwCD>bjQW36eXo(7UtH1Er^xr=8WCiS$K_kn4X%4X0~B;ppnTIU_$*v+Jd8B$aHZ`J zot@#*n4RoSC+({0`euaY#0!FM^p}@K2gSj!);eD1%IGU_yTs3N`c4Luty~HL{~qT+ z(|ZA8f=#`sB9Ag2pY0h?NB>&hxlQ1eG7Z_t_Q6jc>|Hq*)X@mhuL}G13 zX13^$fUjf`{*SLC9Q}e0C>EoYKM2Iq6vE1WUngQoU&x6=%PgiZONB&!D(c=ng=SX~ zKmDQ_X+3tlK?U6BVi|(k;^B}Go!Ds6-ToKSk?YH(*=FBKt z?TGK3Q=mcBtS6lCcE7aLWbygfouQ0KV<#;CPOgk9y%(ywo@L$T9$yv-mqlB{$hgQI z+wuA`F7R>6{j>HbS)F72aR+=S|LM+EA6&?MwT(p~?3=ZW<8K){BR}Cf7z%;Zb&^%E zd*^#%EJHRO6(HMUNZlbGgQbj_sv%#2EG>|z`>R1695Pas&A^RrS~xH6PXAYfO=~ri zq0}&!6bjJ}v{;&PR+hzC)UJzh&l>NRVVyTD#9jKs=r|dRw5%NGiXYW52|+gF(Ej zi_0B3Cr_P+rIbfC656UG@8>$I2~1yM{dy#i)MGvVfQ<@5&#Whm_CwjK_~rRamjA;( zQSM7@5|q4TIWmhtkhYwcpni{p?fuLV{>o#nFS$$ccDge@8C-2y9{ywC#=@OvMU4Rz zsZ5c0@sZH}_Gh@7_m88uxc6OO4huM^-Bls#x-NW@*Qg8ZVzf{h#hNwcin`Kr65sDR z#cGRN8)o8cHZ_f(M;E9upkVqG-#o@8AGPdS|FVH!QYbsYmgq#X%X@W>`C`ur+=L4} zl*_QjdG^_odyp7UOp7&mRDiTy@(KwTbdq9bVnx)= zcQ*v^aq)Q1y0yj`3O)!{?Vp$*Kad3icka{WBSGE!*}uy=-8I5blGC5%Z}P}0r!SqmgqU*c$g zW{i_SV$jvm9>ZCryt>7e$M&bxX?NIn8cLnzPe>UTYo@pA+SFPiTNSTMa}KYZd<*E- zCW{V>=mK6y!CBe4kxgma%qOvd3FhfiIBR%cOM-h!Esz#R(%{>3;&OK{dot$>#fROe zX{!mx7qEii=5b9;M)VnGg?0Vjt{$xY;38J`%5iv}g0zNZP(WSd@O8|ai0wW(!SPtT zcYfsDlehKzvZO`J+btsTvIY&wg@GPbjn<{WqunboAN)#0Ja0o-$vh<22s}}17+O;U z$}7n2xZV^Pr*JJs2y2mLCyu|v^QS9!+euyoY1vrYUOmcGNtO2FIU>tOmzy` zIl9dBsI+}uCO|CI(Io!@UrF-rLikp}=P_ecBhmc)EUz}j^D&cee6BW8`(%H=&_IxP zn!F*G5m`ww$6{%?6B4d%0zrB!aLJzU&tAdaZ;Y9j6bjif1#Q}t zQsd*aA~R)&A@NbGE(bwRenig11#HIHjdKXSjQ7WSW!AfIHHT?R&bxVEF(mI}Ez3XO zjFS$BxTCx`ok#>DHm?pzJsJbldv|96naMz*I^uqIfGi2hhWg~k+?K5UzIoMsX5+w3o zTLVJ%e_nF1_gZp)f~%^5u|>HZ+Xd}A19!=SE!WxP*0UJ@z)AEqxc=P%fD8`c3()4e z9N6E963DR69p8Xh0FmBMbaq{%hVuP#AbJJH0ejpJk zRP3aMhsXCOuo)v_<^p(EwyW#_@lPc?((l}N!QfeX2*$rgRAWihwb9l6?3F$?QCZp9sqJC_kR8Wj{DSiwj~-r26EcN% zYzgVlOCMQVu#eY|nUcCp_Bgajd{QrybzeC~*UqRLv}(-?*yOQ5Q_XC4?1?Zvf<7A5 zNzq=nv=jU%d_2n^bByxwjst=JI+H%Bn%p-vaGu=@FWfG4=R0_n4ud?D9q)ky8XCs3 z06Xn2GU&RL4;cS;@)(oU_qN41Na#%rK&FuJ-U!Au_DH?4ItCao>!iDX2TDWhN3X|M zZ*Anz>ip!M*7uHL8Ul#j61fMp;#!k`55$sV67Mtj##yfMKMjuzKlbk!#8*eH7>g-+ zeZ;^YZw~@p_z#^jC4+!0+Y^~(2FpT9@p-`SiD?f6h%eB57$$ZZi$TpT4xeP1^a%Lg zxh{Q};x)#@5>Eafpba#$=Utv$7kL^q9|kWtFRs%MY5!`B$^<#WIJY;{ z^&4%pnBjU}>wm^v*h_hsYdg*DIE1IQvWD!0ojt?!_a}(Dxgh~0jNYx+zocWo5kx=@LIf6L)-pAN zdGyuXz$-1nY3S`B0I`0HJTdZcz>(?m&~Z7$@4vfU^)5)5=!n!GCH)PVdyEf@IH7*` z9w+dwgj&h+q+9r1lJjbpM)lDhFuUs$sq_;0m}9D?^P4pqH^#F zVYZMrPz~ADQ)a3O^vKlOjFDDjEU>^3NqEQwE3iNPGuq7SsyzOUiLfju_U7F!ma20C{RXAqb^E|qnV`_IpuAppg_Na8R5rqa((YA4ErO;5OE~v>j{-jbFoH!t z)jM!{B)uy8os>@5FGYKkuK~`fYWQja4A!q<9i;J;BQM@==c`S9N%#ds?8Q(18M*NCCVZq z0Gv=+PjIlIqawRhctzq;q{&IT$%cFf237x$TH!dD?%~RIhR^t$f8`!@%+$QMsg3w*8?lVjFhhS3 zf0SVLru3wP>H~bUe^O&f#GS4AD8YjMK_5{1eni(LLWD=0U3Y)B$jld)YR?UQ8>vX} zIJIBEAxCj}lwWoVx>Ou+@}B+Qk^)>2*LIOZe)a4%^4jPMrgAodFA|N=B*rAz6L<+b#Pna9y{VhUMw~?{CSW1cml}^NR|Tw;rzBf?lTL8r#cooEt!6fk~`DpyHGA+hbL zPu8{8^;Ow?N-B~(bgg!`wqw?Bb0cqm27q>z$HMp9S-KzH?>_VoyxMS zo-%}JRe&cF&%vVTx(6oa@J;9`*Ewn8i^qvExW4KesKQo{v_LgUS_!K)6-_VCC&}U; z+?*tI_Opg#!}3o!HM4rx$zm4bxdf9WLie+*Y2viE*_786|H7MMQa!zO`!P z6F^MjBhKL8waE_Cu=k=!?ClRD7D~krX{Y-#dxgB9A*GstD3kbKFj2H|?lBO~Ee}$D zaAEVj3A?hH#9pVg7!-$EhWQy($s|l;6P#BIco#D&$M{(YlccqN9BYV1_uUpP=D9VK z*ONran19hdUYp3_N_*%dWgeb|6{fAv`Wv4;&bib%=jIoqD+_n0unN5avT4UUsu_Fm zHf~N188f%ZWR!_h$l2VWxx|G3z!Ft;X1@WeRyzU7IhS2wv0lO@4bd=d3$GbRyv|=m zUhWOyYc4OF|zSpa7tqkP(Ju{8G}g>!*zQn(%H;*Ij@mzo-J!o zPQ5o>&vEZw3;}tKu;A&dtvxkBJ-=;qFPyJBa;8QC6!LX)Ve;%3Ae*@e>z74~{7{hwX?1!p+gKJQa0J{S2IO;osl%89aP`;!`5w1oRMY(3#LYav6i7_m`R-*{*drjvLC-@DN-j=`7nvj?(i zy81g?;D?kKINwP;<_kxwE|lJijQEqFB1h^`2V|m?v&A1);JsO^zYo-@CUmEl>5@91 zBdJYy^}!O>e$3c7{GWTx51$(wKdE@et794>4{S>mV&HzHkO9+*I!6PJ@orKf;le85 z*52qdIhS`E^#Bf*vjIITh``XR@~En(wWL#QOCg_|e>g#;o~Swre=Sq7P*cmsmZ&gi zYGyx9I?oM>q!X9H$5$W>YFTfQb(3=$#qB1wLXm{*BFmB9noq^WWGf+#S-;!7Eb{6oaBpv`W7NJ>cFN3ybE)AcXq^Pf-Ay00d898oKo5B{# z^Ho?;p!oEZ1{Y-~`pDvMI{-Rp+n3j~?--RNh#IdhZ98Oj8R9qAmtNz~k0KX7A}xz- zoIjLP_WD%{e`l`G9VpqtUb|SSy z1a6-a8u#3MpQPC1+fS|d|JMtEJxz#{CGz}>lj?e;wEnrNzddh7FDn=c%?i72Z0STk z&I-+6eV5AFVICU_SBOg)dKbU?@eEJs_2zhW!Yd&)dXJ#ZFJ1L3EWZ)uq6aEF4ZFC> zjM1%)<(D^@#FI~n-RQU{d@s!g(_MoYX+}pL47E|-hc3tB_h?$ppntxd_JT*1s}Y6f zy5(#B2{AJsr1ifvSFM9Ibsq=l5H^u}87Hi&;#=ejy(6sQ4<)O(v>$j$EVQO({8wc! z`QPB=s;qdD5cwe2wR0*SzstRTlVjS!r*CAustHS$%OV!4Mjs*>x#) z%ErHilOdOhg&R&g#G4=Uvx1Lr(KRjTJ<@y19qfOBcxP-3c)>&buGr|Eo6C@vCJ+ zQz93in8!*m)u)}<4g_4p8z@?^-t(4wSDG%vMsCOS{Ii1H_j4c4WpYDpE2>4c>L|l; z2i?DZzemNzhngyWQ>f5mAt&Fk(Usi&c=l0MBAG1KGr}P&$(fnkLap&J->mnp?HYvMfm?%Re{J&4Vb|{XsT%bS7ouokg>kMBm%Jh7$ahT_79=G&33G z4pNGp+q}9~?dUKG55Bg)v<~QWNUdXEX4q4eO=@EiWS!NlxVB#=OYL#AO>(Arox@Bd zAtP&K<&2eSMJoT^KbkR-r#+;qI*!jgNvC@z@xua_b!AA5&X3^8e~bLl$L(oIw?`2N zGbAp{)3NfuH#M8Y1oaI{YqvwU4!*=RzuxQC^;pt20%*qN&%5{}`xv9XT#xHRk1O3n zJ6|W*zFtE}Os`Mh0H$64%n+G;+jfk3*#!>P2y5)=9TbBXFYKg#P+9v}|%2$@UDOP&k?kAOKDt({-JS&wAjD$!gh zC_Z1BHHX{U)Vd)@qrV;Ms9cHixEG0#SSb6-KQ(35MB{zYHf`uLigBGWS_MT1joM#J zKQH7ZF86rNx58$O-Bh0sKo3)9wp{@ruh~gU`ipw$&*qu&CBc;Uvq^&E`56=cRXre^ z@?=StX74T$Rpe9`)+rAyJsnNi`NG-vnKAG3MQjZc>jC+W_o+Gd(vb4132SH}xKokd zR)*~rf5xm%KL;3$;p~_#P=3q_0Wkq{6KG z^aj_>!1>3WZrrf)YDH6RK23f4gUrDR5=nmJAk}zQ{1Yj-`FShk0Q&EdH1q(vXSU!_ z>{6~|HJ8WZWBiJx!Hk8K&~61DYBS%5QT;cPJIJwMi?%m-T+WVn{tU+@W$gtVXS5Saf>74^cfJ zYCl(_$UH_fG}6@;{?Z zo3>a$3XJ>}>4)97U(5|3%j&Ln;;m9ha@*B0+8~>v=-3XWF%TJ$XxTW$8&Dq)m>BwUj(bK9-_)N9(d?hL|+Sp zY3jgP5?8eeQ5~svqwThZ=0R`n z=B>uT*?KFN@_TR3?jA~g`jH5n&zX-Cguv5G4%X+BO-B>&V|BE!Gp)kH{LUH4{E6hE zKU{lDk?t!*kNJIdNESshrTY4(kr$iP)@Nh}K0b2*9eS8cU8KHc z6QgZ^6^6$%Q!liYX%I73L#j{ZU(q|nZpN#T`LAsSSVGY+_cOVn6>LBKDu*r>%@eGQ z7r5phazz40wm$9d=G9uY509HNYz3`wO%FEOWF3f|7B(XGzpJP`ko&Y}SB^EVXI1SC z?h_t3AK@dRvTd~!Ce`n}f+1@6f6-pl*Jiy+L3gAS&W&pZ16)~ZPk-nlUiWN-uEiw) zNq-fNUCx&Du@)jo8d&CMToV9QCo_0pwKcj;HEfsyI!kt*2im?D%Zb}$y1|3yv~I)c zE$$uyn!S5~7~uSM^nx5-F-9jyvpc~297hi<*`{;5G4o{jB&(Yj?QHv>g~3OL*X6!( zqffVv&j!lha4#kqpfN*jI<}j1#^U^1vrNffl9_|q!o+P=}{`a6J zfd|d4zx+AOhC0kR@c`|C?c^!?emcs)Y1p=oZ?1N~AiHWW)7a%qG#kJ_gMA(+8%ev{ zP!U!KYJKs>m@oJov;bzZd%8i4BV1K__PJI=y#`q!7vkGRWmZ?i{M={Xh0jjUw@w#{ z1i@EF4!x-j_p*TN4i^ERercuvnYGkje9!x10gDuz$|uO8Jx2nd7$Kbln9V!c&OF<8 zKfjB687cU6PxU@Q{x;s> zMVEnJ-H$c4o|FQKJKvjOx`tU&%M7p~XK^mk}DUlLUy1TpKP%7Qs zDc#*A4bt5m(%tcG{M~zJ{xjbhV1|Kn-uK;m?X}kPtY_`L@|OYp zVTdGxvvj>`5u`RyGP{??Ped4I37WhVu zs%4;R)w`i=-bSX)LYa)+B=59rV)0h!pt{&xqISCK^0ngZE;bc3;iirrFP8yB*_UbW z0Od3Adp7|Qd;IiGYs4m>WRLC(I9K*b`wHnu9k>i56Yuy%@p(ZJZwYesFp+Az+|Xj% zR#Y+&&DkZ8N(9S9@)9~zjTQCpagepsF(kF8k?`pO2=Z!%ErsHHXGoIF! z^NC^Tk3jm!rsOeKl^Ax51FJ!gx$GCHv4W-_#M}2=lVah~uuxBVe#XA?!$zb|bn&qt zm{RB6Ki@EWWBpoOlg1+%ze?m`Z{^@g*dyqA_RA6`dvPAhy#T;5>$Pokn$yvq-iw9E zf39-pp7Y+J-{ESyxZCwhPUbGls$1Zfx$K9zy{SAv1>l0x_73eYwuNB*kd*skK3rXE zK7l7zZm)L?-&MDxQk87uw74ucF<&&ic^T$*NVmlEpj*vKpnBGobi0_L397l%%Nq~E z)o4plq6ek`%*xgCA8h9tOF)r&`ltRx+t-!@zS-4hMp1B9uIswR>4khwEjFmb{9XV% z+u=TRl|ho{9eEQaPtGnJmF7X*VqGhT=eZEhXmHQHffJkAgBK0aTOh0{+umXduiTDx z=(pDo`J-h8PT`tl{tY26OOpM$oGX`fIfi?5bn;q%j4=O)K)>86!9N5iLr5XsW2R(U z@mvcLiF6R?BqO0(FT&e%>WDx+zFm?-s*7YoQ{KV5-Bfe^F7eS`rDtbzvu%`jNq6`5 zauig8Hfn)-UGqx{jPD{k9S<6AX0vw4&=X09WtcRL^o^VO(y{c6_PSxYB+LoBlKW*l z(3^m`)5h~lxuewh9jB6-rX8oDyoS|yHj*RiVF*``!6#c(YqxG!C@a&LGh;8hzO(P~ z8H!cHP=YAuW8mzGnt-z#NoRb6%WF!Zk9N<3tFSqYgYB_@bWvZ_{}~KQaV7@Rai~Iy zjmy8H61ZHF7~TI?qRidS~O4fp~&@iq9w3@^i_cB9^FibkMg|@5*&Qr9o$IjkuDhM`5%+p@~yT zf1q-@@oK0so5B*>3u=pz0Ykt|$WqOYNg{~Qx{?$e>cLglYwAbB-auKD!8{>0!vo}c z(`N@BWykvsN;mzE^-6q+Tdq=!_#c!uBa&7&Fh43Ul2iCdTc@ibDhif*Jplvu#~WHf zS5{acMIhu>kEaZjh?7)a)bijpAiIPBF|ECEMOo1cPDfdk5@`4fL3f`zPQLe>%}hq-#-JBt&OoCt zn!Ehy%D>S4I){p(5t$Q}=?R|;Tp&Z4HCSr{xp3IbC&lNjiH))IXWB%!K2lezVE0LS2 zm7YBM{YjnVU&x0$xEW)4v-=~1oX&6;4BQ@csxef zmn`*#m2F{Q@cW!UHWTZrB4!$>wO5C_%RZC^6KPyhK*Twl-rEXe`%X4Ogmz+Tn5!MW z9q{~KXitpknjQNvIeCGK$muvlQuQ7XYn(rVe$aBZ6*hc>dCGv!h}(pd+1)U^KxB|H92$~fBx z`I}SsQnup(`n4*7^X;M>N4G`;Z_*{{*Z%k04ZG6|(9xx{E$Fu2!9fjM^559`Aur2R z?ZYXLwdH(6|J2eSaX*|r*SHfUB;7&bW{#_J)4BO}>--(30-Mdw2FS{6jm}RYdVAMc zOiN^9(k&6dT7!YyTu53O1yWJ$76>< ztt-HgadY>vAu6f803lfVR|Ye7Wba2+Q%umS^il|r07j<96woQ(r@#uYaGzW^^;p!7 z_WKE2Hr}_#*$!mxX&mD|333mZNDU{yc~CsH7^M7OQ>E>l9V>hCq_734FP68nr_9xo zYpUKwG@l9!xSKKZ3fxn|Pw@=}^*{RdtlX?PSL-s{hm;qC0Z>*(naHn4|b(_Z)LXDx;KHG$XrkWUU>3A zPYx~yKeMU!^mj_9_6|aS%H)iq=yiJOjmG_*LKGV^aZdDD`~#7qhQ_!4#h?_1?R^HI zAn2}c9=Ni#{Ciq1O-)$>G&Y;6gA+I9D1~Hv78LKpDP6xB>YCFYKDa0KFNG2=-eCKm zdib;r5PPQe$N_v8QN0EQAl;9!rc_tkX3`7$-DH%_puNZ6a4AQ6L@fhv#n3_P=s8XL z!&sZ-k!zld3m32Z+g~Mr=`}qTFGIEu+;?g3uao)0hEg9k?UF9P)Nf5R{DxEgQGxQ5 z&G*f;8FMiWe}xT>*5c6GGksyFk3-~+I(S{Q<_1^eB`5T~E99$-&kTF0DT^%}3aVvY zxGI4u$iJS$$xdebyya^;Czbpc+yJhvz~$r&b(inJM^Y#Ds{f)X*M-8-=nOw~r!614 zdxijZyczZ%1*crcZ0VSpQkqP^<7;%|4ME0l@boNA=eQ1Jb7a}iSUOkAu0Y@2b$UC6 zxVQ8M>d$|DbJ~1}B7T`TddZb2>9T)tu#hGmoYaebS-gW=how*Uui$w9VG-q;(6$Wp zwzVGpWVR{WaO%s^Vc8|7vPcT`puBZQ|6Ge}!_hw7pGJkBFY|FPx1*q=oYV5n*R4Kl zQ^)YCpH^p-xpZE+5@AlSYn@d>u!)UAZIu8D@NFgkTnc~U*tV^2<@Wl@=hL6JhLu$S ze#$jYVtLD!Rt_!0edGRID|@0}4CBaT?BN&}w9v0DdywXoOAFDZTeo;2t9gX5@A9yo z*ztRMQ(uT#^ZnqPFex1zs-~(yoAcirCm@_{%`cTzlE5)#@6>e+j;v6OwV$XDajlA zUDaRa9-+pu^WEShZBIG`GQeOo2J+xtWR#x4%6zg{J&t9Vuq$iw`MHId-B5vFpa=YV-AyU9uo zW4?tOY&upBF^9&QlP(O^Ity+jnLY-A@I|=T90;=hY;`v#{071FY6?`~y#huZnO!EU zkP@A=V|S+$0b?p4v2a4Iy7)*uCD@4BvW)kIqou8wiDcu(*AWAV4l9WdZO!Hy{?wjb z?%kZQJZtwUUyrqPq_Z@<2A^yhds_;0O~R%rPqDGQk@ESEE*6l6>R8zxMm{21xwX(j z1L1_2fI*Kw+k z4`}(b*aH?MVNEb7&B$XGUU{5>5uCQcpdP&QgQ$Qh7Vi(fJJ1Rm8G8mz;B44z5^x<+ z(>p3ynjxCoa5@=dA1z*A=OyMA^mGfpv-qr6ME^ycgPc~R3SW@^h{pmBqcxOmNuyL3tmR4wEz zx-|W~NUgc}ie(%3OJC&T`Xc6*CsAxg<{}2Yxe5aa$(ONpH9)i{eR=s&={)38M$pdYG1#{o_t}pMjQ~-HA zXmX0LyeejNuDI~%Jj#nr8EG5$m2M0JDnMpDBv6cJ(_Se8YJ4Q7r8E>-J%B)-Kp$xS zF>|{lv2ZR%^8~ebv-@QMAL+)@e)~PQCZISFkWjN?Q(eRjv;{&jYNk40bxpokJ^Wa_ z4g!gfr;nfwuJdUOfS}m-WHz$o6k5AB29M8j&br#I>DjBNw_&TeadPLl|lG#H95 z|BTtaNgif}sDa6j0T@}2mlwWrfq-P9Ne@K*(2K4#W;|cQP_6{iEd|r^@!HlW5BbEg zy_RmalT+x9NbV>^Y5new5wDfAv4F^#w?4dKn4%{06sGYR!%Y3Y@5PB5EQ;O$PCR zr|qX!)+d$Sp09|bI=iL1rlXCc!RTtk%{Mt*BKCk&_nT)V8qL4VT-q(v|290i3DQGO ze7Jz)tp{&=%lWSP-Bh%V3QIKbH*Jt&WMq}$ST1RSh9T?Av(5b57WlNHEdP@`JplQ6 z`u@5RyL!`I`Xf&UczpLtd+EQ+2O4mmiw9G4eWIo#?w!Loy$&{Kc=DV;g=^}HZ9xTe zx3|sC-oVtXZ#+iEZpWf;0ehFl^pAIi_2#Y&`1`f*XuIChWH+g|93Km{2)SHc@mU$0 zNZl+0|I5eGuax#RRZ8>FThR~lRlEAN6uy!+yj(48gMEo-y3>zvX08O(k66FEFVZyr z$DcoWb@x*G`fJTX7i;cRK7r6qpqf@&rD(YR!)UCUxO@Brf3w>L)H$Sz2WX-dI#c6gNm-iVZb}tnmu&L}(}~3qkeC(c808yuU*Ghks=O1QSuVg$cT;Kv}LcjYH^>r?e{I3>306DVkR7C4=djP5v8gg5ayx2GQ zS>3y==x6n&3lPCUUWR;1D=zP`Zeo1Uv=eu{Onkz?=}%r0F80DPOWw_}Jg^M;*_z(m z80sgKKz0Y;5A)CMJJHa_PRpCVcR=mU(>qz`#^D|qmEecf9;l;lr z&I`TfCaHFRnH=YnjX}Q3=l&)3><@n`i_J}Rj@rXt&$fZ&j%&{F`g7vGQ~9T)^&RKe z$og}Jr`Q{UQSc-`|9?@kqe^verv$6wA*QV}btJd|W6xZ&TXWk;t+SJyM%afvJZotq zGgIo07gMXlU^ldee+El4h0 zzyu{<3d$GgH>@)UX;9C}MN&N+hhJ)UTz?UJkio0!_@angU;>XfPj*1mv!oA7`NY23 zTPpr@I@j!~lDxlDh(gxkpnH;HE8o>tv6#$AI(WomJ>UaUGI`Y$L?KD}fD?}5$B z`qZQA!7|lgy^;PW9o$g+bBDUxDSmdCQ#@;ac+^94bLyD_!wrwQ0>T>h` z#?k8JB~tv0XyxUVu@n!ws4NLSqZTWpyx7VeHLFXsf(6XPw72kX?XyKr$QXyU)t^V( z#U$xXASIBaQ16WUunJ{*4^X3i;dJ4W+k^JPM5wZ7D1?iD%9fh*?Nr2{cBv169ZB18bU)M5Sn67eooWT9)7<|K zV|Fy4b~;zRJ~VT!TNKcz3fi*2h5JSGh>5*M;s=+BG~mn6#NFLRD{4p&$6PK z>}J1o`RSugru{y3MdhBAsz)kj9WHI_V(95qRPyrnCMS*59N6OHAsy^7u>`LuC~hl^ z+)mAynN{Y)uPHFNXqoaWz5WN_i=~vD2to6mSzjRlfLDW;@y?yXjGBRie~9)w!qGk7Td?%DFQI>I44-0j~8lPUDozVKS}B$gO-iSGPJh-H(}W~ubwI`5rzCzgOB(> zjT1plrK8lpp9{Fx#NFx7wxb)n8+!sQct}pSzU5m5g0`#6Q$e6v7E6DxwVyN2@2Zzb z6!vH3kMRXiE6(dlHi5z>UnFMSSu?{Eb~5>RNZItaXihqX=*BALbK)9;aiTRG;mZgX%mHlAlT>!ve*P5pK&}OA9 zoGOwiH-q!h392&JfzQ+Q&qOZ%X;GL$sm6oKNY5bHM79|IcCMLSApHoKo+r9J7oF|s z0+o2UUN*;l8vy{_pT?^GcpNV*Tf#JA*>o#$9W|VGj(^wd&W!oE)7_e-rK{mog94t% zqg|(7)K6uv;}F~o+Tyis4QBjwK6M z?4TCGcQ>|b&d%S=QyJd5?;ltddpNymW30zfxJluSd2yEb`{)9<|29i)<1AaSCDQfg zF5L2w0rZ26=A6D}&zec%x+BgsR9hRbe=yTy-b$B=?wVx<$i>xdvB2@?`S*8%X8#)K z0*EK)r|!#^SD0_7a>U~S*F$QLeN6-?Eznq@4~D>D<`5OAxvwusr)(z6ZFpx36y}*m4Rg|dD7c6plYe|v_$}5k2ytYR z!{UhY&j~}A5r>!CwFaf za*KCtfxfmg*LH={VlcLk!K)AeT|jQus`iH2>eoYf@yic)YCS55_yu#f4WUuP<^!Ky zkU%T&ioYNcDicsK95Kg}dH6cr*x2G8Dwz+k;&jQtJ_6B-$9ulieOK(wyOw4q!e4uN zEoic)IUhXwovU>maQE_g%?$y^b@}OMZa7=r>f$%(mrxsn%*$R>cmP1#4j-Nt-u8%_ zKO1O=?&YtK0n(D5VFXEct54gDgTgR?*dzx#-aNH8HRt;Q(vzCrLZ{?(i$rSUX$TfCJ#^;}jl5jcK`&3K z_ff6?bJ38!iEH2wf;5j10YPQr*dlmzhO9H+NZ9bp)#;k`^aLJE>I_LVCrA@OJIBfS z5|iP`kY+iz0%(ky4RFiRN754nEIaG|V};|EwcNz*W2+`xd&pixEm=VTZ@^~Cr^Ezx z$@vI+>3W9P83;1*QiaOj?ie0Ps2uIYviqH|Cn*y4sG-U7uRi-8WW z@Fb94T3-qBHN06b>D&M0jqo+h-QL$I0(nWu)Y+ zxzX{e)cA4~VEmV!ZFxY%=ntHTMG;yd@U1-rcpTzX>2nJyu*+_tA3ubio4N>Wh%e7i zwbs6|u=H?An7ijQx}opUTb#Ob{ehd z$)*Y6plrCfL-fnbB*?C=ANw@g@m15gtTl}`+12v&lxMig`r=#uEI|@C*(Qs?UE!8B7b)WK&M;CI8{v(6y~!k72#*cpi^|ez)A~A;pT~LoX=}`Mffhn&*#yLx+nl zgeT@{gv~k{YPU*w(=$yyRrIkh%-vqvPFeVt)d}asGW7)s-}ElTU2lu$($k6TEjps( z*JFe>x)*l343Z+Wd*f0NNRB1W+UbNy?0iWkl=%R5Dj!G0(j)37)w~ies&C@{VUeOJ zk?0&_;j32s9i44>M(Rh%~CI&s^3lYIlE_l%9+a`W$Ql&Enjn_tN~-Ypj3di}5zF>H3S-Kv3y zT&#IT1cfZk5iVS8y&p47FK}PDX8#}pRhuL|m)JCBNaZZY;nbgC|0=xy`?N%gF<-^* z=be1U>c`2{fx!_KBYO?;sjeBtUi&lV2d~&t2YHt4lB-MeH);NUv*X{U9_|}uR}^m2 z2Z^pwiF}8ALW*G^LgG^pVX>vaUxITaJ;Ng>b-gXRU46l&B&;al$pU9WeOFE1zqN?M zW-ngr%VMKp>h;MlMp5|Q)jH_RiX?5uL(FTB9P;Do%%EO1zA9Wr#4qGiBcgH!M2(y9 z95M5GMRi^k;iPR^p4b7lgW8@yDZ3UfJ;Hjixk&E?sl+|JBv2oSw=y4n?C`nBp4O#z)n zQ+ndltp(;>e3;ULBy}+uxg9vnz8||~N}daaO)d5;s9`cFyhHsG;`TFhg{fV4Co}Hk zsNwVW_F8CZ&aU|Tmg&tKOSP6!9mdq4$Obu$1XzAyd8}WgzWu*^S@g!67(yD_Aaqhr zLi1&A`!;YP9*;Z$j2&8M^M=d^&5sQO3Q;nH*2hEp?#C7HVDWem@i=OXOaM_EKSj*6TN0#(3racJ>yl2mD!(*Y35aSNt@od5I%?)1wWml}jQ`3BL_O7$K!t z6^~0GG<^4&KQBbrl_jE@fqlc%q9Si_)wUObQp|CPKv&An*B0z4f_AYi+QAXSD$8epN|z z->KIxtF(-dg|=4|)=9i7HQ5ekY56ZA9AGCDy~ry%4!;Q=#!_T(oK@S}4u!24ryI`uhkQj-T5{E zB234UaC_C_)xVW6$ca3A`_OXTC}5`1&jmBErEGpd$qAR+4EI$XbL+$9PZd%Q3JMcp z2@47o=sBkvgH&g!H6n|CZwogs!*Gp;c@#&^xa^|6`_Z_0aPe=CVf^2{w@ZII^$uc4)s=5Z>A z_=}p?8{3MxwF$lfqkP*0NUc$whelP4)i(u&zCpW3Rdf5kZyV9Z@-4d!dbm3FpoEb) zO(TCdx|eF2J4IvD{gIKR3stG&Prsn9sA%(CK+n+Z&Vrb=ANujw4(nvPWz@e*7=dLQ zA>yEe^@=rQt@!ohGl&TE0Z-=f2An=nfeo>`YnWPoX8{8j90v=Q6O@qD`@;}KcatC9 zu*4UwY3=cIf(OZI${nfA(4*IVVr-l3WaKbA9%N`nc6GX#%xTaC!=RdxhHkK9r3Ch~ z6FHo1$`w=bW{zELaL89hjn2H(4+N3@$G3~(dfS;tP&yQp1F)}A3N>py(dLB(&7cGX zvYtgGc2P$orAlpbt;rzOK9d_t7%R(Fi%%;)D{CgJenSH1^2f~0?KDZrHuWy!__1aT zg}BM1C)br_+LlC*6(5V|29MhmnXvS4=4##|tIe zS9WqGwe=@&AMSRz`N~*GAzFXAUWq$2{~*siFn6BcS0kMI77^*^nsP$`T;y7-Asvg! zp#1PigK%V*1KVwx(21jvvlq>ZS`zgqBa{?I9;Rqck?ZZc^XMKpF27#|120GZCR{OC z6*Zr#6vOI0z$78Sb_v1+sWONms{3IjclHrxG#*cPchobAJj-c;WVcZ8=-J9vl5QRO zihL=5zb?t3X{q7Pb1vTMfTguTE=Jh-GvHVHnA!fU$k?s9n4b)^r{e)7>V(#kw7!or+C&>x3jz{m7??{d-oPSsG$^H>mj(F8!iJQFkswrlUjtLTl zz3Q~t%@GZ2Ic?zDolYekG=7qsI(sjLXLVeYt>>LxT}I5H)09Lb)(W$lQxW=6sHS0o ztaVhBDz?PnnXWJ*)tpq;UP~8FV1<0++av`6`2(u#7(iYknxo! zUYaiNJiUP}{H)=YH*jfJdnfI9ze)XwQq$Y7$|q>BXbV;;w;El&CmZ}ja2%;Oc_b~f z%fVPeLQFkE359;A4Fwwte;h_h1#9`9 z$eZOf<$FpxKE$sCo>z~u#GS)zEn|XIqhX}Qa=mjKKULli;6Fuv?mq3?@~|eO-t?( zo!uI(mscq0GXu{QkG4_@DpE4-gK@vOT6;$Is~(>5v&MRq9)4OeMwnF|n_<0?vLa~= zmBdTbdc==cuX3TewAV?bsI>#|CIzC2y_WTF172Yz_xPM|NDy9plfSL*b_nw8|NX5) zReiF)qUG$F)qA%>mi>+F=iF)6TxxtY7nyC_*pTtrn&2^dGF}zCAl16S5iQ0``_cvP z>~M<<-Oi6DnKy&i+K#Z@0?+$wI#@*!%t^b!3aS}x=Cnp2ls$e}_>33bmism-nO~i+l+pPI?*Xd-nAb#1A0atDm8=jngxX)-gj9`oi7Y;*8ed}W;q3=vrI$3 zb>X?V9|z=d|ME|XsP)%XPKCq9pFS+o(0S*}_}3@&b&X0GR2S#g&N^^p9EXmfP`j8u zh?^PKSXUIhptVYD#HzUCFs*7Dd^;%NS^VG`g1bir!bDKQsp8id|N5Ubb11Wo9;G>` zXTkJg=naI`GML(jtoVxMtKm?_SNgF`t@bCQ3cKbX6KXm;OlTrd%zrkg=26>c7$9* zoti{Z6L+pap2MDqaOPdpBD(paB|p(HJ4V*~0Uy7Rt#YE}PvtbEJHuV$KaeFxtL?I( ziDPH%>`rf)TQ!2xKHW=1Ram6`<%-%`sth*hmQSo6VT0N0^1o*xq==Eh9zg6DSw)n z3?bXS%%-a3SbE(5ySKz_zTdsQp@Vffg4(fdO6Ry=vqY@6H)B2@tAw;&@4wKbcE+RO zcaxNIMNDq$z@o(uwqmqUGj*HS5cJM&&Vy4dAIjLXffE~41IhN-T);?|gqr8%}2IPAfg&w|Bw(

F1-qsqTdsDSV~BH zBKy-0+xT&5Tw7*qxjTvW)kKbg_Jj!>8e9t&yhf+)@oHWxV|O4MjHT(7?pp7(Oy3m4 zA0)jd4H_WUGAOuT$TRsy?0)BQxssC8?BhT28DyWPO+ne@^w1=g7fE*_Q63zXSjinV zpQb(r>3u6muusbGZ1nHUOQ!2yP&@rHeUlBgsZUvY_ghkZ>f)}=d}Q;UwGNLs(e}fi zsqJQ=DD(kt@=c3(I~{%&MYESUg6=qjIvo}}va65Cz1Gs*@28ZaFxVYURAimgY4D58 z=TPENI^3wlz9XC6@J!Y&z+CJf`i>Ei9k9tIjMwkG`{01Y@L+ul7fr$nvpZy}D36%1 zmLEdp1H0w$Y>foA-x_m-Vb^%e1fD6Jx!P@zQ33M&y0ZA3K7=4NA~dHM^3fZtR^^~ABIn# z+(A*n5BjsG^2c~Syyf}5*S4jG5XeiF&NajeKG|@VD9U?8Xa6&$rd@TAoVE&u;s+1K zu2a1ms8bI{BnoB6m;-K^$`*? zNsg1$^h#QD>|jz6%?CxyizJ0UXs-SA1QY|XgD{)3g02l)c@*vOq?Ttw1>q(6JXuc7 zGo*K71`afIeXYUe8C_e1F=GaV4At_2c4gPPIc2AE*6gGnZpT=kY=%~BHff1w%1G+r zr~witw6|vuKD52KK?I3Cc`>db45Ux89Q@dM1<61frL-inywntaR-e7Y1F_~bQ?+;s z;erq+Db=5&^Hg}MNIybS(D|~9KRD=65sA+)=+y1p@J5?Pe>3k=RaW>h+Nc+$-t0G< zKnVKv)c3Z6S#x)y0Q${Ws5DeJx9?9q-=8O3aFd>6#>h|qUb$IM|>c*}v|&hDFAi z{kLxQ9gF4301Jo1GfvmSiCglB;f-sGzlFoFL`|YOrvsEB1Y!gEv)2<7GSk=ccMa@xSlqM)^9~B0E>jLi{`q z8GF}a(Yn~U0Xeg7f}te<#&1O5K-lxolIoJ*@W@tr=EcOBve9rOG!O$4>&l~1bANR) zSEjA0&!ZEiVhm@sqBVDni4N0rsJ6cfJ5PhdNy+}GQPM;nQN7{JX|7o0+%UVhG_Zwg zU$Mn&A}C~bXhUK3TH?=NHQS~QS4LvEy{^hW^j6~-CE51N+U!%B;gd#p+a%)Tr>wS6 zn4(Saj(mh8xzUb{A|vr#%j6K>y}YimvGn~*MoiqAInIgUn#|#m?s<0A@K}Q2E6qpE zKyw15(hoAD@5kR30MKa)X${_GIBYd>&vcVBpr__LDxbWKva({cLxx*sTtXYCEs&cl zWUFp^a-*YXv&q}O1pJrAdMOWiq8?J4@t~MGIoqW)bbmoRD&sa+I~Wr4gv)qbd_bC) zPIXE2gelF&-#|n(r>-frbKka5%!+*TJsr{1I$5o$ve4a82>{2HYvp|>%Sbu=+{dW) zR%XYkO+%^(&L$LA*|)QEFZxud&Dh$yVA!1BL)Y?)#!ISwIE-c-Vx-te&pR$_7IU6o z=bg^ttRAo!Eid3?o}JC+5=CM$YA`juRFil<=#CHt?1*~I9p}`STW05>wxLfd^tDy_ zMHCN`#76WuIb)`+KR>|RGzIZ9nvwP5-%d#g~5F<`X-S`Yp4JyFZ-z;myIW<7_* zN97x$Ej;Qrp)vryg!-Z%uguvP4U@f7!tnt-55L;l3JxXaH)tERref7;X|G!nXrJ)L z3Tk;2jZ;Eyi|+}2!o&7e6I_>bhBWnPPb8Dm;(lmA!L{G@3bJ1E41C=O)Q#6O%oX-t zS!*AADz9FE5YjQz6Z(YB*}qL`8|=Pu--6jztUZT2mAR56VmawNhQG|pnp_aL+~myrY{tuKYe+PpNWBDg4)2LM4fJe2@B zUJXV(R9PiflGG@#Rb;A|j^%P=q=rW$R|8}X?xXBjz3qFMtJ!3A#dtq6O<&T`c_D@i zDaU+ljxm5Je(~HXSbel1ZteL*9}5+66Qr~2*q$sDZmp8kS&zsnz(e?o#>8Vw_X=jq zc{cQjb_mzM=i~!RKwpnaP*Qz-Rsol0)Gz;&X`UMj2_(P6Tdax$!)a&B5U0hVJ4rZTL^=Cg4l(zO3m$uk!ufI-pL8SAx#MvdBSh8{##Me z=b76UZy#sFzsY~+y@aEPP%|7H6FTHkgrz9XUXFoYltoIe*El*;HM(WBU=&~eC7BOtov&BTyTB&!k~3hMrh38qsqA;dCuwJn+xz|{xxet&mP zDW!3T^0jKB=qB65^sV*5vH{?SyuHd^6U}F5oT$KHpje0jyZp1ikZ!352jG3j!xdxs z;N9~}+J3n(Ya$mPgHqdsmmuAezg_$uQcO+{AM9P+jQ+O&)yg{yugTl9xoUQh4~8Y% zp%q7xczvJy3K_1|5XLl(n`@}rDPgU#9lJ_+3ja*K%|-4s#QefaT(y+P!wPD2Qr(?b zq$}L6#DzqOH_}5y(|!qrQ-BHPCua26Y!&O+L+I+1cMW&DLZl*nc$U}Q+?LyLuWhjf zr$1reaR7z47Hk1bw&+u00RXY~U#>5^92N&{63LCNnJB&EoI~X@BI7=e?rPrcc@0@8 znf?D$bNR6yX7SlsG^*34S$tk%VGNM4ta`IlJ^ePGn1qR&bzciaGL+I$gOuib&GWo^ zV!iU1Y8KkU@fgKO@Z$oz!$iGCG5xg?Zyxq$ z33d8{317Fi`j2)^E;wnBXEbkD+;1e4Y!A!dU*gmKV?cSho07in?jH(x%zoKHyGbH> zH}(=e+^+lq4Pk5(!AOWoO`HK2w~~KgB2efzXKU2sn1yqv^q5}Hdh2o?#r2{bYt2M8 z&$h2M-cppO1-5VTbaA!C8;gvT^_C%}s@sJ9Qh%qT&ie&CWOTWy+LSl>znEd9MMTuo zt6zPbe*xI%psxzs{%;Ah@Ihhfi?}$*`G2J+Il9`4E}00*iSNGNkpS2-gE8Dz?asDA z^NxN1?UV>5ajsJ8J>O^hZ}V+xE^<++!SAVClD<1&Qj+widdl>Lmxc zCOIWJVpv_EA2v8hL?sYizf7~Fo@Kb^W${*8!s_9s{-n$qMAMw|=2NUbDf%(jtz9#* zNgvFD!S~x)9%>HC*+m>Ov49*g$P}w8$x`B$XQT4z)ST(q%}%3A=fVh&jjrd8sn7(w z9K`@M-RZ$WkW(bN%t5|voE)IMcyBfk?;x&PqikQqg+)Z5(IGI)E+sUU&zC_9n@KrM1=2eaCSnCujFSqhK&0YPitgzPaY zPPfm!QAx4OEBj;+m%?jI6EdcWE-^Nbx!=uwN6u1n6dZx_No6YZPWm3bl=y{`vmeHy zb-Iqso1B^C(78V8N;wGvW|you$D=a`xjvWQk*kac>xUf<_Gd6T$`l9-TK^HEW7A@` zyzf#kz7}E3)yKT}bvJESQ=6@8b6QOhwFR?Af_tjbWeM-|2hB0V(I=b3ytt{hN*S=v zt(8JT-5-NoET=WiX9K~(xjY7fIHh(toc_iv-|*1UM;L7DRqw!IfIE5XJT7>Tt&&gQ zO*%~?>OTSVzJtNzvzl}M5yIL!`i%b(hy` z4ocpM;NhQM1k4E1A`2Pm^yT$4ws0{SKVpi>wRn`M^5&o|GP~V7Jjag#6s>KNRCty@ zQ~Wjw_0@gQ@J`E6w3kFXudp*t&n! z`GmKdRBdipOvZDVGg+8Vvbb=gwIFldc+oUiY`EX15`y~7(u9GiHg%6)2mt@UD4q zmfmM>ZC;Z$wU^?F*E{G*Hj+1=V!3uEbLO<#MAW*Nt69<*kLZMOH>&X{2PWsnT9qBn z3dS4O3XW#&9?I1H&AQr86#3POtu?}?aa3;@H%@-e6RkgSr8OYHcXRWOE3_<{hlnD> zy@V+_C+lM0wHpQ^shKj`7I80cq6UNFPJ(PIj_D-0?0szO^I_?u;!dfbU%k4b=66iF z%N0vDbbJ3qaj^ZxLy@e`q#ABk3g82Om|EvMHCN~7McE^s@5)b1gw~r^yU&g22rSw1 zb~Jv@=LvUmNXb#>wt!e2!{`XYGLm4uPSQW8bTzev7`H%B)?iMxGwd8Jq~yyhxTODl zN2-jZnnZJyUwd~CPU&0T8#_~)!lRLaL1O4|8}&45@OfU)oM$AgE#7 z#-lLCBDY;V9}^-6-L5*{Ei}Kbt($!dETI0}l(lY?V}cq?cDVgZyyMc^ziCH7c0w1ZyRC&@5DSbSM^Gb{X~-?+F{5nvT~(RZFc_KIFCUR5iQk zGtXmRu0+FYhVx+k8^)v@*MJ`-ZZMD%K|DrlD*o~Bt-EycWyWLFW^>iZz7D^1I|Hzt zE@li_T+WR0GASu`I0ST&m)R6{X#BQiK0k+thnFONj(+au`^919i*>|g{}$1U;-nI$ zUA~V&tc((v5+aDW$BpG*s9^fbA>F+~02aP}k=y+CfoTdRsIbFkM%=U9OemdFEYE=W zS+P0>r2~VyXz!4>)AFb`OT>h;#+KMvpS_pYV(Ua;YnD-2aifx)%(yX!)+$X*g&nZy z0B9aP&Z!WuOCZ&4Ry&1tf%!b_o)@B==Lb{}Tin4k_m05TiwWJ7v~Jk8wn|V45W}{b z<$i2dh=o!12sl@+gXyX^uMu`mH`?v%r=Tsgq=@Jn_={HwmHIR)D%BT|Z65tAfWwoZ z6c0|17^lB)T}RKky=OImg6x!Y1g`H>YbzFWsZrg+#Vpn^<3Y$I3bpAa!X9&&r^ z`I9Y;GwuFjr!byGa#?SG=9&`&{oDqe7p&Cc&Y$AEiQl8g>UMYBeRb51y0WrDZg12y z8%`-6mY5irB^mpP_!V%X#1*EoAGev5%SBc{x-inw(an22-apOB%J#M&IG%V7kceVm zzhX&ANiDCez|$~#IDi=|>-V=$j@@T!d_)-U{D zl0ycjH9kK6YO3YoXOU{n@Ah`swzf8>^>A^rNb6_qyyR3=&q<+Y=qD#9zfgYq`E7?B zpJPu+t*j6s6fsn(1b>G|)#;C6xO%uf)HXE@wBMavi8oB~3P$F|06sC-aIMHzL2L_ORQHXz6o6mv$l$7a}%YPtj^BSG3_x218iCb6{kEeqN z3I73Vn41HMzDGw^zp}G+Hu|EkuGT_XoQ|~kE~a(4-0y0~$uWQ*t_pmr<|5?ocm~R? zJ}Ucqn$C=NfdKwXLPiGV*|TTM2L~bdx0kwO+0q|Be)LRDCB=I6bA08T8}p6Kj}PfW zQc^+xE+~h(vbPs>x#U60&CPwa9tlq6-cz2ppHjzTH^JhtnD<*<)yWg40)=A}uYXtU z!S<{`T|O0HK0$9aD;)>7f?nlteWL&T#f!Fu1!BRwBUlczY0s!AtU}cq6doR)FTPWT z@o{ll;E)`t513#?=zM&9lo}iuR@c_h2?+!1Y`0dyr21rLQo2E*;N!gN>v{6ppDw8b zvWlmd%3DT8vCp5;l9G~2p|=i=*PDqSrKLrMgdk_<=UFHvnnxEG2LJx|9hkM>UBQIm zz^0g5?l7{lvXm-~(7_wgu&{m<7SjKFmJIixf3qWs|&{DmWl{1U>{`}gmeIXPo_D%~yr z#IZ2HdnY0#g(Mb2L~GCW6i@rNcXxGX%Jr41&F~r3YCX;8s>$i;k;uu(i5UAO-?H8eD(*A9U750VNx~z9!>7h4%k=Y?LotIlPf2+Y)X)#CKMYHmobW`P=JY# zk4Q3>@kL9szu&gP#Q6AfAXBrDl@)VeU*FMQ#SjG;B^(@_FTP>}Qi&YMy4@k2V5wyN zTcp+3H#g7FrYfnBqd)!36c1hPXKLvPA?E$8tnA-#*i2ZUQ1rVURS-#6SNA^?5csiC z>z_M@fq}8SyBlb|*0nO4B{|*T$OPWh_52;MQ&dHD^*wu0$nA(sjh@kTiWF>Y znBXC$gf4}^Iq81>{^2}GPlHdnZo{1|n;J4a{22=yTe~}in3zgy2^REG2d1pn)?o6{(NSxMKW3TrnwVO%oAQ5m5&HxdW}~B`#^c-spf~Rv z4(9#Ga%9>58vrm;ZF6&kPlLnn@(u$N^Z0rz_30#fFzqTf*4AFp(b$qUPkyB4`0Pvs zSO+UB>k*jkCkNwnKB35BG)zXX(TKMMy(G@h&;NxI2}a2UhC1CpH+p?t@9O$m8(6eo zXegK@UaQSN`2QbUZvj=+_C*habV#UlD*^(N($WZ`0wMy^ARyh{At@yyB^?sd-L0f_ z3epnN4U*rw`g`B_fANNI_};j1&)IvgHP@VTt#dC!3ha%m&tgY}{?^Z$o!woZni_%E z`uc>_)Ob!#PPvj9@*lbk;vSgXkWYSi&w&XM|NTt2uzxzudYr7~6+M6c+#AmQV|29M z@1f7dRaG5}5u)LposUOGM`fv)VLuO_1M(?mK$thr&eA}1w&yBk7XxVgyL9l^uTm$c zrwfI3TN293M4nd{PEyj+uUq}FV9ix}P$Kwk7W{zsz@kOpyngLFnx}e)nHk&P-`^QP zaIPuraA=$TK~5*hU; z`~O#oU|S;5q2?g&EFpmc-e%%z{2**(>%wif>zQIBuK_8v;Asi}n}jR7i8l$+dyypD5+F~v2scOfB!w{D@rNuKZZ zu!pVK$fpeQ{g{~0oha7(o4~hVVd;)M^hv|R!-zZmp1_Bnz-JWzcZEplFbcl(oSeu1 zVwZvwOKv1Wv(_H5SVVODpkNdOfkf2m=~{nezH1(&6w zqRMT{VEeVX*&B%%=on$?T-s~Tw1axxcy;N9Oa1_}sD2L{9iKWBgT|de$K#NwP^XE_ zAqVlZ-vBk%FiOkH2nh&~U@05ZbtDLqGBh+aVFDJ%2+qjJh%V3)YX^sKqL;h)4-ZF_ zIy*aI;FuN{7dI0xqSmLXicda~pU#04-cTwjJv%$_Q3$afWGNFX>sPO{YcjU2ALWb8YQ^OSTUL$u@#PL`1~XM^t0fPmL&ncklXl8Nq33i+z5fH(scP0I0Hl zkq`)71V8~Y7Z(@57kv1k*$?YxYDPxe;NP8Qj7vypgUdk7F)=ZT85=Vp>26L|z(Osa zJ+|{hfc;3x_H;4ZG`EvqA3n{h4psJ{d9bS2^q;$t7 z6LFksh=4_oW!JHMCSo<)NM+UdhXLvU9By;X?Z0RQ8TS1X4~~e42mrsdyZb}nsq+g9 zw;hZ}B%R&d?l3S&uW>+%1l5K{M=OW;9W-5CSp8aB(i=>FR9seO<{pM+0vk00q%B>0 z12{^-hyH)O#$YcVQ3`@WLf%G1;J^7Ehb$>6`L(_MHW$|o{r1pE!3S%44050Rs;l`& z#>W1#aze$}vdYT#T8DK4DylFjGIad>q$F&b&FPOqbgiuV|L!1rGwdL{{Zcm(2&J}f z-_WKiE!rro>IdUsBKc5#uVB0qc{ z#i$@{Xm}S;|8G?f%F(zEX@S6%@NjAPRc)6gqRh<9a#Ferz}WOJU!MHq7i18fu8|81 z3+=!5ffDQjD*vmeA-70K?l3W7LOn$we$}jJ2*B^_v3xbaH{rzWY(@|gul|C~X@y=} z!2IV}?bhI%jPIkP{h?X)Yh^`$ci~%cX=!V#KMo-=alqc5ZLZ{9SjjOWBhj8bc|so5 zpTKL;iXaG~p}45%=&b<#Yddf>IVcdl00ffyL{Zl%c;|lB*u5$>z%t;9hxA~ljqTyo zYej`ShaX+LPW_M+vChy?DRFURk&6Q*Bm{lXH8Y!vdk;D&ivI;1=VdS)C-nyK!!W9` z6!$%>|M(-E2Ll7ci$Jh6rKp}WM^BU*;{5#ib7!k=dm%SFSpxPBL;+;P9S7%;9ta?A z@IxRF(ap@(+g;Leu(5Z37^NU1jTLI)2np4-`yEu6jnjvJghgEG-uRS*Vft7EAHi9h zu0-ICV9i-sS^r%wZ*-!-kpy#|jEEj~`=N(PwDznhep?Gcc6a)Bgp0 z6%~~*tl#J7?&g!_SPl*j&U;;qdPYWpXgI{WXGfb%Y-}-tFJYk~VTgrhLWlr2ZyrdK z+>P)$N4dPb4C^xD=H||A1E1~oeM({1TikEHHv@CywEW3W&&YV^!Gl{+2jOrV5&`el z*4C`oM(+LPD7V*$^7HfmGLzXx4+Q4L+}B8b&a`tdtkBlihiA9a_pO7*D|BPS{ND-N zAx;?CQeLD8giI`(mIN#*svmZ(K?-aK&?=l3lMhJA$#1i<;enjBwy{Cv&Yb`}Dr|5H zVtyfpZ59?B0Jp!49Fa#u5{{0%=NA{8jvKEKg%|^$TFStH zzCD759RLDD?$ZMZ6!^LHDFb8U34R588yikM8j(H*^#ua^~e-MfKi81Bs^0-O=aBVc~PRe~&Rwy12q2Rq^@ zn)nFVEkB0L)%z>$2&dJs{jUL+>p)1bq@=KkiC6jR71(FT+Z~}~+`2|aEnAGP=8;AXaN>Y3aOKF^(YP2M6~5h*2cswTWV6Ha512S_c;2w{IgqeDDRu zEzY)*GCooPTpjS`Y4F!b|&=Nu4PuKD~dwSXcvhak2 zgb?I(s>-SZYU5|TXvnY*AjCO1pm+Wja7V{>1eO3Frxg}X`d984fbA`|hqX;sn3d?Z z__jY`_?v#x7ok8^A@0+^-xd@kuc@g)crA*cV-T7S4-YSnQy+cC z>&heZ^XI?RR51d9+9bxw?w3=umtzxZ4M5c=rly|$)d42IPj(mM1nd~LYF4OmX+$Vx zWo0q1Utju@NWb(Sjgh)hT2&PY`{8-{$LQn7k8^=Ep3R++cXsCkX^(Bm6$?$hGeyNpOkNFE;lw2Kq<5<#31kZ68>{>T3=eNRAu3{I`t*opP`E9P5R;d5gKtZR%P{UX?s|i4&bar)#o13#DG$;V^$;nAG zNE4vE2#i{ZWB?}+?D%vcvD}xpL9yPE4sEvU7Y@Xrc24E|^U!)u?0?t-91cN-5F!Lf z*3NoS(``5eZEbD1{zxaBwrY{Kh4LCF&<-FXQB2H`Zns}B-P+mPlK@fj;ll?6bB3zC zU2Q#o4WI^HLqh}ZMiM`r6k<^LE=Q zteOW071suG@Nw|*I{@MYPC*vqeaX-N3jEOfc*YGM(DY@hPM8XDw(bA;$+P)-gLQ}mN(@my%2Wxk&O+2=GJVfw45 zYcl{XYtgQEtvJoNU;q(BI0KNd;4ZNOB;h0ccl(u`QPYi?1`333DAcU+CDCyw1eXQe zg^z*{(xs!Lqxl`yZoPi}+IrzD7NvkKDg-c+)Sr&EHB->VolCYam6gR+RaF;)f`f9J zrkcD&p}vW%uB}zNDWyF5493gXqNdAtAcm?E?$Ccw0b>J?lHZ%g>zojZi=?6=!U)=F zM!|<1LaPQ7LJ#P%LmcFH6(T0&pXa_jfp^>i5TFC04|KXM!K$%qkYS_%R(HFW8zIf| zb(*M+`Vw1!Q|->UZ3C)kgY&Nb2NJEs^THMGM&k2}Gziq*C7_4zV`ImA2ch;=sHm!9 zKnOsJ7;E;mwqASm=+VI7;P0%?AXjPtmy;7`kiHjjM-z62ugt)h%KBb(T|La3qqi0ZLOotNBBW|Mv(usz{`Meic3gbgVZ4)BMau# zZ--(MDGjb6;BiPhYI%4#-p}djI!;7(^&*Jlr%#_8b&7IxTlSWE>NtVmwzRjSLv~~0 z`T@9fMEh+5034wtOe`k%-F?Tl~-fyL3%(IMjyv%VL6aJxV*MT83UjHy$j zk-vlw&_@Tmm$16cIsh#Wn~5& zneN~J7NsD9ML|LFERmlOtY~27b(@<@D=V`;Ilv8pA?E7*0k?U6WhKzh57jR)u*y}d zKm{1kHGm^To=Hbghh=8c!z*?MSWw8>Z-Ey?ct?5;tdkC4kq9J$S|8()sr?&FFu%x1 z#e|}J(N7TEGe;(}%V2Xx>@$EY_zIHX0TGZXZZCl=jGzb7(&?F*s0ddV>T0oJ4>95< z!4P{3hz}d|Tv>Va_hEk=CklJx$?Y$Bd3Cg|K#r{t`@9I^7;$$mnTen*YkM4ywtood zjq1l2J|KV{eh)DLF1NF@^J7W@NDv1VK&vm;8QAI#1dYBm`BhumpubO;yX}+5ya5e z_5;A15Q2!e0_sjt_V$AJrwlckcg^C`D0Bpet_IDuYtN#KQ}ys}n-# zF>}zQV2`zp~mE@RF}a?hv=n`sD1J{5o+Q6!*b8yFca0%rbhUkxfZ z0_*=nedPT(c%O91}taLt09Pj6A-|KEO+tF-yconWDW%>U8)Mm z$5%)Z!is({Vn8LpAArse(Bb}KWMUFb#G=wXI!ff~>bl7`&JlhexE_L@JUHZ(I)|;p{1oo0Y8=X zDudhcmPOgErv9{USrs)u5@B|V4&EoR% zjpa`8a%8~%6*=FLJYUzj@`cT-w3-cvQ!>rJ0awB%L#uBIJ#DO`xj^a&SCEx$!4LvLlIvnlcI)Naxm*q)1+(LF5k|w!PUjs(8mA#qP6%lzh7G z!22@kCpeUjmjwPi;#0cZ@A;&lSL?)fB)CInHn32mqN@IRiTSIcz5Do0MFl08H9zB< ziTIFyPMkCZ=>S=7?dTW)RWUIsi4!DRdkTn)8`5$koJvYc-%~_s;G`{PG!<1<17&DD zUiu;yHv<|N!H{my-kfHf#|+em2Udev(GYC zBwmcc>ZKG7s9c>Vb>bso4`MSAhEwJwCn1Ob#JMD#U8wmwaH1lPuwexXD>vX^GLxa&7NL>#;f4zq+#iWjQl zcBSpolZ_u`*}db?Rpj)#Jhu!795DNwm9^kcqTSr+aaOF`a*gt#Gl66vUbG-l0a*jw90dw&3F7?&w`v2j-uJ{yKz-3@$ATS_1QeAhfElgsPUos^6$4RY?=er;_n1TrV^_q*>xgI4>#3_J7C@P{2VAEhprGhMh065rA4PWX1At7Fy#9s_ zRhAgxAGUOK!1qtVFNcCXh=4v&1^kfr)|cllsHmtA_CVnNdjrDhYY2wn8Vt5W%g|8i zZb@Mwn@awxK~sBpUn@mTO$5aNGfGlH0e^RQ7nJ$iu&}U^wEz1J1}$`N)W$02DKpjC z5~>*;(XD?M$!()cx6FLbR1CMZ`ujIB!RKl)QrT>vA|3V}Ioda6lgL>p&BVOJCAS_5*ws+4`6eXZ#?#D@k2h(@2T%_mG;ww16Id6h9ntpMdKDQ?lo&NusD1HFUSR zfC=b=?c?xjq{GznV7d(8QW7jfGnE_wT-nipcEETOfI->C<=@CUaV9 zHiaU_PVYZ%nQ*&yDeAUDMQs?(v!mm>EllSpmXmg@eTz_0vAH&;qR?<$S#|tS;}M#J z!~ONz7>9y7W+>|Ew}-@C1I1h)OWYW8OEBQtzp&xHA5YIs=fC<#SRwiQ&*R49WVczT z<$9++;T4YEy$-=?8OtGF&&yv5tez(_@D+V^PweN$>)LOkim&3Phe(lN`O+SsN$CVP z-tgPX>kNlEuTA;zQ95t$kJB)3CKQ%Q_+p$@_hUl^6Wv zq(llEek@)5^)ZBHR{BFk3P|v^#8KC+wA*+Ts2(zsX$rfC?UM+YhmY3Q$WF!EOh3g< zabQ8};JXa*4fP0ZI8ne&cBMknm}$!B-FGv6=1V)#Uv4tII$ngBi1_Kg-^(xfL<~oq z;1nH(3G!c+_yQG6f&yv%tCKJQpJrz2HC7YHhFSEF$8KUZ^-y}29(~c~;XCiHb zgTdlag{6NITZg-uD1>I-c=rWp5BfH?QN+RT$BW!WTW~fO_h_(}IE6HeuG!J7&!@6^|e32|6f0 zlERC(D5$Z_U^>G@8r!)_W7cdQtG1PZUPYR=mDrMRaUARZ8k5Y64j>jyz3s?=X#mP@CYZC^~i%p-4%i`MFhtL&|-E zsmXR%>>>CvUm`0#rb<3@Y1Qyt_A+imIjay_Ok@3KmRm#R36G!twlG0OjybGEk|^2* z-n0uJ7{>v#8R68z@5;)SGL{B2WNN^c5wM;^g1^`mL@yqIgVjJ^u=BJ7_Q7+~QuAj6 z)|O~iApOf<$&=T_ng~hAd%F7>7HK#?2DKc0{;|5@`il5i-Y&!|?<&i?rB{;HGniQjuWQ*OyD zZH0qQG$aE`?Wae<*KZk8Ex!}Jl2RN~bo4sn@JxHFX5G*Dahaibaq(<-4}T@SP6c^j zBxnA6uH1(D1;=pFAEEH@zF+i~-=-OZuwq4?C}jkEUz{yl*_R=ExFndxs)g0OHR_ec zf5xOL@})lD*nO9Yv8n;3`HM^-=Smh|Xj(o?h(eT|EzV@Sx~;s0-k^t$&s!8Eh=h;7 z7&u-ZZNiC>o3eB&Otlq`;&aZIUU83cTQkfvGQX2wTv+zc%KBJZCd*&v%DGreQqWDn zw?y8Twe@;op<~d5g8$%RR`$m}=Y`CDgR$#Hm7liH%cmch@ElNhiYJU`Hkb{>b2^M@ zpSG|I*xBBs7NJZ0c}m0Pwu&Kv@r;Ao%E}W>9BCUfNMmB^1*Y$g8RMNhZ}W;&21&uS zLyQo(fJ{Ql$;p`uW=x(7UfS3?RJq9+_f)JIPcvcq>ars+6_Gh$q*{EP^E?V}u^w^x>Bl z&HOyoGeboNBPBr!=|El2jQG(0u;KBMW0=8;#~hvppT z<(WNRA(6)ZHOdv^{a3^U#SICBfDeiE;x^g0oG^SN8hAw&0D-`GEB@}*^x z_!e^qQ-U4(vTcU3TGCotRDwx(-W}9#p`aB$yno-^a6I$W!s0%n5<{OR?<_0vd_r)LRC35)(chFqu{wx zOplLMGK1jdZGAVYu92CzI{h#Viz19k^|wFj7|NH_f0SC@LKQE@7<}}vzz&cQc-%z< z!$6e%4|ZSwcxEH(PVZgb(IV!qH)k?UM(qyliwj%Vy%SVvKYij_V-7(YSa$%}pnKqW zLlWp>MjpYG$?ER8u@I*NSmh1QnaS$pCxFK*j!y4haju35^iXPjC@>CRQ~Yj z*MM4kX?QYxIHe~BQ=fp3)niuZXPuxP8vUxT3lqIX${QrFR{No*svZ*jJZeXLI4GQN z(;kDVS2$Q<2kD8O0_Se&m1NQI;>Mauq;|)odK&*3DIgT;aoNv;v6yF6VKqWy&I3oT z&69D0Wenwq>JH`q9c8aa2-`ITU9!Hsefp)wYEac1a{KIesSX;&8Z*qJ;FacHHWtO) z6xzaemwX*&_*sC_dLR42*7JLPBGQstXcf_DU-`DnyX0oXUBsCsjeh!NWN<@<-w+(& z@)NgQQ1Q*^n44jJ3MCtehVz3JHn#5%r5=ChuaJ~1Vl)}QvbJ?B;}}Vnn|c&g>60_R zA8Lp(Ch};b`rFG`gR-RyA{(o_aRUXi^mdN3Gu_GdHgiWkYDH zm=vau$>4?duLolWopO`m8BsU2FA3WT#>fI285}p33QmEuq_VO{2GNzl^~@Z8#+d1@ z$C+E=lX?tZ&~Kf1!@HqMhdqdK;)gtiqdX9ViIRspo`3GD7mTIXmz2O%arh3%!2RU} zs~ZFa15a;YH%Y@G{>t8L>1FW-JkVEj>rbx~X-BxqUpsWX0=GJY~3C((x41h)RNy}Dr zdEVsVS2}Wf?Z~a)afb!6c{Thp*t!L!ehvKi(yx@TgY}NieBf51)=#;W#GlXLBo_m* zX@&IeBsc0+yP(;&6l`1T%(IgU{c&|vN%^wh#G=p2 zk6BIE_uUki>B!gf$VApFRr*VSpY07F6a4fFeUzD^$8E{mIL5;>l#>g$BMRk(%sA;otzR=L(Qtz-Vi7(;rlWD^rmi+$}Z-qCVInJ5Zs83VhT z9&69j8F}Lksf-RQ#QpN{;3nAIL^3pr$|+)_vu~DqP_fq0SN}0(@OQZ%uh)Cv@Fr(X zx~+y;sJ}ng1WR2{l9W?plbb{bEWN>Fk5@s2wrby<$G9@`=JZ>Cc1a_-meL)bC8OLT zwl^mmQN_(_VRUh(J7T3tvMPxTCFA5i{_Te#J;|dUoF3`V#w4v zAp@ApNpdmhY}r0vflKNpfEO-rY}(Cw%DMd3a`&5IKTom4v&wQOAYBegl$3F$_GsUJ z$mHfRtE^0M{4cYpvlUX7!JDVQH7@u9)`4V4C^OMmL}#+^3{Feb^P8q6d#ilXnYOG5y;5opo>OCAs8LDlpk zDIF|fS>VDl>?e2T-)7mGx3OeWom^|scIh1XxMb_T*u?MgO9Nd_6Wu#d0ke?WQ#vD8 zKHG3swI|+YGo<}F%HNnex*^n8PC?ISB1GMohARDK03VI)Y!^Eyy`C06(N$A9TY%T& zRsLkOjq$WysK$YjyYFkHfsv2!!SP?JnuQu9?H@CCL<#sQfet0 z3WEXIHZC^^fn5h@W!-Wr5*xzzuuu;8`D@ep1XaWDx~QG)9nK84<&p5?&;aM>^E7>l zlc5Q!NC2k=2E|L{6Wk0MlPukWug&{eQfYvKRlA&g*|&&;46KbkwPlj`<*u7z8(vR4 zWxYiicz$P^F+>|fZEAi;$oimZdOU&_vl1NgUKs1jDJZZQ#+me1$y@5>oBai?9AWw- z+KDRS!I2oHn3QJ_W{Glt;-%#r0s%)KHobi(b&JP6nKL_9AYf(g{R9^AQf-#Byt!wT z($oxsLkMJ75)cSb&gv??sw}Nnf=2%fXLXOl`~sr2FYg9nOEuIUyLi6a{rP{!Kz>** zx0ysjkut`=7$E%r#z3&0D$lRg)$i#Tjq|_8st`o+$fJgmZ(Gd$Ejq`ZZ=GD7AresO z<>^!2z(%j+PP#JVoIKrwbJ177h~TR&9!050Lj7tlt^Y;EJm_i{hXN_4sVQt?n$KuG z@Dd4j7&m8{1Mt!h|I=$+t?P5Y7JQs^MUOlx5?!k5ujApt(L~j+-$7g;6?YWsra{U? z^MRSpb1tDeuCuK1iTytrnKY;GcB+4e>KtIQS!zERQMNX?czP>YrE4YP;y|HY`U&x%Ap3#*#~&gjEM9>{PrKO0cGWPf)5VoAyT^?g?b*pEf_RnAjZ2_0jK zHU7rm4hST|6^N{L;^}fzNz1+WZLrJV@BS5o?J8?XA~JmHmRpBG4^IJWA3aoXShJ+)OL)4+hqbfjc&-R@X3Og6dE;AG&Es#AVr*{x=K2B8!rD#fg~ zwJ#o@+&Yz0vYV#j=a=|S+4&PM@}^)RJEp{O+W30S@2muvO~@`ODd}~Erul;hIa;Nh zoSe{sN`fK53N;;q+8Y2h@_mKQ7*dK#F;AZ#80)W=9Q~zWR6xeczf~KVQjS zoB6Pkn8WmaE`%tGRAAdOOZ(8=D&)?=wVUWQw#VNJoD>|0aI`;Aj;^p6;fuGL1~m{Y z5PvECUhq8fy1wU>5El=Rca$qH2YDLfG>)a`W{MHME0wv+GqPDDQN8%W%m+l>Wx8|c zmHk#-N6`e_IOyNa>heqQDuuBYE&b=_wYc%jjG6U1hB+?r44;woDZIH}^KL1mY1M+$ z&+->Mr8M8gm{PvujhJzTp_l@d5SVd>7QEitNbdJUfhd^Vhq>vYkQ*#Blh1q84gzL~ zB?3!SYPx$_Cw1ui4HmJo0PYS4Hb*xqTQ( zDr6>9>Klu5r0Td0B;$1#G znGWN`q-=-S6JU-ikq#Na9|xv_5H=IR>9zDCKf5IoLqB<;Vss1)ncL_J+ZKvo#OOVF z(fkAD{QC>Vk!arptNxxBA2GAXn)90+y>#w&tu@u`YAInA&X{f-g*LIGBu+Q;eYq(8 zV6d}|FK@ZR;1;--$#=YnJ&MNsRnWVRruuQ_r4AZ-uc)!{tKq5F=ccj>fkNAUCHi`k z58}8U^=HZwP;29DSYD!pNnbditB&VcI}$6n0)--mlRzk!uvOUZfAXGR)ss_tHEL?6 zMU)lqs+gY(ufVXgeD31 zDJ$Ps>3Q;k)|BfOqj(t1c|dxPF9Z!(y)s5`@`dEUt) ziYQeUg($weIN>0S>!s?F_z7tb=agXK-tZH2JN1~+TVHmoUGv7Hw%?v-be~XjYLg|_ zy{6`g?iQmW&29}_*;4&e-f$;>=9(|9JqqET%T3gIlAwGFG+4@vG(sZy{#ESuXyH_< zgs9^DP4{HcDRo=5x{cM6b00crkf&07p_{)+T90Y%S5A{U`!Y(A?}E{=lS(&cA-(YB z1wLu!rRs`gyELhzf0xk29fB;89PRaTX1@v-=Z$Vk>qF$($4c=T+$U1^Bny4k${6}* z!wt}w{t^OTg)2%n0v8CA_G6)XGMKi2)^lWJqRwz{_`_ z&cY(AXgK)BM68>uS?HOIh||);TGy7es*l-KdHDaY+lAO7^yHkcMiW1Ac#)jj`T_$_ zWjkq_&i>XdYAZagP0KGDiI^8gEO*v&C|LI?Q+`}0yve$*y8Pw+U;yP;*CcEO;a{bd zOZVi_XN{GTjl8?LyF+U37S24^$Yz4<&jYj?5*Su#}0h`bOFcC?H&MFFRJ#i2W;Ng}o3Hxp)3cMg#C)qv-G4Q=$R z?ixP`!X4v3+2p3`3%tKiE@1B%+x1da*)LGxacsr-@WFw5{BV-p_;^tW?E!sy#D>g) z;88GmpNnJ~cNr>L-b?wVe`bKd$_l;o;DS zIzQh0CqF^`#RofI#4UWG$JtK31aY$JASV@}DF$+Fz;vg=DV&ALlTZ8N7}t5DAIZOz?oW?mSj@?~MsE5Mqo~H`WwvsA?;dVYQ{T&( zS19osADyh`XqRlJpBJ<~cSBX{P90Cct+?C8oLQ-YBHzc%=b)Ut7iyWKIMaZx`7rJF zQx}rDv$r~4QwC_!`Za~95;E$1&nb!xHN)kZMyIGO;&b;1XeH*U-3XYn)WfQQ?_Td~|Xcxy4h|XK4|k3KDmfto(WfG^t2s>qHE?KM;j}y24m2 z8EME}a_y z*=3U%+FxpCt&e^lNSMY}{7^b*|92>{|2q`Hh}DcjIxtz*b(*k&;1+7Qpei(3e<~;E zZLq_EFbGa@i|w_Lt2=c8WuhSGk}P+4ww8$1%AVAint%)JNMNrmg!1gS@&bEx0vJ|? z4^ouL7vJmQ;U|_1 z%NcQ{_>d~D)#WYK6`nCB{Hb+%O!ktzlaHS) zxW{p*q*G}7@J#9+O7+_)u4>*f->fI2JRPGHrcXacPQJ&PBvxyAV0krhw9*-4!!suC zK!^JE9=<_AyQ`Y)J1$>09;@eh_k4e%a4f%xqN`_FE_on#xJXhEIv#m*{y@brj!o9o zs~(bDqQCgKr$ct~kWR5}`4#ILGP*)TIF6;;?Ctu1kOU`%5KQlEow(hKylkDKPTjD| z<+d3YVO4M~f9#A|fzoqSOAwY-=#Lec7I5;os6~{b)775@9`;+5r&|I8>o)s4--g*K zkr<8m-prnmvuz!%MBCczuT|ghaDxnpmDd@RLkeuV5|Z(BkDrSxd8Ss{y6{TuD+lrP zF;B}yN2Op<8Q0V)m63)!x2HV~l zG-5;J%#_X}^rO=HW!ZLv_b{!Fh#hUwB9II};*lB)p!d^~+TO#BGgF(1%>N-29h$oL zm;!fb>~Aj2ZDD+}-N92vw>C3O%TQk3-bjgVseXVaJ*)d6FK@YoRm*~z!`Y+b{>vhz zM%Cn5#FlS=NNJ4C)S|gY!1qTz&*8N+yTQQ8UEzBwf&2r)?VW|`*((*5>E7GgHHmv= zU0Orh3d0G>@VJ}rKva;(8nqP74;i57&@TE0(y9B^*8EL#J4_|F-|Kb^m`w(! zA1s;sMA~=5ijX-BCaf5xB~c#<)r`OAYsP-}=x;u}RTu zEJ!2g@;esQ=gWLT5&4S>gTAPk?TgpCdo%@A^Ec7#l1o|bZ2jZCDzruEXIx!mN{>=L zUz)eX*a+0L=6A40Xt3;u1YkL(xOoj+K5VaYmbTyZ`;A{Ui*S<%>@qhlU-_>gNxaT? z|INpJ_{C^yRG|j)vQ@5mCiUv+c{4=Wf_Ss?!SM?a0zv*7*8tp3RpnzYh~9cSY0~$Kah( z)`lp3(`7g>Kgd|yaxT4nJaa(^E^7O*sBdfN1z`Qh;1HU&mX;F9nyGZ9{YjsC*9IsD z+AH6?*!s(}@RQnZXhi&v*5BxiMLNCnMEYI5lIaad9cX2`%=W31e`=&Q2 zbj*$$EO}Qm_#UslC#1x7A_)sD2&_} zpH_CUs0XsBZ4YG~VSxl+>xKjdE&7q0z+# zSuTtmsq$i*+Og2pJ8m$R3wp7bL6j}Kaz!@wZ7jT9)5J;f@&C zEj<$Qk|%m{aJJEOkHU)PDGa)eN;gVU;yo74zSsP|4kH_3OIRA0a?r3&&Aqp1zQ)Ge zy+ix=9?m?NrB{Bw2<1Mup8 zE?d{~2hn^w4pUSkdCOl3B#65=v+FajA(^V1wGd##lsG%MJN*$nROg?=8+8NZV-mJi zUx}v;xME1&la2vyGU07jv)(-r&{3z@qX0JB2lJlw28hUh$GRsQ9hcrgjgcYI8e zyC$ZjF}Q`dUkScgOT^Sa-yM%Oqkoj`5Ea08!~8j zgTGxfZA($?1ZOeMZcqEU28-VO0-r2!oNKLhmfO7DD!%l}vj8dW|I1ZB-QK7MVJ?5GtAs)ZK&oe(HQ_#J%JTIeVs24b1 zoN?y*bz{nAAKPFrTA|o(6vf!|$&ahvCxtF+Vs)F?zPeO{G690=5w1!!^K;D~KP%i6 zvgAB#bo~H>P3?b2?ExOcWVmn(L`U#*h zxxk<^T)_1|ktpGG1BPxiC&rbD?biaMKMheXu8;QIm#kAJHk>074ASHFeA+rzHF4Qg z_nU8_)zQw&=d>iX>{hbKV?)J&-3FIFuI%M+?uL4Tcz9W2FP243Nyo^NBB#6?_Dw_T zakejT8?}V6|8NirdZD}NKOLrOJv#H1Y!j^bc#k*NlAyko8Fa{ zt@=J*Gc@R7p}Sg6Av<%y>7R}NLMd4W`WLO}mDJg^n45P_AJd(73JQOY=-#`56+{UQ zAbK{hRSd2OkA4_sQBqaI6dNnq?*D_~uF9=Y6)utYX?PD2?8o?FX2;dEm{h~D_Da@Q zCBML07IRQ59K_s&J~)8=`;?N1?MoXII}|+Di*>wfcVu2!Txlj(Xn1x6Tbn00)33BQ2Re9j{c0_GM3tm$ zE?Hq!bni8Qx5E$8@ArD;XkCswPW*Axp<|5%?!LZr34;X+QX?G-Ob})BPg&2%LgVx| zSIs62V*Ya2-GTX%D@3t4^17gZq$ZQY)~k0lNyJ+17Hx6UfN_NjL+(x8smJ#{KeY^@ z<#o;9tBt%1bKbFD^x=Jlpc7#b$tdPw?O`IWDh%mJ9YoGQ9F!Sbz2{NBUM6by!H%C z>G^kJF8KKgM2x@e7AWZ2C!ib8CH~)g{O02;1_D{omkDgA1LUVkPRl)5@)9=O5H zRsEz+7J>Mm(7m;b)=N1_fnIG~xuPLQwgppHG`}j$y~j<>SHC4{>w_IQ_Pxu(N~2s^ zN6TFv)O1m0XWgG94WuB_hi_S^e;DAB8ChV|%4dHr{L)E!t+34g4IXYsPjBm2vgK2l zoKU|IKmM+2#Q9z8c~j)(%s9HdrCVUJxDtX}A{&Yc)=Zyftrym^`R+W04V8de;`)S! zD04f5m3=UsYIg1w)OzJvo9>`R;~1eb**wqp2CHIs$_H6SH>ZP~k(+TEp4>=?cxC)<*iTLN$ z0Z=yb1_;Nwj?RKZ&ISV`l(Q%70FF#uvdu!Y?@Dm43?58o(Y%s$P{RXAf|kAEK&IgV zjf+ie@c2}z;M~BL&3vqa&5gt#XzJIUQ6-|#f1=QWL6hV+mqsx0r&nwR?Yi>Zn!d*L z0)6KMCee?q(q{3srY!7h=+J)HDHk;j^QSafpFbcTE(y^t_YBXv;rJkX50e7LbMXC8 zJ>mCJjMILOsOaOHYfc z{ik=$gbX%O<@|HMixMYJrxlW#J{2ocGK|{VtZpc$nLl_ld)T5JrvZ( zRFads=hoz&nE3U6Xya-GOyE9hPpdFUIf;ZW*;l#707xQZ3RA4mcSaknf!5ac^bXsm zPi*Dido0LQ)_Y-~FtVnl(_VMlrcGF~6rc&9)H~`kli4eDab@n{J&)of5k=BH_!vUw zfrSKpS7?`Bv;GxGVv>_*&^;7Qygv!%(yxs-2k6ha#^*QI^h)xkcl7-V>~#Cm9K7_Q z6V87$EQ-8yJ=kzHl;U?#VKTe7bQ#STTz$U&x~yT|xz&wH=vO%DocZHr!h}Fqoyf0l znJO4xptD)QfN?c}gK0ZlO0T=gp7R!!_c0~Rq-cUg)+{_S$JZy$FE=&a`%T?_UsCtM zz!J)&skZF-xdk|WZG_CWn8(w-qpr#=ZhoH)dd683KMq(2@S?ur{EWc4|Gw8C;1i4Ys1u#7Pe+#2iJq?&YqvM zjlo_My5RdSRb6%R23Sm7{LvZd<**@x>BzYqeD>!$N>3)5@4>p&j=Mi=?gjGreGP3J zW)Jny5oy^`tGc%4a}FbRWM02@_)GrCIeNO&WLLtIUj3r(m?ACR`!$VOeqX7!xjhH( zG~CV;_%sRQoL;BjKs8`6{-rx!2XIQ-~HCaz%CV9=i+Q8|E zUc?dfDIGUiuz)$Cf%0~{_%C|H#J)*nBYa8Yht>9F4_7EIQAUh7>=InJmvM$^RQ7KQ zqev{ILAyqi&h$mcCR)4rmS@Ee)DaJ(0#;|zUz@54O1Os8kD8meezPzbquK>HDtrlU zZ)Z0)6?Bld$k)KQIwf&GByzvt$yY-Wa*~jT=eKz^9o0y%roM+$?F>jhS3w`w#;K?% zHYH-!##Io#p1|wVB#KM*Wo>+PYm>sq{VfOReK9-^Pp5plBZ-8zY<>0HUqBahsQ+pS&h|sC6;Ifq^0WVothWw} zGJ4lWK~$7*6r@W8M7p~~qy*{i?xA}Km6TLz>5}g5lJ4#tx*1@o8Rop~y?sbbk-}^GF(E00+fmWk^JX>B5YILNuegq&$07PGaU@ouneay9h z2dB}Y`D3XU^kQI;pg#TxD`iCEF6gmz^n;Qn&CeLHjEBl&llG7MpSUeLyg4>X5Y;91 z03ff|PZu@QE4C%G5lC*1L0q(?EWux3wra})IVBn(Sol^|L=SBHj_Kuuq3l(apA`>` zD!z~(hl_(3wk44VIe99v@D?fH?*T)6KPV*Ws}9I_^@jl5!|wOp#V?2Ak&u>iEZ6rA zfTyX4U_OWkCqRC(8>1-G>tbDE$QcHp8Q7o_4Fs}VZkxh!9_ysWL+vQU=_5dXBtN?_ zA9q`rwS8(~69Uop!{f*%syK&=k$Q~qO{uSK9Cwu`@pV{BfN`im9ln4oujsdNv()Qfd$Yo$KN)77?4V)-G3CDicMp_FLR_W3 zz-9Fv3n>)Hvn}@%$qXRhkB5G|D);;?{lM2|rRA~hzRNBiv45ZhfI|xp-?YCnZAO9m z#+An#Q;XsP#DMJf<6ZLFjd;@ZJL;au#s6pl+|7?=h|tU^3|H4ZQg+$Ljls)R0DS3R zJikMJ!SbkyO5S!&OibOB&H7Hv5`eQ@py&O-vS07AN!0HJaRU=L&cg#+#msKF*^-A6 zDLe?Z5y*2rS`VI=l!PG5B))u0U5WFan`@T-$MpIyO1q_$EhN<@o8T3`(WcwZyWV4>Oex<_ zi?L;`I8i=mlS2{oWT+(_Ua-iaH~O})ak9L=NRNy8EVj~Ov(tzV>;7lpi1yS$-;V)e zl1*jy)+(Je1Mle?z_{tX-;@y6|K{&snc$ebvz~uushR-=^ z{!DI8r6@Y?1=N$;ZC+3K6#YMJSv-jFrj%^C4{w8dlvUFlgjWGoE&z&j4R=NVOmy0H z+o_c(Dx?j^PhK@!VL=J7nYp>TZf7-#8PDc{Tsn?U=Buj=ckh7kkm9@Vw)yzL?c)Zu zkNjx=)U*}jdLLxq)RqrCccDMrnr8>TO4#XFanrmah!uA%% zQ$^<`vo|#=x;U(9Yec33ik&xd#+fijzaySR&fLp0$niH3$l4>ax1@7&-h!_QI_xI@ z>X4Gg=AA~6l;Dn`g@Bl#M-8MI2m5P%uj;o5??&}oNK;bR3yZv49e@(*;#-Tr4WPYKzqb)W%Mps?RViM{9D5gXa1L_d28- zJ!6*V>}U{M+wqDKkdQ?*@fACnoF~(s+?EeR0hy0@0}8Wy%zvtzTpNW)v~+J!*0=B* z2+t$2xlG+?NT#6T@jb?B3s4vAr+E!LpUz?Jt!!)w!6`QJCf&~lqbG8_45mm|Cm}=Io;Z;vHND8nM8vo%zVA(c_HoIaZ^JOjSmak`fMv~!z?LXQd3V(2?1chFbb&Cw zLa|EPddA03y#{DO^wfJyr&Q0f?a`!rYqw;y^FIC{OT2rXf_TKpnTfLFNy{mlmU{9v zgL+>tRbzS7Ether(WCyd0jPM_p;IE9Mrq(HQ%eS6bbz@lzUN>+{7mq7HBEG}g_0$o zMPq#fmwEw-`QhL7$e@3#<3Y*(=pXcjcH~vpntiBf1*C2uM7YP!Mfu}*&QGIBrpOfV zV&gmJ>ok$V^ahtBA&0J~o~Ppce$6{~gaGpy?v=JRuptkqup!E%fZeRmhV9Zk*iYG8 zLHS*5K=a!O2$ulJ2}&>r0;Ru1e8ePy)(8m-0szu5?aBR|)!guxm5x5_WAu#L%Ab|Z zpBTdxpzHXb0g*NuKu-Z8cXlt*gUg3QW>WfAy3A96u#F$cYg^tG-HgNl{9^2O>RSL> zOx{u3y;Do&X>kYBf37b|^4L0y&RnbKOp{Vjk;=hvcn@9Nyo(*L=GWeed1{`BO<5S> zV@~3TpgG0)_SK?nC8cHH{np_N30769{ok)AZ*F>xrY?Wh8nmpSNQV&NoV8nr%2E;- zGXooC%En>1)P8v)W`gku7Bdu1S3-f$T<<+5ra=fv^!FIK#dGDvjC&z|@gY0&_d^S% z1Ah^(Tm|PEo99pUa(brH$hT8g9#PXw`DmCGIPT$}Xq->RzpA9WAHHqQww+F+ZrmaU zTeG>40b;ei==WU>2B3oBWZaDN^ODKJhR5bsk*N-XGs?-&(;2&V%jsTIu@(o;YhT<(ySY}49RH*RN_YCfIWbXbTt?b`z4o?1Sy%4|Tb!q)PL&@(Pd zWhs>EuyQJezFMojlGNcG_ChOsK`>5L*hjC*2RZdLI_kK0L`4$|dJ-6@ZW9G>`MW9B z(p@Vm)JVy4hNF>&+#{Rf!HPI&KHR}RnCVF3a=be_noTyM6O^X>=2$rVenVvjY&yH3@NlKRcx556tz^>BYmZnl~s1Of&-sTndzVmXegA;u_@LPL z>jsa?%YfBaf<|v+O0}YZ5~bG9k$$q&D@|2s74wbpqCYV&v<^7nHAfp0Q$-eeS#qv> z6Ev&84PPRiUtXC}}mCp0K>s=C|{> zZw#g}u(V=+45)uzL}BLHz%yK>c#HjB1VWss0G|E#y+m5A0!b~Dun-on#Z)B-w*bkp zd(C)1WrEtSpqszp%BzqfnX(CwB`Q{o<@|F8`g)Q6XA7?O^fNvEmb$KP&h{W>_Ug~U zDdGvfLV^6gN~E5PU5iF-)Ob8ROra2#BEo)+=Vo`BTR60G^VIx}eX%m-^n&*@s-jKc z291(0e1_(ykKM{h%vgmpaZYPTl&4S^epqb_nBS zw6y!)PF=|C{2LZu$`JV5jK{#zqb9S{|HDCpb^iC5bS8=N^(vDLMn&XF*j)u3$8cI@ z#d+o-g`01se{IQVXCS;RgvSPJnq1*lr2fvs;Q0KKTuiR5gOa6IxuK~B$XjYos)q8ed4LeX;E-8L7OK6#KNBqgpWimnW}NZNPJ`HoVpRP05|OLPf6I z^`1%lJUlullSXRrXWVh>+tqA&EDvF<(+F$X?q{BGRgLo0IKfA0hLeSLITmxO)=wmJ zkDj7?n`cb%N|TM(aFo`vN6Z?9@&!`YCXDD6!5?BBP}~wHwcuk#F@W~-3kLA{PcnSZ zarc{B*pjzZR10thp9(exZ(B>@aDozxnuC{-fDWp5_*Zy{AiYQWpO7BXOYe5_#Z4;# z-t_m=ic55VIWeVcjG_PN_x}*3prt>1W6;AYTL^VD90yn<55$0!yo&J9EAk1#@ zmRZ8fHV3LD#;$e#yKCJl=#z+i8fuq}ow5BYf1r=48wSSCyL2P7J| zDu$D%{kyctDdLnHN)<>lseE5=Y{b4IR%;Wa7)rLZ=^{+xAtm^TFhp@qGcc+=-Eupa z3JxJ)iY50OzWT-Diw&&y|GrNT{>nv+0mba0o|_n#|2b9-!42RYQ~*s%6+;s-?|Gg6 zxMZHA`#I;p&c^X%QKij3qvM0pBI`7~Q)t30&^~{E?in~OVRp%7eC>mw?otgb32I@H zV`E40q1}Fe_@ny?B6+JqkO}JOtlaRuWSu0d*}Tf5(6LKgVwB~?UUMwTc6tQ}F%F0$ z#>e*S&&}BtZWO%wquM6#fsLI=-YW0)DFACH4T6^S2Um`wreHRCCE1~pomluNDLY?w z;I!CQMIeVKZohHyt+X6@G4bsOFmR7XV2@6p7|vzIn1AqPGBQ_@Q#o!8PHp=!prVdCmjQ5?##m zojTUlMs+U*%qIm`dwY!J9#;9Bq*TKB&a!0uj%a#%M&9RtadgdBYUH+@dHLRyX=QHH z2$7|ENo~#WdI~H~)cv0e1#Hm-;!OP|-$cjxY}#Yb=;d^g?|>pc3(974*bQ3SCYW== zSPleEDgxE^FLxu{F3aTw+sge*LCzO`lCI5hfhnDAe@>kkX*oW~GI~l^D=U}bc&Bx| zV>9!`=jZnSh`Z95CcaEx)PR`>A@X@W6uA)N=OD6KQKGifm0712wOUap-skxKi-_f` z(I2I)8nx9shc8U+HF`E;PcmRQQwc>r1Jo8$Y>;gsJDg9no%0g=zWW|Fe)_(Gt-;bL zZ0aa2Z1`M6TWk z+%}!)z)j^Iv^W3f8+;u;KbrUiX23bp zT!h8e%MS}Ulb-|`)LotlarDFE)FWv@gTaeZ>R84Pn-@KVo zIj&{z8`mIqZYrP9%qvwF;#{0qsQ^tMeEr7070sB!o8NF2-BEi}`xYoT{yH8;y8T3y zcrPm_e+!U5sq(KCUQsedk&_6Qr!K#-t1ejDu9*MO#_&$yd&s=I!ZrUX7Dvm;5Yme6 zkMrcg+IsEf{P?BS4?}^(N1L<9TionCGPO$a&!fzyf&#H+c1^EG+@aR5dIS=*Hx@ zm%FyuiS4_i5NGN2`5aj|-MN$Ag+iu#w|TJ1CmIz3J^Ke1y+_CiDw_)W-IMshDrs}m z(_?e_+u8NR_HFuG1-!(`Jfw?2xd7A!|NGwMq`9~W1JE=8!rCAhlfqe|eDlVHSh;Iw z-6~X^2~kK41fYsS?6p&&0WLsw^>pvI8UN{Dm=+ER`YY&{;D!nA%Qjd<;Qu3xw%91J=_C+%_cYdo<|o7 z9OV!1?g4qc(oL$OPce+p(q6qG6`V?QF5u`GczPC3_QsAR`DTf?8ed^W=#fvhdgy*T zb$l<5z;q^ZX{2@~Iyhz6sIj*=E=e`D?4F2R6BQ65eyz25dpO&1X~oc_fQ|f{B>Z>M z|9e<*ZSS&X{ocF$!ta`fJR~~eBwB_($}PMge+s-TXNm+Ke~lWQIEkBXBK7z7Ul(); zY8wk=gBtG7)7SU%;zC?LpaFPqY=VSyCFkk!Qb9yx2F{SCA+Dl`Ip-!Xcl)A4S6+H& zjAAWiSN!(qP0se+y@S81Z_mH{D^lDPe)P-BfuAMg@1u8~;~QPt(B-jk?ri4!Oq=$! z-(E82xGVj%v7Kg&+iA%8G;HqGaPaQt+WaS}b5j2~@f*8htR_82a-dK?&4FQ2xV6|Y-RQpm!eP6r zO|lGwClAegT?DPoDt|!LAQpFe zAiTO%K1d=et#lLqOi8K}CT}(IKKo*SUtHk0Hhj_<`vBCdb~2SzWh;Q=t_xZW8y9g@}J{$C9gVfe$OlYFDI=&H)T zL0AoTZy=UcPOU?0@WULCJeD;B(VGnD@ zlyrwiAu+~YMP-Sk%FBg5#Sl7aW& z52~5l8Kz&u6T{AdPULF`WpN#D z(~RamzUxow_Ze07fr{h_ayxn8Ws3{Fo_`Bg5%>+z1k#V>{*rBr0nv%Qw*5DvZ)N2) zMC^UQ(M~!_401(5r5=a!N5si;%F28s-@;FAOaP4d^ z38f3{kX}h1FU|97eCv}5{lRfu*6dl~#4IM3$X9mFIrqfCZ(ip1>0{!n@5ghmdZJq3 zKFHf1-(=vnf!&2^{`;MDGOomQ&rU7E#iT^VG;WJXh-dpGaEJB!p7j#ftv_lu5!dfH zu;AN8(HyQ{VFtJ5!*4Ycx^c5GJ9qxs%LIVnk2(BQ&f}GEA^Crr99&8YUvX``6sol z=1UMFqkp=`k&-!uxhYRh1ZU&lB)~|_ITOrb&@?pPV5#~Oz14r>K!Ue62bL+FaF;?SifMW&donU zr+6h#LQp|5rU;<=JMXVbF-SoL_Ra+AcUIlnh1!@4VTiQ650lHfK&ugG`VK{JP zbd(O>CsoP$dzm6kf`>ul*CToj!=_n|_6n*9NN?Db2H1h?n1W(zsGh#oAHzeM)?~R2 zg$rKnY`G%6sw6CUR*<0JWHsr(L?M-%KWvWws({7je06_8ueQ+0=Wp$|;tSedvhdJY zRkxeuqtE0(BLHpv0Xz#&B zU1I#rkKQ)-%xlGrP*}{uP?_eVLe`Tz$5@f#|I|yQh{fK{hOfoC~&2`cqWd!sJ6>-D61G&qr)rhHjy(~&KO?7sOPXn@M~WZI(8}YB9|_0D}jzJ zCOy43Zt5|f0`l{@eI4hVU@_vP&My#e@3E7^?NjhRGvJS~69jK6qE( z&=_{{C_D(!tk>*|AtUIKs62`^aycwl{|iH;PVwhDea>mjC*;aBg|pJrQ9u1kNrTcd zz8fBqH@>>^-w75nC@g>Ms%?V%{6r??K4$Lbh>QR)0O+_Ds<+A<@8kCe!WNJ436{V8 zDGu`c05ApXz(=+>_I!akfKuU!_uj`aZCz)+O5G#8!9nxwxzGJ9c8ysaKb$1U5S=xP zJ}qvZQ1?MHzNv9KGc-1}hdNS%j7UTr7#Zc7Y5{a87Xs>?9e)%9s~G0mf1 z-;Jp%R88!dG8)V7ev@Q`Qb!JTci+*DxnjB&aKg2l*$~KcB;_;2+I~A{9A4#54<7&T zaXLcqZhbCzd6|7)%lW09eGQQgIuhcdqx{-lzD-cs2Kz^ZV;z zK`-(qGpxHQK{jJy9Ux@UDaK<^jAd^38n_hWYr=flM3k{&f2Dvfy}9zfU&TyGaRf?YM{E~24Ibn&_ z=l;D1`*V+_-d0Jp{csKUxm_?V{ii%4{G*2w!keWx&zIZp?tRyh<921Ip7)MAQbIw&Fs`nQQ z6~4!zW#bF~%DDl)nUPn??vx#8M~2QuNMZZiWwMl|D~vOaroM*XA6K7qRc!7!ZSJ6e zM=M*pXyUW-h3ccxrU`wzC@t%gmwiJ=9h`h}%XInY(ou9JoruG(@bV541T2?UOsPhC zm4{x@)&X})_M#|_&4G#c@)@2`t8YO2*k2s~O;k!051&xXs>Wys-Bod|!bF zNH>{97rm#R!nIw8LF{XoQ)yBgMGJ~yf;Lw(rT%s`ng8Z6>~s*^2_uJ=hjO;EQDP&l zaVL(0A`TPzUksCHRo}5+8y{qMV<(7j zu&j`pAw|B@{FP!A5%j#wo{iTJ%WPGVRgg26kq;>m1@yZ zyFoIegAh>zrM0lLukbDSlH9%l5Q>mKa9RQWjB+475Pte5 ztIMd?hc|VOhKxkeT(n`H1aVPzH($LgYY*9H0vzpp{WZhiX4|31K>OUz(e$r!#GnhMf93o(nVx8P19dOJVlDOk!h?FR9%C5AxPUDyvwSi@JQWbub5Lf20GAk zvMamK?1V9@##5xhccS6J70itl&T7^Az{zEuq>1lOd;d|+w=24wKI9AX zBhOeg{IAij5au9Ez7Y@4Qr)&2+#CZzNu_|9T5Pi|-9>m*a!jgmi%%+z^-?KSvY1ye zHoZH$>wwR1XqH~#BG?d_L?|LPo&!~S@K!z^%xM;ejkx|{T$r?0S)Pj@Z8!Uc{_J7t^l7^uK+-$q^`On}YnN9Xk7toJG3V5cVS2rP}&z^xzYFx(Amsco-5C;%zXa7Gg_w6>Qc2iUnw zzf8l2pAKJ_T|POiqM_+r5C`SefzZAP0=MY#`DZ#U`k@8#?tR?vR{hEW-QR4bN<@9q zsvyQ2rEuTZ)*qAIY(SdZ#<%LSb5U!i z+PCe;_0zz0vX@eTGc#Q+6u4+TpH?ZWnRyXqcQa>^-010DwhVvwb_VbVU}474j!kXB z;fV}MwuzY03V60`g#T88$`47)p2y`#4;5%^55uoN86SU-%}hBsVW0u7!1L}JpLixk zBKbZb+VJIN@|CN138GVML~`cDLux-)_0Ui#fjUOCn6ToHyg`KLp{n2gp;xd15(EU2 z5hAIF^($0chgoWhg+A32l)kutG2A!hB>@wP_Ip%%9R3#qNYU++OwO^3qk+95>!f@= z4PLuAAg7pBz8P?)su_y)gq=J04UW9m<7CYjCj%ZFqX%Xx8CT3_d9XAu==2)Yz9vfr zn_Plu-OlO~^McV|Q9Kn=*MOWfFqwawn5Cx^OH71!v_k~}GTtuq|JrCYqw$GLAr7pfZ;hyp1{&9Ejjuz8@6HOMr z(pqXzm1bsXP}}AU;DKddC|1uT8x|TuiMc7~siLt=WQ0BH*&B4!WS}q59`o5~?h9Cs zP9GuvlP(oi({g(%(dSe9eY*t0-Py93Jsqq<@fnV-0xZZhx3<;@84&e5ML$Z2y;xwl zF=}&`z=3P3r{x8s(9G{z|4UT;o`=JGz(jxxI=c8>qIQ|nzp^VF-=WL-8LU4k?EbCj ztoPayROYd-R|igq@Hg*?1=dj+xizIQSqBjq>=QMEVZf0=Ud!|)Tw(yNc89*zwosRj7bXRnE`U{7m(ZlxdmDyWr2 z|N017X@FV3;#aDl{`HqDYr)&W1NQr(t=idOERBqXb0~AL!VRcM%;zhRvNF^h8fhOW zZF=W9_3@B~gca>N?Ou=2U1Nq2#dl0DhTLBbZ^tAE{fvv(V(w6WS=IfcpYFzMKKFRl zrfdkl5X)s6A6l;fRko(Ul(#q;nAeCIlf+M?i`&v`*5R3**(Wb+-XMcHZm1(Clq z5#Q4NTQm}eGul)k`OhD58s?M!Q5t|gxLaV|cnM5Bw~_hmQ+@U&dC3k9=3EtqO12bU zahroi_`4+!r+>c_#|W$=YfqA}T_Utq-s^XI$U>m*$kZ~WhdQPJkFL#J|1|ROJGL@p zC-lkA*BQ8`W2=@ciluQ?+}oL)j8Ig{UyiV*v^4_eOwseAI_jU%=lW?i5Bx7+AoT$gcc)bbznRnAIG$;M?!KXe)u1=cg;~m<{JX5>7e(HClcdp3o=X zV&!J|Rwd;jrG8@5$^UvP12>saMABQuZr!wiND*%)$F>3l_r>Vshgh*R2x#)(4$`BU z{UxNr2=fbecRsngAiZ>6KbaZOtF}L?VUPyaPAl)M@A52v2Rv#Dg;S@CR2RmiLp zs|`M3c#ss>e!IQV|CNU;Hsw3Tw+kR=>zmxeq1W)T)Inf@HsM-aY=&!NJvSGmJY8Fj z1Uo??-p;0ERZ!ePtMQpO{uP;0?06p;!50Q@?URek<1%hPlb-GP2W9-t^{?BM*x)#Y z7tO(cdp+N94={Z1dCR}j%E=8n_?H3q&>U!WagP6);L&#$tYYfr?cQlungXw45=^eA z-LWrt~N}F;^py*%->{TOR#4`L1$zRJYfPMc#1`7XlavO$mu>H$NG%T%7MA5OU zR-yM`??~>h^~wdvVlZb%X}o7=$(P|IXY}r4;D4%9whNJf*M*lQ%XJorBpy6|HSYHk zsKSaVXJ-UXlO&2{e?+f;yx?WNX?VSopW~ z%DP41T_8W0L-bF&M*9Q{x{>`(j#HSL>HbHtEZ?Q!dx~9bXlDovJ=Ol?ZQNeZj76t} zzTx&f$)JaYU`xq=cE{!sbacc4^>JzxB|Xv51=LS**yD@4{wSet4b=G=$avNR)m7lT zI(fW($4}LQTV?nXS9eM4I%&SYWi`h0_~mnsChMtMs`aDN;V~v=7e`aT3?!Duhr1WP z85)TsLw~pId@4-lXhAZ9R~uOim(HF=EIQWiiKHQx?BHd{uZf0j(4ov4VDKM4cRqi* zf?{p`cKNyc73p}=JBpA6ivP;`|I0%blG)w}fWmXHaogM}Mz_1vtyxce?(vP~J>7)F zSy_)Xl2{G-M}G6!GuDs?2$|FngsT-Blne{=a<-oZo4>xPJ)%>y!3ck1QYWs0lPKKL zg%7Lj=z1Ip`KSf)kk)dyCR)43lHq?A>A*e^3wiQUM||?WyES$_Ij2L ziO6K5zDIjpgT}^{vWj^rNbL596uXsr?Cz{EdQscjNi!NkOzQf?!LYBvgjPs55{-?I zPMB#hXf*<6p%>WG(mrWN8^y&YKA^qJjZW%bg}i0zcXY-`xgn8iR!3Z|JA51>4K*-t zYKfIJ;7wV4A|0=O=%>$RbTy777#`h!;=D*siq1mSqzSPRw^aG7uNqhUkIo{(%N?kvPBv@D4#QSK=#iNU zB6o{VxC1r1BF*d*?jm}bZyZmtX@1O}d6ZHVZ7I<_2ZukYzY#da<@FP511&^y;01XB zU71z$!ZfL!5+pyES`k>&W;Q7{!#$@w9M|x7IdYw&4p?!Uz6qeYBe5HobP)|X_);qK zl&eNo3$rqU35eycE>BRlrn=owngx{jzh+1BQ;v=LtS!T=Vc_?!;J{Yko-3B{0F+#V2*wI#)Q!2Rm>!dqm3UGUU3~ z!Q`{rTR)nFi&;*V^66=%G>@H@yX~OyOw=rqY?l0L&YxIrA?7SuN=-zTFJBd07M|At zH#$!Fk%j=6gWx1ToyvI}#svjbiKQ3~#5E5^f@N8i> z*$;89=jc{*&#Aj*#GcD>E-dPONWbfT$U9rZH=9~qFN??x z_TBHCH(Z+o&BjwIh+y6{^w_CZwN+4Q9#9M6His9#G(Hk3SRKEuXisGDa~04N)kYw3 z-5l?tvPKsRRY5|A_>3fV*}ngdzZMTVZdF#qx;KsYKuc#dJ5)9#=NEf}R^K2WB{oM~ z)lEO^1^0KE4GFHI7^Vt9BJ^av&E=zsKYY7rdT^XRv8QSQ)zQcjUh3uYPRrId!Wt<0a6;(c%+9*WclO=cu8RQlSR%Zmt-8;qkqH@vQY| z+VmSjkH7kLCj=sEpfR07Tqox{}}B9|14}An)!L zqwNHGd~qLt_|!|CDBQA47@*c7wHz6!zu;vm04)U(51wsXkc{q_k;*aF5kLBJOUk92 ztw}1I{Zv0PXJ@PE`C@X~x6ovxRTPQbDLnBp_~a{oQP~lbH$im+uHZ6mCfMlYW8Y|i zYO>LRZmmCFGzo|KJ3+09TN}=UT@TtJ+)OJ4usDEU zSibO{k}&{~dZ3{ApVzSp^;IC@uZdmg-F zN6cO?oA4K+IsC3pzrN!m>2D_t(2rhZ8@lG(usAI>MO3$7zxc^kE(gaCb zUX^f5+x`!`91dbKaa3p4uO)hK*6^QqAUwWJs>(+cxH-?3~c#_C>1ih|FpB zP;C&{p{~sVa;de3pv)d6(6722!P$b!!= z4S;M>FSX(irNa>X(Ai<$gbS1O`C2vhOB-lwJ(_kw568K4DGRk;Uh6MU7P+OF$2>gu z!-KVciYAbhl92DT**vAq^pZ)!k^ZSIVs7Y~`%@ZABZt`szNZI|=5A{%4!yO6b`Fa6 zSYD1jbN7EH-NqMR#cJe0W$o1M&qrX5J@U`)MPRT<#1&0`QiXoUcRYn|1Cx^IuRT3@ z(|Nof6Ye7C7gp|T4Ue~MX>Y@O)Mnty`F%tT`@G+ls+TNek`q1jS(ORn*|%oa)Yn*Xi`e=d{_Y<$q3OF^u0f}O zUt>a5({K*ws)#$zWZ`i7Zf38UlRRAu${wd7$(Z#gRhD2n&oWW_GRlm@3tI#2OuI4N!2&9 zE9c{Scr~%jP=3@RxOp_n^X9vMK+#=UyC}94o-ljoe>l7@9?Ef9f+fo%g zot)pXDb(8hcULyw-wRF4B%14STLc&g+6bpXx@BI*JG=P@T^+Dgq5uyx{|8gF$z5@~ z%TPbL-)j)N*8k%o>7A9xBThDw{?;t6I2W$<)7hSuXc76IiTMhlQW5_>Vs0|W8mpP# zhVC1!8UnNTkQ=o#2rJ}{?CQhF=rJO-zNJcSwa)v6n#90aMwV9F z)Cfj_dq$9#S)dfTAybd)NX4~5>dOg+EDv8vb%X6Ag>qMl{6e4kb=WsL8_ua zauxO^EI3^GXPg~kb@Pc^XT%ZEF^|EreR5EX^k(WE5N{D5Bk#UoatEHbb?y!S^h4Ld z^#Jph^pkboeQ?G}Sur_0SYnkCwO-<@GwQLhB9jT@82IhfFJmWl!SUNMkB_XM%M$v+ z%52GYZW0HG?`==|Hy^FItzCbX;YV9{eE@Pe~j7kKV{c=ZP{3rnB8??M*_O3NM?giW1jqztcEslQtto-rk(?1AMcyn~;h$kfnCgpy$;GN8p}uuw zU>~OpGm&j`G9<&&yy%9-pXD?g6e0p~gm5`#FdH%k)l7GHm@z#zobNq%2k;i|RGz8vjK*Hyz zdrpbT=ku=`#HzmATJ%xF`z_N-diz{Lm?GQY@W|$DoI}+~p8o@n`F-vTrOB6*M~>Y;AsND}Us|I)t5_tPNT;2nE$ z!=O`B;oJQIk`|q0FFSxRKO}nt1A}_We#mLGq182Ob;x;#&p91RTZv};`+cHffw2&| z6UQO9L=h~*aPIfHD3(n_;qelMTEG@y_orl!82uvGDtL-mu7J$BtdkzHp zAe)2f$?RX~ad64)kezoL1Ac>YP$j4RWOV?+bO9z!>_0_H)cG)zJr%b~5Yx^3$!m-349&I!6Jmf+R) zz=~9b%uJwK{n<~yT@hce-Qjp!u^NAAdPP-L)M>KM?Z}96?2q~N8)zsKxFDE)W4wFH zb|xV1MDe`~qV&CkzU-0OH39K*mqww?z5x5(L#lCXejt48t*$9}S5g)TLLL0$DHG5z6D7=N{VN4m1@ z)QM}{IIMqI?h37+cqWyV-0ZI#KVWPCaoYIN6ozf5v|r)Qx7xdPZN#mUkDKErJ{4M3+TeAHTx zh9O~#3xl<+CCABuYW$_q*>%wpz#QevgbYl2>l|JZFT}1#Bhmvlw(u{{-@b6TXM@6PWQ79O`q3|L9|~v&kr*o$jsW16lcKb$)VyUSV)sF>MQ; zmk_rXFJW^KH#=kd_JJe(To~!A3XmAowl=1^W&MB|ISE&4&D{?lB>G|qR6s}oeig0W z3$eP(xjC+qEVNIB29R^})z{X)*~oLvqsNzof$iXRx4_(VThUW&!(~w*rdD*Xq_LI$ zXMbJ%Q%J|Z^rbI{zanu`In$f&n}aSk&+T+Ba;6gi0Jh5MOcg-T;(cxvRJDc}DNyVz;COyEbwec$ z0349h9oMQ6j8n+R5DoZiqyk3X1nPeN`pHa{;cCM?Yd76nmHDA>pFf0$`m&}T%<G2Z_ZpO?r1%*8?{^C+1!X zg)|BPy}FK?M*$KvoHD!K)m`j4{gvZnJs&Z!+zYF)H@2dG0u!ReXejmN(<{mzAZ?1C zy`hE*p2gN%E?k|rZ-guAW`Mj3>lQOWrNDJE71*#Tvo^f_`JBw{3H%V;ZrapPC>JKI|o}S`vFOuk?E* z%B}S0xQ}OS(LVrcpVKo?N3U35a!<=h*i~;#Ok7l5w135s@BU*hxTGn?3P5H6Q1kEC z9>iz>hWhmk7Xt+9Tm;bqh7%Es{rKi7zmF)O=6Dd5oTooyav#cZk<`PgEZTKOqybd7M5&l!kBq8X z@d4JEf%Snj@^IPG>s@IuuY0BV;2j>oS^(hqhqz^FkwO-n)<}**;iU*n-yUS{=@oSh zDze+80&@7zB?LPf9G>lB0om~doF!WIE(eyP0~OjISJIv+hx?DvS|r*t@I(;6^pii> zi<2zCZ$0RI>?s}eP9I|97>XK>V2`oyO0U$lj2f}jH$LHyGI@M(R6whFuwZbL(g1iS z)8}CCXb-K{-{dutMI2t9N_A;x#sN&Th9lJw-J^v+o%a?rX*9Z`?gi;?RA=0VDDWF1 z#gkmXXQwRPi7W>v9Bt?UJ*gMGzvMc}K$VnhDjaM84%_St*zSNQwTI>^QrfFQJBKy} zEj+0Foqpfo;5)XR&+GETSt)x|Xh(NnxHTkjpJfAbq6&v;a_`lf!dni~s?UY?rt!BD zmwTWsWolU~+x@zF^sh^YI7Q-5gL!tw{-V~PM4yn`BH&VU1Ag@tsXW#jAK1-%z;A#8 z-i_2W`c}-wcH~ywoxv+sWK*|@w5X_1F99I{tKCbL(9Q~~h}5K11I z%5m}kM+-34yjTK|lT}`4lR<-Na}dL)inl-0w^zC*+EzNtt+7LQ+2`ziH9zV9s9)UT z`sqyiC;qrl1*r0s_#S=#(5X#iIatK`CBV+|m!rWUyo zHfkGbuW_C?{hw9rCxP#i>M8O9aCaY_< z!BhC_Sm+3Ve||^WiW;46g8D~?d-&cAone6Ycx8U%MmwFAb8-!S<-Mk?R=3*A~^wx2%eK)6?nF{_DptbFhw9eFGCv zoH6!%?q)p{Y$lx6ES9>kbC%}H4KN(x`n7Eo@`KV>utA8n;O!+wa--1W|A(}@ET-ygT&;HokwIEVp#SDoGvDS`jg_mhKx$vm*356!ihpiUwnEsY`5HWE>Th~B{3{{_2{8<7I`1_pHX60v@Mvyli?A z$)x%^IC#~%^u6xPw+)#Xj<-=13C)DsZa?B3Cl(PO#KkqHm;PFAm-h1BPlnbk@dtsQ z@^WsvW-mBvjK(5#*S>j9E7HI5#rF0M9)2q?dgpeaz>rWebx=plYC^DU6vft+-KfOa zKv;E))7|NpyJMvbMX#G@fu_a>QDN!&XQq2*_?qud(7#*7^YJG#yTrZTvQ+=eB6O;R zoL!DkIuVAA?*09XQ?5HFavcLj$(yfM&GSFEHuK%pZr-b#a9xp6x1Bp|wMw+>%6_G{ zv#eZlKkr0o{k~+k6WI=@xn=6p*lLuP=SZohRr7SsIIUI5))QiS?|?bSe`31je_*4! znYwz;wZCGz6mOZ2Vola}kwQ#RsbHFQm8;-2MF?wr`jmh!hd@@Z@5U@a4F7f%{pI9| z(4m;Kb2X6lIfU-NH1sGclBFjl#zKTds^3SIP$tQi|5{b_f#{5iTWqP(YuY?fZxmhG z1~ETBU5*8{m|?ZNURaCAnIzD~Cc z6dt^}RusT*>+EJo&)*IXO(1Iw0s)ZOWN@@#dkSsB?XUOEfoGnY`h-rv7E@``>neCq zHoT&Jgw9^$(Fi&aV3A&hzrn|Ul5r|RrfL8uPB?D`FCMr}mZ`_ot3jEWeHqh;tC0*GrDd()t|pYp;` z9(6pw>7zp5(#Grsi|J4eb$-+F*XeSJ%e;10i!+omP8BD8RW6?7xwck(CM3>$G5+->L?&L}=s<>9M>-Kyyh}NCJZ|^mZ?1Y9x7g7!xL{ftmS! zQbhUTg)I-dZu@0x5w8yotF1Ta!>g45dCPLD^Uim88aH za%G@WrQ-h*`*|}!?pQV$u0iE&_0mWHZe|I+*Y+$g5ZY*`A1+USzK82-;0gFK)ZUN<(%vQkCqm zs=LXQISJtj(`+a;w+40=9!OQ^gHIKhC|ny02JT%Q325$(_4@UKq-1&RnSio-&c|Xc z0-oY~_!Mfp>JGyNZpNw7qvj}4-ZRUkSP~y7w6I!MWj1UVSBu*}?6QB_P8^H|Iq*=) zQX(qlc@g%Jr-buTce*a&({}S3?`)DuvB812!k|dKj8&$6?~rvFZN2K)|Bmn`S)c zcI$bpDicA1D}ryrbxr7ZXCgFT2^%91^#xiD8LpJds^r&aP)?V@FHnPI)O;uCr#*fN zfjw9LEW{Go-Q*>8M733GhtFtOL)9PAkn}Ctrm5;~d6wt4lgV3v>`;YcYAp7AHO%S@ zB;CbZ0$Us?ac7m&$6}tz<=+ctgn_Eh(=t(Ttv~(ii4L=f^6gd|LY4?kgS(!x?5CKc zJP)k9HXk(zo+{paL`{X*KA2DBw3!x9m5Xn|pmg(UHn4S+;12ci!C0%@!oGk1KFTNe z^*u{)Sz>VXfjlf@fvou0Or3ln+&q8e$r@yYje{a7eLi>ki!A!Nv-7_(SXLEhSgy8^ z|Mf@Js-#PrGap?0!;3wtzRIpL&P&}zRkKd^YQ!4mwwz*?KR~E1O%~}*Iu)}D%(~al z*%#-bLAq3xsXt&T&+^>!D^hP>KU%A?cP5=)h87!a>6??F(J4+q(3`9 z&uKouBq%62MjnYO{I|Yblf}igp$`-TK1k7|4etq_ns~PUMd^o~2|}^ZF>wIyV20|n z{p!^#nK<4MSnP2-^}p#ep!Eq9QJ;{`soEv+L@sN`a2jL7@KY*k%UH%-*QzdDxPY>M z1qFqDXvMg(*~3P2#@i^2hL_X7R8SM{p0^vn87xuu=0dc|xP&BgUb|i%oBQEQn3LM$ zgRK}Y)6fdBazv(fO#;f-S`4wFe65?C8*1zHJ%Eo(O0_yV62U{X7g^0dln|ZE>?&9; zMf_l(q6!)xYS1t}8u;fdl!BxQZpcWBUf%k4uRN#qgy6~150S%Xb`Q#TgV5;yA!wb>k2R2+R?j*nKk z@<1=p6zM1yCfNPozl%Eh{PDn4H$~yQ(|2s`>|z9+Ie>8CZjEH7=HTcVzuo*C1Bb$( z&KH-)1Fb&d31SDHK}j9AWOtdxCuAS>Bwyc~;|a<===8br-LZaOu>(yY|M%hZEjJw!1dD_OBt= zJ%m+~$ik(h?ELk^yX?i(xmX_SRJ-{O1h!<$Eoh|5Z9dRdW@miq8cAIcxd6(H&aTqG z7U^b3qDW^~l9;5dtReDnr_i*wVf?lv-~Q22f!l%Y;r61KfdP$ri4{!XnMG4g)1U_3 zAmDz;b^a38EwB=1_2RC4Luq*8o1f(3`Q4y(GZyK+fTku1r5vr*e~%gyHR?bDeEeD% zHRk2ZI=!i~@Q4+V;E2NFKft$~#~i}+_Kt@QfFhK-}dG#%=r z_R9lv(2I^nNGKjWRQbP*v`h-MCvlZBReoqXj@LtK(F_eK*Ef3-bC$;`Pu4Ncoj;G- zt)`}?m3tGePEJmx0!)AGtmTA!UMhvv|Bd!(X%%9jX49`QD87%5#-e6EE{^PEC&yEl zBj#UE-efO}8o+??>9HN1TwGIMy5hkvZ=7(Qa0Nu!JjF2*8N;S~4!+&(c%$(n1M8W! zO+TU_@UNdn+!7bhRIPMk52Kg=9qf5bZC!nkT2UKfW(7MWfI>)Z4~y_@yf&P&3^zi| zOeZRx1-HAzWDe*z~E3Gft1I}V64=}z{u!dlN7QX8rlU9S&7^o6+GFWsoWhg zhYo(d<5LpXdTKm92eQ-~JK_b(Ahg1M`S+F>Bxi19rs{72dyHn+zf@q{`Fq$n(cY0) zL5!ULr7te^qw5qD9pJPuuU@tL*Jc{L)(#%eY^G>X3%Ujpx5aQi#x#MmG4cF)R^$9E z8l~Ui(-IOAFaF<8;g%GrFu}9M^V$7o^E`2*ll?f0_>dCGYrk}()(5AtwbdV7!1e!i zb!I~FjkqQGDoldN?OxP!Gij7Q!8A#K(jLoW4B^_z*|{5@_j7Xc_@6#QA}cMXi)#9w zv$L~I?7cvF5o9<7@Yi|zjWCVrU#4efi1}=3qF6Nb+COp^nh$o2-+q7QaQf6f!rrwC ziH&UqIJgguq*bfk%J8}r(oyal_ONMB3g&qX>{$r!|DK_uNYt{-X-Gv)4N^%o(t8%411ge_!bbs9Q)yg@=oSABGN|nVJ=m5K2%nL{LabHCG2cSorV` zKAntC_veRSik-ok5DUBU5)%_!`93*wTq#DIwvK323KjK@jhuRQmszx{+aRKuj+Ym~ zkQrvDrhdRc{D&=2@Nsr_md&u`2HJ$%mh8#lV2vI}Of=v%7;R-NyvFmNE1g)733lfA zeP4;ymnX*uKUGuA2eZEzwnoAO)}^Wz7y*pIGU`kSEGgjuxMVP82Wu54?EVoD1J9#7 zXIor>(}b?j_nDt!nj9*;S5{UI!PF z@Ts_i5n$Rkjn*cr#2-ECsdjhu*q_2!8pv7(Q;f?uYA3O(K{`NN?xxPplCpR(I^&MG z+cY#OSCao6gen)ln)uy1#CQd24deOk_3Hg@N{LDbhD1jensYGFS6>xOu=;){?Foi$~&}n1Jhq4EvG$7;k?d`&H zODiiDREo2)vGJS?PT2o_NwlNDcX%scsIt}KQ6esr>j2vmsGAEF{3bHDXlC{FPmSnC=i*GXN`9!grwJ?vG?v z-=7ybZO%7rg|X1k)2FTT6%5PB$Y8;;TLt`SyDmL4Cb$e?&?B4EYK#|AzRW_vs+D=6 zu#f-0@Rdx^>4Oi2%jJUM0I)Qjws#5K=8>_~H~z6y-1G$0)N1VhZ>E>BRv@uT2>9t} z4a%%*RgZ0LIbdS~4ExJzcAf1Y@ozW5kJQorH^n;M2=<(X9?mZvdC>#~dAi4MH`&v` zxn4N)JNJF042~KEs3X!TkfP$>8bBm5Hq@|!VEgB8-?+098L8v|tx?DeZd_okTtCNY z+yVEZvYIm7O@=e}FUi5@6QFGMQtlyE=Y!q+M<7~3>P@>4jYe?2mQU!sGraDQEu6x3Ki?3*}Wl> z{O3^DKkJBX3O7+P%u|8pul#nu+jM`tz9{pNtNCA!(pTad3fY9~<*7IwE~dr6lU*fb znFU<%@32LsAO;A|mb|62v(X^Gn#5B}ivr-^Os~9%VRI;L0J%W1UoyT;FvwR`9mtH}o1f5qGb`N6j%&E(<^7gwz{vulob=dqr z*X&_3O<|Kg9WCu!@O~j5KT5rL!KRo-(p$b zj*1`4sE*p-PskI_ub&f(EvuXaHmb7CK0up^0Bv(?tA*Se#F#~&Z!m_Pt@bl>2xl6` zkZ_7UdUOd6A^A{x5NT^`qmrdko0*|%cYzG$oK)+{Y6P}o%2;-a=4?fY6)muud8}DK zcs^<6%~xPKhlka8Jca||Xc|Gmbe!C;)*a4gt!DSo#GTyqg7Y;|E-aan%CAWZ9ZWq@ zb(-c`$>oU|bl(NuH?9*yiYKBuwnbWu51Kj7Y+7Q+2$`BorNF3J?G{rq;o?6wrhx{B zSYaQ|mdz*V?;*xB)l1|6p>Pi{J4J{4vtz{^>!ypFz7n3%Vm&@Rm{EsQw4byJ5YKNU z-QMlu2U7CzbamX(>Dlv>#*IB0mo-cpnr#x7wOg{H&#vDX^m|)hl!+J_D$-Sds%*h{ zZ`=6(!;7S!smN3I@FcuM?=aA$T<>XZTMIUS_eLfZ^TLCJ$^?3OBZSai+#27W*7`;( z-+bTFc|&P69*f}|rRK5P3WCkXsMA}O?Vrl8<;RT#Ef4ckx}T+{A?05HIz@%>OgMRi zv%J!nsl-@d)IL2EERqUAbLU2k#5jND7EkE35+1QoK(0~MHzvZ7LZ4N;mXjhbi*B5- z;q(VFD>E2;Bn9E2(}F<=t(FCh>hodE4ku07lYAi#*9m!8uh?-m$pqC8_xpSBR7=S< z;5sn72fHuNzZl2Q;KeJ5mKCXzNL)S@+d|Bs^OhSEPrM3Tx9+;)HT^nlMQxV?Y3(v@ zBC>j`LfJ!H?I!_HI|3@X3u>eu};G)I2J>zjvjd@JXj+x`ILgx z(=EYD`81Y=I#B2r`TO*5!imkL=M2b4AO9>)+*rq)T0qbiE+Gl2MiWQuggtr%gX)+X zYU$rZ8?JHwp3(-=I7=b%()b~^TsDGiqU=MVn0o1M_oSpiVIa4*$ZKsA=|{(_(j0h> zdA7UWP6s?X`{As2>z#%CTv}Hw{{{f7>-GHjhsT@iNmTd-ZDDCz$#m&-jq+x+i09;xZBjwUyGCRC0usv)H}n6HU5#{McUnlv$ag8 z+Z5`~j}Z}J{-jzbQ#XDa+Ds35@CP5$C$+n5&ee=|+bp=3mLBnr8UHiiA+7O|GX!Na zs00eCaic=Yk-ii>R%Cz#csoPh_f_@1kwtsMWn8`p8&3F#O(dVnT6cYNrld-iZ^ygTBoXj~z7&)AeZ`{iZ*3K3r8rHY zjqR%i5e&>MG=`@nRISX*?#Js6f^H8kTlFP9aDQI^Ofk`1AR7i(FuirO;5cIr?J&>7 zdl)5jt>_MhO^a=<5~}O0KVpcMu%G^H@2zPOR?Q;l!M3C=G{sSv9_&Vbr027-KoL)Q zp2)%NN`$IyL8zsq{flEQ@^O8pz=_n;RWu+`G9wkF{8mnfp@{eQwF_9zmbj^@Ne2?b z2-+y_p1-vKM)#wP^HktnQhE@qErxQZ1Rv2W?D=gLps%lE+kSNeZ&B)e@j4N%r9kn9 zk15xx?KQqdAJxN+@e4eN2a}{)mu_+Eavt%xi3OV{WIpMv-qD^R9QaurTu`s@pyh=7 z#&4sZl$iyoRf_Sd8)3umeeZd*#l){)wS4rfF~kYu-ZvGiP6dsz%J(LmLJedbk;?eb$M~~`l+=fvG0X357@PTvg9ngS^%f3v z&TDrc#O~wB45fm3wA^R>C3QCnCA26&v!dx zW$4kGt1Od8 zYqytq>`NeI{WVv7YlB+Acakf3T`A2-F^$$Dwe*%x@p(k%hs&4lFtFUB^>Vil1oXGElwKId9?v3y(mSdXCltA+ycC;P-$Ov@2(aE40yi4Y>rby;FgcSj1h_dqx17-3lUJ}W780Ay{lC0Hl2(5ijZSwsy8HJ& zrJ{Nc#K0`x-sI^?iNd*&`udAr*yQ}{P=vb<=s`-m=y;7L5$Cv{V_2K{ip^5P<`u=?qRp1(^-6##E$`L$9tm zT@?RdZ$SyO5Hy(~vgeI$Zr1i@LhzKfJiy~d;-`iPMEu!ie%4u5eg1lg9X-@Gc_!U@ zBi}gK*d(Q-ywRWnc>+V^Hx z48g~}O#H$YdQskbJ=P}vno3|K(vreyc{CGgbax}RCi%X9^-FRj5sQ@;+IGx3)pE6~ zpJuDbtx7|YLpdPPhcO-3M1v5jk2>=@pJ==YEquegU2_m9wPAURytZq(PvUiLQhuhZ z_@auGf3rx;qmiVn@Edd8Gb3r}`jZQ(<9At1R}uIRjCv^4f?_Y}&^)X1=Bu>3?M`2P z&dWcRUikh~vXN>pIckb?U+>Ws6qpyeXRnrijMpfg4#F9#)Zw4Xy7VO6^L0=yA}4pv zVRz$#p0cNu%@4`^pjG1qO-fw{hpc>gh9f2L!Vu%*bTl*kxeh(R!M$^Ako@Px1MoE>A^p%?VgTdkERLxQ{cgMI*HQxXTwSzII@-_H} z=H~a3VRRc!)WI6IuEO#OF;6FN`!+pX5nn>Db}z*|vEg=uTIOi#y} zW4)ZFiyLAV&RkF4z3b-^^mmdaExu(W-rby}=H`}w;*jN}Q-OdLKU2+_I>X)-d zp@Z}A;SOn7lybYFxOhhil5`#_Sf)b?>Nn2psqZ2rkt|Qc=m#AyP*D+9N6%4CQx2Rv z%_SfkIzFFuIQDGvkJ_ciHuy`Rms*v!b&&q#XE>+aD0>abb8;mfR zpLXPp@wmM9=?)X^Llx#P;>DErUp%89@Hnz=IMx?Ni}i4s3eeL!T79M$>8Y~3ykbLh z>2ZTd<<57`psAM!^u6ornCS(F9VJ^rT66KOc@;xzXXl|bTu_e{qQ=P3qCY-H@2iO< zu4)jH_R-xN?O0Xk@zFlzN$8n=K$Yx+0yD!U9@u57%{zD*UkanMYARcHCnsrKnuM?t zwi8x0jBJ@0jYUL92-Vkd%uNM6QrY*)Joqt32|mO|yd1DmCKR)5sL75KO!$tIgEc>( zyxXrDKQHYbpzJ(vyTbDO=x-~bqKabqYqpAtttP_ivQGj4g50IqMpN6Z4!P~SvITmhHODGD7Wj|shl7)f zXFQ7mC8_RD$O6RagYWJ=pvc+mm>beu**i<%Su`O*_Lay=smq~u*f9o;D_^%&OauAj zp33FYE#gScMjUJ7#?K|_CjIk96^0sPRm3kx1)}3vg6i*g?CsCT^EPzmXv-?uYQ*7+R85OKe_}xlkGzD-X20hH6Sr z7Cm=tZFN=MsrM!m$PK|3J9(7GNU7I2U6Q9F1;X5ss+K3`NQ!m4vQ9I~wv-ql$!klB zubIZb@ldYeDLBI}`#yc%veM^wJzk8u-8((Tb5><|!@VpyNt!x?KUSA?@_a6!q2^s_ zmeN%L!qZ@CcK?lS^Y4IZAXy0ZRFMW`c58V^OTB7KYeimShD9ZdU^gpPU%+E)TjgYb zlM*$jY?b8RR<0P(`gj2FAmAHCH4TX{x#UHmsfU2b$w|C#CXTlPC>rsPPET z40nISwJ0^YoCZMk^N6|wON04N+~c8wrPI4RLe7&U$E1aN@KCj^nHOV!*XTH|T$I#nFMbgQ0l?gw@4Ind!4~F zKSk>2BQFs#KiGlfS*~&QGtzA2SdT1W6X4@KEqV%0y8`!g#3u&`Y^d^=A(~HvPM0MoW1$Ve zDA?W{=t#zZPju$4RS#aZLIPfn?TvGm8DnmPi~-Ls(bSHdz1-LIOCF1UO0O=u@fQv@^wc(lqaL1BJ>2B)CVZe7 zoaQ583xDIm%{_8NqEHdJ=i_PNQhQ-ES0#5DKrVD)F%jmxzjwRd? z>{5LB8aA{Zyy7m$X-0U+tK&Js+!;K4R$}xmiFNRnlaa< z4i-cM(S^suLF6KZ*SZ;lUBvEKoGB^x+mdUA;8%7E&^yM&b5v ztQ4Qwc)YKP2sd8qy{Dvpmhd&beEht7#g1_rd9FK4&1pezB4*P{-~L^FJ7%8Pl3Vo1fJ5cf;+ZvxG3qrW zNk;zzsC_jH*aV;^w`~)L$a%74pT}hGiAItAJ^f#ElvYO?AMD7ytP_`?r;m-Vr6h)J z@T@%2`wjT99XCMp+k113^{PQ`zVQCVu`FgB9&7-0t10 zYFR3oU!vP1PQPt1l|*gzytU>g7L|YP-Gx@4>#)f{blrm(B#8YakPE2O^Umd_5D8z`C zL4z>*Y-$Wul{;R%IEpoRsr?8|r%26=+Uf2pg27Lb(eZY3*$p(%hnfBlZq8?;}E1R zTFnyEIf=dVw^ZjMC#;6d&~(~dgpn8>?N0IO`FU5(`l?6fYh=I%FwH0YgT&U(-=b!J z7k!gbNquj4;!Lv;QjS8k9KSn#pzluw;d9mQXYU>O|?+Mj86%`3I&DmMyL<$J2wzfso_w4tCc|WyCOG|&CJkJTcc|Z zrbz6ydUaA~wd9n_s(n5)4vE$nY>`~5aUi>;ty8<#+awZWB;Y_}gsYNugD~MR>N+If z%GiAdP=S<3VI*65nu5a&AI3JR4u%q@{DVT8?M3#I1)HiY5lI_HbbSYVsEmU3zN9#K z@#QyXSO6jNm(mQ5chiC{*P26oEmA<}9Y+x{IOYzi_xeXac`SCIuy8?iCMX#VlF6d@ z(ZkjZ3y6b8^z&C{v?G79#|@f)K+Jb*G^3v*}80jBPpb-y>)6 zi;p+&9u0IRmHwg;%5jZcA2^Rb#C2MKr9jB8Ak?I1@$P4SjrYSVGFrRrP(%6nZ^i~4w zn=t*8jOhz4cyKCpPv^H#51DHij(8nrT9*}bji`C1EnEf0-u`XavxIime^VYB*}_{z zOZs^)-47foaII$ogpIZ!xTG8D$?-Nbyh^-?vLm-SacXHwJ*_i?dZuVGjgU8g*-_m& zqbU6K3fFG7P|-{0`&M*MS04|N3-HL-m?fS<)yANo5N8@1*@6?kF`H`lat{w~oEv^4 z#N`EkmdokI(|49D1I+VEd%v^aV3)le-_e8*KaH`Q!PE&7(qmDY%+WxLczVhuh|Q zvoy^MIh|gtW~-NWseE>84BDD3_H9xvP_uMpILkqs-bzcFl$o?A;yex_lD1J!Q!i-& z;U;G`&NXf$j>(t!0Yp#p+SY1nU!8ySnUDIsp8k(s{F5W?nd6b7t{h6<2=x%VR)U$m z@2`f6^ezgX9;dIpeVc27E4X>Na?|hWV7}pXGAzZkguBK?B+^cmX; zP0q6YI$Ws-tq;vR$n+;(?}%WoseAxD;OO4Yq=+oAVt7Qjn!!*1U|waz-$eR@9GJ~C6lo`N za#`C=mq~z}0=s0=>X=N}g2pk5g&Pmm$m~OmDUA;4J+9Cqh&9{2X-fi|#@H#Io->XL zcx3z+&R=?F;W#Or95AfGm)f5ZNZgZ_sGeW9uQ@Z4^aJT)o{to%O ze*l7S9|-kqyIY!HUAnfCSh1_7zqnlQ56wMv#&~D;73GQNKXMB^cNk>3jKzi570XjQ zs7;CqFV;92k!Xl4DsjjPsSFaft`f+_)R( z@o@ptZnT8-h;?u2A_YZ5-mC$y%})ufC`oB=N)NW(`I($dd zr(-ALOlrleRLa;G9UhjD!nmXqWIVtGtyI=`vYg!d@9HPcX;lTR(bBHB^Q`B15>F0h zd0UOkMV#*I>lg2Qy5A5w{^d(hBeXPO#}}Z-@beGc;PpT?I2=kVXByT}S#W}N|Km!7 z8as`*lEh_5RPHc|M_WqSj2N#!)C2o?U$L&1TH8jSLE&ety-rc^s#SHIHg>)@Onr zQT6MwhyF}Tf<~qhdn{U&LlWiKWF~EX6vCC$)g5;8(D;Z1bIAi4aG@wH>}eoSeRoJJx#Rkl5I-TxPAYps6N*@7#zT&4&Ic_+CdvDbY@6qIDrTg;lucvCaCX zZRP67mCL+5o?|izF*b5bKp*jqhvQDXw4PF%)ct2KYIK1Ix%zXMCW%#PW1|6Up$2(P z%Pp@unNQ@e?A|{f#G8L#+`W*>?xa{SAQ-d1PV)Y-U&O_iP~zJi1B3=!EF&v1%ikYC z{j_BV6G)+eWh%758U;0-SlPJ;PAFX&hgjk+ON;a2&6IJ=e07lwF}N$p7}T5 zrh_SsNpxS0AW$+M28puVQ_6TdBqDs9)3eq~k$vI$I+p?6S6qcuA4 zDI|3o`cu?+ZmKmvy_GG!m!`VH>3nb2{r)zxs)l@rV?=mo& zU!OBQFM8gq!fnR09dPK8R6cgdc=jBG!ccP-XL$i5c*|)`^9^|!v;x(u`;ekAo%~Yz z%pXw4cOn#MF%s{!8$l4EQxu+HLvFvSvHPDdB>UGFqO@gE@i5_ros@}PGau;zs49l; zWu?~U9xb}fiC93Drh}G#>rOUBHDJ)kTNE?z11LI9b|!NnNe9x753iW@*3K_FzpMF+ zAbF`aHN`s&RfDGr(X-TSOmW8mwqazejK{|&{lkHfP@ zv>~xEZ~QBGsv2uV4@2U^2?+5Drp2I;vVP4>VcGbHmG83wRHe&&%noY9d0;q9Cok}n zCj@+^6pacXGq5pkm|;n*OOFmqLCE(lP~s zbj(=3ko?ZewHB$WgLx4xnX!8pWch=Wo{rvzDzk^P9TO;rUXtyKmbu(xcWarC6ZG({ zrX%{M&ENg#TpbTKrYki-fYplw9L2xtC;uOj3qH*-HXm9!@ZT$guU<5V$!8;FRB{Z7frIfK6E&oIxJpW}V62hy-(;aZs z>5WVLCgU~o!U@iQh`@W?s)Y~COdF?PJ8;#o)*N9oP%g0FFaJ1_l@6^YT3GyVQ=0}e zm#Jxq*4{&d%G~os4G)LAkv)1+{+kx9=0|UfZ}BjGfwx?KY$qq{he|3wcB6|+95?DI zuO(~?Up1C9Ky0}ayX-ZBz)Qo>eeU@lQ(r18+HKkLb59h)ef(pUzoe`|Wp7Z`v$bGP zIDEc|bG-7%X~6T8>+v2_vh1nk^T;##cZhTtDp027sYx9y7KH?q&R=zVO#&&|B=O+f zZ*uXUyBC4~E1pg0H@gkn1B7n4rAB8fkIFAgV|(r#C1i|nBq)oLiJA`A+MNM;X=MRi;{ z#_*r0d8@AdzNFouSWkpcJ#0ionNAS-6PQHwfRwGprTiN1hEwC34A`pinI(eI+BaQ$gWb`UzcpHWd$J%v|D_*rRC{@ISdwL$a~iORDX1jalC=zw7x^ z9p}QQ<>$d6?t-r@YudlEWfTJikufj$z-2nyZ&fX;zj#^Vw58;H7sN@hY1NGb_Zzd% zWZwOrC(FrYwLjo(GcpF1P9RiTE$8uPlzKdxChzt=RZ}xKipyO!E)R@Ro2kkTCr~zN z?as5MNsX5_nx00;CX%KCWo5$Te$DCdZAd(cyobZLRcD5ra^s}bYSH>x3$veebQAmo{zN{dRl*5K zR`TbflqH~Ud=F_w3tB1ADm;)gqJrw|%}DVN^_?dL z@fJFWMM4wfTROgQf?V^Wvb+eYj>z^oe%wKG+UFdZ4#ro8ODgww}skvxk{|&lL-YCC0R4=C}AkunhVd$6ri@3(rqDd8~MRk~^3GZFEIdrh*<4~MaEZW^IEqk{gX zgha(sMp~r$YC#z1V+YoxhryU!7Q=*IW0?jHEY27?UYA2>ltPIr#-@xxI)&r6DL=F- z-OHj}U^%tSTj6wl=&KNmRRW07lED=lBQ5&+CO=MKgbg`AH`#Uyh zG{`8K-;5RZi+lX=;pB%{fjrd0GyPefnRWYUuYG+`q>7?OjU|kkYJTwl!r_I`{LoiI zh*AA;WCCyUYzI;ilA?g8_)-Ye+bwIVFMZGcvKAVd`z3+;OrVU*C(yA&?&a&-G}pGW zA{Esg++(<%yhHxaFyYqmU2qWNUspOOiZB23l86Vk%Jx26EVYe&{F6WO1k@ijslpLP zmdhO-?k^lpimPkkkj2>*Qjmf=-u>s5((xD7K^P9GVW?`8+NVX0i58$s8XM16T#0>I zuL^O;9`AztKlcgo4?#K6`6r-<5~&m{tgbCJnKhzAvFDiwhj}Ee;C)a)2~`1q9k*>a zGVld4KiK$!#>ggOp7l!}f2`xCTd?;8#y`UB>(zM!vbnlEckx1U4a1nLhM668i!-kG)@BbVFsg9= zSrpqm)M3t9GLG1IQ-NO{huAZp^*99jKj$tU7ujP2Rjz+Pub8VQwaol(U)IiaWJj&d zXx^-~e@`VI({;wR`2V>d`?r%*UVmSW&!{Ychw=Sb8x5o@i$W(C(KtdK@M}ydK(lI) z1_Jl}dBDT3fK`QxzD2p_4lk*P8+PJ%3AOFYSB8nlH*2~GP{9W@%6z$V(4Wu!^;4X- z+M4@}(@LHl3C~X(OFfw}e*KE11WlO#@bKHdH|;MgmTb;Zk0=j2ym&TGa)fu(n6`2- zgYTlTMU&_0Cbe1J|B}c-BtGZZCrjqIp={QGqQ1X2Djd0NGNCUBK5@9_gw%oAH5jF2 zgE*H$F(z(v|DJnxVo<+=6p+#=VhQy-NYXm*%8_P7?1;$J_K*9VkFBBS z;2?9C{C$X!dutn4&7W?Gec79O?Lzs_rbw|u9qG}CM8Q~KMIWBV8vUBW#}fSy{FVbz zuih_aYus*^TM)%B0>A`0A=I0xq416ZvL?gJk3euF2Kqi(i}O*3slzGbPbRRUGL*s5RLsZok(V z!n-PD*X>PDT7w}AnV(|kg2&KmVzW5F{1iG1I(CPPVu-lmP}eSd2i~$pNoh1&*DLjp1(a)LF{%^A&zsxsMEG2Jyh+bx_9yUo!FQg(xC4` z`)E(@uWe!nNd0`5&Hnki%>57l(RIG|R`*O9jrJVP-dV>ia-Y~8H3y+<=IRj$K)m|R zvWiy&QiO_&Gp3iOFm&3C{(mPL&-CMf(3kc}+EXHB6g8E+4K(_9Gup3DU8SV`?=Z9E zw)Zi0DyX%=X@MTs*CBT}W7-NAJq6SWWYT7GF)ZfP{_m8*Jtu1kkw|Sb;`&=odGzS1 z=BeB3ShTLe0(-iLmB0= zggGveTWqMLrWu!9)@5o4rKrS=Xxzq-yJj&oG7M(+{ZcmXU*A99%$fOqzxREf=Y8Ja zhX+??n(X7K3=no8zijjiQPjpo)STm0*aL5|cfN_YY+hXD9fx(KDDw@QZ*UGD7mBm^ zy>qp?Otz8PP$j=b=YI9lhN^!(%+pK6z=||D#IaZ=Urh}0bWd8*0~Td$t9g5pmDvxb>zzX65wshh!tps^`@W5hPG8mYPup$3nXYx;2l ze`9S%SUhmjxSZgv03sdDoq=s1NH5IY+bv9hH@fkHsY0#jOaqmZPIUJEIBknPUp*yL6&!MA4btZ!3#GtLIV}?S$6Yk)8>AlMz94=wTth16Y^45TE%p9x zdD+O$G1RuAR6a>b8w$(5T%7>uFf$@>3k)}yTXr{aO1C#PvQb6MA8fsv+_C_A$7oF% z3sMy`=C5Hem~ywS@-7pCst^sIr36_6#4f}|9qGd=dGk?YrTMh#bsaUmj24msQhrH$ za$g#}72DIyAXk!7Ix?7!RFvPMpy+zVI&QNA<0TnOSZ>a9leCEUFcZExxU}+*vpS%K z4z3oIc*3)Z~usyTylyP*j%Q-wv{@2;D`08(!7+4~$E2Yvb*_q`t<8^u9q zc|l0y?vV|xopu&%FF`*m@?ksPrn{--K z2T$QJY(B`Lh|~7;q{MC4K5_q^EwIrfcn5l*%pm9jB+ay^!O}p(cdBTlj)WHl1QK3o zlf;QMCrGuCP~TybtK9RF2bK_98Pj?NWeOuoVjDKQeMPsEr+kn+W)tV9x z<_+IDBN4X)JZB(!E7qaCT0_7a-ry(7CeX5dVdA2vG5XojDUer`)RtrstqfM1gNLEX zKz!+t03TRYEgZ#DPCilFR*c#v`;I<+$(DHw-BTMk`950Vx`*Rv=viD4_oy|a?#<*` zc@H2v3&g6j+H@Q2v=TVrVa!N+sGy{_<5k|W#u-B3bC%IgJ*xcNMOQ1W4+jg~BS(^c4&MbaOj4yor)Y zqCO_g5=ZQ0`G8mg_!9YW{!fAbgX!EN{-8eX)c?dF)spB9MTmZUud*k)tuH@v?cQxPh4a1Z=Dp!nRp5(Tdn#XU{>rn~*a=(&HJz<;E(UkYTFU%# z;VOp=(yt3nB0{;o4?8^4`T0Ilb%!^Fxq!5>E?z$z6m19?-|`lB7cC_QVPR@xQgYZc F>OZ_h>}>!5 diff --git a/nav2_bt_navigator/package.xml b/nav2_bt_navigator/package.xml index 54ffcb6e6ee..d3bc7924c4d 100644 --- a/nav2_bt_navigator/package.xml +++ b/nav2_bt_navigator/package.xml @@ -2,7 +2,7 @@ nav2_bt_navigator - 1.3.4 + 1.3.5 Nav2 BT Navigator Server Michael Jeronimo Apache-2.0 diff --git a/nav2_collision_monitor/package.xml b/nav2_collision_monitor/package.xml index 29220e934bf..94c5bc5610d 100644 --- a/nav2_collision_monitor/package.xml +++ b/nav2_collision_monitor/package.xml @@ -2,7 +2,7 @@ nav2_collision_monitor - 1.3.4 + 1.3.5 Collision Monitor Alexey Merzlyakov Steve Macenski diff --git a/nav2_common/package.xml b/nav2_common/package.xml index 1d92b77acc7..c49482cec59 100644 --- a/nav2_common/package.xml +++ b/nav2_common/package.xml @@ -2,7 +2,7 @@ nav2_common - 1.3.4 + 1.3.5 Common support functionality used throughout the navigation 2 stack Carl Delsey Apache-2.0 diff --git a/nav2_constrained_smoother/package.xml b/nav2_constrained_smoother/package.xml index 8d9e3e5113a..5cf083fe56f 100644 --- a/nav2_constrained_smoother/package.xml +++ b/nav2_constrained_smoother/package.xml @@ -2,7 +2,7 @@ nav2_constrained_smoother - 1.3.4 + 1.3.5 Ceres constrained smoother Matej Vargovcik Steve Macenski diff --git a/nav2_controller/package.xml b/nav2_controller/package.xml index e0595725030..192550dad01 100644 --- a/nav2_controller/package.xml +++ b/nav2_controller/package.xml @@ -2,7 +2,7 @@ nav2_controller - 1.3.4 + 1.3.5 Controller action interface Carl Delsey Apache-2.0 diff --git a/nav2_core/package.xml b/nav2_core/package.xml index 3ee8d8a5595..7b1db907f65 100644 --- a/nav2_core/package.xml +++ b/nav2_core/package.xml @@ -2,7 +2,7 @@ nav2_core - 1.3.4 + 1.3.5 A set of headers for plugins core to the Nav2 stack Steve Macenski Carl Delsey diff --git a/nav2_costmap_2d/package.xml b/nav2_costmap_2d/package.xml index 1ff54d88299..3a76f806262 100644 --- a/nav2_costmap_2d/package.xml +++ b/nav2_costmap_2d/package.xml @@ -2,7 +2,7 @@ nav2_costmap_2d - 1.3.4 + 1.3.5 This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending diff --git a/nav2_docking/opennav_docking/package.xml b/nav2_docking/opennav_docking/package.xml index eb3711eb476..6b45c77e089 100644 --- a/nav2_docking/opennav_docking/package.xml +++ b/nav2_docking/opennav_docking/package.xml @@ -2,7 +2,7 @@ opennav_docking - 1.3.4 + 1.3.5 A Task Server for robot charger docking Steve Macenski Apache-2.0 diff --git a/nav2_docking/opennav_docking/src/controller.cpp b/nav2_docking/opennav_docking/src/controller.cpp index c0e45ee4223..ec2a1de9ab9 100644 --- a/nav2_docking/opennav_docking/src/controller.cpp +++ b/nav2_docking/opennav_docking/src/controller.cpp @@ -144,7 +144,10 @@ bool Controller::isTrajectoryCollisionFree( } // Generate path - for (double t = 0; t < projection_time_; t += simulation_time_step_) { + double distance = std::numeric_limits::max(); + unsigned int max_iter = static_cast(ceil(projection_time_ / simulation_time_step_)); + + do{ // Apply velocities to calculate next pose next_pose.pose = control_law_->calculateNextPose( simulation_time_step_, target_pose, next_pose.pose, backward); @@ -177,7 +180,10 @@ bool Controller::isTrajectoryCollisionFree( trajectory_pub_->publish(trajectory); return false; } - } + + // Check if we reach the goal + distance = nav2_util::geometry_utils::euclidean_distance(target_pose, next_pose.pose); + }while(distance > 1e-2 && trajectory.poses.size() < max_iter); trajectory_pub_->publish(trajectory); diff --git a/nav2_docking/opennav_docking/test/test_docking_server.py b/nav2_docking/opennav_docking/test/test_docking_server.py index 5b76f6095ce..4874d771201 100644 --- a/nav2_docking/opennav_docking/test/test_docking_server.py +++ b/nav2_docking/opennav_docking/test/test_docking_server.py @@ -19,12 +19,18 @@ from action_msgs.msg import GoalStatus from geometry_msgs.msg import TransformStamped, Twist from launch import LaunchDescription +# from launch.actions import SetEnvironmentVariable from launch_ros.actions import Node import launch_testing +import launch_testing.actions +import launch_testing.asserts +import launch_testing.markers +import launch_testing.util from nav2_msgs.action import DockRobot, NavigateToPose, UndockRobot import pytest import rclpy -from rclpy.action import ActionClient, ActionServer +from rclpy.action.client import ActionClient +from rclpy.action.server import ActionServer from sensor_msgs.msg import BatteryState from tf2_ros import TransformBroadcaster @@ -32,10 +38,18 @@ # This test can be run standalone with: # python3 -u -m pytest test_docking_server.py -s +# If python3-flaky is installed, you can run the test multiple times to +# try to identify flaky ness. +# python3 -u -m pytest --force-flaky --min-passes 3 --max-runs 5 -s -v test_docking_server.py + @pytest.mark.rostest +# @pytest.mark.flaky +# @pytest.mark.flaky(max_runs=5, min_passes=3) def generate_test_description(): return LaunchDescription([ + # SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'), + # SetEnvironmentVariable('RCUTILS_LOGGING_USE_STDOUT', '1'), Node( package='opennav_docking', executable='opennav_docking', @@ -74,21 +88,26 @@ class TestDockingServer(unittest.TestCase): @classmethod def setUpClass(cls): rclpy.init() - # Latest odom -> base_link - cls.x = 0.0 - cls.y = 0.0 - cls.theta = 0.0 - # Track charge state - cls.is_charging = False - # Latest command velocity - cls.command = Twist() - cls.node = rclpy.create_node('test_docking_server') @classmethod def tearDownClass(cls): - cls.node.destroy_node() rclpy.shutdown() + def setUp(self): + # Create a ROS node for tests + # Latest odom -> base_link + self.x = 0.0 + self.y = 0.0 + self.theta = 0.0 + # Track charge state + self.is_charging = False + # Latest command velocity + self.command = Twist() + self.node = rclpy.create_node('test_docking_server') + + def tearDown(self): + self.node.destroy_node() + def command_velocity_callback(self, msg): self.node.get_logger().info('Command: %f %f' % (msg.linear.x, msg.angular.z)) self.command = msg @@ -175,12 +194,19 @@ def test_docking_server(self): 'navigate_to_pose', self.nav_execute_callback) - # Spin once so that TF is published - rclpy.spin_once(self.node, timeout_sec=0.1) + # Publish transform + self.publish() + + # Run for 1 seconds to allow tf to propogate + for _ in range(10): + rclpy.spin_once(self.node, timeout_sec=0.1) + time.sleep(0.1) # Test docking action self.action_result = [] - self.dock_action_client.wait_for_server(timeout_sec=5.0) + assert self.dock_action_client.wait_for_server(timeout_sec=5.0), \ + 'dock_robot service not available' + goal = DockRobot.Goal() goal.use_dock_id = True goal.dock_id = 'test_dock' @@ -188,11 +214,12 @@ def test_docking_server(self): goal, feedback_callback=self.action_feedback_callback) rclpy.spin_until_future_complete(self.node, future) self.goal_handle = future.result() - assert self.goal_handle.accepted + assert self.goal_handle is not None, 'goal_handle should not be None' + assert self.goal_handle.accepted, 'goal_handle not accepted' result_future_original = self.goal_handle.get_result_async() # Run for 2 seconds - for i in range(20): + for _ in range(20): rclpy.spin_once(self.node, timeout_sec=0.1) time.sleep(0.1) @@ -201,7 +228,8 @@ def test_docking_server(self): goal, feedback_callback=self.action_feedback_callback) rclpy.spin_until_future_complete(self.node, future) self.goal_handle = future.result() - assert self.goal_handle.accepted + assert self.goal_handle is not None, 'goal_handle should not be None' + assert self.goal_handle.accepted, 'goal_handle not accepted' result_future = self.goal_handle.get_result_async() rclpy.spin_until_future_complete(self.node, result_future) self.action_result.append(result_future.result()) @@ -216,7 +244,7 @@ def test_docking_server(self): self.node.get_logger().info('Goal preempted') # Run for 0.5 seconds - for i in range(5): + for _ in range(5): rclpy.spin_once(self.node, timeout_sec=0.1) time.sleep(0.1) @@ -230,7 +258,8 @@ def test_docking_server(self): goal, feedback_callback=self.action_feedback_callback) rclpy.spin_until_future_complete(self.node, future) self.goal_handle = future.result() - assert self.goal_handle.accepted + assert self.goal_handle is not None, 'goal_handle should not be None' + assert self.goal_handle.accepted, 'goal_handle not accepted' result_future = self.goal_handle.get_result_async() rclpy.spin_until_future_complete(self.node, result_future) self.action_result.append(result_future.result()) @@ -247,10 +276,19 @@ def test_docking_server(self): future = self.undock_action_client.send_goal_async(goal) rclpy.spin_until_future_complete(self.node, future) self.goal_handle = future.result() - assert self.goal_handle.accepted + assert self.goal_handle is not None, 'goal_handle should not be None' + assert self.goal_handle.accepted, 'goal_handle not accepted' result_future = self.goal_handle.get_result_async() rclpy.spin_until_future_complete(self.node, result_future) self.action_result.append(result_future.result()) self.assertEqual(self.action_result[3].status, GoalStatus.STATUS_SUCCEEDED) self.assertTrue(self.action_result[3].result.success) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + + def test_exit_code(self, proc_info): + # Check that all processes in the launch exit with code 0 + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/nav2_docking/opennav_docking_bt/package.xml b/nav2_docking/opennav_docking_bt/package.xml index 39a2a3cbf74..074d44f2a9a 100644 --- a/nav2_docking/opennav_docking_bt/package.xml +++ b/nav2_docking/opennav_docking_bt/package.xml @@ -2,7 +2,7 @@ opennav_docking_bt - 1.3.4 + 1.3.5 A set of BT nodes and XMLs for docking Steve Macenski Apache-2.0 diff --git a/nav2_docking/opennav_docking_core/package.xml b/nav2_docking/opennav_docking_core/package.xml index 895d4f68cdb..7d46b360f0f 100644 --- a/nav2_docking/opennav_docking_core/package.xml +++ b/nav2_docking/opennav_docking_core/package.xml @@ -2,7 +2,7 @@ opennav_docking_core - 1.3.4 + 1.3.5 A set of headers for plugins core to the opennav docking framework Steve Macenski Apache-2.0 diff --git a/nav2_dwb_controller/costmap_queue/package.xml b/nav2_dwb_controller/costmap_queue/package.xml index cf0df0bda41..fd60e9e89de 100644 --- a/nav2_dwb_controller/costmap_queue/package.xml +++ b/nav2_dwb_controller/costmap_queue/package.xml @@ -1,7 +1,7 @@ costmap_queue - 1.3.4 + 1.3.5 The costmap_queue package David V. Lu!! BSD-3-Clause diff --git a/nav2_dwb_controller/dwb_core/package.xml b/nav2_dwb_controller/dwb_core/package.xml index 3ac03b05692..2586220ae80 100644 --- a/nav2_dwb_controller/dwb_core/package.xml +++ b/nav2_dwb_controller/dwb_core/package.xml @@ -2,7 +2,7 @@ dwb_core - 1.3.4 + 1.3.5 DWB core interfaces package Carl Delsey BSD-3-Clause diff --git a/nav2_dwb_controller/dwb_critics/package.xml b/nav2_dwb_controller/dwb_critics/package.xml index 6e2976b0ecd..e4561d0e4ca 100644 --- a/nav2_dwb_controller/dwb_critics/package.xml +++ b/nav2_dwb_controller/dwb_critics/package.xml @@ -1,7 +1,7 @@ dwb_critics - 1.3.4 + 1.3.5 The dwb_critics package David V. Lu!! BSD-3-Clause diff --git a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp index b556a06be15..e2dd85d15b1 100644 --- a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp +++ b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp @@ -242,7 +242,9 @@ TEST(ObstacleFootprint, LineCost) costmap_ros->getCostmap()->setCost(4, 3, 100); costmap_ros->getCostmap()->setCost(4, 4, 100); - ASSERT_EQ(critic->lineCost(3, 3, 0, 50), 50); // all 50 + auto max_y_in_grid_coordinates = costmap_ros->getCostmap()->getSizeInCellsY() - 1; + ASSERT_EQ(max_y_in_grid_coordinates, 49); + ASSERT_EQ(critic->lineCost(3, 3, 0, max_y_in_grid_coordinates), 50); // all 50 ASSERT_EQ(critic->lineCost(4, 4, 0, 10), 100); // all 100 ASSERT_EQ(critic->lineCost(0, 50, 3, 3), 100); // pass 50 and 100 } diff --git a/nav2_dwb_controller/dwb_msgs/package.xml b/nav2_dwb_controller/dwb_msgs/package.xml index 753fe239c07..482cf9c1792 100644 --- a/nav2_dwb_controller/dwb_msgs/package.xml +++ b/nav2_dwb_controller/dwb_msgs/package.xml @@ -2,7 +2,7 @@ dwb_msgs - 1.3.4 + 1.3.5 Message/Service definitions specifically for the dwb_core David V. Lu!! BSD-3-Clause diff --git a/nav2_dwb_controller/dwb_plugins/package.xml b/nav2_dwb_controller/dwb_plugins/package.xml index d795771b147..3d651305ff8 100644 --- a/nav2_dwb_controller/dwb_plugins/package.xml +++ b/nav2_dwb_controller/dwb_plugins/package.xml @@ -1,7 +1,7 @@ dwb_plugins - 1.3.4 + 1.3.5 Standard implementations of the GoalChecker and TrajectoryGenerators for dwb_core diff --git a/nav2_dwb_controller/nav2_dwb_controller/package.xml b/nav2_dwb_controller/nav2_dwb_controller/package.xml index c57410066e3..eff7c399786 100644 --- a/nav2_dwb_controller/nav2_dwb_controller/package.xml +++ b/nav2_dwb_controller/nav2_dwb_controller/package.xml @@ -2,7 +2,7 @@ nav2_dwb_controller - 1.3.4 + 1.3.5 ROS2 controller (DWB) metapackage diff --git a/nav2_dwb_controller/nav_2d_msgs/package.xml b/nav2_dwb_controller/nav_2d_msgs/package.xml index bcbaee02e00..5d0f43cbe82 100644 --- a/nav2_dwb_controller/nav_2d_msgs/package.xml +++ b/nav2_dwb_controller/nav_2d_msgs/package.xml @@ -2,7 +2,7 @@ nav_2d_msgs - 1.3.4 + 1.3.5 Basic message types for two dimensional navigation, extending from geometry_msgs::Pose2D. David V. Lu!! BSD-3-Clause diff --git a/nav2_dwb_controller/nav_2d_utils/package.xml b/nav2_dwb_controller/nav_2d_utils/package.xml index bf0f68c58a2..3d13cb5ea1b 100644 --- a/nav2_dwb_controller/nav_2d_utils/package.xml +++ b/nav2_dwb_controller/nav_2d_utils/package.xml @@ -2,7 +2,7 @@ nav_2d_utils - 1.3.4 + 1.3.5 A handful of useful utility functions for nav_2d packages. David V. Lu!! BSD-3-Clause diff --git a/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp b/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp index 1a77a3adfc6..8669aafeedb 100644 --- a/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp +++ b/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp @@ -107,33 +107,23 @@ class GracefulController : public nav2_core::Controller void setSpeedLimit(const double & speed_limit, const bool & percentage) override; protected: - /** - * @brief Get motion target point. - * @param motion_target_dist Optimal motion target distance - * @param path Current global path - * @return Motion target point - */ - geometry_msgs::msg::PoseStamped getMotionTarget( - const double & motion_target_dist, - const nav_msgs::msg::Path & path); - /** * @brief Simulate trajectory calculating in every step the new velocity command based on * a new curvature value and checking for collisions. * - * @param robot_pose Robot pose - * @param motion_target Motion target point + * @param motion_target Motion target point (in costmap local frame?) * @param costmap_transform Transform between global and local costmap * @param trajectory Simulated trajectory + * @param cmd_vel Initial command velocity during simulation * @param backward Flag to indicate if the robot is moving backward * @return true if the trajectory is collision free, false otherwise */ bool simulateTrajectory( - const geometry_msgs::msg::PoseStamped & robot_pose, const geometry_msgs::msg::PoseStamped & motion_target, const geometry_msgs::msg::TransformStamped & costmap_transform, nav_msgs::msg::Path & trajectory, - const bool & backward); + geometry_msgs::msg::TwistStamped & cmd_vel, + bool backward); /** * @brief Rotate the robot to face the motion target with maximum angular velocity. @@ -141,8 +131,7 @@ class GracefulController : public nav2_core::Controller * @param angle_to_target Angle to the motion target * @return geometry_msgs::msg::Twist Velocity command */ - geometry_msgs::msg::Twist rotateToTarget( - const double & angle_to_target); + geometry_msgs::msg::Twist rotateToTarget(double angle_to_target); /** * @brief Checks if the robot is in collision @@ -153,6 +142,21 @@ class GracefulController : public nav2_core::Controller */ bool inCollision(const double & x, const double & y, const double & theta); + /** + * @brief Compute the distance to each pose in a path + * @param poses Poses to compute distances with + * @param distances Computed distances + */ + void computeDistanceAlongPath( + const std::vector & poses, + std::vector & distances); + + /** + * @brief Control law requires proper orientations, not all planners provide them + * @param path Path to add orientations into, if required + */ + void validateOrientations(std::vector & path); + std::shared_ptr tf_buffer_; std::string plugin_name_; std::shared_ptr costmap_ros_; @@ -164,9 +168,12 @@ class GracefulController : public nav2_core::Controller double goal_dist_tolerance_; bool goal_reached_; + // True from the time a new path arrives until we have completed an initial rotation + bool do_initial_rotation_; + std::shared_ptr> transformed_plan_pub_; std::shared_ptr> local_plan_pub_; - std::shared_ptr> + std::shared_ptr> motion_target_pub_; std::shared_ptr> slowdown_pub_; diff --git a/nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp b/nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp index 7594524cf0f..dd4d4df09ce 100644 --- a/nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp +++ b/nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp @@ -33,7 +33,8 @@ namespace nav2_graceful_controller struct Parameters { double transform_tolerance; - double motion_target_dist; + double min_lookahead; + double max_lookahead; double max_robot_pose_search_dist; double k_phi; double k_delta; @@ -44,12 +45,14 @@ struct Parameters double v_linear_max_initial; double v_angular_max; double v_angular_max_initial; + double v_angular_min_in_place; double slowdown_radius; bool initial_rotation; - double initial_rotation_min_angle; - bool final_rotation; + double initial_rotation_tolerance; + bool prefer_final_rotation; double rotation_scaling_factor; bool allow_backward; + double in_place_collision_resolution; }; /** diff --git a/nav2_graceful_controller/include/nav2_graceful_controller/utils.hpp b/nav2_graceful_controller/include/nav2_graceful_controller/utils.hpp index 788656bd64b..65aea70d87d 100644 --- a/nav2_graceful_controller/include/nav2_graceful_controller/utils.hpp +++ b/nav2_graceful_controller/include/nav2_graceful_controller/utils.hpp @@ -15,22 +15,11 @@ #ifndef NAV2_GRACEFUL_CONTROLLER__UTILS_HPP_ #define NAV2_GRACEFUL_CONTROLLER__UTILS_HPP_ -#include "geometry_msgs/msg/point_stamped.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "visualization_msgs/msg/marker.hpp" namespace nav2_graceful_controller { -/** - * @brief Create a PointStamped message of the motion target for - * debugging / visualization porpuses. - * - * @param motion_target Motion target in PoseStamped format - * @return geometry_msgs::msg::PointStamped Motion target in PointStamped format - */ -geometry_msgs::msg::PointStamped createMotionTargetMsg( - const geometry_msgs::msg::PoseStamped & motion_target); - /** * @brief Create a flat circle marker of radius slowdown_radius around the motion target for * debugging / visualization porpuses. diff --git a/nav2_graceful_controller/package.xml b/nav2_graceful_controller/package.xml index d84e35ab80b..747f0864ef5 100644 --- a/nav2_graceful_controller/package.xml +++ b/nav2_graceful_controller/package.xml @@ -2,7 +2,7 @@ nav2_graceful_controller - 1.3.4 + 1.3.5 Graceful motion controller Alberto Tudela Apache-2.0 diff --git a/nav2_graceful_controller/src/graceful_controller.cpp b/nav2_graceful_controller/src/graceful_controller.cpp index f8610a55c90..aba04ce4ced 100644 --- a/nav2_graceful_controller/src/graceful_controller.cpp +++ b/nav2_graceful_controller/src/graceful_controller.cpp @@ -12,6 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include +#include + +#include "angles/angles.h" #include "nav2_core/controller_exceptions.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_graceful_controller/graceful_controller.hpp" @@ -58,7 +62,7 @@ void GracefulController::configure( // Publishers transformed_plan_pub_ = node->create_publisher("transformed_global_plan", 1); local_plan_pub_ = node->create_publisher("local_plan", 1); - motion_target_pub_ = node->create_publisher("motion_target", 1); + motion_target_pub_ = node->create_publisher("motion_target", 1); slowdown_pub_ = node->create_publisher("slowdown", 1); RCLCPP_INFO(logger_, "Configured Graceful Motion Controller: %s", plugin_name_.c_str()); @@ -111,6 +115,9 @@ geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands( { std::lock_guard param_lock(param_handler_->getMutex()); + geometry_msgs::msg::TwistStamped cmd_vel; + cmd_vel.header = pose.header; + // Update for the current goal checker's state geometry_msgs::msg::Pose pose_tolerance; geometry_msgs::msg::Twist velocity_tolerance; @@ -126,64 +133,15 @@ geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands( control_law_->setSlowdownRadius(params_->slowdown_radius); control_law_->setSpeedLimit(params_->v_linear_min, params_->v_linear_max, params_->v_angular_max); - // Transform path to robot base frame and publish it + // Transform path to robot base frame auto transformed_plan = path_handler_->transformGlobalPlan( pose, params_->max_robot_pose_search_dist); - transformed_plan_pub_->publish(transformed_plan); - - // Get the particular point on the path at the motion target distance and publish it - auto motion_target = getMotionTarget(params_->motion_target_dist, transformed_plan); - auto motion_target_point = nav2_graceful_controller::createMotionTargetMsg(motion_target); - motion_target_pub_->publish(motion_target_point); - // Publish marker for slowdown radius around motion target for debugging / visualization - auto slowdown_marker = nav2_graceful_controller::createSlowdownMarker( - motion_target, - params_->slowdown_radius); - slowdown_pub_->publish(slowdown_marker); + // Add proper orientations to plan, if needed + validateOrientations(transformed_plan.poses); - // Compute distance to goal as the path's integrated distance to account for path curvatures - double dist_to_goal = nav2_util::geometry_utils::calculate_path_length(transformed_plan); - - // If the distance to the goal is less than the motion target distance, i.e. - // the 'motion target' is the goal, then we skip the motion target orientation by pointing - // it in the same orientation that the last segment of the path - double angle_to_target = atan2(motion_target.pose.position.y, motion_target.pose.position.x); - if (params_->final_rotation && dist_to_goal < params_->motion_target_dist) { - geometry_msgs::msg::PoseStamped stl_pose = - transformed_plan.poses[transformed_plan.poses.size() - 2]; - geometry_msgs::msg::PoseStamped goal_pose = transformed_plan.poses.back(); - double dx = goal_pose.pose.position.x - stl_pose.pose.position.x; - double dy = goal_pose.pose.position.y - stl_pose.pose.position.y; - double yaw = std::atan2(dy, dx); - motion_target.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw); - } - - // Flip the orientation of the motion target if the robot is moving backwards - bool reversing = false; - if (params_->allow_backward && motion_target.pose.position.x < 0.0) { - reversing = true; - motion_target.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis( - tf2::getYaw(motion_target.pose.orientation) + M_PI); - } - - // Compute velocity command: - // 1. Check if we are close enough to the goal to do a final rotation in place - // 2. Check if we must do a rotation in place before moving - // 3. Calculate the new velocity command using the smooth control law - geometry_msgs::msg::TwistStamped cmd_vel; - cmd_vel.header = pose.header; - if (params_->final_rotation && (dist_to_goal < goal_dist_tolerance_ || goal_reached_)) { - goal_reached_ = true; - double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation); - cmd_vel.twist = rotateToTarget(angle_to_goal); - } else if (params_->initial_rotation && // NOLINT - fabs(angle_to_target) > params_->initial_rotation_min_angle) - { - cmd_vel.twist = rotateToTarget(angle_to_target); - } else { - cmd_vel.twist = control_law_->calculateRegularVelocity(motion_target.pose, reversing); - } + // Publish plan for visualization + transformed_plan_pub_->publish(transformed_plan); // Transform local frame to global frame to use in collision checking geometry_msgs::msg::TransformStamped costmap_transform; @@ -196,24 +154,107 @@ geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands( logger_, "Could not transform %s to %s: %s", costmap_ros_->getBaseFrameID().c_str(), costmap_ros_->getGlobalFrameID().c_str(), ex.what()); - return cmd_vel; + throw ex; } - // Generate and publish local plan for debugging / visualization - nav_msgs::msg::Path local_plan; - if (!simulateTrajectory(pose, motion_target, costmap_transform, local_plan, reversing)) { - throw nav2_core::NoValidControl("Collision detected in the trajectory"); + // Compute distance to goal as the path's integrated distance to account for path curvatures + double dist_to_goal = nav2_util::geometry_utils::calculate_path_length(transformed_plan); + + // If we've reached the XY goal tolerance, just rotate + if (dist_to_goal < goal_dist_tolerance_ || goal_reached_) { + goal_reached_ = true; + double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation); + // Check for collisions between our current pose and goal pose + size_t num_steps = fabs(angle_to_goal) / params_->in_place_collision_resolution; + // Need to check at least the end pose + num_steps = std::max(static_cast(1), num_steps); + bool collision_free = true; + for (size_t i = 1; i <= num_steps; ++i) { + double step = static_cast(i) / static_cast(num_steps); + double yaw = step * angle_to_goal; + geometry_msgs::msg::PoseStamped next_pose; + next_pose.header.frame_id = costmap_ros_->getBaseFrameID(); + next_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw); + geometry_msgs::msg::PoseStamped costmap_pose; + tf2::doTransform(next_pose, costmap_pose, costmap_transform); + if (inCollision( + costmap_pose.pose.position.x, costmap_pose.pose.position.y, + tf2::getYaw(costmap_pose.pose.orientation))) + { + collision_free = false; + break; + } + } + // Compute velocity if rotation is possible + if (collision_free) { + cmd_vel.twist = rotateToTarget(angle_to_goal); + return cmd_vel; + } + // Else, fall through and see if we should follow control law longer } - local_plan.header = transformed_plan.header; - local_plan_pub_->publish(local_plan); - return cmd_vel; + // Precompute distance to candidate poses + std::vector target_distances; + computeDistanceAlongPath(transformed_plan.poses, target_distances); + + // Work back from the end of plan to find valid target pose + for (int i = transformed_plan.poses.size() - 1; i >= 0; --i) { + // Underlying control law needs a single target pose, which should: + // * Be as far away as possible from the robot (for smoothness) + // * But no further than the max_lookahed_ distance + // * Be feasible to reach in a collision free manner + geometry_msgs::msg::PoseStamped target_pose = transformed_plan.poses[i]; + double dist_to_target = target_distances[i]; + + // Continue if target_pose is too far away from robot + if (dist_to_target > params_->max_lookahead) {continue;} + + if (dist_to_goal < params_->max_lookahead) { + if (params_->prefer_final_rotation) { + // Avoid unstability and big sweeping turns at the end of paths by + // ignoring final heading + double yaw = std::atan2(target_pose.pose.position.y, target_pose.pose.position.x); + target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw); + } + } else if (dist_to_target < params_->min_lookahead) { + // Make sure target is far enough away to avoid instability + break; + } + + // Flip the orientation of the motion target if the robot is moving backwards + bool reversing = false; + if (params_->allow_backward && target_pose.pose.position.x < 0.0) { + reversing = true; + target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis( + tf2::getYaw(target_pose.pose.orientation) + M_PI); + } + + // Actually simulate our path + nav_msgs::msg::Path local_plan; + if (simulateTrajectory(target_pose, costmap_transform, local_plan, cmd_vel, reversing)) { + // Successfully simulated to target_pose - compute velocity at this moment + // Publish the selected target_pose + motion_target_pub_->publish(target_pose); + // Publish marker for slowdown radius around motion target for debugging / visualization + auto slowdown_marker = nav2_graceful_controller::createSlowdownMarker( + target_pose, params_->slowdown_radius); + slowdown_pub_->publish(slowdown_marker); + // Publish the local plan + local_plan.header = transformed_plan.header; + local_plan_pub_->publish(local_plan); + // Successfully found velocity command + return cmd_vel; + } + } + + throw nav2_core::NoValidControl("Collision detected in trajectory"); } void GracefulController::setPlan(const nav_msgs::msg::Path & path) { path_handler_->setPlan(path); goal_reached_ = false; + do_initial_rotation_ = true; } void GracefulController::setSpeedLimit( @@ -240,58 +281,66 @@ void GracefulController::setSpeedLimit( } } -geometry_msgs::msg::PoseStamped GracefulController::getMotionTarget( - const double & motion_target_dist, - const nav_msgs::msg::Path & transformed_plan) -{ - // Find the first pose which is at a distance greater than the motion target distance - auto goal_pose_it = std::find_if( - transformed_plan.poses.begin(), transformed_plan.poses.end(), [&](const auto & ps) { - return std::hypot(ps.pose.position.x, ps.pose.position.y) >= motion_target_dist; - }); - - // If the pose is not far enough, take the last pose - if (goal_pose_it == transformed_plan.poses.end()) { - goal_pose_it = std::prev(transformed_plan.poses.end()); - } - - return *goal_pose_it; -} - bool GracefulController::simulateTrajectory( - const geometry_msgs::msg::PoseStamped & robot_pose, const geometry_msgs::msg::PoseStamped & motion_target, const geometry_msgs::msg::TransformStamped & costmap_transform, - nav_msgs::msg::Path & trajectory, const bool & backward) + nav_msgs::msg::Path & trajectory, + geometry_msgs::msg::TwistStamped & cmd_vel, + bool backward) { - // Check for collision before moving - if (inCollision( - robot_pose.pose.position.x, robot_pose.pose.position.y, - tf2::getYaw(robot_pose.pose.orientation))) - { - return false; - } + trajectory.poses.clear(); - // First pose + // First pose is robot current pose geometry_msgs::msg::PoseStamped next_pose; next_pose.header.frame_id = costmap_ros_->getBaseFrameID(); next_pose.pose.orientation.w = 1.0; - trajectory.poses.push_back(next_pose); + + // Should we simulate rotation initially? + bool sim_initial_rotation = do_initial_rotation_ && params_->initial_rotation; + double angle_to_target = + std::atan2(motion_target.pose.position.y, motion_target.pose.position.x); + if (fabs(angle_to_target) < params_->initial_rotation_tolerance) { + sim_initial_rotation = false; + do_initial_rotation_ = false; + } double distance = std::numeric_limits::max(); double resolution_ = costmap_ros_->getCostmap()->getResolution(); double dt = (params_->v_linear_max > 0.0) ? resolution_ / params_->v_linear_max : 0.0; // Set max iter to avoid infinite loop - unsigned int max_iter = 2 * sqrt( - motion_target.pose.position.x * motion_target.pose.position.x + - motion_target.pose.position.y * motion_target.pose.position.y) / resolution_; + unsigned int max_iter = 3 * + std::hypot(motion_target.pose.position.x, motion_target.pose.position.y) / resolution_; // Generate path do{ - // Apply velocities to calculate next pose - next_pose.pose = control_law_->calculateNextPose( - dt, motion_target.pose, next_pose.pose, backward); + if (sim_initial_rotation) { + // Compute rotation velocity + double next_pose_yaw = tf2::getYaw(next_pose.pose.orientation); + auto cmd = rotateToTarget(angle_to_target - next_pose_yaw); + + // If this is first iteration, this is our current target velocity + if (trajectory.poses.empty()) {cmd_vel.twist = cmd;} + + // Are we done simulating initial rotation? + if (fabs(angle_to_target - next_pose_yaw) < params_->initial_rotation_tolerance) { + sim_initial_rotation = false; + } + + // Forward simulate rotation command + next_pose_yaw += cmd_vel.twist.angular.z * dt; + next_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(next_pose_yaw); + } else { + // If this is first iteration, this is our current target velocity + if (trajectory.poses.empty()) { + cmd_vel.twist = control_law_->calculateRegularVelocity( + motion_target.pose, next_pose.pose, backward); + } + + // Apply velocities to calculate next pose + next_pose.pose = control_law_->calculateNextPose( + dt, motion_target.pose, next_pose.pose, backward); + } // Add the pose to the trajectory for visualization trajectory.poses.push_back(next_pose); @@ -313,11 +362,13 @@ bool GracefulController::simulateTrajectory( return true; } -geometry_msgs::msg::Twist GracefulController::rotateToTarget(const double & angle_to_target) +geometry_msgs::msg::Twist GracefulController::rotateToTarget(double angle_to_target) { geometry_msgs::msg::Twist vel; vel.linear.x = 0.0; vel.angular.z = params_->rotation_scaling_factor * angle_to_target * params_->v_angular_max; + vel.angular.z = std::copysign(1.0, vel.angular.z) * std::max(abs(vel.angular.z), + params_->v_angular_min_in_place); return vel; } @@ -357,6 +408,46 @@ bool GracefulController::inCollision(const double & x, const double & y, const d return false; } +void GracefulController::computeDistanceAlongPath( + const std::vector & poses, + std::vector & distances) +{ + distances.resize(poses.size()); + // Do the first pose from robot + double d = std::hypot(poses[0].pose.position.x, poses[0].pose.position.y); + distances[0] = d; + // Compute remaining poses + for (size_t i = 1; i < poses.size(); ++i) { + d += nav2_util::geometry_utils::euclidean_distance(poses[i - 1].pose, poses[i].pose); + distances[i] = d; + } +} + +void GracefulController::validateOrientations( + std::vector & path) +{ + // We never change the orientation of the first & last pose + // So we need at least three poses to do anything here + if (path.size() < 3) {return;} + + // Check if we actually need to add orientations + double initial_yaw = tf2::getYaw(path[1].pose.orientation); + for (size_t i = 2; i < path.size() - 1; ++i) { + double this_yaw = tf2::getYaw(path[i].pose.orientation); + if (angles::shortest_angular_distance(this_yaw, initial_yaw) > 1e-6) {return;} + } + + // For each pose, point at the next one + // NOTE: control loop will handle reversing logic + for (size_t i = 0; i < path.size() - 1; ++i) { + // Get relative yaw angle + double dx = path[i + 1].pose.position.x - path[i].pose.position.x; + double dy = path[i + 1].pose.position.y - path[i].pose.position.y; + double yaw = std::atan2(dy, dx); + path[i].pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw); + } +} + } // namespace nav2_graceful_controller // Register this controller as a nav2_core plugin diff --git a/nav2_graceful_controller/src/parameter_handler.cpp b/nav2_graceful_controller/src/parameter_handler.cpp index 3d3389ec1d9..f8ba2aa075c 100644 --- a/nav2_graceful_controller/src/parameter_handler.cpp +++ b/nav2_graceful_controller/src/parameter_handler.cpp @@ -38,13 +38,15 @@ ParameterHandler::ParameterHandler( declare_parameter_if_not_declared( node, plugin_name_ + ".transform_tolerance", rclcpp::ParameterValue(0.1)); declare_parameter_if_not_declared( - node, plugin_name_ + ".motion_target_dist", rclcpp::ParameterValue(0.6)); + node, plugin_name_ + ".min_lookahead", rclcpp::ParameterValue(0.25)); + declare_parameter_if_not_declared( + node, plugin_name_ + ".max_lookahead", rclcpp::ParameterValue(1.0)); declare_parameter_if_not_declared( node, plugin_name_ + ".max_robot_pose_search_dist", rclcpp::ParameterValue(costmap_size_x / 2.0)); - declare_parameter_if_not_declared(node, plugin_name_ + ".k_phi", rclcpp::ParameterValue(3.0)); - declare_parameter_if_not_declared(node, plugin_name_ + ".k_delta", rclcpp::ParameterValue(2.0)); - declare_parameter_if_not_declared(node, plugin_name_ + ".beta", rclcpp::ParameterValue(0.2)); + declare_parameter_if_not_declared(node, plugin_name_ + ".k_phi", rclcpp::ParameterValue(2.0)); + declare_parameter_if_not_declared(node, plugin_name_ + ".k_delta", rclcpp::ParameterValue(1.0)); + declare_parameter_if_not_declared(node, plugin_name_ + ".beta", rclcpp::ParameterValue(0.4)); declare_parameter_if_not_declared(node, plugin_name_ + ".lambda", rclcpp::ParameterValue(2.0)); declare_parameter_if_not_declared( node, plugin_name_ + ".v_linear_min", rclcpp::ParameterValue(0.1)); @@ -52,21 +54,26 @@ ParameterHandler::ParameterHandler( node, plugin_name_ + ".v_linear_max", rclcpp::ParameterValue(0.5)); declare_parameter_if_not_declared( node, plugin_name_ + ".v_angular_max", rclcpp::ParameterValue(1.0)); + declare_parameter_if_not_declared( + node, plugin_name_ + ".v_angular_min_in_place", rclcpp::ParameterValue(0.25)); declare_parameter_if_not_declared( node, plugin_name_ + ".slowdown_radius", rclcpp::ParameterValue(1.5)); declare_parameter_if_not_declared( node, plugin_name_ + ".initial_rotation", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared( - node, plugin_name_ + ".initial_rotation_min_angle", rclcpp::ParameterValue(0.75)); + node, plugin_name_ + ".initial_rotation_tolerance", rclcpp::ParameterValue(0.75)); declare_parameter_if_not_declared( - node, plugin_name_ + ".final_rotation", rclcpp::ParameterValue(true)); + node, plugin_name_ + ".prefer_final_rotation", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared( node, plugin_name_ + ".rotation_scaling_factor", rclcpp::ParameterValue(0.5)); declare_parameter_if_not_declared( node, plugin_name_ + ".allow_backward", rclcpp::ParameterValue(false)); + declare_parameter_if_not_declared( + node, plugin_name_ + ".in_place_collision_resolution", rclcpp::ParameterValue(0.1)); node->get_parameter(plugin_name_ + ".transform_tolerance", params_.transform_tolerance); - node->get_parameter(plugin_name_ + ".motion_target_dist", params_.motion_target_dist); + node->get_parameter(plugin_name_ + ".min_lookahead", params_.min_lookahead); + node->get_parameter(plugin_name_ + ".max_lookahead", params_.max_lookahead); node->get_parameter( plugin_name_ + ".max_robot_pose_search_dist", params_.max_robot_pose_search_dist); if (params_.max_robot_pose_search_dist < 0.0) { @@ -85,13 +92,17 @@ ParameterHandler::ParameterHandler( params_.v_linear_max_initial = params_.v_linear_max; node->get_parameter(plugin_name_ + ".v_angular_max", params_.v_angular_max); params_.v_angular_max_initial = params_.v_angular_max; + node->get_parameter( + plugin_name_ + ".v_angular_min_in_place", params_.v_angular_min_in_place); node->get_parameter(plugin_name_ + ".slowdown_radius", params_.slowdown_radius); node->get_parameter(plugin_name_ + ".initial_rotation", params_.initial_rotation); node->get_parameter( - plugin_name_ + ".initial_rotation_min_angle", params_.initial_rotation_min_angle); - node->get_parameter(plugin_name_ + ".final_rotation", params_.final_rotation); + plugin_name_ + ".initial_rotation_tolerance", params_.initial_rotation_tolerance); + node->get_parameter(plugin_name_ + ".prefer_final_rotation", params_.prefer_final_rotation); node->get_parameter(plugin_name_ + ".rotation_scaling_factor", params_.rotation_scaling_factor); node->get_parameter(plugin_name_ + ".allow_backward", params_.allow_backward); + node->get_parameter( + plugin_name_ + ".in_place_collision_resolution", params_.in_place_collision_resolution); if (params_.initial_rotation && params_.allow_backward) { RCLCPP_WARN( @@ -126,8 +137,10 @@ ParameterHandler::dynamicParametersCallback(std::vector param if (type == ParameterType::PARAMETER_DOUBLE) { if (name == plugin_name_ + ".transform_tolerance") { params_.transform_tolerance = parameter.as_double(); - } else if (name == plugin_name_ + ".motion_target_dist") { - params_.motion_target_dist = parameter.as_double(); + } else if (name == plugin_name_ + ".min_lookahead") { + params_.min_lookahead = parameter.as_double(); + } else if (name == plugin_name_ + ".max_lookahead") { + params_.max_lookahead = parameter.as_double(); } else if (name == plugin_name_ + ".k_phi") { params_.k_phi = parameter.as_double(); } else if (name == plugin_name_ + ".k_delta") { @@ -144,12 +157,16 @@ ParameterHandler::dynamicParametersCallback(std::vector param } else if (name == plugin_name_ + ".v_angular_max") { params_.v_angular_max = parameter.as_double(); params_.v_angular_max_initial = params_.v_angular_max; + } else if (name == plugin_name_ + ".v_angular_min_in_place") { + params_.v_angular_min_in_place = parameter.as_double(); } else if (name == plugin_name_ + ".slowdown_radius") { params_.slowdown_radius = parameter.as_double(); - } else if (name == plugin_name_ + ".initial_rotation_min_angle") { - params_.initial_rotation_min_angle = parameter.as_double(); + } else if (name == plugin_name_ + ".initial_rotation_tolerance") { + params_.initial_rotation_tolerance = parameter.as_double(); } else if (name == plugin_name_ + ".rotation_scaling_factor") { params_.rotation_scaling_factor = parameter.as_double(); + } else if (name == plugin_name_ + ".in_place_collision_resolution") { + params_.in_place_collision_resolution = parameter.as_double(); } } else if (type == ParameterType::PARAMETER_BOOL) { if (name == plugin_name_ + ".initial_rotation") { @@ -160,8 +177,8 @@ ParameterHandler::dynamicParametersCallback(std::vector param continue; } params_.initial_rotation = parameter.as_bool(); - } else if (name == plugin_name_ + ".final_rotation") { - params_.final_rotation = parameter.as_bool(); + } else if (name == plugin_name_ + ".prefer_final_rotation") { + params_.prefer_final_rotation = parameter.as_bool(); } else if (name == plugin_name_ + ".allow_backward") { if (params_.initial_rotation && parameter.as_bool()) { RCLCPP_WARN( diff --git a/nav2_graceful_controller/src/utils.cpp b/nav2_graceful_controller/src/utils.cpp index e6cdbadd569..0e79879efcd 100644 --- a/nav2_graceful_controller/src/utils.cpp +++ b/nav2_graceful_controller/src/utils.cpp @@ -17,16 +17,6 @@ namespace nav2_graceful_controller { -geometry_msgs::msg::PointStamped createMotionTargetMsg( - const geometry_msgs::msg::PoseStamped & motion_target) -{ - geometry_msgs::msg::PointStamped motion_target_point; - motion_target_point.header = motion_target.header; - motion_target_point.point = motion_target.pose.position; - motion_target_point.point.z = 0.01; - return motion_target_point; -} - visualization_msgs::msg::Marker createSlowdownMarker( const geometry_msgs::msg::PoseStamped & motion_target, const double & slowdown_radius) { diff --git a/nav2_graceful_controller/test/test_graceful_controller.cpp b/nav2_graceful_controller/test/test_graceful_controller.cpp index fd5f986c76a..de95598bb0f 100644 --- a/nav2_graceful_controller/test/test_graceful_controller.cpp +++ b/nav2_graceful_controller/test/test_graceful_controller.cpp @@ -59,19 +59,6 @@ class GMControllerFixture : public nav2_graceful_controller::GracefulController nav_msgs::msg::Path getPlan() {return path_handler_->getPlan();} - geometry_msgs::msg::PoseStamped getMotionTarget( - const double & motion_target_distance, const nav_msgs::msg::Path & plan) - { - return nav2_graceful_controller::GracefulController::getMotionTarget( - motion_target_distance, plan); - } - - geometry_msgs::msg::PointStamped createMotionTargetMsg( - const geometry_msgs::msg::PoseStamped & motion_target) - { - return nav2_graceful_controller::createMotionTargetMsg(motion_target); - } - visualization_msgs::msg::Marker createSlowdownMarker( const geometry_msgs::msg::PoseStamped & motion_target) { @@ -86,16 +73,6 @@ class GMControllerFixture : public nav2_graceful_controller::GracefulController angle_to_target); } - bool simulateTrajectory( - const geometry_msgs::msg::PoseStamped & robot_pose, - const geometry_msgs::msg::PoseStamped & motion_target, - const geometry_msgs::msg::TransformStamped & costmap_transform, - nav_msgs::msg::Path & trajectory, const bool & backward) - { - return nav2_graceful_controller::GracefulController::simulateTrajectory( - robot_pose, motion_target, costmap_transform, trajectory, backward); - } - double getSpeedLinearMax() {return params_->v_linear_max;} nav_msgs::msg::Path transformGlobalPlan( @@ -289,7 +266,8 @@ TEST(GracefulControllerTest, dynamicParameters) { // Set parameters auto results = params->set_parameters_atomically( {rclcpp::Parameter("test.transform_tolerance", 1.0), - rclcpp::Parameter("test.motion_target_dist", 2.0), + rclcpp::Parameter("test.min_lookahead", 1.0), + rclcpp::Parameter("test.max_lookahead", 2.0), rclcpp::Parameter("test.k_phi", 4.0), rclcpp::Parameter("test.k_delta", 5.0), rclcpp::Parameter("test.beta", 6.0), @@ -297,19 +275,22 @@ TEST(GracefulControllerTest, dynamicParameters) { rclcpp::Parameter("test.v_linear_min", 8.0), rclcpp::Parameter("test.v_linear_max", 9.0), rclcpp::Parameter("test.v_angular_max", 10.0), + rclcpp::Parameter("test.v_angular_min_in_place", 14.0), rclcpp::Parameter("test.slowdown_radius", 11.0), rclcpp::Parameter("test.initial_rotation", false), - rclcpp::Parameter("test.initial_rotation_min_angle", 12.0), - rclcpp::Parameter("test.final_rotation", false), + rclcpp::Parameter("test.initial_rotation_tolerance", 12.0), + rclcpp::Parameter("test.prefer_final_rotation", false), rclcpp::Parameter("test.rotation_scaling_factor", 13.0), - rclcpp::Parameter("test.allow_backward", true)}); + rclcpp::Parameter("test.allow_backward", true), + rclcpp::Parameter("test.in_place_collision_resolution", 15.0)}); // Spin rclcpp::spin_until_future_complete(node->get_node_base_interface(), results); // Check parameters EXPECT_EQ(node->get_parameter("test.transform_tolerance").as_double(), 1.0); - EXPECT_EQ(node->get_parameter("test.motion_target_dist").as_double(), 2.0); + EXPECT_EQ(node->get_parameter("test.min_lookahead").as_double(), 1.0); + EXPECT_EQ(node->get_parameter("test.max_lookahead").as_double(), 2.0); EXPECT_EQ(node->get_parameter("test.k_phi").as_double(), 4.0); EXPECT_EQ(node->get_parameter("test.k_delta").as_double(), 5.0); EXPECT_EQ(node->get_parameter("test.beta").as_double(), 6.0); @@ -317,12 +298,14 @@ TEST(GracefulControllerTest, dynamicParameters) { EXPECT_EQ(node->get_parameter("test.v_linear_min").as_double(), 8.0); EXPECT_EQ(node->get_parameter("test.v_linear_max").as_double(), 9.0); EXPECT_EQ(node->get_parameter("test.v_angular_max").as_double(), 10.0); + EXPECT_EQ(node->get_parameter("test.v_angular_min_in_place").as_double(), 14.0); EXPECT_EQ(node->get_parameter("test.slowdown_radius").as_double(), 11.0); EXPECT_EQ(node->get_parameter("test.initial_rotation").as_bool(), false); - EXPECT_EQ(node->get_parameter("test.initial_rotation_min_angle").as_double(), 12.0); - EXPECT_EQ(node->get_parameter("test.final_rotation").as_bool(), false); + EXPECT_EQ(node->get_parameter("test.initial_rotation_tolerance").as_double(), 12.0); + EXPECT_EQ(node->get_parameter("test.prefer_final_rotation").as_bool(), false); EXPECT_EQ(node->get_parameter("test.rotation_scaling_factor").as_double(), 13.0); EXPECT_EQ(node->get_parameter("test.allow_backward").as_bool(), true); + EXPECT_EQ(node->get_parameter("test.in_place_collision_resolution").as_double(), 15.0); // Set initial rotation to true results = params->set_parameters_atomically( @@ -356,84 +339,6 @@ TEST(GracefulControllerTest, dynamicParameters) { EXPECT_EQ(controller->getAllowBackward(), false); } -TEST(GracefulControllerTest, getDifferentMotionTargets) { - auto node = std::make_shared("testGraceful"); - auto tf = std::make_shared(node->get_clock()); - auto costmap_ros = std::make_shared("global_costmap"); - - // Create controller - auto controller = std::make_shared(); - costmap_ros->on_configure(rclcpp_lifecycle::State()); - controller->configure(node, "test", tf, costmap_ros); - controller->activate(); - - // Set the plan - nav_msgs::msg::Path plan; - plan.header.frame_id = "map"; - plan.poses.resize(3); - plan.poses[0].header.frame_id = "map"; - plan.poses[0].pose.position.x = 1.0; - plan.poses[0].pose.position.y = 2.0; - plan.poses[0].pose.orientation = tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0)); - plan.poses[1].header.frame_id = "map"; - plan.poses[1].pose.position.x = 3.0; - plan.poses[1].pose.position.y = 4.0; - plan.poses[1].pose.orientation = tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0)); - plan.poses[2].header.frame_id = "map"; - plan.poses[2].pose.position.x = 5.0; - plan.poses[2].pose.position.y = 6.0; - plan.poses[2].pose.orientation = tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0)); - controller->setPlan(plan); - - // Set distance and get motion target - double motion_target_distance = 3.5; - auto motion_target = controller->getMotionTarget(motion_target_distance, plan); - - // Check results, should be the second one - EXPECT_EQ(motion_target.header.frame_id, "map"); - EXPECT_EQ(motion_target.pose.position.x, 3.0); - EXPECT_EQ(motion_target.pose.position.y, 4.0); - EXPECT_EQ(motion_target.pose.orientation, tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0))); - - // Set a new distance greater than the path length and get motion target - motion_target_distance = 10.0; - motion_target = controller->getMotionTarget(motion_target_distance, plan); - - // Check results: should be the last one - EXPECT_EQ(motion_target.header.frame_id, "map"); - EXPECT_EQ(motion_target.pose.position.x, 5.0); - EXPECT_EQ(motion_target.pose.position.y, 6.0); - EXPECT_EQ(motion_target.pose.orientation, tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0))); -} - -TEST(GracefulControllerTest, createMotionTargetMsg) { - auto node = std::make_shared("testGraceful"); - auto tf = std::make_shared(node->get_clock()); - auto costmap_ros = std::make_shared("global_costmap"); - - // Create controller - auto controller = std::make_shared(); - costmap_ros->on_configure(rclcpp_lifecycle::State()); - controller->configure(node, "test", tf, costmap_ros); - controller->activate(); - - // Create motion target - geometry_msgs::msg::PoseStamped motion_target; - motion_target.header.frame_id = "map"; - motion_target.pose.position.x = 1.0; - motion_target.pose.position.y = 2.0; - motion_target.pose.orientation = tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0)); - - // Create motion target message - auto motion_target_msg = controller->createMotionTargetMsg(motion_target); - - // Check results - EXPECT_EQ(motion_target_msg.header.frame_id, "map"); - EXPECT_EQ(motion_target_msg.point.x, 1.0); - EXPECT_EQ(motion_target_msg.point.y, 2.0); - EXPECT_EQ(motion_target_msg.point.z, 0.01); -} - TEST(GracefulControllerTest, createSlowdownMsg) { auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); @@ -522,6 +427,19 @@ TEST(GracefulControllerTest, rotateToTarget) { // Check results: it must be a negative rotation EXPECT_EQ(cmd_vel.linear.x, 0.0); EXPECT_EQ(cmd_vel.angular.z, -0.25); + + // Set very high v_angular_min_in_place velocity + results = params->set_parameters_atomically( + {rclcpp::Parameter("test.v_angular_min_in_place", 1.0)}); + rclcpp::spin_until_future_complete(node->get_node_base_interface(), results); + + // Set a new angle to target + angle_to_target = 0.5; + cmd_vel = controller->rotateToTarget(angle_to_target); + + // Check results: positive velocity, at least as high as min_in_place + EXPECT_EQ(cmd_vel.linear.x, 0.0); + EXPECT_EQ(cmd_vel.angular.z, 1.0); } TEST(GracefulControllerTest, setSpeedLimit) { @@ -937,12 +855,12 @@ TEST(GracefulControllerTest, computeVelocityCommandRotate) { plan.poses[0].pose.position.y = 0.0; plan.poses[0].pose.orientation = tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0)); plan.poses[1].header.frame_id = "test_global_frame"; - plan.poses[1].pose.position.x = 1.0; - plan.poses[1].pose.position.y = 1.0; + plan.poses[1].pose.position.x = 0.5; + plan.poses[1].pose.position.y = 0.5; plan.poses[1].pose.orientation = tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0)); plan.poses[2].header.frame_id = "test_global_frame"; - plan.poses[2].pose.position.x = 2.0; - plan.poses[2].pose.position.y = 2.0; + plan.poses[2].pose.position.x = 1.0; + plan.poses[2].pose.position.y = 1.0; plan.poses[2].pose.orientation = tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0)); controller->setPlan(plan); @@ -960,8 +878,8 @@ TEST(GracefulControllerTest, computeVelocityCommandRotate) { // Check results: the robot should rotate in place. // So, linear velocity should be zero and angular velocity should be a positive value below 0.5. EXPECT_EQ(cmd_vel.twist.linear.x, 0.0); - EXPECT_GE(cmd_vel.twist.angular.x, 0.0); - EXPECT_LE(cmd_vel.twist.angular.x, 0.5); + EXPECT_GT(cmd_vel.twist.angular.z, 0.0); + EXPECT_LE(cmd_vel.twist.angular.z, 0.5); } TEST(GracefulControllerTest, computeVelocityCommandRegular) { @@ -1117,7 +1035,9 @@ TEST(GracefulControllerTest, computeVelocityCommandRegularBackwards) { // Check results: the robot should go straight to the target. // So, both linear velocity should be some negative values. EXPECT_LT(cmd_vel.twist.linear.x, 0.0); - EXPECT_LT(cmd_vel.twist.angular.z, 0.0); + // There might be a small bit of noise on angular velocity + EXPECT_LT(cmd_vel.twist.angular.z, 0.01); + EXPECT_GT(cmd_vel.twist.angular.z, -0.01); } TEST(GracefulControllerTest, computeVelocityCommandFinal) { @@ -1200,8 +1120,8 @@ TEST(GracefulControllerTest, computeVelocityCommandFinal) { // Check results: the robot should do a final rotation near the target. // So, linear velocity should be zero and angular velocity should be a positive value below 0.5. EXPECT_EQ(cmd_vel.twist.linear.x, 0.0); - EXPECT_GE(cmd_vel.twist.angular.x, 0.0); - EXPECT_LE(cmd_vel.twist.angular.x, 0.5); + EXPECT_GE(cmd_vel.twist.angular.z, 0.0); + EXPECT_LE(cmd_vel.twist.angular.z, 0.5); } int main(int argc, char ** argv) diff --git a/nav2_lifecycle_manager/package.xml b/nav2_lifecycle_manager/package.xml index 6a2df2f39a0..d13d19dae10 100644 --- a/nav2_lifecycle_manager/package.xml +++ b/nav2_lifecycle_manager/package.xml @@ -2,7 +2,7 @@ nav2_lifecycle_manager - 1.3.4 + 1.3.5 A controller/manager for the lifecycle nodes of the Navigation 2 system Michael Jeronimo Apache-2.0 diff --git a/nav2_loopback_sim/package.xml b/nav2_loopback_sim/package.xml index df450febd99..eb34bc37573 100644 --- a/nav2_loopback_sim/package.xml +++ b/nav2_loopback_sim/package.xml @@ -2,7 +2,7 @@ nav2_loopback_sim - 1.3.4 + 1.3.5 A loopback simulator to replace physics simulation steve macenski Apache-2.0 diff --git a/nav2_map_server/package.xml b/nav2_map_server/package.xml index 2b27d23e5e1..ce7462c12c0 100644 --- a/nav2_map_server/package.xml +++ b/nav2_map_server/package.xml @@ -2,7 +2,7 @@ nav2_map_server - 1.3.4 + 1.3.5 Refactored map server for ROS2 Navigation diff --git a/nav2_mppi_controller/package.xml b/nav2_mppi_controller/package.xml index fa105867d4d..f12058fa479 100644 --- a/nav2_mppi_controller/package.xml +++ b/nav2_mppi_controller/package.xml @@ -2,7 +2,7 @@ nav2_mppi_controller - 1.3.4 + 1.3.5 nav2_mppi_controller Steve Macenski Aleksei Budyakov diff --git a/nav2_msgs/package.xml b/nav2_msgs/package.xml index c30ea21c1ff..eae04b4c640 100644 --- a/nav2_msgs/package.xml +++ b/nav2_msgs/package.xml @@ -2,7 +2,7 @@ nav2_msgs - 1.3.4 + 1.3.5 Messages and service files for the Nav2 stack Michael Jeronimo Steve Macenski diff --git a/nav2_navfn_planner/package.xml b/nav2_navfn_planner/package.xml index d8745e96dd7..ac33cb68e3b 100644 --- a/nav2_navfn_planner/package.xml +++ b/nav2_navfn_planner/package.xml @@ -2,7 +2,7 @@ nav2_navfn_planner - 1.3.4 + 1.3.5 Nav2 NavFn planner Steve Macenski Carlos Orduno diff --git a/nav2_planner/package.xml b/nav2_planner/package.xml index ba9a85b78e0..91bae80cc58 100644 --- a/nav2_planner/package.xml +++ b/nav2_planner/package.xml @@ -2,7 +2,7 @@ nav2_planner - 1.3.4 + 1.3.5 Nav2 planner server package Steve Macenski Apache-2.0 diff --git a/nav2_regulated_pure_pursuit_controller/package.xml b/nav2_regulated_pure_pursuit_controller/package.xml index 06ca9ccfba2..adead1f74d1 100644 --- a/nav2_regulated_pure_pursuit_controller/package.xml +++ b/nav2_regulated_pure_pursuit_controller/package.xml @@ -2,7 +2,7 @@ nav2_regulated_pure_pursuit_controller - 1.3.4 + 1.3.5 Regulated Pure Pursuit Controller Steve Macenski Shrijit Singh diff --git a/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp b/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp index 03c1c9881c3..78307d7ebf6 100644 --- a/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp +++ b/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp @@ -20,6 +20,7 @@ #include #include #include +#include #include "rclcpp/rclcpp.hpp" #include "pluginlib/class_loader.hpp" @@ -106,6 +107,11 @@ class RotationShimController : public nav2_core::Controller */ void setSpeedLimit(const double & speed_limit, const bool & percentage) override; + /** + * @brief Reset the state of the controller + */ + void reset() override; + protected: /** * @brief Finds the point on the path that is roughly the sampling @@ -183,6 +189,8 @@ class RotationShimController : public nav2_core::Controller double rotate_to_heading_angular_vel_, max_angular_accel_; double control_duration_, simulate_ahead_time_; bool rotate_to_goal_heading_, in_rotation_, rotate_to_heading_once_; + bool closed_loop_; + double last_angular_vel_ = std::numeric_limits::max(); // Dynamic parameters handler std::mutex mutex_; diff --git a/nav2_rotation_shim_controller/package.xml b/nav2_rotation_shim_controller/package.xml index 87b6f4776de..86274088e08 100644 --- a/nav2_rotation_shim_controller/package.xml +++ b/nav2_rotation_shim_controller/package.xml @@ -2,7 +2,7 @@ nav2_rotation_shim_controller - 1.3.4 + 1.3.5 Rotation Shim Controller Steve Macenski Apache-2.0 diff --git a/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp b/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp index 6b3d24a4ab1..10c6a7211c9 100644 --- a/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp +++ b/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp @@ -68,6 +68,8 @@ void RotationShimController::configure( node, plugin_name_ + ".rotate_to_goal_heading", rclcpp::ParameterValue(false)); nav2_util::declare_parameter_if_not_declared( node, plugin_name_ + ".rotate_to_heading_once", rclcpp::ParameterValue(false)); + nav2_util::declare_parameter_if_not_declared( + node, plugin_name_ + ".closed_loop", rclcpp::ParameterValue(true)); node->get_parameter(plugin_name_ + ".angular_dist_threshold", angular_dist_threshold_); node->get_parameter(plugin_name_ + ".angular_disengage_threshold", angular_disengage_threshold_); @@ -84,6 +86,7 @@ void RotationShimController::configure( node->get_parameter(plugin_name_ + ".rotate_to_goal_heading", rotate_to_goal_heading_); node->get_parameter(plugin_name_ + ".rotate_to_heading_once", rotate_to_heading_once_); + node->get_parameter(plugin_name_ + ".closed_loop", closed_loop_); try { primary_controller_ = lp_loader_.createUniqueInstance(primary_controller); @@ -114,6 +117,7 @@ void RotationShimController::activate() primary_controller_->activate(); in_rotation_ = false; + last_angular_vel_ = std::numeric_limits::max(); auto node = node_.lock(); dyn_params_handler_ = node->add_on_set_parameters_callback( @@ -179,7 +183,9 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands double angular_distance_to_heading = angles::shortest_angular_distance(pose_yaw, goal_yaw); - return computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity); + auto cmd_vel = computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity); + last_angular_vel_ = cmd_vel.twist.angular.z; + return cmd_vel; } } catch (const std::runtime_error & e) { RCLCPP_INFO( @@ -208,7 +214,9 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands logger_, "Robot is not within the new path's rough heading, rotating to heading..."); in_rotation_ = true; - return computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity); + auto cmd_vel = computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity); + last_angular_vel_ = cmd_vel.twist.angular.z; + return cmd_vel; } else { RCLCPP_DEBUG( logger_, @@ -227,7 +235,9 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands // If at this point, use the primary controller to path track in_rotation_ = false; - return primary_controller_->computeVelocityCommands(pose, velocity, goal_checker); + auto cmd_vel = primary_controller_->computeVelocityCommands(pose, velocity, goal_checker); + last_angular_vel_ = cmd_vel.twist.angular.z; + return cmd_vel; } geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathPt() @@ -285,16 +295,27 @@ RotationShimController::computeRotateToHeadingCommand( const geometry_msgs::msg::PoseStamped & pose, const geometry_msgs::msg::Twist & velocity) { + auto current = closed_loop_ ? velocity.angular.z : last_angular_vel_; + if (current == std::numeric_limits::max()) { + current = 0.0; + } + geometry_msgs::msg::TwistStamped cmd_vel; cmd_vel.header = pose.header; const double sign = angular_distance_to_heading > 0.0 ? 1.0 : -1.0; const double angular_vel = sign * rotate_to_heading_angular_vel_; const double & dt = control_duration_; - const double min_feasible_angular_speed = velocity.angular.z - max_angular_accel_ * dt; - const double max_feasible_angular_speed = velocity.angular.z + max_angular_accel_ * dt; + const double min_feasible_angular_speed = current - max_angular_accel_ * dt; + const double max_feasible_angular_speed = current + max_angular_accel_ * dt; cmd_vel.twist.angular.z = std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed); + // Check if we need to slow down to avoid overshooting + double max_vel_to_stop = std::sqrt(2 * max_angular_accel_ * fabs(angular_distance_to_heading)); + if (fabs(cmd_vel.twist.angular.z) > max_vel_to_stop) { + cmd_vel.twist.angular.z = sign * max_vel_to_stop; + } + isCollisionFree(cmd_vel, angular_distance_to_heading, pose); return cmd_vel; } @@ -362,6 +383,12 @@ void RotationShimController::setSpeedLimit(const double & speed_limit, const boo primary_controller_->setSpeedLimit(speed_limit, percentage); } +void RotationShimController::reset() +{ + last_angular_vel_ = std::numeric_limits::max(); + primary_controller_->reset(); +} + rcl_interfaces::msg::SetParametersResult RotationShimController::dynamicParametersCallback(std::vector parameters) { @@ -389,6 +416,8 @@ RotationShimController::dynamicParametersCallback(std::vector rotate_to_goal_heading_ = parameter.as_bool(); } else if (name == plugin_name_ + ".rotate_to_heading_once") { rotate_to_heading_once_ = parameter.as_bool(); + } else if (name == plugin_name_ + ".closed_loop") { + closed_loop_ = parameter.as_bool(); } } } diff --git a/nav2_rotation_shim_controller/test/test_shim_controller.cpp b/nav2_rotation_shim_controller/test/test_shim_controller.cpp index 1d63a77b47e..b202d96f44f 100644 --- a/nav2_rotation_shim_controller/test/test_shim_controller.cpp +++ b/nav2_rotation_shim_controller/test/test_shim_controller.cpp @@ -314,6 +314,84 @@ TEST(RotationShimControllerTest, computeVelocityTests) EXPECT_THROW(controller->computeVelocityCommands(pose, velocity, &checker), std::runtime_error); } +TEST(RotationShimControllerTest, openLoopRotationTests) { + auto ctrl = std::make_shared(); + auto node = std::make_shared("ShimControllerTest"); + std::string name = "PathFollower"; + auto tf = std::make_shared(node->get_clock()); + auto listener = std::make_shared(*tf, node, true); + auto costmap = std::make_shared("fake_costmap"); + rclcpp_lifecycle::State state; + costmap->on_configure(state); + auto tf_broadcaster = std::make_shared(node); + + geometry_msgs::msg::TransformStamped transform; + transform.header.frame_id = "base_link"; + transform.child_frame_id = "odom"; + transform.transform.rotation.x = 0.0; + transform.transform.rotation.y = 0.0; + transform.transform.rotation.z = 0.0; + transform.transform.rotation.w = 1.0; + tf_broadcaster->sendTransform(transform); + + // set a valid primary controller so we can do lifecycle + node->declare_parameter( + "PathFollower.primary_controller", + std::string("nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController")); + node->declare_parameter( + "controller_frequency", + 20.0); + node->declare_parameter( + "PathFollower.rotate_to_goal_heading", + true); + node->declare_parameter( + "PathFollower.closed_loop", + false); + + auto controller = std::make_shared(); + controller->configure(node, name, tf, costmap); + controller->activate(); + + // Test state update and path setting + nav_msgs::msg::Path path; + path.header.frame_id = "base_link"; + path.poses.resize(4); + + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = "base_link"; + geometry_msgs::msg::Twist velocity; + nav2_controller::SimpleGoalChecker checker; + node->declare_parameter( + "checker.xy_goal_tolerance", + 1.0); + checker.initialize(node, "checker", costmap); + + path.header.frame_id = "base_link"; + path.poses[0].pose.position.x = 0.0; + path.poses[0].pose.position.y = 0.0; + path.poses[1].pose.position.x = 0.05; + path.poses[1].pose.position.y = 0.05; + path.poses[2].pose.position.x = 0.10; + path.poses[2].pose.position.y = 0.10; + // goal position within checker xy_goal_tolerance + path.poses[3].pose.position.x = 0.20; + path.poses[3].pose.position.y = 0.20; + // goal heading 45 degrees to the left + path.poses[3].pose.orientation.z = -0.3826834; + path.poses[3].pose.orientation.w = 0.9238795; + path.poses[3].header.frame_id = "base_link"; + + // Calculate first velocity command + controller->setPlan(path); + auto cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker); + EXPECT_NEAR(cmd_vel.twist.angular.z, -0.16, 1e-4); + + // Test second velocity command with wrong odometry + velocity.angular.z = 1.8; + cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker); + EXPECT_NEAR(cmd_vel.twist.angular.z, -0.32, 1e-4); +} + TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) { auto ctrl = std::make_shared(); auto node = std::make_shared("ShimControllerTest"); @@ -387,6 +465,84 @@ TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) { EXPECT_EQ(cmd_vel.twist.angular.z, 1.8); } +TEST(RotationShimControllerTest, accelerationTests) { + auto ctrl = std::make_shared(); + auto node = std::make_shared("ShimControllerTest"); + std::string name = "PathFollower"; + auto tf = std::make_shared(node->get_clock()); + auto listener = std::make_shared(*tf, node, true); + auto costmap = std::make_shared("fake_costmap"); + rclcpp_lifecycle::State state; + costmap->on_configure(state); + auto tf_broadcaster = std::make_shared(node); + + geometry_msgs::msg::TransformStamped transform; + transform.header.frame_id = "base_link"; + transform.child_frame_id = "odom"; + transform.transform.rotation.x = 0.0; + transform.transform.rotation.y = 0.0; + transform.transform.rotation.z = 0.0; + transform.transform.rotation.w = 1.0; + tf_broadcaster->sendTransform(transform); + + // set a valid primary controller so we can do lifecycle + node->declare_parameter( + "PathFollower.primary_controller", + std::string("nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController")); + node->declare_parameter( + "controller_frequency", + 20.0); + node->declare_parameter( + "PathFollower.rotate_to_goal_heading", + true); + node->declare_parameter( + "PathFollower.max_angular_accel", + 0.5); + + auto controller = std::make_shared(); + controller->configure(node, name, tf, costmap); + controller->activate(); + + // Test state update and path setting + nav_msgs::msg::Path path; + path.header.frame_id = "base_link"; + path.poses.resize(4); + + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = "base_link"; + geometry_msgs::msg::Twist velocity; + nav2_controller::SimpleGoalChecker checker; + node->declare_parameter( + "checker.xy_goal_tolerance", + 1.0); + checker.initialize(node, "checker", costmap); + + path.header.frame_id = "base_link"; + path.poses[0].pose.position.x = 0.0; + path.poses[0].pose.position.y = 0.0; + path.poses[1].pose.position.x = 0.05; + path.poses[1].pose.position.y = 0.05; + path.poses[2].pose.position.x = 0.10; + path.poses[2].pose.position.y = 0.10; + // goal position within checker xy_goal_tolerance + path.poses[3].pose.position.x = 0.20; + path.poses[3].pose.position.y = 0.20; + // goal heading 45 degrees to the left + path.poses[3].pose.orientation.z = -0.3826834; + path.poses[3].pose.orientation.w = 0.9238795; + path.poses[3].header.frame_id = "base_link"; + + // Test acceleration limits + controller->setPlan(path); + auto cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker); + EXPECT_EQ(cmd_vel.twist.angular.z, -0.025); + + // Test slowing down to avoid overshooting + velocity.angular.z = -1.8; + cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker); + EXPECT_NEAR(cmd_vel.twist.angular.z, -std::sqrt(2 * 0.5 * M_PI / 4), 1e-4); +} + TEST(RotationShimControllerTest, isGoalChangedTest) { auto ctrl = std::make_shared(); @@ -469,7 +625,8 @@ TEST(RotationShimControllerTest, testDynamicParameter) rclcpp::Parameter("test.simulate_ahead_time", 7.0), rclcpp::Parameter("test.primary_controller", std::string("HI")), rclcpp::Parameter("test.rotate_to_goal_heading", true), - rclcpp::Parameter("test.rotate_to_heading_once", true)}); + rclcpp::Parameter("test.rotate_to_heading_once", true), + rclcpp::Parameter("test.closed_loop", false)}); rclcpp::spin_until_future_complete( node->get_node_base_interface(), @@ -482,4 +639,5 @@ TEST(RotationShimControllerTest, testDynamicParameter) EXPECT_EQ(node->get_parameter("test.simulate_ahead_time").as_double(), 7.0); EXPECT_EQ(node->get_parameter("test.rotate_to_goal_heading").as_bool(), true); EXPECT_EQ(node->get_parameter("test.rotate_to_heading_once").as_bool(), true); + EXPECT_EQ(node->get_parameter("test.closed_loop").as_bool(), false); } diff --git a/nav2_rviz_plugins/package.xml b/nav2_rviz_plugins/package.xml index 5cc51009da1..20621ffb9ca 100644 --- a/nav2_rviz_plugins/package.xml +++ b/nav2_rviz_plugins/package.xml @@ -2,7 +2,7 @@ nav2_rviz_plugins - 1.3.4 + 1.3.5 Navigation 2 plugins for rviz Michael Jeronimo Apache-2.0 diff --git a/nav2_simple_commander/package.xml b/nav2_simple_commander/package.xml index e1dd961ac40..8c8205d79b9 100644 --- a/nav2_simple_commander/package.xml +++ b/nav2_simple_commander/package.xml @@ -2,7 +2,7 @@ nav2_simple_commander - 1.3.4 + 1.3.5 An importable library for writing mobile robot applications in python3 steve Apache-2.0 diff --git a/nav2_smac_planner/package.xml b/nav2_smac_planner/package.xml index 9fc728ad34d..ff4974fcaab 100644 --- a/nav2_smac_planner/package.xml +++ b/nav2_smac_planner/package.xml @@ -2,7 +2,7 @@ nav2_smac_planner - 1.3.4 + 1.3.5 Smac global planning plugin: A*, Hybrid-A*, State Lattice Steve Macenski Apache-2.0 diff --git a/nav2_smac_planner/src/smac_planner_2d.cpp b/nav2_smac_planner/src/smac_planner_2d.cpp index 728d9910fd9..afbbce075e3 100644 --- a/nav2_smac_planner/src/smac_planner_2d.cpp +++ b/nav2_smac_planner/src/smac_planner_2d.cpp @@ -258,7 +258,7 @@ nav_msgs::msg::Path SmacPlanner2D::createPlan( pose.pose.orientation.z = 0.0; pose.pose.orientation.w = 1.0; - // Corner case of start and goal beeing on the same cell + // Corner case of start and goal being on the same cell if (std::floor(mx_start) == std::floor(mx_goal) && std::floor(my_start) == std::floor(my_goal)) { pose.pose = start.pose; // if we have a different start and goal orientation, set the unique path pose to the goal @@ -268,6 +268,12 @@ nav_msgs::msg::Path SmacPlanner2D::createPlan( pose.pose.orientation = goal.pose.orientation; } plan.poses.push_back(pose); + + // Publish raw path for debug + if (_raw_plan_publisher->get_subscription_count() > 0) { + _raw_plan_publisher->publish(plan); + } + return plan; } diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 70806aae201..b5a785c9ce5 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -361,8 +361,13 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan( _a_star->setCollisionChecker(&_collision_checker); // Set starting point, in A* bin search coordinates - float mx, my; - if (!costmap->worldToMapContinuous(start.pose.position.x, start.pose.position.y, mx, my)) { + float mx_start, my_start, mx_goal, my_goal; + if (!costmap->worldToMapContinuous( + start.pose.position.x, + start.pose.position.y, + mx_start, + my_start)) + { throw nav2_core::StartOutsideMapBounds( "Start Coordinates of(" + std::to_string(start.pose.position.x) + ", " + std::to_string(start.pose.position.y) + ") was outside bounds"); @@ -376,10 +381,15 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan( if (orientation_bin >= static_cast(_angle_quantizations)) { orientation_bin -= static_cast(_angle_quantizations); } - _a_star->setStart(mx, my, static_cast(orientation_bin)); + _a_star->setStart(mx_start, my_start, static_cast(orientation_bin)); // Set goal point, in A* bin search coordinates - if (!costmap->worldToMapContinuous(goal.pose.position.x, goal.pose.position.y, mx, my)) { + if (!costmap->worldToMapContinuous( + goal.pose.position.x, + goal.pose.position.y, + mx_goal, + my_goal)) + { throw nav2_core::GoalOutsideMapBounds( "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " + std::to_string(goal.pose.position.y) + ") was outside bounds"); @@ -392,7 +402,7 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan( if (orientation_bin >= static_cast(_angle_quantizations)) { orientation_bin -= static_cast(_angle_quantizations); } - _a_star->setGoal(mx, my, static_cast(orientation_bin)); + _a_star->setGoal(mx_goal, my_goal, static_cast(orientation_bin)); // Setup message nav_msgs::msg::Path plan; @@ -406,6 +416,22 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan( pose.pose.orientation.z = 0.0; pose.pose.orientation.w = 1.0; + // Corner case of start and goal being on the same cell + if (std::floor(mx_start) == std::floor(mx_goal) && + std::floor(my_start) == std::floor(my_goal)) + { + pose.pose = start.pose; + pose.pose.orientation = goal.pose.orientation; + plan.poses.push_back(pose); + + // Publish raw path for debug + if (_raw_plan_publisher->get_subscription_count() > 0) { + _raw_plan_publisher->publish(plan); + } + + return plan; + } + // Compute plan NodeHybrid::CoordinateVector path; int num_iterations = 0; diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index c5a9ecdff60..447a15ef623 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -287,24 +287,34 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( _a_star->setCollisionChecker(&_collision_checker); // Set starting point, in A* bin search coordinates - float mx, my; - if (!_costmap->worldToMapContinuous(start.pose.position.x, start.pose.position.y, mx, my)) { + float mx_start, my_start, mx_goal, my_goal; + if (!_costmap->worldToMapContinuous( + start.pose.position.x, + start.pose.position.y, + mx_start, + my_start)) + { throw nav2_core::StartOutsideMapBounds( "Start Coordinates of(" + std::to_string(start.pose.position.x) + ", " + std::to_string(start.pose.position.y) + ") was outside bounds"); } _a_star->setStart( - mx, my, + mx_start, my_start, NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(start.pose.orientation))); // Set goal point, in A* bin search coordinates - if (!_costmap->worldToMapContinuous(goal.pose.position.x, goal.pose.position.y, mx, my)) { + if (!_costmap->worldToMapContinuous( + goal.pose.position.x, + goal.pose.position.y, + mx_goal, + my_goal)) + { throw nav2_core::GoalOutsideMapBounds( "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " + std::to_string(goal.pose.position.y) + ") was outside bounds"); } _a_star->setGoal( - mx, my, + mx_goal, my_goal, NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(goal.pose.orientation))); // Setup message @@ -319,6 +329,22 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( pose.pose.orientation.z = 0.0; pose.pose.orientation.w = 1.0; + // Corner case of start and goal being on the same cell + if (std::floor(mx_start) == std::floor(mx_goal) && + std::floor(my_start) == std::floor(my_goal)) + { + pose.pose = start.pose; + pose.pose.orientation = goal.pose.orientation; + plan.poses.push_back(pose); + + // Publish raw path for debug + if (_raw_plan_publisher->get_subscription_count() > 0) { + _raw_plan_publisher->publish(plan); + } + + return plan; + } + // Compute plan NodeLattice::CoordinateVector path; int num_iterations = 0; diff --git a/nav2_smac_planner/test/test_smac_2d.cpp b/nav2_smac_planner/test/test_smac_2d.cpp index e2dff5a56f4..89ad666b789 100644 --- a/nav2_smac_planner/test/test_smac_2d.cpp +++ b/nav2_smac_planner/test/test_smac_2d.cpp @@ -77,6 +77,13 @@ TEST(SmacTest, test_smac_2d) { } catch (...) { } + // corner case where the start and goal are on the same cell + goal.pose.position.x = 0.01; + goal.pose.position.y = 0.01; + + nav_msgs::msg::Path plan = planner_2d->createPlan(start, goal, dummy_cancel_checker); + EXPECT_EQ(plan.poses.size(), 1); // single point path + planner_2d->deactivate(); planner_2d->cleanup(); diff --git a/nav2_smac_planner/test/test_smac_hybrid.cpp b/nav2_smac_planner/test/test_smac_hybrid.cpp index 9952912596b..a70ae86fc7d 100644 --- a/nav2_smac_planner/test/test_smac_hybrid.cpp +++ b/nav2_smac_planner/test/test_smac_hybrid.cpp @@ -76,6 +76,13 @@ TEST(SmacTest, test_smac_se2) } catch (...) { } + // corner case where the start and goal are on the same cell + goal.pose.position.x = 0.01; + goal.pose.position.y = 0.01; + + nav_msgs::msg::Path plan = planner->createPlan(start, goal, dummy_cancel_checker); + EXPECT_EQ(plan.poses.size(), 1); // single point path + planner->deactivate(); planner->cleanup(); diff --git a/nav2_smac_planner/test/test_smac_lattice.cpp b/nav2_smac_planner/test/test_smac_lattice.cpp index dcc925e9e72..c187abd8591 100644 --- a/nav2_smac_planner/test/test_smac_lattice.cpp +++ b/nav2_smac_planner/test/test_smac_lattice.cpp @@ -84,6 +84,13 @@ TEST(SmacTest, test_smac_lattice) } catch (...) { } + // corner case where the start and goal are on the same cell + goal.pose.position.x = 0.01; + goal.pose.position.y = 0.01; + + nav_msgs::msg::Path plan = planner->createPlan(start, goal, dummy_cancel_checker); + EXPECT_EQ(plan.poses.size(), 1); // single point path + planner->deactivate(); planner->cleanup(); diff --git a/nav2_smoother/include/nav2_smoother/simple_smoother.hpp b/nav2_smoother/include/nav2_smoother/simple_smoother.hpp index 2e8fea4a945..f9839d92eaf 100644 --- a/nav2_smoother/include/nav2_smoother/simple_smoother.hpp +++ b/nav2_smoother/include/nav2_smoother/simple_smoother.hpp @@ -92,9 +92,8 @@ class SimpleSmoother : public nav2_core::Smoother * @param reversing_segment Return if this is a reversing segment * @param costmap Pointer to minimal costmap * @param max_time Maximum time to compute, stop early if over limit - * @return If smoothing was successful */ - bool smoothImpl( + void smoothImpl( nav_msgs::msg::Path & path, bool & reversing_segment, const nav2_costmap_2d::Costmap2D * costmap, diff --git a/nav2_smoother/package.xml b/nav2_smoother/package.xml index cb7702903ce..00f82870b7b 100644 --- a/nav2_smoother/package.xml +++ b/nav2_smoother/package.xml @@ -2,7 +2,7 @@ nav2_smoother - 1.3.4 + 1.3.5 Smoother action interface Matej Vargovcik Steve Macenski diff --git a/nav2_smoother/src/simple_smoother.cpp b/nav2_smoother/src/simple_smoother.cpp index 0b494d96c6e..5b4c2fff6e0 100644 --- a/nav2_smoother/src/simple_smoother.cpp +++ b/nav2_smoother/src/simple_smoother.cpp @@ -65,8 +65,7 @@ bool SimpleSmoother::smooth( steady_clock::time_point start = steady_clock::now(); double time_remaining = max_time.seconds(); - bool success = true, reversing_segment; - unsigned int segments_smoothed = 0; + bool reversing_segment; nav_msgs::msg::Path curr_path_segment; curr_path_segment.header = path.header; @@ -88,15 +87,9 @@ bool SimpleSmoother::smooth( time_remaining = max_time.seconds() - duration_cast>(now - start).count(); refinement_ctr_ = 0; - bool segment_was_smoothed = smoothImpl( - curr_path_segment, reversing_segment, costmap.get(), time_remaining); - - if (segment_was_smoothed) { - segments_smoothed++; - } - - // Smooth path segment naively - success = success && segment_was_smoothed; + // Attempt to smooth the segment + // May throw SmootherTimedOut + smoothImpl(curr_path_segment, reversing_segment, costmap.get(), time_remaining); // Assemble the path changes to the main path std::copy( @@ -106,14 +99,10 @@ bool SimpleSmoother::smooth( } } - if (segments_smoothed == 0) { - throw nav2_core::FailedToSmoothPath("No segments were smoothed"); - } - - return success; + return true; } -bool SimpleSmoother::smoothImpl( +void SimpleSmoother::smoothImpl( nav_msgs::msg::Path & path, bool & reversing_segment, const nav2_costmap_2d::Costmap2D * costmap, @@ -142,7 +131,7 @@ bool SimpleSmoother::smoothImpl( "Number of iterations has exceeded limit of %i.", max_its_); path = last_path; updateApproximatePathOrientations(path, reversing_segment); - return false; + return; } // Make sure still have time left to process @@ -188,7 +177,7 @@ bool SimpleSmoother::smoothImpl( "Returning the last path before the infeasibility was introduced."); path = last_path; updateApproximatePathOrientations(path, reversing_segment); - return false; + return; } } @@ -204,7 +193,6 @@ bool SimpleSmoother::smoothImpl( updateApproximatePathOrientations(new_path, reversing_segment); path = new_path; - return true; } double SimpleSmoother::getFieldByDim( diff --git a/nav2_smoother/test/test_simple_smoother.cpp b/nav2_smoother/test/test_simple_smoother.cpp index c8f7da8e871..6c845bfb6c6 100644 --- a/nav2_smoother/test/test_simple_smoother.cpp +++ b/nav2_smoother/test/test_simple_smoother.cpp @@ -180,7 +180,7 @@ TEST(SmootherTest, test_simple_smoother) EXPECT_NEAR(straight_regular_path.poses[5].pose.position.x, 0.607, 0.01); EXPECT_NEAR(straight_regular_path.poses[5].pose.position.y, 0.387, 0.01); - // Test that collisions are rejected + // Test that collisions are disregarded nav_msgs::msg::Path collision_path; collision_path.poses.resize(11); collision_path.poses[0].pose.position.x = 0.0; @@ -205,7 +205,7 @@ TEST(SmootherTest, test_simple_smoother) collision_path.poses[9].pose.position.y = 1.4; collision_path.poses[10].pose.position.x = 1.5; collision_path.poses[10].pose.position.y = 1.5; - EXPECT_THROW(smoother->smooth(collision_path, max_time), nav2_core::FailedToSmoothPath); + EXPECT_TRUE(smoother->smooth(collision_path, max_time)); // test cusp / reversing segments nav_msgs::msg::Path reversing_path; @@ -232,7 +232,7 @@ TEST(SmootherTest, test_simple_smoother) reversing_path.poses[9].pose.position.y = 0.1; reversing_path.poses[10].pose.position.x = 0.5; reversing_path.poses[10].pose.position.y = 0.0; - EXPECT_THROW(smoother->smooth(reversing_path, max_time), nav2_core::FailedToSmoothPath); + EXPECT_TRUE(smoother->smooth(reversing_path, max_time)); // test rotate in place tf2::Quaternion quat1, quat2; @@ -244,7 +244,18 @@ TEST(SmootherTest, test_simple_smoother) straight_irregular_path.poses[6].pose.position.x = 0.5; straight_irregular_path.poses[6].pose.position.y = 0.5; straight_irregular_path.poses[6].pose.orientation = tf2::toMsg(quat2); - EXPECT_THROW(smoother->smooth(straight_irregular_path, max_time), nav2_core::FailedToSmoothPath); + EXPECT_TRUE(smoother->smooth(straight_irregular_path, max_time)); + + // test approach + nav_msgs::msg::Path approach_path; + approach_path.poses.resize(3); + approach_path.poses[0].pose.position.x = 0.5; + approach_path.poses[0].pose.position.y = 0.0; + approach_path.poses[1].pose.position.x = 0.5; + approach_path.poses[1].pose.position.y = 0.1; + approach_path.poses[2].pose.position.x = 0.5; + approach_path.poses[2].pose.position.y = 0.2; + EXPECT_TRUE(smoother->smooth(approach_path, max_time)); // test max iterations smoother->setMaxItsToInvalid(); @@ -272,5 +283,5 @@ TEST(SmootherTest, test_simple_smoother) max_its_path.poses[9].pose.position.y = 0.9; max_its_path.poses[10].pose.position.x = 0.5; max_its_path.poses[10].pose.position.y = 1.0; - EXPECT_THROW(smoother->smooth(max_its_path, max_time), nav2_core::FailedToSmoothPath); + EXPECT_TRUE(smoother->smooth(max_its_path, max_time)); } diff --git a/nav2_system_tests/package.xml b/nav2_system_tests/package.xml index 91b1b846705..1cb400360cc 100644 --- a/nav2_system_tests/package.xml +++ b/nav2_system_tests/package.xml @@ -2,7 +2,7 @@ nav2_system_tests - 1.3.4 + 1.3.5 A sets of system-level tests for Nav2 usually involving full robot simulation Carlos Orduno Apache-2.0 diff --git a/nav2_theta_star_planner/package.xml b/nav2_theta_star_planner/package.xml index 420c5322f4a..fd6c269294f 100644 --- a/nav2_theta_star_planner/package.xml +++ b/nav2_theta_star_planner/package.xml @@ -2,7 +2,7 @@ nav2_theta_star_planner - 1.3.4 + 1.3.5 Theta* Global Planning Plugin Steve Macenski Anshumaan Singh diff --git a/nav2_util/include/nav2_util/lifecycle_node.hpp b/nav2_util/include/nav2_util/lifecycle_node.hpp index d652982aef3..38b2ef11a0a 100644 --- a/nav2_util/include/nav2_util/lifecycle_node.hpp +++ b/nav2_util/include/nav2_util/lifecycle_node.hpp @@ -168,6 +168,11 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode return nav2_util::CallbackReturn::SUCCESS; } + /** + * @brief Automatically configure and active the node + */ + void autostart(); + /** * @brief Perform preshutdown activities before our Context is shutdown. * Note that this is related to our Context's shutdown sequence, not the @@ -207,6 +212,7 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode // Connection to tell that server is still up std::unique_ptr bond_{nullptr}; double bond_heartbeat_period; + rclcpp::TimerBase::SharedPtr autostart_timer_; }; } // namespace nav2_util diff --git a/nav2_util/include/nav2_util/simple_action_server.hpp b/nav2_util/include/nav2_util/simple_action_server.hpp index 342f930ab9f..b391f59ddce 100644 --- a/nav2_util/include/nav2_util/simple_action_server.hpp +++ b/nav2_util/include/nav2_util/simple_action_server.hpp @@ -150,6 +150,9 @@ class SimpleActionServer std::lock_guard lock(update_mutex_); if (!server_active_) { + RCLCPP_INFO( + node_logging_interface_->get_logger(), + "Action server is inactive. Rejecting the goal."); return rclcpp_action::GoalResponse::REJECT; } diff --git a/nav2_util/package.xml b/nav2_util/package.xml index d43a35fdd0d..1168f181625 100644 --- a/nav2_util/package.xml +++ b/nav2_util/package.xml @@ -2,7 +2,7 @@ nav2_util - 1.3.4 + 1.3.5 Nav2 utilities Michael Jeronimo Mohammad Haghighipanah diff --git a/nav2_util/src/lifecycle_node.cpp b/nav2_util/src/lifecycle_node.cpp index 5976d098a86..3bc9dba1574 100644 --- a/nav2_util/src/lifecycle_node.cpp +++ b/nav2_util/src/lifecycle_node.cpp @@ -21,6 +21,8 @@ #include "lifecycle_msgs/msg/state.hpp" #include "nav2_util/node_utils.hpp" +using namespace std::chrono_literals; + namespace nav2_util { @@ -40,6 +42,14 @@ LifecycleNode::LifecycleNode( this, "bond_heartbeat_period", rclcpp::ParameterValue(0.1)); this->get_parameter("bond_heartbeat_period", bond_heartbeat_period); + bool autostart_node = false; + nav2_util::declare_parameter_if_not_declared( + this, "autostart_node", rclcpp::ParameterValue(false)); + this->get_parameter("autostart_node", autostart_node); + if (autostart_node) { + autostart(); + } + printLifecycleNodeNotification(); register_rcl_preshutdown_callback(); @@ -74,6 +84,24 @@ void LifecycleNode::createBond() } } +void LifecycleNode::autostart() +{ + using lifecycle_msgs::msg::State; + autostart_timer_ = this->create_wall_timer( + 0s, + [this]() -> void { + autostart_timer_->cancel(); + RCLCPP_INFO(get_logger(), "Auto-starting node: %s", this->get_name()); + if (configure().id() != State::PRIMARY_STATE_INACTIVE) { + RCLCPP_ERROR(get_logger(), "Auto-starting node %s failed to configure!", this->get_name()); + return; + } + if (activate().id() != State::PRIMARY_STATE_ACTIVE) { + RCLCPP_ERROR(get_logger(), "Auto-starting node %s failed to activate!", this->get_name()); + } + }); +} + void LifecycleNode::runCleanups() { /* diff --git a/nav2_util/test/test_actions.cpp b/nav2_util/test/test_actions.cpp index 5ecd95d60b9..0ae2ffe0c0e 100644 --- a/nav2_util/test/test_actions.cpp +++ b/nav2_util/test/test_actions.cpp @@ -258,6 +258,7 @@ class ActionTest : public ::testing::Test TEST_F(ActionTest, test_simple_action) { + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); node_->activate_server(); // The goal for this invocation @@ -272,6 +273,7 @@ TEST_F(ActionTest, test_simple_action) future_goal_handle), rclcpp::FutureReturnCode::SUCCESS); auto goal_handle = future_goal_handle.get(); + EXPECT_NE(goal_handle, nullptr); // Wait for the result auto future_result = node_->action_client_->async_get_result(goal_handle); @@ -320,6 +322,7 @@ TEST_F(ActionTest, test_simple_action_with_feedback) future_goal_handle), rclcpp::FutureReturnCode::SUCCESS); auto goal_handle = future_goal_handle.get(); + EXPECT_NE(goal_handle, nullptr); // Wait for the result auto future_result = node_->action_client_->async_get_result(goal_handle); @@ -364,6 +367,7 @@ TEST_F(ActionTest, test_simple_action_activation_cycling) node_->deactivate_server(); auto goal_handle = future_goal_handle.get(); + EXPECT_NE(goal_handle, nullptr); // Wait for the result auto future_result = node_->action_client_->async_get_result(goal_handle); @@ -430,6 +434,7 @@ TEST_F(ActionTest, test_simple_action_preemption) future_goal_handle), rclcpp::FutureReturnCode::SUCCESS); auto goal_handle = future_goal_handle.get(); + EXPECT_NE(goal_handle, nullptr); // Wait for the result auto future_result = node_->action_client_->async_get_result(goal_handle); @@ -478,6 +483,7 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded) // Get the results auto goal_handle = future_goal_handle.get(); + EXPECT_NE(goal_handle, nullptr); // Wait for the result of initial goal auto future_result = node_->action_client_->async_get_result(goal_handle); diff --git a/nav2_util/test/test_lifecycle_node.cpp b/nav2_util/test/test_lifecycle_node.cpp index 07ef0177d72..d29da5e6df4 100644 --- a/nav2_util/test/test_lifecycle_node.cpp +++ b/nav2_util/test/test_lifecycle_node.cpp @@ -26,6 +26,27 @@ class RclCppFixture }; RclCppFixture g_rclcppfixture; +class LifecycleTransitionTestNode : public nav2_util::LifecycleNode +{ +public: + explicit LifecycleTransitionTestNode(rclcpp::NodeOptions options) + : nav2_util::LifecycleNode("test_node", "", options) {} + + nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &) override + { + configured = true; + return nav2_util::CallbackReturn::SUCCESS; + } + nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &) override + { + activated = true; + return nav2_util::CallbackReturn::SUCCESS; + } + + bool configured{false}; + bool activated{false}; +}; + // For the following two tests, if the LifecycleNode doesn't shut down properly, // the overall test will hang since the rclcpp thread will still be running, // preventing the executable from exiting (the test will hang) @@ -48,6 +69,30 @@ TEST(LifecycleNode, MultipleRclcppNodesExitCleanly) SUCCEED(); } +TEST(LifecycleNode, AutostartTransitions) +{ + auto executor = std::make_shared(); + rclcpp::NodeOptions options; + auto node = std::make_shared(options); + executor->add_node(node->get_node_base_interface()); + executor->spin_some(); + EXPECT_FALSE(node->configured); + EXPECT_FALSE(node->activated); + executor.reset(); + node.reset(); + + + executor = std::make_shared(); + options.parameter_overrides({{"autostart_node", true}}); + node = std::make_shared(options); + executor->add_node(node->get_node_base_interface()); + executor->spin_some(); + EXPECT_TRUE(node->configured); + EXPECT_TRUE(node->activated); + executor.reset(); + node.reset(); +} + TEST(LifecycleNode, OnPreshutdownCbFires) { // Ensure the on_rcl_preshutdown_cb fires diff --git a/nav2_velocity_smoother/package.xml b/nav2_velocity_smoother/package.xml index 2f925f1d414..fc0557e96a9 100644 --- a/nav2_velocity_smoother/package.xml +++ b/nav2_velocity_smoother/package.xml @@ -2,7 +2,7 @@ nav2_velocity_smoother - 1.3.4 + 1.3.5 Nav2's Output velocity smoother Steve Macenski Apache-2.0 diff --git a/nav2_voxel_grid/package.xml b/nav2_voxel_grid/package.xml index 78cd7d1d4b0..852feba8d62 100644 --- a/nav2_voxel_grid/package.xml +++ b/nav2_voxel_grid/package.xml @@ -2,7 +2,7 @@ nav2_voxel_grid - 1.3.4 + 1.3.5 voxel_grid provides an implementation of an efficient 3D voxel grid. The occupancy grid can support 3 different representations for the state of a cell: marked, free, or unknown. Due to the underlying implementation relying on bitwise and and or integer operations, the voxel grid only supports 16 different levels per voxel column. However, this limitation yields raytracing and cell marking performance in the grid comparable to standard 2D structures making it quite fast compared to most 3D structures. diff --git a/nav2_waypoint_follower/package.xml b/nav2_waypoint_follower/package.xml index 38d2f9c72c1..046ba692e29 100644 --- a/nav2_waypoint_follower/package.xml +++ b/nav2_waypoint_follower/package.xml @@ -2,7 +2,7 @@ nav2_waypoint_follower - 1.3.4 + 1.3.5 A waypoint follower navigation server Steve Macenski Apache-2.0 diff --git a/navigation2/package.xml b/navigation2/package.xml index dcabfa10b18..de6a4411e52 100644 --- a/navigation2/package.xml +++ b/navigation2/package.xml @@ -2,7 +2,7 @@ navigation2 - 1.3.4 + 1.3.5 ROS2 Navigation Stack diff --git a/tools/bt2img.py b/tools/bt2img.py index 2b12d777d82..ab8307b2138 100755 --- a/tools/bt2img.py +++ b/tools/bt2img.py @@ -186,15 +186,13 @@ def add_nodes(dot, parent_dot_name, parent_node): # type, the name if provided, and the parameters. def make_label(node): label = "< " - label += "" + label += f"" name = node.get('name') if name: - label += "" + label += f"" - for (param_name, value) in node.items(): - label += ( - "" - ) + for param_name, value in node.items(): + label += f"" label += '
' + node.tag + '
{node.tag}
' + name + '
{name}
' + param_name + '=' + value + '
{param_name}={value}
>' return label