From eb27eaa2800e946cc68a5a0735a9cfd194094ec8 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Tue, 28 Jun 2022 15:04:36 -0700 Subject: [PATCH] Port NavSat (#224) from ROS 1 to ROS 2 (#268) Co-authored-by: Tyler Howell <76003804+TyHowellWork@users.noreply.github.com> Signed-off-by: Michael Carroll --- ros_ign_bridge/README.md | 1 + .../ros_ign_bridge/convert/sensor_msgs.hpp | 14 ++++ ros_ign_bridge/ros_ign_bridge/mappings.py | 5 +- ros_ign_bridge/src/convert/sensor_msgs.cpp | 35 ++++++++++ ros_ign_bridge/test/utils/ign_test_msg.cpp | 29 ++++++++ ros_ign_bridge/test/utils/ign_test_msg.hpp | 9 +++ ros_ign_bridge/test/utils/ros_test_msg.cpp | 31 +++++++++ ros_ign_bridge/test/utils/ros_test_msg.hpp | 9 +++ ros_ign_gazebo_demos/README.md | 8 +++ ros_ign_gazebo_demos/images/navsat_demo.png | Bin 0 -> 192735 bytes ros_ign_gazebo_demos/launch/navsat.launch.py | 63 ++++++++++++++++++ 11 files changed, 202 insertions(+), 2 deletions(-) create mode 100644 ros_ign_gazebo_demos/images/navsat_demo.png create mode 100644 ros_ign_gazebo_demos/launch/navsat.launch.py diff --git a/ros_ign_bridge/README.md b/ros_ign_bridge/README.md index 16d633d2..80beae71 100644 --- a/ros_ign_bridge/README.md +++ b/ros_ign_bridge/README.md @@ -50,6 +50,7 @@ service calls. Its support is limited to only the following message types: | sensor_msgs/msg/JointState | ignition::msgs::Model | | sensor_msgs/msg/LaserScan | ignition::msgs::LaserScan | | sensor_msgs/msg/MagneticField | ignition::msgs::Magnetometer | +| sensor_msgs/msg/NavSatFixed | ignition::msgs::NavSat | | sensor_msgs/msg/PointCloud2 | ignition::msgs::PointCloudPacked | | tf2_msgs/msg/TFMessage | ignition::msgs::Pose_V | | trajectory_msgs/msg/JointTrajectory | ignition::msgs::JointTrajectory | diff --git a/ros_ign_bridge/include/ros_ign_bridge/convert/sensor_msgs.hpp b/ros_ign_bridge/include/ros_ign_bridge/convert/sensor_msgs.hpp index 7eab5e2e..683c6bee 100644 --- a/ros_ign_bridge/include/ros_ign_bridge/convert/sensor_msgs.hpp +++ b/ros_ign_bridge/include/ros_ign_bridge/convert/sensor_msgs.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include // Ignition messages @@ -34,6 +35,7 @@ #include #include #include +#include #include #include @@ -126,6 +128,18 @@ convert_ign_to_ros( const ignition::msgs::Magnetometer & ign_msg, sensor_msgs::msg::MagneticField & ros_msg); +template<> +void +convert_ros_to_ign( + const sensor_msgs::msg::NavSatFix & ros_msg, + ignition::msgs::NavSat & ign_msg); + +template<> +void +convert_ign_to_ros( + const ignition::msgs::NavSat & ign_msg, + sensor_msgs::msg::NavSatFix & ros_msg); + template<> void convert_ros_to_ign( diff --git a/ros_ign_bridge/ros_ign_bridge/mappings.py b/ros_ign_bridge/ros_ign_bridge/mappings.py index 28b532de..fa0953f6 100644 --- a/ros_ign_bridge/ros_ign_bridge/mappings.py +++ b/ros_ign_bridge/ros_ign_bridge/mappings.py @@ -58,15 +58,16 @@ Mapping('Clock', 'Clock'), ], 'sensor_msgs': [ + Mapping('BatteryState', 'BatteryState'), + Mapping('CameraInfo', 'CameraInfo'), Mapping('FluidPressure', 'FluidPressure'), Mapping('Image', 'Image'), - Mapping('CameraInfo', 'CameraInfo'), Mapping('Imu', 'IMU'), Mapping('JointState', 'Model'), Mapping('LaserScan', 'LaserScan'), Mapping('MagneticField', 'Magnetometer'), + Mapping('NavSatFix', 'NavSat'), Mapping('PointCloud2', 'PointCloudPacked'), - Mapping('BatteryState', 'BatteryState'), ], 'std_msgs': [ Mapping('Bool', 'Boolean'), diff --git a/ros_ign_bridge/src/convert/sensor_msgs.cpp b/ros_ign_bridge/src/convert/sensor_msgs.cpp index 3da2265d..23f4fb6a 100644 --- a/ros_ign_bridge/src/convert/sensor_msgs.cpp +++ b/ros_ign_bridge/src/convert/sensor_msgs.cpp @@ -416,6 +416,41 @@ convert_ign_to_ros( // magnetic_field_covariance is not supported in Ignition::Msgs::Magnetometer. } +template<> +void +convert_ros_to_ign( + const sensor_msgs::msg::NavSatFix & ros_msg, + ignition::msgs::NavSat & ign_msg) +{ + convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + ign_msg.set_latitude_deg(ros_msg.latitude); + ign_msg.set_longitude_deg(ros_msg.longitude); + ign_msg.set_altitude(ros_msg.altitude); + ign_msg.set_frame_id(ros_msg.header.frame_id); + + // Not supported in sensor_msgs::NavSatFix. + ign_msg.set_velocity_east(0.0); + ign_msg.set_velocity_north(0.0); + ign_msg.set_velocity_up(0.0); +} + +template<> +void +convert_ign_to_ros( + const ignition::msgs::NavSat & ign_msg, + sensor_msgs::msg::NavSatFix & ros_msg) +{ + convert_ign_to_ros(ign_msg.header(), ros_msg.header); + ros_msg.header.frame_id = frame_id_ign_to_ros(ign_msg.frame_id()); + ros_msg.latitude = ign_msg.latitude_deg(); + ros_msg.longitude = ign_msg.longitude_deg(); + ros_msg.altitude = ign_msg.altitude(); + + // position_covariance is not supported in Ignition::Msgs::NavSat. + ros_msg.position_covariance_type = sensor_msgs::msg::NavSatFix::COVARIANCE_TYPE_UNKNOWN; + ros_msg.status.status = sensor_msgs::msg::NavSatStatus::STATUS_FIX; +} + template<> void convert_ros_to_ign( diff --git a/ros_ign_bridge/test/utils/ign_test_msg.cpp b/ros_ign_bridge/test/utils/ign_test_msg.cpp index 02b7bbd5..511fe1c2 100644 --- a/ros_ign_bridge/test/utils/ign_test_msg.cpp +++ b/ros_ign_bridge/test/utils/ign_test_msg.cpp @@ -831,6 +831,35 @@ void compareTestMsg(const std::shared_ptr & _msg) compareTestMsg(std::make_shared(_msg->field_tesla())); } +void createTestMsg(ignition::msgs::NavSat & _msg) +{ + ignition::msgs::Header header_msg; + createTestMsg(header_msg); + + _msg.mutable_header()->CopyFrom(header_msg); + _msg.set_frame_id("frame_id_value"); + _msg.set_latitude_deg(0.00); + _msg.set_longitude_deg(0.00); + _msg.set_altitude(0.00); + _msg.set_velocity_east(0.00); + _msg.set_velocity_north(0.00); + _msg.set_velocity_up(0.00); +} + +void compareTestMsg(const std::shared_ptr & _msg) +{ + ignition::msgs::NavSat expected_msg; + createTestMsg(expected_msg); + + compareTestMsg(std::make_shared(_msg->header())); + EXPECT_FLOAT_EQ(expected_msg.latitude_deg(), _msg->latitude_deg()); + EXPECT_FLOAT_EQ(expected_msg.longitude_deg(), _msg->longitude_deg()); + EXPECT_FLOAT_EQ(expected_msg.altitude(), _msg->altitude()); + EXPECT_FLOAT_EQ(expected_msg.velocity_east(), _msg->velocity_east()); + EXPECT_FLOAT_EQ(expected_msg.velocity_north(), _msg->velocity_north()); + EXPECT_FLOAT_EQ(expected_msg.velocity_up(), _msg->velocity_up()); +} + void createTestMsg(ignition::msgs::Actuators & _msg) { ignition::msgs::Header header_msg; diff --git a/ros_ign_bridge/test/utils/ign_test_msg.hpp b/ros_ign_bridge/test/utils/ign_test_msg.hpp index e5ddaf12..b190404a 100644 --- a/ros_ign_bridge/test/utils/ign_test_msg.hpp +++ b/ros_ign_bridge/test/utils/ign_test_msg.hpp @@ -46,6 +46,7 @@ #include #include #include +#include #include #include #include @@ -325,6 +326,14 @@ void createTestMsg(ignition::msgs::Magnetometer & _msg); /// \param[in] _msg The message to compare. void compareTestMsg(const std::shared_ptr & _msg); +/// \brief Create a message used for testing. +/// \param[out] _msg The message populated. +void createTestMsg(ignition::msgs::NavSat & _msg); + +/// \brief Compare a message with the populated for testing. +/// \param[in] _msg The message to compare. +void compareTestMsg(const std::shared_ptr & _msg); + /// \brief Create a message used for testing. /// \param[out] _msg The message populated. void createTestMsg(ignition::msgs::Actuators & _msg); diff --git a/ros_ign_bridge/test/utils/ros_test_msg.cpp b/ros_ign_bridge/test/utils/ros_test_msg.cpp index 8965a533..05fbb236 100644 --- a/ros_ign_bridge/test/utils/ros_test_msg.cpp +++ b/ros_ign_bridge/test/utils/ros_test_msg.cpp @@ -919,6 +919,37 @@ void compareTestMsg(const std::shared_ptr & _ms compareTestMsg(std::make_shared(_msg->magnetic_field)); } +void createTestMsg(sensor_msgs::msg::NavSatFix & _msg) +{ + std_msgs::msg::Header header_msg; + createTestMsg(header_msg); + + _msg.header = header_msg; + _msg.status.status = sensor_msgs::msg::NavSatStatus::STATUS_FIX; + _msg.latitude = 0.00; + _msg.longitude = 0.00; + _msg.altitude = 0.00; + _msg.position_covariance = {1, 2, 3, 4, 5, 6, 7, 8, 9}; + _msg.position_covariance_type = sensor_msgs::msg::NavSatFix::COVARIANCE_TYPE_UNKNOWN; +} + +void compareTestMsg(const std::shared_ptr & _msg) +{ + sensor_msgs::msg::NavSatFix expected_msg; + createTestMsg(expected_msg); + + compareTestMsg(_msg->header); + EXPECT_EQ(expected_msg.status, _msg->status); + EXPECT_FLOAT_EQ(expected_msg.latitude, _msg->latitude); + EXPECT_FLOAT_EQ(expected_msg.longitude, _msg->longitude); + EXPECT_FLOAT_EQ(expected_msg.altitude, _msg->altitude); + EXPECT_EQ(expected_msg.position_covariance_type, _msg->position_covariance_type); + + for (auto i = 0u; i < 9; ++i) { + EXPECT_FLOAT_EQ(0, _msg->position_covariance[i]); + } +} + void createTestMsg(sensor_msgs::msg::PointCloud2 & _msg) { createTestMsg(_msg.header); diff --git a/ros_ign_bridge/test/utils/ros_test_msg.hpp b/ros_ign_bridge/test/utils/ros_test_msg.hpp index 9569c9fc..0396a566 100644 --- a/ros_ign_bridge/test/utils/ros_test_msg.hpp +++ b/ros_ign_bridge/test/utils/ros_test_msg.hpp @@ -58,6 +58,7 @@ #include #include #include +#include #include #include #include @@ -423,6 +424,14 @@ void createTestMsg(sensor_msgs::msg::MagneticField & _msg); /// \param[in] _msg The message to compare. void compareTestMsg(const std::shared_ptr & _msg); +/// \brief Create a message used for testing. +/// \param[out] _msg The message populated. +void createTestMsg(sensor_msgs::msg::NavSatFix & _msg); + +/// \brief Compare a message with the populated for testing. +/// \param[in] _msg The message to compare. +void compareTestMsg(const std::shared_ptr & _msg); + /// \brief Create a message used for testing. /// \param[out] _msg The message populated. void createTestMsg(sensor_msgs::msg::PointCloud2 & _msg); diff --git a/ros_ign_gazebo_demos/README.md b/ros_ign_gazebo_demos/README.md index 238937a2..ab7c2de3 100644 --- a/ros_ign_gazebo_demos/README.md +++ b/ros_ign_gazebo_demos/README.md @@ -122,6 +122,14 @@ Publishes magnetic field readings. ![](images/magnetometer_demo.png) +## GNSS + +Publishes satellite navigation readings, only available in Fortress on. + + ros2 launch ros_ign_gazebo_demos navsat.launch.py + +![](images/navsat_demo.png) + ## RGBD camera RGBD camera data can be obtained as: diff --git a/ros_ign_gazebo_demos/images/navsat_demo.png b/ros_ign_gazebo_demos/images/navsat_demo.png new file mode 100644 index 0000000000000000000000000000000000000000..1d6c342853fbafe3591b82f30fdffe29e52ab74e GIT binary patch literal 192735 zcmcG#WmKF?ur`VX2*HE91%kU8`FWdFrVs6{UAr7-Sd-2nbjo-pi;VAfSK|5Re4WQGx&X1a;a0 zzfjzyKB%Ju!ynx|68KE&F01YS$;r~)%f!_J!OGFe!Ghh*%+Z$6)%4VuYjl1`H_P%uU+*c_qIR&y%I)l4cxuB{hw{&sK2pqRgoBIQQn83 zP<+If;tUDydPa^s4w_l^s=F1WHiVE49?{ z=8{&{iXK1scbK(ajtcrj{x@zu+hhjbKqc{+NFsGJwgmwO021dvJF*odPe|W;ocG>pd36lxZGuE|+yme9K7G4zQXe4_-`WV zR_bp0I-0>{iy9vyG^=@dc}su%V8A80-jVrlvgwF&g!-c_xnC@F%~rK(aKG19*pDO- z|L+s%cdttF^YghqbbE(~M)JS^RBH=Z%Jh4aeDMO zybdR4=3s{HB+_Sz`-Sf{xutg)o0Q4F{Cfq-2M>JBULJ zH;#@R$IWo1?zXo3od`*i3zBKR!NI}wZ_0d3OH2}%4Qz(L_+SC=u&K9Va-Wt7v>1SS zz)doU_UD~`^I_%OufX~E_z-@29aA;8G$U|fhFy{is0r8+$;!&Qdw8A>vHA(S-f)5R zeVNPWD=2@CePU8R9hp{60)hJb6hWU14VARCh|zG`hsx2e`t2d+J$;I7+KrLmF{OI3 zCkjPHMFevTs~Q)$B?~KSHD%^>iPGsh*gzmokn5e9GjXln+C|MA5>fWDKnWXu#WdJBkWdo0InevEjb?)+IsW(MNU4!TJOW0hY| z+_zB{v+E6oSpKm&rBQ9-Vzz$4NzxjwqL{xOK=I&M5_Sh@nh)JX2ob81? z{FSx$sVNbs&d_3w6{5A1)Anvj&hK-vzn68;rHI1Z~jIIySTvD!Q}>u)@a z7rg_e3kFH-3)+9*^2Zt%zr&PIWwW@ACVaT&G;+bSs2LIp*dr)W&PMv)z=q`S?e-U+hwlr}d7u~uo*OG#l|Y6a_FJH(U`R-V$%j}^Y{AV)Gskah!c2wYa4?v z`S|&{{jTf<9G4Wlw1|gOtBm(kw{5Ir6_AXy)dzrGkAe#kfC#1+Cf?iGy>M`-tgWk8 zHB=oe+UKB`l+1n8xjxY)odNy$SJ<_Mq2*&^@sFN=ykV<`wqv>5OgO7h$&y)Q$@T<@ zV~5*gy z+pq=fdWY%B$+z#`S<~$k{yVQkQqz$x4fWRqbOdTb|GSizc7QVmY~KG21;S@q|Gi*c z9s>;Q{6FJ22=h2q*03z*KLO!ImBa%&`ak3J)&JLB1pnvJoXm~*|J`7u=KQ}CXfIs* zt6={O{|{X$|4rp4DfIvT3*A0Y9tm0#9pb2)RE1KDv}{Ag!x z-^=lAOKSAu1K0M{H0nfN!WadZw2#r1OKknT3#ou3*>=%Q+bhCOX2j{Lhyf!nuQfmEd zc7};=9=a>l=(QeBpsQmnjEl`wt@JXKbnPk>9{0lRvK>O)z2HYZhtnQ2i9b)Od5fCW@`&VhdoXZu4?~T0fcE*`SdnCZ{Q0jq zep3_Z%aRg$6SD^&1*G{Y#T`}mf?yi6X7}Ut+E(PWR@g^d*K4a68d;$@csGyJiJJ$X zNILEi<^0hMcI}*?E!scB?<;ft(R66N;FFtI zuC99GT`uu5&52pu>V8E64J4mS%^0}$%k8$l@jCE=M!WR};d`GEsD$3VJMJGAj=t>` z{b}eB!*;iBMiO^z(($k&r1gjs!X!t!{I6XYh&`L-T@4lnOQ>Z#D;2p+YdkAJy8UV) z^@DPKTi@t}_MpT6-AI-y$Ng0RN}yluF{B+$TSrBOh?E1}d5^2r6U$J8gYPq{Q_YEQ zmgF6Y;jvS7`=drIHUhHKW#);i9XIt8^l^eE|C!nFCzAP&XI?hKTTSPQnc_IMfnm3% ziX*=S`s(kvogRsfia;=N9}Idc!qsS3q5FUlX$S6MPcyMQnl182((9?qL<@e?zp=>Q z5sr&hng5hiaSNVtA+%_C+wda&HnCue+|Nq9Z&;5GQFTsjIZmG2G>D2c#u<94vs^y6 zX3@855;}>lLyDPHhjA@!)XBb-a9PyRUy;D5o~|NJ+^XNINBujn1dZfExy)h<)}%us zd;7-7*#d#xiY8DOe57mrLV9p{Kw@*GYnY!4FeSeQQ@$u&vg=_H8UKy1|BfWJ<}zdT zah=$34((=ws)6pESQ`(KQ}nqGN&MUE48KzWwm2VS#MMe@w~r!rALmnO=dn@u&JGf! zSMQEA3&)7xTW`*O`8tr$>I3VRpk%a9E&Y`ey7oi>lG$(p35<46oLm$y1yL#VnK*fm z3oSkF^9F_e?s;!V9Jwkt6P)6M%=W-il4ssdcVuIm!X!9tXm(Zx%YRz(+VOtHz$WO^ z&_qZQx8Is*Y?P2@8d;>m3C-Ue-o8iE(4v$RYxNn6(4tckHbxld6X1Nn<_sMzk#Tvzm)94eWXziC&FAexb`{7 zOf?pJb8LtO$(vbn7cBzJR+meNi@YBqbUx@mKC40q|DV|qoF2^=_vb$4tTknLNDSCSa5pfn^N4s)+ z-lLrB6SLi-kD)=a(K;e7N1ngV!Ls0fvbZ*_^^n@9jm;`|sR|-r75iR~-AY3+7AC(M z@7Lb~8!#iG#iY@qI6<>R`_S3k zzQ=Q~H4_{%mq?h2*tH3gq(AuhPO5eONqmgD4Uuy`8WW8V(|L(I{*mll^x9NF=xa6N z_UbV_=K*6b@v_mWiHfraMgNBn=016Dx7Z?S4eblfAoRPV>-7}Nt67tt>Zjj-#)!G> zzUlsFdQRGX`^dTaXWx}ES#{e#)9R^q&HI7LDfpsUk1K5ip=D3#CmgLux+O=Z(dQU@FXgz^oxA4 z6j46<`6f8w-A-%$btFHzT$S|~dQ2Nd%nNTj5sFV*8CZxkIJ|6V8j%#CM} zKn7E}-^$B(>Abop_s4%^;2{NLZhHF(BD$?-sx`hto z<8=&-&u1#&eJ~2dM7r1h^exv;o?nuZTyi$4;vma@fcd=#DPTUsFQl zq{djA+wXWv4h{~u#U+4b{S6mM)JOVu!YV`{nW^tFVvzegj`Xv2}Vk3 z{dC!O37ZiQC(>Be_nHaRH=Ah+GL#{25Rftq0oy0X$;7EioLP^^T~t5mspi5& zEAMY0H-2Wgz(L^vxTlT)N}|&JLr%QfY=1M))-irSkFvnRk&0 zA6cb(xI!Sh+P!)NwZdrigk4i)WNeNJ3EY?3o&>dk%zQ@(J07kukclww@jRkOJC)zm z?^k5(s7%&tR(CRS%9@#UW~Nfrm#6yjAhWF!>@s(ZCN)Cm+af=C*xWOE${1LDmz2;(lBdh{<-T)ATP6r^tohlJ6ONY**1X)aGfpq;*qwblNFB4Jmd_jUGge#zl5Gr z@Jb#x7=?n}pEuo8I5RJ2kok@R;AY21md1?O36{WzwT=_pu`FQ#SxM)$QZpF(Tvky= zH?ykrn&6`c^R%3&=T#xNqrBWsAwj-GFmG4A{C#V>28VaB%O|eA+~n=ui4mWSXu2l57{d#5eNv0up8SN8bE!;jAbmWXv=|D z%fdM~D`v?mm%mlk`09##PUi*IKzwzP;AdBn-RHKE1M95AQzYCA#Z~1z-{q|ka{&ez0B^9B@xllIu-g&rkxHU#=&JnAJ5LuQI`WB z{jm@P05azuJ%SyOQuS1wTvo7{K`|9FilyR$LoLK9BiMVqp)r4grvccvKj zq7*$G0)>b$>VZ?%XSuM(;z@T^Bo9hTOzdiM+XgVWVGa#hR-dh>d`lVa{#9WDWdLAbx7k^(8nZi3 zV4IUQozgISzBkrl3Z_LYlINFJOU%ByO@bnaR;R_^F+B1tj#s4_4RuJ*fQHd~%i ze3DMz`_44mm6RJq1Vn?SeCB_T8rUyyx}dHuh1{_*M4q$lTX8WX85x;S(4$ygUERgi zm6G<`$-|6d;j`{!^$ifw+a=f^bOtZO{< zkJUS5WRN|ti}-`w(49}m!ou?BniCiOmkFHF*UxXd_`J+q^I16Q_m+Z`_;BB|^B1qn zv%>5mY;1qXd-(96JX4~>oAyCBp3%OVJU$l)k&JJmj({ol2_)x%D@&p60Mf;RNvhwA zgI7^iwY}CAR-sc99vzJVyhpp*^cetC@d*g1efrdM3h!q!7cwXdEw89x`zvc2u9KfK zP!u-Z+DM>~fK4SPv{@HtK3g_h(YQm0*+WBsQ62OoF_t6D`&wPU!vtC7t(TYJ=;&yc zuv>Ld26F192c;nk!TWD!=(_T@B2X(#cS(8cpdsefRArtV&c7}Ni7NaFIVHUr$~&n36g&NZ!etPFC|BegdI2kx?ksXI}CyfMYb_dCQNxl1iG7>TQ*F>wxdcK)J_5r@8_ zd@>DxOE(o2vGMUrOArWS`Lc@}w{@BLJ4ZvRqLf*Z@Q`gE_d5RR#l^QSvK}Az%5r!! zJwS#$YxU9*2?_%n2UQ0U$*txo{)!Lt%@&sFvD-ExS$xG1t~V!6{~Dw@_v59HmygOb z&^p<3B!3(1G;xmHCwb;N}k>m~*zPgP`r)ShJWY zNcw(<9st7bx-;?i>R?s;d5RKd^1yj9JwZP3F#+Jn_N&fN}kr zX_i)%ZkG#_Ybe1aiCQ!z-*QQ%RVKXLhVdYX&aiW>`D2(qrtVnF{poGm9hbJD<&>+Z z>uSxja|Nm=0qvTp2# z(4&*=MgqyIfeqwaDkI@TZkL)gos>%<&25^h(}l%t0LG%KXBU8b(%{# zF3%S4gO_D^m#cm|Z@0qh-Wr8R8n+t@^H?5*)sB&MWF1tUafp8rC&nOqt@p;qn9&vN zmVFAU^F@M%f}=*Hot>REAaJ$>lqW146MK7SvY_?;Z1@AaXgVhtFgJfib${=V0MvK2 zCk5XD7`j|va8N%qH$6Sdgai;WaNq@h2Hbht+M@Db*pI|B}8iZ?#$6e3N_5>jz+ z@Vw04J+zBP-Dn7;Conao`$l#PRYJQx4m|CLhEjUC;v&9u^u_CKxCyRn=qC-=rL+$w z!wO4Uq`8BE;2UO?kD4NAhJh~dc1&h&n~1;78&W7S^rdH;3#~E zMcVg`DD(anKPK~Io|tv;;pvocM91p(Su~~2Vy32^KixQd+)L;n8mo&fEWruG*`cM! z&+sZO+w4uka1P3Jo9DH&$&TT~T52!RagLd@YUfvdHQb1BkESn7he0U0x3v1cV_%_qThe(1N#5G@7-M2OCpPXq*{nf;I z9zRCZikxkfZ-7V4R!^+`EP52jOv1>Bi?cI`~`473r%iTQ~S9Ug4n~U z>}I1G{K%oD%gg$6m3o33X5lT8ONySCKwJ{^6nJ$A5rpyMFbQ(<1gX9IVW!{DMiI}4 z+^5VSK^R>Iay6PKq_9t)4$`Ys?S?kAMO|93`n1%2**a%J7@$!w)Dc#45(FHbv0UhM zcfRR}F(d3~?prPY9}m|n_vfxtMM{b0iZgCYIC&HAr}9KuhN=)jM&0Z{s^p{_AxeKT z-JT%(u3(thPNBVNWFz_S>_OKFY7K_fPtlMZ2ld3!fun2&vB zL|HFm1A*{?ZR^RxvT3sDu*p6*$al@UB|^{UEb$pfM7-Y&wuh%ZnZ7ELUc88Z>1dcj zn54F;%W=xvU%6Q4#IC8WYSV7_9S@Y6gEMnUtY`wH^V zTgC=Lzx%D=cMw^ZVKhuI%jbR^VSj-Qya67cVYQel145dc+R=_{tb-Fa?R2Y?b`PS% zZOS8Ilp0nxi3Xm|AhhmQ$BuV{WDn<)Ir(vM2B zG&i!h^4Ai@M5TXg=yW_I@d>MEE&1t^MgJED%Qj|n(6$e#*qQlwKm<`g4N~^=N96jH zj{6eot4$4Wr8J{2sndEYqmc8QlHL0#<`tX{r7;N&0*BNZ-iT>_Quk)29Su{+f|$C~qIY@qPCy^dGc`X*M@zgg2lIcH>3 zO`71>a3@$B>Vl$$P+3`du+jqZ*q_6?>$V|51>$LXdit<7zw31&dK}l>ikGm5yKA7N z)@1=QkOP1W+;n(pTU$V<>+S6=3Q`E|@%ZTI;qlTQP}=-LY`8X4`YBoM+*x1n47HOl znfh1ydqYDGgq0O$?|M(Z?zv;>TUYIK%YmxkE0G_P6zSSDUd~)gOH-jHBm{(@DRp9> z64&#Ju=@jd-j)TmBu6=o{wO=zN4)qE}2z$t0;o=g!~ktANV{u{~nj+ zHZR=!6XDT~12h27)@Ne!;7oa2flA-frH3?=DMFi%etK;QBU#>+b{s*$`dR8G!eQ{? zS+X0I*EoNZZ^v+zUkGM0gcS=r*K=|5niM<_KhsjaK0CHxJkGLnHA^2PC)T~6q>Djj zvUglMbmeHiLuF&-Z)#uoPKQpULU#3fnD_N>dQZN!9|_u3!^qp>RB3jU}m1zI5Jx^L&smD#lpnIG75&9s5*qEiFGd*1D7^$q>}ezQ~)sK z3s}e2)dQh(qeotWY89TuL67S8f<4f+skfJsqvQ8RG6)U5cf@B?@Oc<(4_8v)TT$;5 z8o(=>%~ilSad6R5v|Bvci;9ZuA@vTw2S=FB3y(JjlYzY1<#rR4oSZBTl%x|R{_F%> ztlsnqs_E-vem!}dZ#(h;5`alytLq&gKg!GL2?1WgX={?|C_fP=D{D-CJ{-HSytTK2`YrxvN(S@{j~PV-V}z8K1= z)74*OHzeLOQzHC1;Y9VAu*!$I8+rr>f(p1S(e_m~MNGOEoW_>rMOWEgeA14n4PV#BDb;+!&PGXPaUn@@)knB6Kci4T||!9 z9lda7nouoBGv*A;%hH+{smlc-AER`|<~LI5IiT`k;PPdum|O$G^y$4ZcI>C^bbr{; zK$g}GU+c#k!9~8&!sdLMDTj;o7|yed`Buw`uW!fCQCqpl!ryv$@K^b*>@Tzjh;ENz z1rW9lN+6b&m&4Poa!lZTac0;78JU@jz_&nJNY5$u!Em(&)aG{;TV7+m+UjF&VF7RE z*p9eOS4fYSd!3bivEEBKd*9cX#LlF+s#Tvo)CzZ>E9^3gm57UrJ6LVY3=c=Ohiv^m zHT#>CS`4Q$o4* zUZS7{iUv-^T$==M#l5S{r3%vLE&tV?xi6R zBH7WJ7ORO*w~T_w-br)0rIII zm6aB^XN0v4CD(kJ7&$WGf|T3UWKqxvgwT#|h7)D+QfzHY)A_0QkdL4aL}f}(?|P9= zqY*b!E^b-eEmW9y%{zPO(>hPG4=QFORnzwAJ}*a5&Ctf^CY9i5Xm(X2MYJ%=+n3$X z8I{M;$;`=B%&rZ%xrmoJ62!T4A2JqE1ql$iS5WJbO^|=}yV|b%-rpAv$GyNb6xnnU zfJvd&xM4PnQW!?1V+*C(xjImhoSJ|voC8X`=B0?iQ;pWCgZ}gI#QFtk$-u{iM zEyJDqXkDK9jl&3oz_pqQrc}VMc2Np|+?&K+p7$^8yWHNSa&-)!-BjZ2Qv>@{>v_DY z2po}T&z>Q){@E)(SZ+!NJXDR%G~?E2rr?^aATGM|q6J7*S9d6$QWVt#Q*n0C5x|=7 zt`h>!_UYfnD@gIb?El3EurHsZhMAjNPED_f(`@iyhLx2qRzQD-7;}X=3ymDDw79I` zaU}C}iH*alp)Sv%KI`b)x@hB7bqpmjE!*>x_|xb_BLkf|0i?NAdZYI>Xt(~iX0(P|H9t&ZcKuFzNR)}Z99Wsdxy+iI>#VGn=fI0r$W3n}p4iJ8*`0MJ- zEiGUQr{m_YF}^1iz`yzKy5b9}P6bevC*D*`vkY;XsHvAp7bV)NG|WBY<(_dB)jtx4 zokCtQ79%Rl9`9Uw7ri)2cXD;e?wK>x*0(qveTMt-glNY*ZunRWwbAWMzuNpJJwH`- z%u1uc02&tPILmo)>1fh{WQ1AZ7Q)Zy*3Ds55r-ntuh&&6;1iTG%w#7P%a)t~u4x=F z>9lT%=SVou8H{sN%n>`B+>&wwy$eWMQM^l7)c3G&d?glN?_FySnVFw`%W4g>Tva%x#p&iCoEnhGvZ-+iEKKu6td!&04;v>^?i=D=whLxIo0zF*8R214%`&(wmo(Vm`uRkP*PHgosaNV z=+;GRlxtopTVp2%+rzrQ0Aj7TUz`eRvCv@_zSRTJxEI76D0Im+?>4u$&-(=1@q#P$ z8m6Y!d*0^C#Bcw>B7gn*H4O=7QhK^97YV>l%n8`Ck;=pEGX4s142d|j-}}fu1F8cM zffmoh!lGCFE1HyX+c(LhuWHGj`R`YUT_E|$aZ+n9#U>{XGrJ*bGrhBBX zO)oa9yYD?Haq&x-RO4-DWl{Rv-HlYXjY+Y(u((5sl*X`(bGmMN1)y7}bdO^F>_k7|nDUDrC(c;{;!n&UPR@^Fa^u&!1|W!SX^BO78Pt z6{gKsnms5)++V|R>vd`@U4Vq}lZwj3lhhIr(!diWC5$6=fnrxuUg#-O2tt+5sNHLJ zcFGH>V;`yrY)aF4u)!z8d22TP#z=s6j42ct51*Ksk@55t0N9ZacUwMGhlhs;OSe)( zjGzQ9ZFPkj9htX{iAP{15m(Fe%B7TzQNxilV{ynn((7=hQ;RhwY~dWG6bnSPizXIUnOq@bzhWx~!gQoQ9@iusp78dbN0<~< z6Nd45?o~EQZpTX@~}2p_%(}P?Xjd! zOU>)?SlijbZ?|))r{PttXG3|MX#oGZ*e2d~CvCs^V5!b-fOr-FoT>Z{xH(!5c(%rK z6W~Gz3)NOOLnVG-vAu0Ls4F=J!c$-a1RjB?|~rQ`rob zf_^z=Fj`nxyaDn`NO5Il9B`Ukme9`Kdu<(T`U=x`DwNV4N^aaO$T{n%=?GqLtS0f+ z@)cQ9mBYMq1b2L>+t?=$-vqrYfC~XJ@g=974$zxbh$R>w@6RWh#cb7|4 zCCO=wwW0?uY+E&d^7dj@1*bd>oOV>~3LV_9d?^koeS~pN^o8bOx!bw#c|@AU3{^;8 znQ95yuGRF_q-<=M#l=^$#NCMcJ$Co@7=ZemogI0eieH($qOP9Z zix?Y3a$SFst*enmH(W0tcwey`8F}Ww$OwhApPiAQX=6hK5G78otcGdRxmZavbV&U`2nM*M}g@0Z;v1BGTH z9RC)9xa^$?v6Ac|ITOTeka}U~waztDq(oP>hjnc|y)~ny zB89=BjGlDf5@FwqowOh(Ip1aXOt>WF zk{c+(|4b1PEB7TS^f&}+$O@0MgsL@h29oUwepAQkkS~tk6+z*eh2)GJGTw=bcsK3T zzZ8?u1sTF+Wz6vzC|J^VWVx4oHigDMw`r4y!&;O83If9{NI;okmMN5uSGDlpyy(qVgE}51JSLPg;#JbDucIEe;K8*45jhqJ3PfUKzB~PL&BbI zSd@0^7YiMd@WeAgO}gn>>mX&Tvn;KbZ&%D8^R~Bc3gM^ccB5s(K@jB#XPf*6(V6{e zl^(>G5{$5kPTJ<51jYb40flVFC1u2X3?LiKd$<@7_mi$11pias4+3eFL4~3etl(|Y z6YhNJuqg$h!2Db{x?NX=d+icxyU=t}wjx(ZX(N)!fk4EI22-MF38A-K{0hNECjeEq zkJ+SuR)sU?w6b>+cj#P9f4=v;_3RR2iJ+%NA3L=R_fBvv@xoHTAV4Ck4Beycli(N$P~UGq&J$TyQ zVSi>kY)ZzFcXHo6KQE*j%H*r?r1Ext|HY4d19eBE_k;#-p--q^v|J3d{#oibBrc&s zvOT+R-K>chU$MJVkX|RkM!(I^xGyV9&SvfDsd6govkQ`E9;_io$S8OOk z;nt?4AWrEPbTT|nJL^&Cd#B1<&ZI5RKy?|+qXrQCD z%JqKM+H1zgOH@S%y3}a0J`$+M)t!HoQM02H0Z-AAe0W9)x+s{h_+1Qf`2c!2mCp_= zrJtR$xPfY8Ui+rJu88Jv%CLO82JeUN2Tu}f%TiH3|D}NcS!?pHZ6}=3Y#tD9I7vO+ zwh>$oGqk^CeE*xe8|GXle}eT)k!SKk7nCyv+un*GvszDi#6SJS4(HZy(6|qn>||*^ zF1A@0;t;~t{{2}4HErultL={y4163?^?85+#=v|s*U(NFsUN_$6hPR9uXAyCgUgz3 z@|nJEqGX+6ijxUkTG7MV-#I>YOVT?pu@YMD{ z7UWYJNE`HWCFX_xh(iBC;2ITqqqjDYNPpq!1^=`0lI zAVe_HAp-1}j;30khP^i-wRW$k$14qG=pT3-A87tP0nnp&qxHR|oOPD}f2eafP4UtV z@Hckkob8RtnNE-NNFi^6oC&E7dp*suGS=G0RcJLUthY6Og{U7Co(-}|rrycQFz_Rl za=iJ6J9-aT^UUT9GPYql63nXz&B-Uzu=0gY7R`(Lg-+YrbA2p9EzNt+K71MGR(!lu z>VNwbc-Y4Ol7=3-)Xk4rYdY>&t~wTuN*40MqT2fmZ%TvoT%b%C#rPhYScJB(eD9tA znfP#HX!-YDS09%bc4rWsuhX(NawPpW{t$YLbb|2zv_S^NM(6te>Ei2`lj<4&|VJfnnVauzv4m&4Pb+6b$s z(ItWsg6 z*|`=3C87PqGTD=!m>*&Qz3Vg_;u0?z$L;^Q$yS5Mey zk3sTjJlDneDG(sm-0TUq_W}Xm$>O-buR>jHeQ_z@c(2H4-UbV)c zR?vG2oZlE&>XcBz#;#2KE^k%puZsM{& z57)VbuWHXwr_P_62b6*V!83cTTvpLaN(N1(D$D8VK|X^y_kjK_C4l$=;1H&>d$Sbc zuAc$GYI1g#e`|upmXH7X;^Jfi`TCQNMz5XGwXejjU{F7k`i|%ZI7DM;iHqQh?6WYzOlLh}2w2 zrFlm)Rsqu~+D1s9+k|&~Z1SBkt9SaMyHRcWQ4E--b?@WyayKF*I^4P%5{FfX|3$0% zE;%KoXyPN_zVm|wMMXtJqH_0HN;`%?1hrVrzQ#`&M}L@6cz#m1lZ%kk3vQ+2H(sJm zK)wV#RfbU|I|x^B+HR)zB~@!l$UdIBJ^cn+DqpU8oy=<8UO*p4|MvWz0{o)eRh%Pu zDO2wEt$QEG$AX5Frl1?l>}<;W4jli;+ZRM9L&KcO+1b5&{B})ngNBm_>c>ccL4`o| zxEORQ`Sc)9<-7Js+u#Cyz+u#H|M4U8`u=pKqSc!a=FG`?u+Sxqv#jjo

C}*I=Iq z(4$zvt6p~|15|7*nK>p-CP7NI`o3;DtkO>f#&XUonzc(~^ zsrPSyI&Op!s)BmrDsJvid%T(9__ww38uG{wcm@1aiA&*+#?o&JPnF8p+% z*J}`y{JwgFUGaAby+My!hRb!yoB^u+hq{=86B=U`JLqoI@$T! z^M@gy{!rj8sjHFqw~+@3$)RxE#TX(&xts z3t8b}eVhXXXya7sR0Zs>4*-L}oHu%Q7r^CFUuR@KX@U4~0<36|3tS09Ajc6|Y6Hx# zoFT|0gv8P`ZUYgOtQYeoaA{JOS|sgu(_R9=2-54cS+XCuUK(7ud%0a5kV-rbD!WV$ zrHI{)OuKt|)%cE<8TC#5#|2n=wCH#ktpaFIQQJQLm(cc+Ps$S92hA_pok&n~?;#yl z(_6znfFOiiZ_owXPZe9QkNi-@uFhD&f5}uOxxPt0=UeC7LAP4ZpT3fZcl~WD*LT^} zI9PnZ7xg+YzB&+o;6!*yo5J5vUyt-PJ6n9OSxdh*={o2{+8f;O)$yPhPbDlRM6uNZ zePle8cGolTxa9v!sR3Od0b7&g)#`SF#yprYvYi_FUL*>u!g%fXLA5k`0j;Kc`)f!& zx8DBX)20@)@5T%BBdEZUF3+`7(GF}p`RP2U$G()DOHkuJ1*d@0=#;-d+!=oOo(L~} z*B(N3A;OK9M8P6-@ge!)WCg`B2*GUb*L&}0BsHn)v((*z8#%Ppf}+EcZix)=oa^>X zmDecxHzt+R>aC*QyZmfg&c=14O40PPvL+klrWmOoPB z=a<6`+UzG7j#R6)xMH($4S_bvf#1MEHRcjp3k!?dY5iCRFJm)HQ@#@=ccE%Vt~#RW ztFQpX3gf5h3ETm{kVbp?8e2ghtxG*JToVC+@R%!rr~n^G(5uDIo;%7~yh12Z&e`jL zx-ngqy{XwAL0tPC_43We=yCdV3AbYM&`{aqX0wRs9rR7EZ~$uXdeZva{c>>5i_YqT zcTBZo>T~)kDxE!&cbx54qfXpjtA7DxQqT6EW-}hSl3ql?8s+lam4; zn-G|Au#!9!%X+!Be4R`#DSfK1(|?YjXvVPp_D}>vg>bvk2MJ7uss7 zC8kHdKO@`QzmsH-3+&EF$>z6#?BhtSGkQNed4J!(#8;4eg554DvW@!kK0;zneSR4N z8CIr#e4ZDN%aoA2c5`ZGR^|tps{~s7ZNN=eB6Cg)2%YC0L4Wz2Ntv0V#U4mmVm|pn z5*)$d;o+Z$6))Z7WqwzgO6OVA5M-x`dm?#8wzg|KU~Pzr_iL_7FejfrXCF>}Am9LR6Bv^X$ak(_+j1$!l;`2pn4H9m&K%D;2qh zyS$R8?ZVmH_RO~S4RcWkM$vmpX6#=1yxMQ;y}HZdv`7CBQ|}xdXWO+8Cu!55L6ZiJ zZ8o;r*tX4y?KCzgwr!)aZQHgd-`vl0Kfmu?YyOxuYi6$N+~+6s=fs5*HKg+3d0tKT5Wv!@_ zYxlSGrIi(Iri#9d+|S$nm;_lkzE?LlU+h2hS(ztwU1Wjm?SdsrNoKAB-4C&`u@J7W zPuLIg-J@SCR3sgh67-wXiJCt>JsmVgMukz=zlVgtLU_KvA>7^x8;*|Doz&@o@e^Ga zpn|@4X7*99C@U+gn{gm19KmK-I;U3{-fB~9OpJhn!Owe4NyNYmC~7}h^0$`(C*qRD zOlwoZM~c{t4Ax)HIa6{#`FE0VtRKz(-$XaTGEK7uY{u!!a>2!CmUg8XJ@P6|*|Jnzkq!El3}~ zySF!%!QBLhj7)>}xyyB%M_*rmu2??41kfI;QPJH!?FUUTPE&{Z5so>*AJ6CWFzj#e z8k>^hvFcC-uft-t6!Z0PGH>4E`ue^A@Bzs(UKU(nYHl7H9gS?Cf}pz@*4*at4I8^B zU`kFg&8IYTpaCp|t6IiNO@nl|f=MH$N;hM#b3pmT#iZutwl4x)iPWhUx{=obyZxI* zta_btCoN5ejOmlP)~ke%7FhZ{;U&L6Jxq`TY25W?$Q9;{S#WM@%b0ei%L&5JoUp_* z)b}hFXRN}s9*A4)-rZwID|Ndb5Il%sh0M)Zura)^vGkGgry9Lrb_{kyA|uBaP2O8s z{{#oiH|cnls#ItcXS)hQua559V~k}Dw$y#hbb7%+K?N+mp4zBXXk`LAmXd#fQK9B5 zfx!ZmZ<1hp%Ti@SfyMU7b$lwdS4U-si>&V z-ksPFFfdpE({W%<3N~xCXpM?O@mZ5{-8ORFLIo2Oa+rt9!T$chpSuIhZYL~!y3HYe z0l_@a;#37icGhtIgzZuhpHu}pw-R&oJVf9zKHmIjX?9Z{Ws?&9=8rpuX5$eXnj(Bo zUadT7|065Og-+=*(M|5DV7`SNQMU8|tgg?oml zGsFjM$OLyWxSNsE*vcuGn4mVpyo;5nFE(0k*8)_)V*SWM8*7}|e9_{^l?C72>~VGb z{attsf7t&0ccZyevmdQy791oA`U{C{0e_N7=N9Oj6Fpi^p5ej!HzdL1tgjov++d{$ zS1az3i?=aeZJ--*``!8%SYYPKTy8tJ7yjZ57G0SISt^xAOR%Bz+HLyA*3uRh)S}V2 zCbL0^lWms&+yw&`jK^L7(tShT81bc^-R#WL$Ifb&rVfALNw*Wr zhBCr^Ma0)Z;5{ZmYMUk2x(mDXqRs9&wsGsRDQ(8AWZ_MJ!@!vK4VSVog3Px+hvj{j zFcul<1&?0IIIdq!>(U2T)U~3pveqAdRnW+r(+Ph2!*pN%NuZ>pMD{!gMRqiN<*>L| zjPF(V8hSH}0!0h$^Y+JgFKL=xY}J8oLghU?BTn__fe&;X;<&kT4wUiSy>?o9aghva z8><_|#BxFaiqUdPaStH(p;U`fvHYygso@Xqdw848crv=2XT~7Vj~v7X{8a|zxS|Bx z50=D}@Cc)ZIOrzop9_bACCpV9CTiFF>tO~V*@UoQ;eaKbeF@xd3{3-(-zbOI8HyDRU%6DlE;W)K8o}8T`BH_-*n3 zk;^}#;fM%OeSwJa=E$Tz(eZ0U4zErl@10PXDBvDGOVIo|MHMd@^nm)9tN47DgjZ8+`4_Yc!gIpQXZl87GO(b`wu%^ zwR5mS^q9Bxm`%IWz36-6<^PtAXt;RS-CoCzuPMu*MK@2{KM;4ulg!G!NxXzR6Xh+? zRMRHrVB6m>Bd8(8F+H3#=Vb^zN-@`yiZB7~kk)r<`Q zI}wK~wO@ntT%0}woOT@De&k5vbJf!Qi`3sKm|3ym;^wJ)>S#FR zFVH6`Xpg&F1gA=-IO!_MpJ3S8UNyIbXn5(uXP%+GIDJ0^9|mss_2^xo8eNqVrS{(M z*i0kXVl0?tBaztpT39_{@Gt;bnFvCajbo86Rn%rv;7^ZxlouEclF^pQ!cec2_j7m| zr}vOTHeaPE3YVTBdR-r*-fm?4B+g!}*&)lyD=WSA>e)|y&Z%ikyHaw$ z$0ZL7H15gfxHM$ui5H(Qur>s#FS7V2NT8 zUmkwq+V^=LrPDp!D3?9kc0=`h(SODB2Pn|JbM`Vg;yCM9W?5E zY0_DLs*}aA(K#^x15es|PfsV-{r)!fw7!^CBY_VOYwCo%FoWw?b0u5i9){BCLSS~* zLiM{E?RjepM2wpqy9a=C#>$-}-PbAu2~R?aIxinG1uF{V7Zl8L8u+`ZbIUp(72!uD{9WPXTLVU+#B$YM}zFus) zRd0U&{D@jRC5B3vGfPzx8xz&3>QDH_j*i~$9vh%Sr~~}3N`t*8w4%!qGf3M|x$+K2 zIeB_faySJi)JmKko<&^aL08rwYb4BXqTu5wx3Q63-M2#uzV=X@t0`+XRc~dHPHk2- ziJ{n3;$a?u_5NZ|sp6T@ujzfbRTG~MI)vp%x`WJ+4|Eq6Ug=QyeqVxjhCDBHL*}yvTz76qDwAJ{#M&uRP>-0|~B1H#F-XR=TJA2!kBUf(ow56T$ny z?yr6>!YDbiH!%rdbX{;M2Nl5(EOd--lRVm;*TlKJunQ4f&a6k1(vta1+FSbanmqiY zXgs?D^WpgQP;#Jlx82(duyy*ct}*!WBjeGq$f{%$Dm0cMtHd@*blIiEWp?kIf6JP9 zsiwU!Gy1IRxZ}VeNzHe#c)q;<9(I2EU9zo@Kok}3$D;2|fsT4mO9PpNG?%$LGR$#7 zmgeY)q4*Fr+EJP2S9f-r!7;D2WjPSSa>L*>+0Lelm+5Vxp zq-ww#Dvl)C$(^J99gTP>u4YZ&8 zSq!)w&SIJZhmDL{o_V@ej9odF8E1zNrllnbXV)2YH{l=d#f`OI!@J`Bf2=I!&D}Q% z1c{!inz!E3@!@hr)M;B9es@X=ps+7qnM+H1bb?;to^BRpJ{z#o>sOY1mO}9oEPEpd%x8*{(~)vwF9Sz|2Y9YyVEcM5y9KTMocsB zCweaLdk*KC8Umkw`P_LaQldQv!SWs3c8jlqOyZ=7Z06~~Q6U-?q$BECYud;Hw|RQ_ zIPp)-fPj`bJUE-UI zc9&ax`Iyw(`={7ZV;=W!X@6uWP*Clo)7SwhSdUM_{RHe=_q1514Cv`ufRso)DppNH zJZC&NnFZ$ayot5Ay{!i^wuhmwM*dij9kk)~U%{f2jjr9Dfax=`2)B0Rqfd+CCb;sD zWk6~F*EoXe6ciP%ACZ5P19PSmXk+r_sIRX}hQO0rem#CPn4-)BcaPaB`)kISl||RR z2et;^=Zu%{O>>KV6HBt?+!M)3gSC5)v%Dtjqs1FmV|6;9N1#$v2E14ky~v={z}IIW zf6nt)asQd3p|eUbTvxugQDW($@?L*{b#Z+?rhCP&L%@6C<^s-k{)wqvg~0M3+GnaK zL(qUUW5wRHPZ`b$q>rNZPS#CXh{Uz6SKT(N%5@@v0e=9EIS9P{s{d{);FT@shB{9E}OI*h;J)kAuqA zLiAy&jl$gD3&5WkG_Jd~p@u-Bzv!1S*57%uW3idLs#!SaH=_i9_EvAA-TB;Pv)SF< zpK+7PXFM$o!R2)JcT4aSV)UxZ$w;cx>8RD~zxrBtclEJ3Z8*41palJqO|4X>o~B~G za(xhyqSfqLGvpKzd3+gK(ctexUoZt2F@BM58RG{kR5z$F7Iqyf@&v`L*1LVJSaHtw zgw}1R{&Ho}1)0w0Q26^4qnyC_O_3g$SLZ-fBQ85bz2MH3!5(*jDP>T{cXX!x6+MC- zWKOL{R$KA!dK(TKt_o7?(C<|;^EO5tlpGojbiQtS(pYt5d=XGu^6H(dd!@NMeYNOx zGu}?L(Jt2FJgQklMnKRTUwQK@W3^mFK|_1W*B&j>S?8)ZU$2#FDpBe3EZP0P5ooU3VxRgSiZd*F3P%n z@VI1lzN4(v;Ta6g3x=)KPP^cJwcXmvF<7MIxRdc&b=WPZ2^8{M=|Hu!4vN)kcvj?& z+B=~Owf?~7#0QZxcSY3og<)@i6F|a*$Xajham;3Hh4sW~4**JH<}W38q`b!s12LyX zPnz`Tak@$~FcD1hf2s|{n>@aws+Cs~ld9ME$hpqzL7or&z#t7sFbgC{bMx(doU!A{ zN=B0P%52dGA-Hpn_)5*8bmc7u+pFV|kzLAqU4r(zsB&FgMuzHUi>nbJYNW&hq}PQc zq!1l19M}B8W@OvxYUvSGt$>l{DnTanYh#^fsHW5}-Nz8!p^1!v-)e2N}QGcG>{L`vL9~ z%w6yFv>!Y=kK0Fw%a5rp24<7a0MdO1Gz01_McX62?q~a!bX*sHgH=R|N*zqcgCt{T z1TF{3of8)_at1TwcG=xdG+b;oMrJ7l95nEGwU;f^(aTXiBu5`XZxa%79v*n5AS0Wt zbK%!u0SrWz0iWD2Itd%Tb4SLRSdo=w1BUJ>UnD1HwoP?XX!Hv*?%(&AZ#J83UY>=uNfC8vQpP&RXIderJW18`@nZK?w|(!j z_f?W=O~ZZ8SkV(3=z&7=W}7bzOOdY%N}Iw5iQvRD-c6&b=ow1&F}^N&V=De;!6c!H zZFi6!vb+s99sn)sU>wTUe)-5>UE63dkT%Q6&P>9{=v$&lUSk5*+H-R0AHfodn#uMj zd!gyPE}1y&HW(`#fLCwPyy>fJQ3op3N?eJ8xG(pohSt{FR{TN8cs-5h++f70(S52@ z#1A%>&710KTO5SN zqH6D4hiVpT1ttMObXr>4uoMY0GBSk0?oQZxP)Qp?D!j(=Co!<@MVySoc^FgYtdqwp zwZL&Phoj{?Rfhr+@(UdRHn;25p1e zpaxuSkV~gGxH{z7-f?@+?4r(*nb`tZk&%fC+Q-0XIV7Z`tN86jdCd2F>c64m_Wn04 zENI`30I$%+;x8R_s9rY8X*px!X=7Lbd096VxgJSkj7#ix>n)i{kdIt-Mi>X6m|;Xb@_ zgI{tcq3!VU3o+>4fZ56 zk{*^1oKE#bqC^2Pc(}5!?>86|JTx+b$}R{B4sX}8vwilY)<>c=J zU0ShDhenPuI<@Oet{bz77h|w-c$ZKd=|&bWaG^p2n<+=4tUb-L(;Y(Akl=r@2$49d zMg>NLhP10I$7xq4IPJq~+~&3!2`zvmC+x=%OnHn_M7lxTteaxVgL-YF_&;}w1d zvqa(wIsT8(;YBz;dAf|F5(M=#my=H}idgystKbwch@nN98eK(2B?w3IAAj}?4(k&n z$iN+eM2Wz_Kxl~qCfzSq>hi4`)Eqa2&#{Qwbm-+4monlm)&RgDSO_Wi-MF0^wF&n7 zBR{Ks_{n9{W2)A-{5~D6bYT9hv70Ny89PZFmB!C*XkhI+TN-(-<0oy_A(_KQoG(?; z-)&_LT*2THD~MB}(?o0Wd`8~9xhP*|F-5! z!(NQ1cwp{}=YzJ(l$Qa=1ZwpA(|O~?hYA*prEIxZ|BoUZaAxyKXuywXcMF_1h{loj z24lY;A*4tJsidU^no!#oY({}O9Bx{2ssXra7(q}F4^!ItlX zdzXO(EJKNcnX7((yELZd#Xygo8Ov7^P6D8|QQpeL0a$`jO_8Ni&hRZRaOGR4lYw|52h__@U1DP35YnMChy# zN)ws@vpp}{+cj6Fh-MCE7xd582L@~4bUma}k7dTi^?*s42rPA_)7XTMt@Cy!bvDl0 z!RgzoIXHkLCejSZYl&N-$GE$0$|=gS4rTr)zWwL5ZEUPtiTn8LV&`->SfS*PCe7Y8l83^Vk}Ojmt0^U2u(A8oBjrUTw~)Eo2IkzlH(Y=J{XbnJS7e8$E-AQdP0*Ls zvFbP0L049l$dWGr0C1a`KuB(-rAEZ{3EYKr}IOHv@8nFJ4tK04;fdW?- z|C`nFB<(;6K?k3qrx(p0OMM9gyKH!*W11hhG)tI@E_Kx6Q>D$%;4k;wlKr0_vF-ki zDG`V-iJ);!PBbnRXe;4XtxJij zt@Ssl^Vzv60majh?0@2{QQ6Ox|7wdMWzCMiD)i-wsuG0cN1I)ZGo`1fpyDg-#e`44 zv2hBq|36JV20oPkzksL|_Vo!30h`wXR=@kX-&hMB$a-Jwt7;yVlOG0OpIBg8gDgl1 zXGaG=84mk@Dqh0S;dfzW?8h0%bZPX!$w*-7<7 za=9}NlvZokQ~>DEa~)#MFEj#( zC}aPVWjJQ`)=%{iapPTk&MTq9f{ARU-@DM&j8@TGBf%{qg(IxV5WcqG>PS5C-d%{e z%IQuAsbx9iG^P~9P8D4`6nP@nS{*7Z*?0|z@DH;V`DrKw<2gpqIQ2VYtB7o~=FpRt zE0}Pl^MTxO)lJ`~J@Jo&mCg&@Dk${#;SaIfPD8A9x^FnWA_g1{&ObNLJH^`95=$#y z87*8*->e}>6{^nlj^m`?y!i1XF9+_@m{R!W&tf3$V1U(E(L-RyZS{HMr#3HGru$HJ zuYigyP+ynZ;z9)6xEe_}CTD|5GPI7^e-KB4K^ylU? zEpMo1`09++1$4bmRn7YxW_>kn-ULwK&aX=C&6EX+j)J)^9tHyI5vj)d6d&osBRm8R ztCE%br~Qa!{S_l~2Z}V4i|m<6Z=o)y7X#wgOOd-2j!-_R@`_Oe2cj~y%%oS4Bqfe%G*7gKO_QtOUo$a~( zU;q{%g28$Uo-m46F_qC#m52VF&B0EaA^k4Ao-@Cwz_4Q2BmD^{9;agAXDa5HOE9RLB*b%sX5Qh~=ikJ7ozWoe8)#>4?>hqeaK0;!<;pFY+EqS^2v z%fqLUFm;nH?7LrF`p!bQ!5hML#aqR`GSIRa zU6UQk+8SYIquUiVP`oLw`mtkjPLQH8S7fYC4s7!3@1fDa^_bs|gfo6KN=QWzj~6eL z3IBsIw0)ymHT8CjQ+zUUxOd%D{PG7FBUMID!kc&|HJ*n9Ecnwg=52`LK|E88$B~la zR;LKk9$n=AUc6EL1@Uc%qsapUPvzWTICMSYn#Pm$ApJD~f1O>f@|~u>@=~%dmcXrI z8ymEC!_M#M^o8*KF4*y?8qMjk1i=z}d}8_B?D}#NS9<|PbZ6;Zgq=JCIsaF1(A>24 zep9r2wezXf!v_ed8v{ZfSG_ao_5O6%I)v3tZrygo@lW}M?CdbGgxedpVsG%N6F`E* zz%>vR>rFXjcYB)2;`+g)g70jWr(J{pcA?1I!4NKLqSau%c%gpx>l>)eh{;B)O9niI zdwUT|m_TP|-G!^OaCmHd-bBb_8jOseFa0WWM2aUyNJMn(NGL8Ahm=7|bWAERVoBmh zY6qVC9NZ}4i!UXGEYGdY3!|RWi6d03v5qj%XKG0oqH9R$3*Ow_2rxsPZBT1|lCQ83 z#vOOye=8y@jL8{Z6_dffjztz*EUsp_6arR7+3R;=1XjQ}r`Y`_HNs{~i~k`bCI%00 zsmfEq3>z)}>#G`v+pY=8FNtU(7W(f-@K)M1Tgkw=d}+Ato@H*MW|h25Q+b#I66P0j zU}aETxqXpDMX6G?*OQ=j8n&>S5ZlmLHO*y|7YZCDv^x8T|Lr!q-Mr71_n~qj`%zyQ z>j&fYZK0Z)%hoAPUWt|26}h%<)#Tqxc6;k54exyaCZ%{g*jv&3ogDq8|2Gb+_#=bewG1w{CZJRa`R}@h&o}IuT$0eq8KNfp zfm!u}dH4YPYT zGSB=`WK5$oxkkZLy9tuhi%-vr`FY9-KzcV?_WRDc!4RWo z)8;CRMV-HL5&8GE87@F2E8V90ByhYOou$ODU)X_`2mggKyOOE-FJVG>3r2XBL#|&`m1mucXkB1OAn^-KlP=x#VGW$fr8O0l)CfDKaq|tGU z3Fp#T;L!nhCJq&%KbXw*`Sa%)vz5y}(Q;$Cdk83~mD;UMT8P>S`fP0h2*~*_b@WV+ zZjwBANReKj%;$2xTU)4-nhjwXz&mrlGi@Rl3%OmUvYakOR$8Cz9A3y)8Dk<6oG2oV zWs8G<-fg&yuDf?k)mP{*KL!7H1YMSb*%6x#mC)gV9bN-+Y3oG)s|DhUKM-GF;gikU z=m2wbD-lHgRrxRLMKcheW2DvJwP|Ra+To#@gN7j@=C4*-+SO37n}b2U@GD4`0VfA= zQMkOL>%Z@Ny^b!bJw`d#biFbPTg!0yJ^$PiQJEnkCM>mZ85B+sDt2kee8I9nkE(ni z58^0odAt1ra`Fhwslb)=zLA;|zA$!=hi`^q&D93lI9lj@-@Ng=({U!cYzZ@%4O#g| zO7?FEFP~rJI*d)Z*sH>HZ#mPYM%SazUb$yaUcW6>JH=?OqM4V;l; zOs#2&Ok&TM=y-f9!|%IY?Hh3XI3VW|@B$fXJiVaEwP0>;Nbg*EjKdtcK|%^TzMVlW7w`m!`m|5t_{`~Ftd3VRIYnY+U6v!%I)Y&{ zsjxpF!*0C6)dmQA?lrCP>5}=DoWX?KGyW8rhN$uDAxneJYMk*=?ft3YAAeC@^0Lu= z6U!)Ms1dQHK@-M*GWM^wziT1M_CA%HU*a8zC9|J%tB&Jf7ZVpdz`PMh+wIxdXe0#& ze0?~8SCaV2Gqps*T#27pO9Lx(ZKU@kD*p{6+1K!H@2Z|v1Z>y@*WY=n!RA)|VzYW( zv_6rW-Dpqra;7EjgU#G$l86I%v z^eqGPZuXeeu{NyUrvkG!%f*&x*^kTXMPU*JE%8h;h6*AdPk-a7KV3GS@%FqYVH#2V z&54R%c+avg7Ww6;^(!yw+vVQ zi1U>QlJQallpADIChj_0MfP;R@>kWCJUii*cHRaVQ$6b>8LeEzbIfzY*<|YEqKzGi zVt9|i=wjV-rX_0eQ0e}L%jmb7T7EuwED%YT!Nzn>gvER!d4qOHmu>p1V4XTQSMilY zyj`kOn$7m+hi2*$nwA=TtH;~Z3S$x|&3~;0>-)w<jutX6L2<`_U)L@_;UkEW1XuP3+kSU zGzM{R=R_Go^mF2TaIYM+qk)xaVhBgrGLDzW3Z(#8uJRKr;2 zOK;J1?=iwC@M0L#HBLyC$^MF1hC)-`dWpi5=Wnbbf$V_Y{fQD?#)0Dq1nBE_rqp0WWfBdOSxCW5)WrUx@DPqJxv-p z7&iE&RG|k}vY|i-x-B@;is!m^a_ce1wLXD?5tl8rE9vbo=j6p$3Ba@FPqj@?*;!0M zd^&k=-KpuB27l&BQVbTzS1pix!v=YlP?=t*xoig(ancuiU&7rPv`Hms=X{NvN65no zcilw##{Q2HzpCYvWw7jm7W55Pc$ixzfEagwp|;DEf#Caw z7i>)25bb8Bjnl)`d?@$X%QMSuYLm#tVwP-@3q%XueE3s+k$5B#n>0bQoZjwPScSa5 z=s=(_!VeI0)U1!OjKg=7^n~x8a{wmM(uw`1;|4}fYKB zwoiun{RNBnNp*A$8&>`y>FuN&riwPKVGJ;CZ})P#a2IFnY$Yt~wIxT=`)|b*Da%b5 zC7OMLJ)(F{6Rh|Qs#QEcTCBY%-RiG0CJO;P3GU+YWVG7gaS8 zz1*>b%B2dQIm#5R#sx-0RyV}DN4K04fvZeJO5;XHC$dcG0V|W>`!7?-ke#Uu=6r~S z@x$tew$P{H+2Sk=siMnYHyep$Lf-2`*G7NqNP4+AVo{6o4rnT_cset#cGH${xZ><| zkm^&O@iMWv_BLz^1CU#3;|#tJkA-&+S7g}H0K2=RHw=6-WI5-0(c{87lrj+U=gV@$ z>&Z^Lttaq60S?nuTl?ys&1#q}X;fYZC^OHRNJu3y9{BakduIETi395D)ME)T@$rgV zU9q&4v^afJ^B7W3`@b|!cco44Q@n_Svff8>1f<8NpYJX}Y`NYAPJu0K-m2T$j>(!K5`KM9w__kS3rVf& z*q4;&Q9N6M?*qMKG~K$!}nTXY_?6Yekx(#CFO+2 ziWB~dp}RC%+@7kjyx3_du!tOr^~CHmVeN0-oj42HpH+RminM~__Vx})6&7*bQ^IZw z{G>u~buqInwWcRp0h)D-TrPLE>wynlr6IrFD0wO8=?KcSVIoX41hD3vE=?ZWn((on zpVcHSqwo}C`W-;1%waEOabCIquv*Hl6W3*h z@taB;<&8T=y|E>ZPzyMuUAD2Co_L&_Hx^P%1c3$|%+>+un(L(M$ zG`DF$2}4&(h{fIb|KzG4FywVA>Fe8Hu&gWD3dqC#n+o4)lZ+AvbSfYsVhW=5y~1nf zH4+6`oA!T8EQTa-!G6FJ>fL#XwTn<6cdz9_1$S*O`@C>3>wxTyEzEn0=oBs&zjI*8 zJ`J@xglNN@%#>Qo*?h^8{5mjc9@~`Rld@Wh$c%}Uy$&3gHi3f@``LAC0z`Skc;ffg zohD%LN*`H^vNu`I&o>DGc_(sGkrs|t)0rA3SSR+5qklT)Ifd+C2MzmUJRq}Qd=sGS z<;7BJX3Odsv!QW&KcXTo2@S8nJ4n?eH9eYAwT`Qe6B}VG^0$TypMK}R7c$mruvzu< z`}E3eGIu&@mF0hRx8M03QVzM@b=cqBxVr-;E-n>2>d`)1HV8KLim` zQcfAAl>o*B%BHKWj#bHlMFj=BdnXg)mcZ+4w~;0)A1j7|TP1hn&C58RL;ovXR_~tA zq;Q=e_v70Oc)4c6Hjt@&Z$K7@q9pa3MQ%q!__*nez`>14LP~J%2UJ>w(KJG5xhqgz~l;CNQFyg4haewqN&9?a*^&088cPG5pq=HzLI84 z-_qp7=eHZYQSrb^cavwsXTC%*6>$3{mWy}(5UTC#HH>(RRDNYLdoxF-PCP*JB(J1P z3}?qzu_d7k)nqrAYIqRNbPq1eN%2MCW{|zvufYmx7#Rj8n4U@tQ*ibf+da;??OgSe zom2bhO3@0#+@24`$mh#QlmCJt)jk-r&Ld1-Lz=u<5I`DkszNC_4(ebE)l}_`2!b!Q zy}#}YJI!yoH(igNG`Atz#|!&y;)!a4o|xS+m|3-8ORg*=Ux0jhSEbWjnJlfDq$8~- zzagGLH8#ZA_|>7GZeiSw#-%WyoRcc!Y~CTo>(T4s=#%O|InUK&J z2s$@9{fpX*`N*C)i}g&iR3jPr&ki}ojpS?7`zBKIpS*RUZ_yqP7naRQ6;^mx$fYB} zw+DH%$C(-gF{Hh(%I4%PS`)c}S-U3(8h4Fut`R9IDao3NyAS8w&?^bvn+!d-EccPe zfh!FbtA3mghrA!4)FYPA{eqJUtT?bwmcK6?VVWi;Lz%>3y2$?Iv8!a%Eq%ZZJ(zjlr>_$QYj- zp_y@Hn<%G|z}g0uLzZ0t(n3yE7m&gqXc)1|$0xg= zb5Q(>8=gLqqtG$fPrJM|eO^r7SjVgWTV?VM1IS)?VoQrH0CbOv#F5FXPy&wZ``(;m zO_$&ndB24E#5rY4ZXG?AaT>1sMme1e97ry9OAl{6^5RtH6XlTGZ!TIjp9tMHD%boC zEM;8_d9g-syD%muibbzYOY9QaQpn?~43d=G0Zq)~s?_VN0f_;JW^pB!ma;822!L~h zeEX}8i@OxIfa!G|!+tNgvC`eqW;dYN*^Mq&$^|m${PpELN20mmgI< z%d?1I1st5H-dCM-G^>!GNQU7z2?4Zz=|22D@n{wi35)4q;R-^tRCKnO?3Q>E=m*{Q7ba(SOVmj>^=kj&{@^j zR$PVgKa7WzO@dD43m{IDvg}SKq`^Z{ncNvVLKGgB*ps|Nfr!1u0`L?~;QVDsX^sm| zLz>#f=Q%+b#vax}>$|A$UdPzUM#glR&4EsrxTtH_DFhow=kN-dm#xf5Tj%b~G(__J z-n_SR%j+z$b6}aE#NJfxCFkx+2Bh=|B(@M+RQ7xREsJKoUrVI%Z_xuA5_(>j7FOZlG1Kf3jXi0R~G=vddBjq-Eb7 zf#8*?RjJ~w!9^g3ox5^SQXgsIAuD7A9&gxOzUxjdiCV*sXp+}E9gS**+sP~4I~UVH zBwm0vXIt(n+7g>v9fGxMyBGhZxDR1rl&ZU6^x=Ih$#RP&`}H;4^TB3^M^->E60^nL zP?2**2>2SaN>gCl5F7W#h!!80-t!iXnef!xGb#ga$;J=I)GCULi7`rvr(hd-_olG_ z{Gq9ivB=&r*@uiISEGwLa!7MxBOO0{Ib9Y@k^;*4Jo#G3bS*Ik&)c8(df@W^@dCgonz42wcMiPP6i>GCdr7_C zNI2G*F1H#myPP6yC&Eh@F>x}bd{&bKEFdk&n*S+#L2Bdk38={l6_XR(* zdI0m>AlcM!5RpE<2XO&5Q`=~M$jyH@h4H}cNM$@#(d=A*AdXslqpzmpnRkI>`M}IlOI%pkcwU# z{GL4oI;)A5!Fk_HbF!s)vk!rEUT6d$HVu$3M@itF&G2pS{``Y}7rWIUM{?_66XxmG ziqs+n_d}n6v9*nlYr8oP-62pWB|lTt1>R$qI+rSRsmlI+?> ztVtM_qrUkv-tuVLf5C8c3=rNqPV{8dN7yy-94ifoRpVI3uCxwRi1pxk9u4LFg2mL^ zEkTO^;``v2$-%i~2)LAq6ikzkRO=q8Nwl8~MaZ2XI1o{=k)4^aGU{D6LXGn3p=t0( zSOm;pNH$kOGv+;{@n6}U??#mF1cgfqyIa*8uH3lQQ^9=e_q+G`RvEPgG^YdS2W{Tj zKH3BCs9${_CM<$rJhqJh(H$9I=Yy;SSsgjcC{!nKP7VaSgu{2-R#yEAhFV6GR&jwur*W@cvX>~4)f z?cf-pEjnThVNFZ>*<=}&ht~nXv0SK4@dfE<@JOBnvf1U5?{ebB_dA7bY(}E+e5vws zjWx5gb0F#`=dcb96qz+lo`w>p!z%lKzCwLJ_hSU9--3YX2@zECi{ z9p1ftCNlbPvUjER_vSgQP-t>%qsQZMG#H~3-ubr1SS4D;r*wDEsx|waTw4Dl3r0*r zs%L#Y18a6uZ)vI7uV7B+Cx+~&Q^~yPJ&y^|Xgn~` z5a;%AoYksI#n$U!!YxaO*8{@#ZpqGMGG(ygbkWY<(P*d7PU;8yLkU3_Ay4J*VAO1( z7lmV7)cz>&_VKz4k$@?`{iy!W?*RAvADs4|<4B2s!yMp;D>{CZ0ADDP;zV<|~;3xaQ5twP&KDmV&ka>1Ynj9-lYu z*RzH#sk}j$mk+ZRIWkb`Pq0sCFE%>kD;1SeFyH%L91qt;Ae@weiLO09ZDbUi7k^_7 zBLK`0+xw_-*|3vQJ|^(Ck<8f8gU`sx%Z7!eAM&rJ#Gr+x6h?Wa?lI_xKMAXJva>Fq z>C0*jGw@UXhW`0;0o}~1oavWB;~Bv7yIs5#Q%X)V<<5bhC;2e%WBOydhfUmT$K`8g z2MiUmniwEPwpYqS8VP?Mvs7~cT>Zv1T}nd%KkA-D&@ta9l^~iSM8}c?df0#6Mi60s z8%|;gHz|a-yENd8Tg@*iPBwlm;Ysc%0u(yTl0!BWZwZk!JX6hl<1(y*n;s?%kIYT# zUaUn4uP(xyvB$DDE+JVLRSQ)E^Nv|F^11$`K0#yo0E>AtTHF6e(^rO7)pcEiba#m~ z2uOEHcXvuicXuNqAPpkja0AlajdV+QcXz|Lc)siPk{_G{hrRY*YtAvpj3JViy>WTR zOkcUFE7-?YZ}p(zlJ#yRSu{7$=7TbdwIA0?76wO%OQ1fJU+GSgb#vmSZ3Pj3%EEXo zx~#xj6ETIyX_nNYcS4ob#k>}~pq)MX_i>-F8pAA@mb-Vnp$RFQIo>q$tszdb#3M*5 z7@J2B+7S^#_}SoWx{3Z zG@oGo9Y6DK-IF;wS1y+2cF4lUqh+^=SIp;c@{0`U3(4mm_Ei(KGhk*cVe=6{Qhrn? zS?Fo|M2M1#8-x4XO9si~40hwW*W?Rk-FW=uQV5Thu8e7if?KY{7Wbjj5i*Hnn47AR z$wY~x#*xqLQ-iOS51|J2OlGpzaUyO?)b3?-QBfF}7yDfD;C*xC`FUXe@YLk04v6J3 zesH0!Uva`B@x2oO#h2?Bbit%_h*;E1IJC`2&D->MN5*v%jgX8NIcV+{L>+dP9 zHJX>7_H)7sTqb^$7*r#Mbax(*_=&~mspgzfNuiItj-+=_cb7-D*3!a1tu9s{CS^+O zG47qG%Nm!FjHqj(?f&eeHm*;_3$btG_^wPLDK-e?PolTBOmKbAd4NnAUD^A=Em}oZ z(+diZ&-$>)AO6M^m#t-%w+FAD8c$stH=cfzZaG_8RgihbqGbM=xfpCH)>Q%FcDyo@ zQhV625!M-d+mz;u8!hle3Q8G$YPYO|k%<%@-E4UdOGaZ^SAFXPnehCAb7+>l9@FK# z_6%3jUU(sL%bLG|=?r!D&j{sx-L(|uNVO=S&)wy~2+yO!iwin1PNWP!&m3f3yZ zi+O62i5ySo4(x>v?3NY(TO#0+@O_t2SZ*@BqI}bGhA^9cah{9{vVkwCwaa?~kBOcd z+ez5s=?6Mrw7x~(*oJM6E~^$(2hgbl&HA{xh#cKY|B822*oJRFWtjs<@++}jKOhT&C8 z_^N($J_!Lif07r)ac(p?SCu-+$@jEi7K}Edo;ZS`n)uZ*Mom+|RJn5}v|LQuTI^7Y z*ql(>l^{Pa&Opog*UE;&Oruezg*TK_I+<@g3sNQB8a+SPsZa|?M(2qG=hl~>&m%)57LthH88SUGop zA}^c|GgPNhF=QrOU&&YTN{11sVDy|sVBG%gP&pBNeCM{sPCd51zLwD%e~+BkBHMVH zUp;(JrtSD~+SLY{G91eMSelZz-*P1()LA=?D4*db4Y%eec2O}hX+I^0jYKMMpN3E! z(HJ)olyKKUXt}t;V76oNgYFh3eN;a_chF8|~xB-9odGNw$}Q&mX{1G58n( z`lfa2Yz7(}-Orwom>g#t_$EY5?c1L@p_N6ZT}~P{$3CCW{&_Or{J2nK83}386jii8 zocT&?rL=uc`zu!DBvh}-<KeE7hQVkSk=O0A8Z0-C`5 z{XSnt*VC1BSQMwbwQf&c-)nRrSvN3vs>$N}a9EfUmA|h=k89VuZKftK8E<0Oe2r_@ za<4(`xkV=MvZac=)(J-q`L$BV)8ZeLF83bh%gyklBPXTQne!iOJHn1(ZRb0O6-kQ} z1#N8tOC zg(;(8V)*?-s{MS+zMxhqXNd;k?UFOss!uaEhsn@=t9P}S46XPy} zlaJ_X_f8X-qkQGm@Z?2SDw@`iLd{@qdl9o6(8^^u$hf+wB8!?ixn3Yai6wiRGOlE2M3k_JfZ3_ zfy?6SV#elj@YiXh1qc3_4(+eB5|WI(V%INr1NA#U-AlTMhCeA$WvK{0#(lkVc|}&d zuO8Q~jLlanj7>m9Gz(bUC7;R27XDj3Mj$U}VEO@*QVJZtSI(w?3ExB?E7l%uv71R- zE8u)#b;tf9%sOc7Fi~Sua`WFe8map}ribF===BZYR{ACM{Z{U)^L@M#*HA-jUoEjz z1taUxvEb%Osi`lP%&KESHSNpuK z^ge0Llk|V_~HI?swX3hMj?#}#=*1OE>P|?lT%Q%?lgB< z_ZQ?W=5P{#V7H%{vf=&T25{_-Cn1vdv{w|O)V(<5Ch8nbVXiY-%hTsKb_BAWv&VaLNY2I ztXEt0<0n;{O^L|4T5q(be6lb>He62OK!YSV+l90B$I}$11HO9{ik%OkiyD1x-68rT zTLaP6rbDlSL|+IZc;1Yp)mx zP5s?#r*7G1VkI0Ts8d3Iv(30ZJuab9i5ZP_3Gzf2pajj-; zH%v*APBnASgb63`y&wpqd#rVa{Bdf82h!G>r8x`7Ws~`TDbBfx zNTx3Rbi8=+3_gdxSsCTHhP6OH$H!&CeX~shI8ZD_({7_f@|g%n~F-? zPT3(XY61ooXYsdO=XcM75I~x=un0O(*zIIt#QXF$d?wrB>>_4us>Rb8`D?d7=f!qT z&$;WAI+N0PAqF_LYv8K8Ak^eHeHBzV3}HQ6YJRRMOKuAM%hi=jo!zS6(#?woiDA^u%LbKf($!jb z3!6JCOyv7?r_}CfV9F<%>&a##K8Wusr01YLk5v8S+eo*`=}5&eGP z$9KkcCam7R;NkbMo}P_0HuG@`>CNcyca2wZvJJ0o-sHQZPtiN)d&a-^|6S{TCPo8d zCdkcR@KCTfoz1dpC9peID_}9H|rrESx(9j zJU$cmt}uU$Yk9J`$*=+r)Af0dd6lca^?nEW$xpDmoQOcxYy_>iLMJ*l`3kR!Z@3?W z!sDuPKn~wubNFU6-C*4dsEarylxqn`XS9MD%(-9c%W7;U$W`i$`%s@&mv{ikDZqE1 zg$CCKte0Ga^^*P0-A5^<)T;SQ-gDWx zs2s?}thoqbivx8c5ktdugyVXkRyw-p!)dKi9>!yi`|`Ld*RrcWQ+|JLlA1!=iE!?` z>lSE`IC;&TUgkzEa5-`9*!48CgvD>;Aw0Tn@cPSq@)8-;X2r2dz>K z8%{#paG3C(K>DHnst8Ky*ml4tgc&V~q6a0xJyqd-ezQMk-kZCj8hx0>2SeuStGmv6 zr?a>EKn5O&tMV0%Tu)S+k8PecY-}wlM^M)Ga9g^5lyczxx-$8>(zD$1{aEW6In*nA zfJ7vc(G3T=Kh~~tpz6?A@*;wtufpu6OVdL7|D4m?ACh&-$xw47zPa|OIrKUjoLJZ0 zti9Cv(etP2bEzNgX>n#^+Vd{@uNuyC3ii%d^k8Kyf9DT2cVqr{lRxk#^Q4VeGWgm2 z+V{4)5HQnZ6ddfRxy94U`u1IF`Gf;kc_#GLCA~k4Y#wwjmj93D3# zNa#jHGl;T9+ z9)3l+@ak&^ON24GrgUn3KSE_zCT};J=by=w85`^71-bjYaJM*>Cy(}pG<+gD5+BVo z-602P|3E(pd>Takm6jIBPy54HyxEcWLtdUKL`+;%PuWH#0+++7fkCHTY}BEL zR2WQRF_=e9DJK1M-VC2NxGWn6$|5)b_u8?@`w;CO^?`q{DkN>`U5g!_sU+$zlOb`{ z=@ic_wUleZogZaAMpWo$eNz-+tW9Oa*R_;%{kYb{ek%uIyoVS$xJOky!|GMf83){t zrBRd+J{g}To0)@1!&u5oqfEq=onKZbz%}YG~%tJGJf(? zxbKh}<+=)B$mHe?mN)?v5m|iG7i@7g4s@=MhTim?)I#aTBxTg}GgD>My0D=&=2?B$ zwKrN*8PrxCip*=`2@EW@(CS132b2_aaEZl;?&<`nvPV29q%uxRJXpQV5&h@rVi=GZ z@<=IlA%2S5N23k88nw#L0)a(5?nesFEO{1WgQukun$OTs!vCBvHtQrGNW2uQcn@oC z#qRET$`sIn<&KT}PF*_+ji3M*^?Ry}lW3vdd^IDTJQigUi!E-GUq;TBInSt~1< z5GdDV!M5x*DVQmULJNOgE;_|`JY24^Stf=k9}A%z!k9qp*u4btu&x-F-3;r+)6&ZG z{l=y{0xT4bObPzxZ4(Ccw{qO!Zma6`+xxkO9dAZrR!rqM464fkaG^U!(T}1GGNX4#ZXT)z<~rb2g}6*Cb+_W(>*K(FOC>#&i(!IyD~%*-a6M9m?Q@* z-|ew-|DdTCZ1@+R)sT=}pB+E;)*6d(^HL3x^e3wqXtNJ0c!1wMh$IegdiWHI*;FPj zw!>^C#r&I+wru&1cXK;(!B~BEPJA}^@O;z2dv(FLkiWb;XxDyx_YW-{9ax}7F%yeX zTp1an%2EqU^dG75UE#^;B-^@}4rsE+q#Q!nDw984^y8l;cDy^kLg>vJ z354YG|8da+F$|);I*jGKXYBFBiq^zwI&u`PF3h{mU;mT>p zmarW>{tXb~%J6qSKGk1|?;}&!9W^&yn=2O6_flkl(-_U81U5$_6$L^b<*cXR)u>OA za6AY5$3hNH5|7()6eXp0e$#^Z{x{#bbm^@vj-TGX_Y%~DsrT+++#(02_94_`cZwo#O1!~l z?#5!BcB9lKo{)FKZNEvsKnok;l9%|LPECSZS97Eio&>L$g0>f{Sb&ATSAxZhaVj3A zh!>Y?W{AdzUaaSxt4B=FGzrJbx?^!`=}lVLrAx8qc(Hf;+3J~_a=fz5O`*V)hlaMv zc7yn^1s}9>#JNa0gT?e54JLfjF+w0MYj0jU!td#8Ufg|z)|r~G7XFa(;pu$&1h9~q ziC=|8XRo;{Wg>WCsSjbdSbh}$C)>_Xi$W!J);^jo3a3zu05%pm<<8B1=e}2(f@U)o zCAa$4&dzhrb+{YU{71t|gnnFvdGc%;%s6`T0rD!!6k^r5P#VO52#Y=VoB%yX^fOO% zXvk)DL;HD!rkj&7S=E!b$7f=)jSgQF8W&myL(Ah5uoT!EPs|%SZPs^qeYV|qT46uN z7`*C%H!vXm0Zbd-A5;8@k6cl1ffh$Y`lSTO13qPZN*frsI^cru9>;)=jkInz->E5R zc>Uu~D#Kcw$Y3=2KyvO?G{LS4fgz^)_q?%qf95a{e*%%Ty^^-=4_vml>*cg5QrGGvgyYH1P#AEaVitKPmaf?v$~sg)BHYI2N4{aYkg+^#Mf} z6n8%Qtkr}Y=MD4C_3+_F!gX2|^G6tlR0_C(@K@Z0_9tg13cH}f0>2%0a&!=**cyM0=c zTen)joI+S=vZnvA0z%Uuy;fXJbXMeAwhue4i&zE&vZBsBo;09@bU;RpsB%3zwu+1} zH(J^^!>sn0wL9;>7?ks_$etZa{IlMX?-d2)0k~J@)8EwpZ!SQ#EJt8bnI%maj&K~y zRLW(gS&s=3Gz!dB%zN6EfnHax8;F%ydl= zUrY`#>nhJsoAyQc49T27w0F3!k2l>o1FK9pEHtV*sWj$|L^AYH5sL`|Egw#8$@@-5 zGHU8vZ*`@tLCqgMRurKUN-oCL7A~i30ZcosBZYjYRBRMb?zQ3agfruXo`i1ptAo9+ z#rrG8BvQQFA>o!YO+?ZFJF5S-6)f$ss?IL@goCraN5)hVjNwgD)XZBTONrpyIMWp+>j}Gd}S9aVZH=vxma!>L3hA zoh{!9zdxlIVs$gel$1eLo~xsPcyv3>GfhQh$yR_FL7ZY9wvB7OpA(VmS`Rgwtj?R#e<(xgmy@jY}_zx+Hyf@*GNIWfLJG<@kPYh%kEcFwA{z6c7KI z;&>8T7&*u?%kUXpb`y3mMrp6s3Ayu}(xR;MK&p&@B0Pd@fm~ms$uOWSyBN|%J~GtN za7u`j+-&-04q?}(D7xYI{L2v1-P{>_a_)UEQKA;uAC(rb06u$r1yFNaLYC@kVRvxk+~E zA7Z@EU5#c$+7bBz{RE$b&!#D+9Cbu3ix{lMruj~pIBz|s)nQ&LDZ^yv2b+kg^==X3 zZW`NU(0h30Yl5aQ(pmT~UU@bpyT5UfbN1iokZvITj0+?s4eqk+Hq2c)_!OuEQM~+f z`Xr*7`sgQ4-G2MF*y!`G(SzTsfVFcx3RKR^&!713i+oibj^Ocn8r#AL(`W!e`RTZ9 zwsXo#6>ACpZ;L~};-~~ep~w7U=wJWa85ZElVVmXo9NGju58LU)CGsO+IyuPR9igdP zTp`3wm&J%)9WJcH(BW&J8?W05YKlTnXDcOj0kg*)e%t*mbwiPvD%e)L&*vg0;v%Z9 zqo14MNQR%OO?%+ZAAS160!L27*wj9Fdi`zg+o?c5OAVB%Ee-?r`>xe4!RLWEGNtaX zojT1*d!okiSe|2b!rgZPx0AVGnlOM0tvaG-H+!wBo%cHYWMsoEr}K$U+pbwf%Sa@L zG)gPAN{79@d2x$z%4fg#9gD=jp^*QmdQ41rvqD7dq?!C9U8fL4 z@kp;}ciHB!g84ccw30fGyt=YFjvh+Z0W4Ti{vk9J}p8x_&?Ur_u;gv^RoXDx*aBC*AkH3S>I?(C2R_ZcxPRWsxbMk_b z#$^_pRE;d$%$XB{7prA}HFD5Zm=FO5f9spu;1Q@L>Hz6o-Ff zf*7uS{gdCd)qa5}bCrG}TpnHgov?o@$US+LLjxO{<1 zzs82KOOTiB&=zlx*3%f5{boEQoMnC#4-O)N-ZxK?#}fTU`kh+hux!Pcwfcwztx^6r z=KPJE;1jA!#nW&~ftoi8V@w!Uqtt!}ZF8S2Rkd$vY(FvHvWEeac8nB*{^vsd>&Wjv z*h>LI%s5YBscbKEI7PZ2{#;ESMR3+w&SFT%O_&grHerIGQnModNdhK<;Fk2aDHXS> z&6WvHh4rr6C)AVwylw^J7I2iFCk1RgF%x1!*$#i3!{0skSIG%ii!io&;R|TOlrCfr zJhB;xCzz_KZ#xW-*|<>`VL*s?oL(AL&sUh>=kbUP41O18Wo1*wPA(dh0rUJt>jkfb z+0@=|aTzV&u70Cgmy!{VF{!iFRTSRbiBG_;c1>-(Q_%k|hb6wFIPUh}U79k%xbCH3nqrcuqE zSo!L0^PdUK*PS(g#U}T}9NI<4(+bq2v^LkX?L>Lg+W6ysE%V@Ze_#)eY7N)0<*Tsn z<6QA_M7;g{f*F<9q&dq+{G|NzHeFgeZPA?c)#Cs%PDRDyz@fruK!n%z8LF%Z5n8#c zsK22|Z!Ud6O;bHCA>-R}au7Y@9hC53(I+0ChF&DOI7;B)F_0h1LI7G;;y}ZBQac8 z)rRmRUeWj43;OymQUVN;GOVVOpQPpGe}1VgcN?vkt7y10xvBk=E=floCw~0JfU(d* zPIz-}gc94Bo=eVE75GKG#|&t?xGmGO5gkGXGyIBukFQe6fQ?`3Ow7Zt@)L zs_L7f@9UgVGkv_RRb9k>u^+S~(V8P9a3eyc@F^I7h@$6qKZ~GM^FS)cOrY>f)UYB$ z$xouY@MAX7LO;{+ab+DX1(=RWAyT_o7J{-_Z81wwbZ!(&)%h>2g8$p3Z@CTCmFCL3nk=OgCzX=y*tDAoR1o^%?eq& z*RXnB&9Z6y%|+nSrXm^di-eHmwdMw9Yy2sn zl%Fsog?)3#cW-yF4euw_yYKxb-YxytGxv*#-BLf)1hSne;IM$)iI+WV76y;)`JOh< z)P!7`RXznTN9*{G1J8EsXmHTJ&17ZKUTH3$-`o9kZS93$*JWBND*ktDk=nXNa-=-2 zl#Hc<<+-p7>InsPJw(9Bp+6-*8GuuH+{i>qIA+_2GuD{f?lcT(Vvm-Behy>FbsSJ(8~KnWpv)->AEox zjqU}F?TV_Z2WIOE=}0B=GkYu0@i$9S0)E)(Xu9@DPziHW(e&!IU1G*YB8{Z5fwN&DZh zNY1Fglwf?LE=2tNxCc$_=jKJ3#t`uh0}Iv?@uLPkCsMFQIJ{uk$WPpZ_A=OEb=2vv za(g-vyNYwkA@2=~>&%sOqiDMeRqu-MgvHkO5SoAJ80XGl2xz5NbQrr*_C=JIS;tad z*Iw%X5T{a(M=!m(lgT|0NPyGO%Tebh`8{9o-tbV1r<=SE$>{Imr?kh<|3Y$0km1EX zmv#~R1`Fq91dJg;lGKs3cU7)iAMwr1%(wNllMJmtbGwznbxf8}OcRZEdz;y-^@wOY zvbcpnX%Bo{yCfZC4J1WZLb*9%AZK8RbSwSx>{X1IA;T_jyf>Z=?nJfstzF5CSKR3| z%lYHge)puJpnM{u;OqCR#J{JvlSS%uZ7&bjDV(-mMI#{j?B4ke3eI9OALYOQ{%g7V zCo7l69s3iDn$`7SN-Ej=v^BBTdba9oXW*}YJ4j3|9dzX_U0`ILBX4?*?P3BPiBAm3 zo0B*jWR8U_+nF!c+1A)-SJ&KT34g!4np89%yg6P>WNLqk3ukIe8XO$_W%S6@!*|-! zz54p%K2!Qd($&>d%G&GVk^8g1V&?B_TU+;-98eq zTcCsN7zL0x2{6y_3i?H8+l0ixb) zgLc0bAiN#RQY_Dmzg5{sY&=tnJpS3m7L6G zelex0SZO`W$jZjnxRYY-@pRr7oq|O9=BE{)A#vBRy9^m0Q@(Mi_bWNw@G#`b zGd3?C>)S0CSKaKk6LDb|PDi7ZC7gV5G;#B!i6m`by2_5f0Cv@#>K^rtKk5nVxvw)OT`c;I(X<7o2uCn`_G7#wVGl*QbY0+ z(BbI;uO=_Y0Ovc;g8~l=1^l0pGdC^2Nw67X$}6f}JzV>kaoIs(-)=T9#ydX}gW*(B z9UWe~`jCz9j}4!;p0_WPiFq`<<@dBYRDVwETsC)SX5-A-Tp4M z6r#LuB;k5>vc=Z?eZ7Tv<~L1;y>Uoh7oKP&#>V%l)1#f=z0dET^78Uy(>DH+(-k(! zn7VR=$c8yK%iCvE?7;)Z7i2#;d+4%zMP(CAQHkeB5W?f3F@!Z@P>e(q9}R>N)#Yj7fT zM8W+2Motbr;a^;T3b_7|3wB_ESAOd9w-Sg9|Xzp9>$(^A_7%U(hpj}`)qXJL!#%kqmJd+x;fG@4QLW)bdM z;UQ_J6 z!&1jZBqSuy%}6d98k!DJGkCWK#n`xo>2|yzZfC~`hNXYLnKK5ukw&#T+RbhZpxS~8 z1_nmg?|$3y+A^gVSgi(d&hMWt#{h4EOd^n$YS#oR&>!Ff$V7u<;^Y7JMiR0he~+b* zWVM~{+Q3$1oL)R&w0J7RZ2xdCE2WJ=z(V8CrU5QZtAFp2{#f7nnKX=l^9IQ+>-S@;J`ggB|(en$@k%k8UHp^bN7-*_4JrI@FD@2}5X7 zZE)~rqE^#?^msY*JKPO8*Fqr5r7$(!(}}r!K!*6*vvE&ZVCvKpnySTZ&lsFdA%hv! zj{;?fB4|8#^E$I zL_mT{V}{XF(BPUVi^Nd{#oWfy4`o?{8?C+UO-AD;;D0M09MSj-w{!s#{j4e0suW`P zawZ7(ok>vKILNsnrqp$9x?v#0ZUoU~u11r>4?p!yg3}42R=>5&?|*w%14TziOcql~;DUrO#br>B*1PLp2exzVDApXa{|FBb z4LPc-f2~{q#v!MNIb2)_or+y39)^uNo;0ag^j!{vUnMQDCXpUE_ts_aEb%2M$^7*G zdI%$!Ik`2?j4;Y`?LM8uYh3@7lZjuB)m5-UN9K<^`<$|{p5%&g%%P5js8y|#^Ztxt z&~+Pf(x|1}sHHQa0{vr_HDq9?R(eN~)&V>Q@^o?X{Umab5&=f{_=L+ecC`!CZm=n( z@1wvB6yL$oWYk(PqHR6! zmt|h{T(%4GZ)YXwF!CfR-}3F8&K=(*HLsoX{UBDR*R6g7R#5*=xXzQbm0E* z1n@<}vRzsGi&t6m2`_|i2s+Ly&8=%lOPydl`d9^q3U6R-{2p}Da zgG}&4MMW1&&SRB6_fGk8$s)?i7=fhYRi?5l{;$4b$|gI*$-_x3-@n750dLp!W)yZa zyp^zj7>b5`gX|7Q6;;L#MkUhOh0zaOMR2wF1>nV|z5nA|@f0Xr2u307y&MxnOCqM; z?29&^uQHX2`@7cpJ(<__lS09-g9EF$U%x!hd+-2WKm}wusN`ZX?nQpjVI>B@MHJu3 zS~r^D-`&gDgoNI$fnNkHM$iz4Go{8$4UQ#x%?Y5ANFthe&K>F#{f6TIQryu9Qz#P9}^2<;laF}2+Vew0r++ex*TfKJT4_P)Q^ ze*0aUMIiG?#OE|2j>qD>BM0n@&#*7#&PZw>7z9pU4h*X0L=MdDvb#ZRwkuewF({}7 zwdRR6HSEF21YN%r1%CDzt^d~4Hw16k%vF%7yy+O5jigk%9%^Wm=}Jcv^W!sjJULp{ zF9I;8B=>CG7iGHM^#fqlUx|r*t+y+L_fPwa_4ZrkpqkvF8)XT=P9b@P;03V|L}Ff- z(9v|h%dKCEtX@|Z5WNuu-F3E$S}h)x_qk`-=)}=rmb*@^70zXo>*37Zv!5F%2?Vwt z)U00}Ow(1hR#dztvqAmiK}k6f#_bM4V{<#wN>iW)&tknhgw1pi8$w1__8#08E$}h( z^E*XSzo-@S!LG!{!2zIfQ%Y~0g^r$ntEjll2y6`&+fuE{Ku~GFP;ajYwhq^_3s$j4 zsmLTd(1T9qb7v&tbNd{-&THCoF-Rwu#QcqIlp89b{rT9w#%ekYKv^J)_}Fj(d?s=I zikJ1@?gIcQH-F&izdd)8zo8glT-^7mDYdf3o%ax<+?&V`H^)O@ael1|RG{F_{~do} zuD2+elJKM~*@ove9Vxp1`Ozmfc;a(o`SRY3*a%I*Kz+-Fon`fiTEkCqlYv3Bg`f#z zJ4DuEsl-&Q@Z4kMjGw{6t0&D{pJeoqEg;J*OX{7d#7gK}QA1LOR2(J6&v(J3IWSOZ zlb1dvQP@6qcsk?J`G2nV-N_)zpN}z~1V}~@7nyyoBJoqg4Eq5rwBh7KP5m*|8ySO* zB#;@Bmq!_w<_2c{!-YjgnY)?~1bSj0&x`)b9~pNc8aXqp#V4=Sz-w2CHdUjCL3OUo!A z<|Xk_KN_xhB)II4nr3s-?F}LJDHAyd|M#z?K&ZqKWNr0NM)Rm!zm>n^;O{u1U^aQO@`SNv^XE?~?v7sGSXzW~Nq ztJDnMG+g6&?yTG0=VFB(T384Lmgh7ud~ezwJ*6x+IBr9f=Dyh`I8djQlQ-QJRsHvG z=RIIV%dPas^|EPNF~f z6UfUCrP}mKn#ytxKMgv1>G#y?N%kAKRNa5=2oL0!kehVDS=Ph~Bv3Fj&|Fn8*_MHV zg3gxsi&(l>V5!r;DbwBPM{5~wMy5{mr(M-@gp78o%$iB<;eg(Zzv9=?#XM~`q|%KJ!4Hp1YC9>07@i9hyROD0sjs+{D^sxg5DV zn*Y`Qw9O<`Qm_6U79~nq^eBK{w}I5feO9d&m*FAqcEvkd0Te``)7%V z<65K)Rv3!j_X+AtC}Zn;A9M6ZwSEJ2ZbtQsjT>P@p0~@d#%mpdkUKvg_6stZeIHyp zzCPVGgT}fKng+fcMMYHrASxjj32SJ4oGfS;265(Gtu>x;Z$!56_Yb{ML_7-2aMtG>6873O0Zp@~E16`<@cEG%rU&Xy3^&H~A3VtSpL(6?yl0fugdTFA@`;kh;M`7J%&2dC+_V<%gK+7EoUMhQ2SW=kmb&efRAcEzeRWs}kX7PLS&?wg@ zLg33_F^1hucPD1hsacEmf1)UFy?GB{GYzP?-yUWgqvYY?$$u%+Yrgo4r5KZ(JOEU> z8vxg^KUYZs+As_!a>T&~$7RsL#`@&Z!frDc)9AeGG(eR&{+}$~Oqt%$)BUA(wb=+Q zR%uisaLfN1oy}YHnbg(Qb$!lz99K+$e`W;SLoQfnSC@!H)CX;IJ>UVBJT@a+ULFoV zUr(tv=rXSOJ=y}7^=_&mchsdEi<5ATRgsK?m zQ``o97Bpd9fToB}u0O9AF*T(EtzSR)4Gay*Kr8`(d6~j`QCqVa*aU{aa3kY02LQjx z2B7?#X9N%R?x48bWBa$J-$dJ6vGgpJ)9y(Ko;{8CaeQDy7D~t)(iDx`a?UQ>p7ye({_UlLRT`E zO8>s+Xyba5Ssszj01_7LURX1lB)cSp0(HvI(`E-y&E3-C;yik|3v(&E57PbN&XRnSr74?>{J9)~BuRilcf?Jo*ao zx}4zdCaXGqW%9l~rdo4V^|Bzbl1f_yHDT{}@W#)Nh#}Z%EV>$7;m*3Nn1IdRP2&B` zh!-x9+Bf2^n5~S(CbIT@zFftp;^XX>a1EmSq1-XR(Z+w^?YNAN+ATS0m6nz-S1qJN zgayeusVWh#{NxJ|lQZ8&;&Ch0gil=|N5v;N?2k`i5GK;6NjiC9yoEdb_B z`9l=3FYI`pI-K8wAx!$%anE3RyO0L<=!v61AkBIacUR|kxPks*a(;^NqA*re62?;1 z!V-CIIhA-5N@cM)%E@AxNpfT2Ufmxm-N&l2FqieA^wKn(-X;p^@U@!GCCC5$M`F4? zx*(#x|SYd-h*tcs76M*q+vj|u> zz$i^tOGZ}=_j&Sr|JxsC>tufGG+_8r^R@foy2fH9Z7CRKAaZcmaj~@iVxhRa%JkBV z*Y)79x~9H#yWcYnE#pUO>X0#k=lF;#mnQc^*x+yC%5!bDgn)CRW@3tFG|wbr9a`(6 zVJh7jNnx?tl4^T6pzB?65dB-%PtkdrHfQ_+7sv1ET=L@LLP}OP7r;CSA3)PVd_Mn+ z1;PCRmDvBu@!@J8i$YgEjhh8C&JCC$W?<+bN;K$z!Fhw=8Q|JMR1kW{=l|jZkRF{#D3zgqD z0e%#ellL9D1HcNpw%8zucwN@=Q|*iZz1a7GjrsE9_1*-<$z=iXl1rYu>2G$|bjV1P z3Z?;IONueji7;|pzdE{`=|38TfF&g_Z+f=Y*#fYv%ll%D~bCLlzBcx!8u{`FCO0kp#tMt{D5XEPgySX&Pvfem%6Tm_^D zAaVaPBLlYBVzG|Fd3Q9@ayK_xU}J=96?)jY6a*I|sa%tl#*#YqcFzV;gXNM9tF>bw z9;r!U`ML8?mT4Qbmzj-c34<=FceG$|?iqw9NO89<$C2MTy@pBH)`v^$cCgeo7d9?+P+J z^mM;Wq+wUKs9|=0C}u?vjUq;?2EO`TmlleL=sOLVz^}om16A|EtE%z}Zk&*rd@AK- zmNk~fCkwl@V(h zCfzi8U>aVrV6#&crC=^51j%+ZZdLnM$YUxgrNGku%C6pn2Y<0yRXx7XB#0Anv zecKzA?GeK0R4w{w0-12(%b-TR8<>2lu>m0dX)!pdb3)5RF2fpfbGk#KN|G-7GG1|KOc5Z7Xym$dGgWS`8)= zs7&3y`YS9u{oX{4a>5oC!+;hSv;2h19A=PVsg{;FZSFzlywVoh;z@wdQyID?l(Ax5R>Z5m-OPVoZ~RgJFw` ziXisptHJyr)GYwc&4B6s{BpMmEM4d0%>9b@>GsW{{ce(RR5m#GAa~GrKP>&=cYIrb6BWeTJN@auTLo#+g{uk?HN0=$95YMXEC zg$TThUO`>m%&*A&_Yxr@WCw?bklXOx}LIxKJBspv-Ce6v`YzBh)TGZKU* zlLaYz)5UmS>ezjA-!eXWDu;QAV?#ri7}Nk0gG&Mb!Y^OI^@2{<=JMmIS%zsCF1fQH zEQNmFUeHn$1O%Zk0RlGB^#+{x-6T+O0CBy;hY%^s4cR1zUIKGw!!BsM#%)}%ZhmmJ zI~2`PyazO6YCZs~W+;w_koduO*w!!izENA?eZWb9zDKV-4cR1iOUzka=g8Y80J%pJ z(m8G4&+54oJ)X7;f=Ixm*!C5ZbchwOo>tccgfg1f&Cxyu58ys%85rJBy2)TX zEocM&{T7K4*p>oE2Vw=MZWJzNKu?j!!UF(q1emlEt;%=OaUOtRO6GC?`227!I>`>$ zo*wJ+)*Ww>>x1cV;L5NZrhfu2up3Gd^%W%Qpx;5Z-EANNL;QJrC6a5Ue_GRE1c5qD zNKcOlSZH!^gRNt~KK_?gF}~dLAK~-t)Rf2UKNj~B-5~V0aOvT}>!Vy!M+}*03y06z zH@Jqojqv-&)z?u#QO#8tLIDrF0Un$Q@Nt62K~DW-A(<#%yGCNh$P{)t?p81MlZps@ zR^;zdxF)mcJqZ=HRfVisEi^Bdo&z-EqH%uaCULsi8ZRQyuNUEe=#~&OMvwn#W7QEC zDCPNy?7dPRgbYoz(pZ#KQ(y^gP}A>k4$Q>|Uu^U>o+*D<$Q#_$sKv=Bt6?(;eO_=% zoj=GIMGD5iSih$e#zHVlb)=`8bkKtjw-80Kq8AZTR=Q%A$me_T9mBF{UocfFlL~=IqCOMV#SGpLDjAR6!%UZ?Hc?> zaHnuc)Ow|OebtMBfuT08H`-k0R~ob+dC!o4`MV<1l_T8e9uZ6edXf42Hp^8}rsb_2 zZQp~l1~Fr$`2Qms^i8$X<$-qFd`5$VDk2&q`aO1as|5ViY zJMwD{viEr%yM?A*4y>&U%gZ-YnFMopiCh0Hzc9e`92XXsnqBsyfGTuHWsGwvqE4~J z#d=%tB;iH(paaQ*Y%!w6J^vqDe;pNN_x^#xiYTd)Do8U(ONRm?-OUivB@Gf%iUCMT z4&7Zt4={8ijdUyBEeO(_eLw5_d*5}|I)C88McpuaU;DZ~wU=7I*Vr-*-<7B?mbO+5Z6ClRuEEyj3&x#ib<($7MhV6mp`^gf!x zL=KH?U*Bk09MOKEam^-Am%QJ3-M4Qtk_9YGb^c_wu=L(;Pg;S$8i)pN6wD%gSpHOw z_63!R1*7mvTN>M}1^tPE*!3j!&}q*sF9j#L-qeENs~_WgBO90bItYMuCV3vMIbG~l zyX@7jqX3?9vw(i4lG^{jSzo8jSnTPz7A*62lGbueoRM3*L}Jk~4_t|P9b^nVnz-CH z68>|#JlFXS^f!9}c9}o@{w(WOS`jwCTzm2g;F5ZdwLj`7EC)qukHUmNX@RJ=o+!o& z_xUD#a^66mJY@)a1*AH;ZmcKRNxwo}MzWvh)tt|Z#p($={1OBV7cfi;pDy?&dn^S( z;4q;3HPqA=&tB%x%hmB?>Bc7T***frATu}DAD|pA092^}VK^)-EMP18a;#YXu6zGV z{JlHb24BG1+HWwzgD!A`HR-ypwk|_85Rh&^*4<-*!JrQDSpZRO|I(7*odncIAB=s{@~HPgh6TWddp(#Jz#8_zOUeoWM7% zezPBUj~3H*f|o-tpaDBgfYc`&NT#?OdRwt$A<(MkW-rpR{^s{t^Lb2rc_!LcW2r!u> zar|D#3M2Y`*=PfNBq!|Xf7OS$o{95wP|rRxjIA9jvi%w{?@xonJdng#kZ-eBl{e?? zw_Y4|Ijx0FOAs6RV--(RWJROT{BPRQ@-p^UvhM`g{*8+6=+yLS8JSXy=R3HRl@2ZA0X<9vJ+oUSC_9UA@b3K)cy-A!SsBbN2gTqF`p%+=5# zcqXbTMngiEtlctG`s!KPJOO{PLF;4cQuB>`dNp{=tBbusU-#eL@g5;xFQ{dO$<2FAo7>QKDuj;&*xT;@7}MJC;9g4QI-5|MPq%rFb22Dkl-rb>cvM;w6wjdQw-EJk zULq3q>Sl%BZuW$b-GZ_=NGfZimFBH*?+K+4)ArCXJdu=yC{+3#TavM$Bqs?hHZVQ7 z%glAYT}AkZDOYcAy+<}_ODA7iy7f!y#%dA~0=g%-kw&U5|B@yw2(;^;%F(gud90MQ zpcVb>Jy|&WILrKYHNNNuaiiG-e~_2&J`*ph(QOl0}6#X;1A zt6m}TERsroC;Q+j0!G}+aneaEDQ+KgP)8J&q(ne3J(t%vB7;L;>c6+&8pZLtG8A`4 z)lu+|{*(t^Lu0Eu^G(I-*gxtAUMBTn3g#?eW(ul$E&LoF$4qB z7U}u7Tn6Zov9RD8%q-7Mck8NL_lHGX-hjP8%X72}Ix7%D25U8r00Vc;pBZE?*o`#+ z+pD=e?1PwiK>XWHqrQz7YFpkXRp`=lY?K1H-kp2+G@_zuOG~Ev)LB4i6b4v2XP^#p zYQ6io4D^r=4S%G63Lo{SnNMt5+0TK=`xWR#{|c9Ya!xh4jLfMkZN7d9;9UXGnK_{M z=dVwyp>|aG?~nvV1oo!Al~oIh?cM_l@J9nwuM?nw&QTb>sQzeXjhgL}dWeGpp6_7y zT_AO!1&D@Pmh>?2Bta-Bz=8!qU5>O!03>4Y_wUm#gCe&lpWJ|P_oR*Xy+K}fwjcQE z=UATlU$+;lfG*+H<$(l1Xa}as&0cJz`zA6_e|j*54z*5<&%FTM$QrrOvw^k8&-J?j zoUt*Q_pqv}3VJ2&e%HkSGK%7z(v5}gTcExGw=5cZEZ)67pKNvpu(XHwFV|5ed1NyE%frn9o zGKN>6xTItafC|9kl+l!8kC3+C>`OlnbLHsN4m({^@&Q@r@g!y4aJ(%*tc=`ih%OVeGxS z3=|@dc<*gU5RZ*Uyt(0vCM{8CLf(g7~J(|>zhIwi81(ngZ0eq%lY(1uDtC* zYPKoH!p(Jmsv74^yr)=<)CeANHPj+8hf6$3AklV7m{&K^y@x6?C3EVB5yq&`6JqoQ z)6)`0hcMckOo>81OwvQ+pS8B4XlzjV`$8xI!#3qJ*in(ve` z^Mou+k}>d;r`#BT74nc?dczrhVnKPk}wv(du*M^wQa} zuW4j?$ukb?*(+I@bI^6Emu=$Wp5Hn$2~8tkdhL#fyHVB|KO@3pLhTUpHA})O;Mc08 zPt3JHPsfH@lk1Kf`IAXZfkb|r-^i-miEhV>=Ff}VuT;5IDC zxQ1XBJ^5Hq?BFuNfoBETPxq%LnwLt^HRNfe+%YRUj3>Vbl&BgG){a5 zx`*WVYv9UaE{rdI&l{sPlwTzv5Jb3mcrQ%x71NptcBN>oa_!|EcLhX?`R}0n#IY=`jaP>CX-7I6V(n_zAURVqzdI1VG%f zwqF8HP98@51+Zm*0I|UhIwU}M$N&ypBUf>{>fdbmYulqw0NXrkr@n64nXZ_2pZ9)o z)X(DyT136#B%Ao(6u=Fj^7%Z9gQOVD>d>S~;nYDG9TTIbuip;}G$aQ5_+CZy%C)5N z0J9R5J~;5Af3Rm4tPv8Xx0XzRB3 zOAe^UY8QO)Kzi2E$K`7PvxH>rZ4QgmD<%Hh%!#Ok@cOWDldtLZJXw z9V#&p>I|nIZ16m4;Cr>19R+F3AWa7tz`-+ffoQYj8I}NwYalIn#%$|r?2;_nee_Lh62i+co zZGTBNAs-zX`O17Sj$V3q!j_+1#s@h;gi*#gf>8_65X?8RD2Sn}B?8y1^TLxQV89Lj zU0Gi}AozyUg-fwrr37bI8YX_LB1{ka%|VR=OTfXIX-**;Wnrd3M^*x=DB%&YRU(!6 z_?`Ga`Rl$p`Q()KZZcDks7no{;*?VYrM4m>Hh+I`gz2^_KAG#HKX%>I{Mln!C)dNa zNP~07M0YCkjh*pEpadDW9i~trvYUgAmH^*Wa*HdJ>Fc}O>U5R;Xhr3lc7}$EmAkQx zm+rmwZp(f>JX3X^_t6&IRvS!B=YQ!-nmx!-MVxf4ve9C$IqJZAH0guuc;Q_Q2`1(Xh;@M zgz!1p_aFJCg$&KvU`l-=yu+CpDQ(x+NyJ|+>o@pHcbB;)eU+dg`z9L3%7hF?GRX#u z>n0dAm?m~|Ah2h5w>TDY&FuQxDitN=PqQo%recFE_zIf)C8s@v_XwqWRh)T0UCk-~L@(*4$>b#?E&PB)$8muRar7%3!$;S?GNg=i9s zF{^sR;<8!ty$DS3c09(sDf=NE=UfoQ$j7EPZIuPn#@wgrzTQc5549Tt>yFOmA+@hGbdYPIDx! znSM|~sEsC+Qg-~}S703-yw8aT8!f)SU!}i0AU$1xvUfKvCiKxdVlyQsRg5UighSTv8hYBk6_E{wrO+EFL0pI zU*Ngx{w^XS0#0c{){P7!v+W?nkeXB*yT#Qm35RRKb3S!FX!~YDLCZbx1D@j8bd75w zy;;9c!$G2P-%s~s=BS~0hmUPE+bjZHeGP<3~^ZncUI5ar@PNz>$s8d^i(81iZ!FBcuGsb)_3Bm zB&N~%TDy2(OR@1W+5)xI=-xOfM+XEd;g|~kiwq+9n(SY)netISnJoFJttJ`xu}qYr z=wnntbaKbK=V9WmxAYX)00}hZcI_Qy_=@e>N4{}tW!F)av6>q$+=`92ys`<@mDzswp_Sf&XM%YAgIKqyH1&gNv(EGAw-8>B8)=C zz`$TaQrEt<%%uIgF}ToeS6=6E>wCREYH>iaB4qWCySAIaFgM&TQ&Iv7!iQS zqDa3MQNLGLs5_5@0q{GX&sHm}vUibD3dCN;)$%~AoED4IeJmrc>JBVA;@;icl5Ant zZ>DlzI~oO&ey7{IFK*CVX0t_j-$`6Vp{&r1pc>niS&ElDuqMo(UjGZ5}R_n229o+A@+DGXGyRxBSBd^FL0A0N|NOna@BhZ?QjcW=2EQ= z(rgTt30bq@z9oEQGJWh!84cyV?1P;Q7Kz=Nv14$u^J(03ijMYH`~^Te=}%Bimk|qAiVE_G<^iN`BD$p z#AaUN_N5ORdNaL`z6h{p_ayy>Z7xFTPy5Uxyy_qN8~Rfw6g}yc4Fg{79;F zP<1q2xBV?7y=jvyQ$OF`XY)*LzFK|G)|Xjn#_08L^E+iIzsMx=q5)|m*j~!~z65NH zd~$FaOx4-fe}0a$gr21OkS>p#Yi}xqL2IX281&!5^Ui;R`{T~gdv>MF10`XpBA8;k8;3`$LiiwTNDX;At_*C zWZk&q?z^oX)%>>DyoG%g3A4NMxjv;#N_l1kYqHU-(3EZ4S$|AkyS7J=PL3Uv; z5$E(vTp9Zo8-y-@!+vR*}6i|klIsAI- zSEb2>!gn>zyLtS$bqWqlo@Y$Rui2~{tGoI}kKkg19Jl1e5w8c_1^5uroPsJ-76r=K zYLtxEjrD&JeeWwTg)0#l5ex#t94a!gu1k7_5l60-ms+M+7B~z9y{ZNl1X|3piIuEh zRUeVYkC8mLvScy3<@0;i(hv6~7bzzXfAfGnYSt$^m_&=gb{2lik#y z$wIzFAw3u0+pEc2i%n)BUt|{SnmG}h@U7>?2s^%M>zhiEMARHsF=B@8m=nO?aQa26 zN>`1A%QP|c)|yAB-BL(%+1g$c?&-(Oz)VNp4yPfqUd(xbFIC(32M$tl38#5frUu-XE^&1OE7`0uCRDmp`Gep|sT-rtoyA7X7yl{MZyWQf6rjbU#MQ zA6{knoPEtz71Q)kSQJ)IQ#7~J0dW{Gi^XT9Kk?RO&&t9 z08`P%li8v^ITTZY=vf>3qnzh0yS`qUiUu!c^C;w2H)_N=pGFC0g7jk5>o#FA*OiM; z6Ywxk7z<&JpZxrE&s%{EHj4912Aj>q{C)s$C=-(K9nbSz0+Sxk+zC1D2?nJjjjm`| zFt==nq*akche(y)NR8-w5k3*WOq&k+``xG=`f77sF&VLkw=-5;5=10CDr|k1kt=>Q z4vg4*CT7!G{^zWZX8DfeGMT8RV>CZAD1q15MO4Lt%$$rb;~HT>CWQeLJ+qi~qhlKv zd2`bMPamb3Dx@BJbh{u}fVB6-uMszWS*VOQ$&2-UBt@x_l$shzT(<3AV`brKIAe)C z-l5>hLbAK+gBL3i694<>lA`QB-V#5_?#!B_HjU!b;)a@IpD$W(0=3k?=)%J(aL;8k z?fha0eRX19ulDQxU2sQED4;{@#^zi<31dGx|WnuGNvn)LV_K{_py8l-a) z@?}&0yNCF6Mo-wf<0{Ae;Tp&0`_-z)*4?j4Nx}=qTzUvz)3R|88`n9GKm2N+P_jk$ z4RHVTwECiXY;$U_@2N$V7|Jt#_-kzFPsFIl-!@i*~{amuxLn|vn%exG$B+Z-_? z+m?%vl4~y3YNw+7YLWQr&bghWp`NB)aZJ>#VED>Z#qYwg7hdvB9UeRly%db?Rz|U_ zMX*eZCscnTUj?kV007!rvOJ{b;u81Y^oUPJ$a*WlP%Y~IDcg{zl__%Ir6zX^#s{zP zu=Q|zCSr~}q>ukr=Hy577FXqJRmb7f40+y%+VMN@<1?+cn-xlf<+U&%DH8WGBAIQUunOl6CV2g0Cxrd zhOIp?3;6(rV8}6j8eub(3bP#<7i6b}TZ~P-+>|YjD{f-POx)9Me}Ue88xmzf!QE35 z-ASn1wtyOFx1}$CkShNC`*Z`WuSD0AXYFJl^X@!qtlXTbdW2i!Syx1pLqP&fl16(@ zVW0k~9Mz(rZjAG^tfayele}9d$FZ*bpn3wVlKZN;zi6L*@PlH_K6V$O(5hMd}G3%ZnB^2aqqVJ+PFe(ZsX{JGYqNzY>Kjh{R# zulZ^*8}Co^hy@nDe;H~^xtOo8m~BQAjk0?4Q1C53=Hac|Zd{l|%Mss=$Ml~#lM8#3 zHe5c>zQW|*@Kwfz70)ymLY&@j)@et6XQdq#z+Mq#yT1OvO* z&`sP&DG8O`%c7@4^Tmo69CsA$v_m=3t|Pr-7M9+$B@EgTj_zxtRo+T{{`+mT=ufPz zsgyj?)HdY02>hVlw;`!ExvA{^gO8Lu-wG43ydEW%k9mt7s+mb=oja#48j-SK^B|Gx zU3)l{IM3aCsPlbu2?K?u~4|tU%r(bWmdc6IENp8b4QxZUjyro+Ud4OeC?BG zhIa!Vyh}NeXj~iw08BJTfc z=}MWg)tOg)hy<~x4p*FF8J*KoOcjBPK;|)=ApEt7 zC7B4`3%i%fTZwe`x68=+WQ{ zjV6m^zD-np>cjz)&vxu2e!C^EW0-HGpnH23w~NrQe&HOIORQC(i;4wJY!3x$m%#m_aLu zH*&sz&}|y`EUX27=QlDZqk>4BuYB3kyx1wxCIsL43BHec%G6aON=w)Jx2?U_)WiRB zG0a9-jJs$5i@M)~>bbBYm-eUDLP*-}CHxs+weXJ0jFqfeA)CvH^wY=uGv7v^3ruj_S0)II1J-_Z&?0Hg;0Cb11N(wXQ~SK z^?@d+cG3T7!=%ev|6=8+@P2NI)x|rJCeMtE-8pz~1mM;%i z`^W&f1lVkVw*vY;x#}7yT0&uR5TaS{ZTH{VD@r1c4d6P!*iwS%-etgT=b=!jA1@)v zBM{dE-h&GGU)x@WEb723z(9gq4kQLgz$v#s z@?>VD%lF|cSs9q`8-># zHr&K9EinTL4GW(-|J0?g^aVIolAM0zcIufuiA(RyPFJO}|$Fo?T(ym^oHduzqtYuRVL<$$IChgV!rVGlq zzHM~FKG0m-q`n?stbb@(cx`6?1+<)*%v9C~BwEE}8y^Ng&s;ovFH-DB{W$DSSSZ0G zbXl1l@o2DF!XL~<(hPKwPo0DHr-kzHg+lAYzxLj64cz&L`Kco-1 zxebwQz{j?SR>ZS!1v0b2VHxTH0N|gVZQ0#Nd}IVb?{v*0Sv!0wWvb)dupm1fcj6k zO#SvRf$17Tzq6!6O~JN+Y<9pi^m!3I>u}TyNu(1K$zR=Ex?CTZelB-eSB97mgXWVN zThEn983@In28J2{m9Kz|iQJ4_Jpa_Qui)~-@h%zbhDts2#`FT5pjB6Pj`!ij6_#l!@@PEM?+rA)enT9PKVwr zKi1>$I+V7Ip-QVtR)B*HeD@md1Q8`MBpS!xIV$QULIF7o4U5xp9T6uMgRKBJgO;6jw@xud1=#a0c!x?7n z=FrM`$L8 ziJcq5#wv^Oqbn3dD!)(j<$ij$B&JhNy%C z0W}-gJB!&-%9-Hw>EmclzP$VhWE9P3y#on60U+9C6qpz0&mf22lY3Bx!{WPmh%u|5 zzX}5;1mbt1APQBl6DX#n0LVoNJQazyC5yG|so>5Mr7ssZ9YCfs1*l1!fOc@7&-mE* z_#YsDy>$RQ#?E7EGEP9RL5Phh2xQ1)B3`_BkJzk6p~G{g%2tFgzGNGEXrP}x0%hTj zs-9jSFi)TEI(}9#G^7HpWU_NF^W6I{e6|yin77V#Q(TY&QZ?`Vs*M8o6FmYqbJh3& z`@?YK2lxN!x_$r_weh``eerF`?#mJK>M3L$2@_nx24;UUVGmAVkT3>rZF|E2W6tig z^|V1Cd&S25q@$Hj@fsV;OeRZ(v`mjy0rMs42U<5;zO?GNk1aw9NhF^p4ZMT|em43( zU7uS_`2b46+{e{4%pEsO1@l9n2U@VO+D1ac>c}Hk43Qba4NafeG!;!u>kwOZs=|pl zLV-gfo5HnbJ6E=+exF7BMun}ja+ymgW)JaaD+uM~e!vl$^55(Q2#MIg5#~CaSG1y& zu#3&7HQ{kZOn~<9#zi7M$QJzGsa95=Rniu5%1P%CDHh;nuc5GVSyT}b<_T72l;!?2 zZ+Te6pDmir@&_l%#a3p2l5iG5Vk~|nflG|v*(1cxxZ6HgwF2^=P(|r5)VLgK2Vpl5 zKhPIc^ltN*J7D-w%Mf9qU65V3l7QT5s(P^cm>ByT&(^6SN851@35FYO05{sf@o2KLJa?PnAYB88nOi#|ahxq_mJ3V>R&W;tvb*k(>j zWatPV2<>n}Msc7pJlm-l)B))xz%x1=ZuEuXn!e1q6$7dg5cLaw1hh$cdXqtT0JQXh zdgu_ie9FL$63Q=DN&eg7kV^)bA8UbE2vno{gThDnX!{DgX>Q<}ngXjB$g-9ed>^hA zSI-?Df4DlH`mxXW)}U%~cD;s9v)d8|}NMOTW8B_7m2 zT*|{I?HG7qC8HFM{|3F1b}O})W%l;LwWu}`%jmE#%_hPYJ(opkBZtjEAl^49GeJVW zOkOD9YIi&oP2(vRnm#A#fKAJ!rGZ1~u3$lS-T�V7T#M7?}$(`dea24R zRGX?GdP3Uf$zlnM42hJ~Briq=hNg&L3D(fDqO-OZ39rbP%zy@+6s| zW#_ZpN!{h?cW+EMj%L7-nNs>>)t fC$0y;C%yF?#@JuDJM5Wam*yA9pa)vqRCQ(KSC< zf&1GWk!0Q@{H%Ktdlx$6*#3AptB*gd-H@5d()+G})>}+fj%Yz}?}L$gMD~hz ztk^@8{X!(K+eYg9Pp_t&%Gk;>jnT@2d~O>*(O2OZA{)p?7#XZUjx?5gkNW$~%cU*o zpa4?^NZA11?;rc0Z$8Ab=^j>uEe?LZ<^h&xZqO)-$6A2wiw;OkV(=MA^=`${fFTHY z+1`N+owM#@itFlfAPoaw2x)bt>)m#ln3)$R^c+{gTxS8)5iKR6+sDVpAZ*4gT%;4s zOe(+)eDm+~O;_osW7g6El~-qeqBm!QFN_Kyp89bROin{nb4AEVUw_A-Pb)9yFf=qY z`Tc}0v^qC*`9lM!yqHjIE(3g%1mRt0AVf@rK@*e)5FP=oOw+wzwLl)I28aIuTAj_O z`{1w{1oD*u&@(FuQ>}w6ip-3RR`)CL(M7O(I#FzpxCAo4?|a#rSt(FMHf_*7Y>wsu z;SSK7Qv)0NUr$9P&>sWYNDw$ufv?h!piPDowBYzsYCwLA2fhX}-$0K@cGG|7BT&`> zwO#-aN_)BwWoBR5{ZEK+$a5|^b}F#jd=&Vt0jcjlaJ*F#;#=vHR-W>n~JLgX?!B zvI?hJ8BCm{ppg4XlRL9?99>lm3yS>_L6N9dI7G4)E02q9;%TnHFN;b}X|a+!X6Vrg z)00u)2}gf>EmxV~aGGM1X#cc0siJ=I3%~f(lk!eKF86I4-dS#MSb}{5S%*BgkkM8$ zLKg8Umar>CDv*E7m~mp5hg`;k)(+@gc=yYnk)|#&x1cPJ6^=W5bJ4xz&*SjFD)Cr8 zw${CyByoNeeO*-f=w5uo;PjYE8wvW#Jc9sY5kY)Y1DLR;&;yVc3>*vcPELPRgj)Y&kf^`3i3=2ap3nD! z$!z}(`Xzfz^9n-YbiDM_kD&~Siiv%Y0{{u?p>q+)X5Y5?;V33>-_?z^p8R=y3T4^g zd=vk>JsA!xs?emAg=7It`mO#Hp*WD06$xxgBUQHAK)lonIfS6e%LJGl^j(LgfU*oS zTO1|LUv}2d#d1|nbU~vVIPXBmC+utT1mHCSklrM9$sKsCAg>V^EeV1ofnpX5{K<@g z;Yl#ecUh1E43DlmQ<3(wXu?owNGeA!9bycGWlek^KsF9EkAjX;pcxFEjYq}B$0Z9O zlnC0zkmq)8z6)Ih4iY?~Ka`r6jxCwzT|_B95sg^7i_j#eh*HW}mW1EZC5@PY^~sPXgT%OII{DxII(DAW9}gf4Y4Cy=YkNyH5&eO+vD|X%r7sxtSeVza7yCX=Q3Op< zj0DxM=&;X9!W!_R%vEgsUsG>dS!(Cx%(+a)4K!+R&Y9*~XWH7d)fep2zTboy*_xnw zoXiEHs*}7sNA`UQV*imvBxjXuQ=P35=@rbm#Kysg0E##m6n#+AE1MaiIs#h4#%2p$ zWdg|{FO)yh2Iq$BD@+btsyQ$haByXkH>?_Kz_6=4aZkvp^5DdpX}dGmWVvAP0|AQ8 zB+1FWDcHZ{uBy5FPGZRi+8?5i>KO$VIWU3Qo8t53A84S0a5(^4fmqodBVb4=TCMPw zn2O~Fi@wA36Z1RdKUH7~;o+u$YiW6r;n%zGD@#e;HS#`&7hbI&GzWpcf}+c0xib_j zraK;)x?=yQ1$ZYRj+mS|EXotDuPXuA!G*a+BM@8z1fl3nRdB`6m*2q~-a7$zXvl%$ zEfwOPUs*p(g0SczX(*lu3=xpV8{EM5pvF%DC{iko0M%-bHv z(LICD zAgM|XK2C21#B5O15%jijZpt8%j)(_|RzR+GY)I`oB=!o=ccOFX4K=m*U&8-0sr(}7 zgTw~l(BJ}2`BzteHNf8ijHa%anK7^1UIS zP=A6F=9;v7i%bT=)fLuy zgvVOML1uVZQn4E(=pnwFpX{Q8@M4|VmX3WT*1P6`zUB!Ls$}=%zgOhjQn1bblqH;R z47jk!$;A5gj-&4&FiZ1C5Ss!SODwD>#;?pi^S+Wi2mM4KRsYe2%?mmSG1H_!AugMS z`u0*T$B5<15J6>mqiOLG#ClZsR@Gm60zQ2oF**7_s5AOIWVTTy4|?yJR4c}2XTjmB zy~e>aczysl@U~}2YhBsS7Dd>)rtvnrquzd0jCEutsbCP7ozi;775|s-C{n?} z=uINIK*BExJWSwwgEQjL+di>AJUh57bsHA2(WXI}E4s>=4KPp@*VK2SLNf0*{;i~=F}#E`>O?m4y4)aOfI5J!M$q~eRyK7itT(|apptmpXN(NRfY;vBK>)yO1BsAJ z%w}4}Z+-x|;FbY3$nN>$kqm(Yb#*Vnssb(AU1} z4GacARE6MSH$AY|84w}b%?9ItcMbWAeU~_<)H!~2x>Mmze7+Qu)^NaH!9GaZvk6532L%H zEKQgdZ?BTTZ%G4#6q!osp!o=#EpzL0*>X{kJ*7~)G&eoHg;fI#D_{pePCn=u0p8t| z$u1g zFa?hSUFK`|t0od8JG5+PRY51;!D727*l?cU$RiX7s5+sH{gG{NzPZ|mEP{}`0-V4^-+u)D zFr5?FwAZyA^Oe@xbpx8?+&Nuc-A#xP!im zUYg)aJa{?ezPCZ>TeA^v$(J$&PtJcmLejrqA;S~TOC*3_7tOzW$8PZz@sCB8VBBhA z+}+osXiu46oPlqS$+F=rY_lh8PjArVg`H{Xa)FYkhBPgY(~6c(w%_vXBglU7+^|r+ zdB+p}JaKR|{MS0OgIynts`%dnp1n_=srWZQzf5RbL=V7t@d!JfJ&jhT;4LDF0hqoxYh2B@1srPEM`9d6(2*^K4ObQFNF+n7u0v7H~ii58dm0qwQ$V=8Qwyq=n?F6-^E4uVdH$1Nuf1n zZV?mCH!V7IRka8UGWh6kwty)BU)qyNe)wzFKINk0K1E_v_t*aDa;t8)?*qvE8Hltb z+(Zi?xBO}45v)EDq(81G)S@M8(uE!c{U&BPHOi@hf;^!75*Z37Ob~(yl973UlN5;4 zbBb0k{_PI}Zxa;I9Bc6hDB1az+qZ#LVG#h6nMFnTw3zdsF4%#)fu%2w!?NYeZP(qI z7!WQsoToxv`V*X2y->mcXvcs{Jts4>?E;HT|Hs7tmtDaeWGB|7y>)Uv4R42rGys&T zKz4tEP~hz%wVJK?1VtQzz7;~(fCH-=d=tpAln?Hz06YU=sUX@43Pk~^9mYZdMwBW% z29Rx_791QY2}8=vjJqHLAqlvz0M#Z3BQgO8I+QmscMRC%;IpIk4~E|0)35<3zvhGY zd|}qHIS0y)25$8x&IV18^a#>Nz0(37iu@%210$?lCj>wb;UN8bCaz@(kaNbMVT6D} zV7YYxhO>9Tdg?jJ%E}5Mv5?Olw5Vnv-VrbqgBmSwVt+t=EU=)3A(0erQzmRiO}_-t z|DD2&DXv6%XuJO+8Rr@jz;6L!%(l-Y;F_8T03JH*61|QDKqLkn4xRX(i{BnM@TYpN zkwLLw5L&bJM-bEx#&FSVLCCLp`V(*>z=Ut)K~r;Y3uGudj=s48i0tZDEUE)Tke~p1 ze-0>V$F%&3z?=uTo@b{bTpOgZg?rf8Q{I9;3dN(ffP~7Ly}Ipq0BZpV1{Q#pcwpVZ zzt=LMDQOa@>WR}iW1oLJ)L4ou^Lf~#5!J&xg8pAuz^%+QY)?%(B4Grf_cEV_5xK!% zDtC0?Fj*Pk5r*Dd3(IA50{U~GV!h_0(AC0$S!3%c)W~JYy((A;5w5A`c%7vBBchgU z!Xn||cKD8+)w+FfAKtQL@tQR0A>$v0lC&xb~cdGUz(BCoa!u=d~X;6&Xz z{oDR;+IIeHL$w_a7XEKM5&bXLl02v*99n&6mW&lSK6Cfdyl@36ytmpva#*X(?+RcJ z6Vmh;ZqU?h(ZL_m*a>B1$|1AV`Ex`O8@{X)sZ2v|-RuZ_(8cXEj3zP@YP_J!etu|C7$RxaTHg{{0!fzX$g ziY1SK90p{u6bjC}Kn5QwU_$bomFBXSQTHdWh9fIC&)b;+Lznf4zX>j%nUJxZ`Gc?z ziOX4u8s!WCQMFR$98SAPCi}D2vmF~zA{oLzMu4A}FHR{Yoaiw~Tkpf#xj1)SM-!r(RP=x-+|!-XyVA zk+fq`t5Z6cPN4owQ0H^+Ak7^mr7n@F8V8ZaHWSV9`}3M4lMy20v%O09hW_?vTkc+F zL?Ej_&)fZ7x?p{^uwmvbDgXbHurV&ASU5U&A4Foyz)*@W_MSbDbdnbgilFHd6U69p z0t$E#D{^!*Ews;Bi2QK%`DA7{dQ*bZx|c?Zizb+fiCn4Vi6n1FI@fSM?3ozxk0%2h z!3-*YS(pV3vzRA|T(Z<0VA5tkd`w$?g72xm_6i`&O-9e|hkKvAx~NRx!HzX=ezl(P z!m_k+VrF;2Yu$T(Uu`*j2YrK;+7NCfDWhhQtn?x9q*$yll(3*gyjM^b6>29xwR=w- zyYigL&6d$d0>8NYQDN0@qm_6eqV6ifmHY?H#LP%KsUz*UO_*e{*CXL`?ClAMEw@j; z0TeAS)|D8Uo$*fp-qVKXJhV$6^13sWfVA8Vd+7?N!SnUK*x6EtuVy0zgM(EMACE{| zh8b)4j*t0}3FgWSI)F%MK@n9>HG2vwV$lBU^we)jC=n+Q~;^)M! zETWsfl!bv)SQe4=Elb9Xlu!X}ai+y1HGH_^H0*I-`sKL2Y*mu3xg{$euBONm>yH)& zAz^3Q8k&EH#Xf;ryWV>?FNYUryL?0$XahU`6HC;)Rdc@mg-s$&?!_GhF1KC1HZNmyFNo`kub>OK|B)@ER!fM!(EhGNo z5?QCN4)~hQUccv356Zlt6)aU>##-M<`R>O&g|en!?xfyztmwyAF!W3yq?aL7vl!`d z`%Lw%BQ4WPR=l$t7U}m|?JvTH10KE-nM`H!7*_AIu1kcW6mA*b#~Q;Z%PZkiV3Y^hi zW8GA~QFw=LZji~_GWLJ-_XKSFs@^Mzi)p=g+nMHKpUyMf6F}WC7-)h; zho?QvU{TB0Ltl={*h!sXAu5zoBh4H?uB@s8QCUlww(2;*({@^#Q-e!LCmBdUEAEF) zNY~NzB_vdzQp&z)z<*ypFy7}D?1yBiRHVgM7|dM1%BQ^kzNN}NLT$CDrup7*Nw$l) zGo2=)R=JtVDp_m;x|yjSXd#*9MG7&j*bHc!6ezu4uppKCiwje23VS&|mv zbo8Whq?~0Pn(zFDe(X1ba$$A(bd%+9>TAKRNIhvh80#BML?Q>e{)g*@5i5T*O{hH89q{YFL_`tfdyO@R*A-%Kur3yv9w$BCDZ#;- z<*pajQX$-6yb5B<6EtC*9Yt#3m^Ot=G|;;2zJmy^F}Ez)D$ca}5ks!9 zLfnT6Uj6+vtmWsM+ags-u-f^DZBG02coE-1iljL$?(}iLHox=7V!F{S_FLwbED8hd zTVm~Sx2I@VHTGBkid91=V})P07D4|Bt?+C*!Gi3CqW#?)Q?1tjy^{aEq&r4avEM8N zCC|siUxu2HcmEMwcr%!caVXKj>(2EYGxN>A$EM%5SRU@yw%E zQ;Ae`Ro9zWMU(5zd8n7;GS&?ARE#7{r~P)*LyNlKn10t=q%fC~iZM8B;|>j$OBMIY z(@YJQn3TLG0Z^f2Z1c;S^B+Jcmjbu&aE-2+a2#1@I@uAbg4hL^FOA%w2g z&oqDE4T~$p*j!U54XAyLFkW3F#uwga$rs7*Cqk(YpZy7+LzBl4 zmQD1^dewVEqh{VRXV5@Ju1nk_Ry?R^tDNzu7l{cVHRTg>K}4Fsv&j2(?!S7!D)Unq zXpzAB;O01b3$n^u_ZjH>FuGzRE6k%TK3u#^x5Ac^=youSLB3_Bdt3O34u@B1fJj%J zAC_vj3h!bp(#IHRe2`k_W<&!k`EN7+Z&#{ug&0r@B7${OBu6wgbr+tHb!$D0w)i?K z#eD26i+=rVv&Ii@=1`u6)0m%_K2d+K5gkuZd)=GnGN9xle^NU3Lw0v2Y&=0Mte#9d z$?XBi95<&mnSKxo4?^*a$*BG2{_|x_s!D{>I_sDNzuMV^(Oi4@*2m+^@3$w3j;Sp_ zrmR!nu%g&bN3?&o^Q%j(5U;S7)oGZ$uWHQOV99SB(`mhAGx_eY`)$bk2OpEl`AT>( zCYy2XM|$1R%#GS@qM!{a$$*jqUjDj{Tnq9h@y?1RPx5&wgpE&BQ3}o zdh%&ZmIs7R=Oh;SD(pwA6SszKL>~@_4u+-3B+6kEl$6WqF8Tu%EXWl_tULUU0!z+W)o&^F|KaK_psI|z zu5CcNMOwO~K|lm4=}tLxr<6#Dba!`mNvCvo3Q|%^BZxFe$G`9Qd1HM47&?Y|IKaL4 zUVE)MulZz1Y7SXhChJiOB64`FcU^&W2TU@|4E@w(<@EwZ5TcL ze#iE_xQt#9*nIzI7tW_4t~`*Sc_UX?W7`pBt3&*UC!B^zd%9KZ4cZ?Klsx%aUV_I@ z!lqxYedfI$;oG5Uod1T%`_Q`uy^iR z`pUmC!#m)M&iWF3;#eRUU!vw{Z7*BV?)#VhBIOA)vFtEo*4>?&|g?~v$X6ZpL2CH(O`5AN&!QqSOai}lY8wg`9>o;(Tl=>zf)gen?S zg#%^Uw}*~PbxD74G6em$vKs|Y``#LFo|?n)0MVuL>chgK)At`g25&w;%2xZKeE(8P zndbZ=P7CXZLto?66`MjJ-8uh>kVew{@3q>3TD+=n3Um2|tP6K5w{WxP*15{>L?WG| zUEk5Z1i~M%JH@$Gt8*6zDe{~wnL(X%*mS*?=)Twmz8eW1}B;7 z%EZfSwfxb-j;6z1So5V};amLpi7g$&7zKBsWKqsPn;v&$q!@XLFZxn{lZx7$xDn5Rh+ z{{4NeqNzXdx4JWwwJ%OO$JeSb0yVHIQTg_nev~f$1RIMRzu0ynLy{KiM zG0D!9hQ|7ieK*(b#W^5qB5Eu^jnzha1s@=p-VwBklWkYi}_LPPS*-sAP0q6hU;dd}_Qi za*nr6tk0>@Y!TyWTSl2)fA}@obQ)o$#p}+qQC?yex6ClsODV4UscEv}G$O{R0h8wc zcVawEM6SG*BA{B_TS6$n`Vb9cYF<>~Dq@Cj&D-&~O!3TPlnB0n&o%A4X&*0-LHGDf z+E8_8^6M*IejKV@8?RIMS{@ux70 zh7xQCTMXIZ5=Y*5qwk_Z539$dN3iy=ixTz3lGD6TY~iwVL~=RFv}>+2W;%WuS|=r_5>_8eju+Fx~3DyzV5V- z!wAlOvj4L^&GPUOBPZt?X3LV}`&3(vNoGkQ`(?mj9ts?8!ltC1Q2TvvdF0~;TB-#p zwX=cOe(ha=gCjE?ETYa~j=8Z?cW3hU-3na_Hab}u-!ikxl<0TyU*pY4 zgh(elQs~sOJcOsO&yGh_E^ePfjV#cIy#$euKm!XVpnz84ZEG5g3eO1!8B&qNC$h?$ z++oKpSpPXAgh>h$YAoy9jLPho6?K^E$WVDW6#eNmKJ@Ie>LXR)xsEci#4*&@S7!W3 z>e(ANI+S%@p7=_ZU(2`5YmZ2U7vLvUDag46GXT#fG-bL ze+C8-0)EzOUt`lDgyUh#hmgjLi}2pQn7a+4>$~&n(`zek;z!CCgh5p}WWr?Hs;+;p zcb-}!fgl($lB4C6&xY=3+*uNY;Wl|=7D8_8t34^8 z;@}#S`6A=e7`OkPesN0f&6FtfloYr}c15c9Hq4t(Ka`jIKe1p4(8%vKH8#4H7Bx18 z$HB|rY6zHaoN@F@42V-o!kXZaDDA^4s}_tOZTyx$NiW-5$CdiW?1w>GhqnbOcS1ie z7TvN$G67K1z<79G`Ntvx0a+Py_+D_e0Ja3pRC^@Ln1c#z?nRxM_Ellhuto=d{BXu( zC#L0N3N5Jjt}1Ag9nSBO33QH)3T$0r*uxqq;&mmS(Do&CS`-%>Si zwNAd8e+g$Kk7@Lq=((fEgsz`%EG#R!gCLE~?I8?_)qPJDo8QyF>pL4Au0LwL)=F<% zW>K|35R5u)n~yh5{lyb{An@z0Xu7_w|XheficsfJe^%e;_nrt^~~ygFi` zVsz~J-EuG2!4V?1L1&tth!^6P({MB~*@q|A!^yVde#rmzePUm9Mt|NAnYf2M28)45 zf!SPhah^B{*v`|;;*lOdv52wIf_vco>(#AqUx-d`-YM66Z|~)ghQQIryb0f~?hH59 zd0%V2;(kiSvZt#4 z%?l~!^_3?9Gkm4(2W?#aIQ2uO(XL4a?svTM6}a&gJ5ickC`$1vFrlNBl)&R8l`3Wy zX{tCZxz9DVtbLQsj^zZcX_^K}qOVo-n>F4JG@vst>ah$p>Y2!Iu?A9<21%>Mm9sL+ z#%E+T#Ngs-=5S&b)MfBVg!&MGE^B6TGGVmv&91ULvq#kbZUW5WWduu&t$`|vK4E)Y zRf3Yqs+%Vt&{%Lz#8Ix2;6=~_H#BCsK7Wc`smbV|udbNDES+0c-D_ocv;Xqz!Sux1 z;;~CtmM?(X_9fUG z;(@2+pzd>9)(mt`WC4KduX%%^{16J}rEJ+EVs1CCWUIQnqLesTQqiQaJUBG|ymtMl z>H&+X+nA&OYP&pGQ)^mUS!v;Xfzw|t@{dPsYBaupf-bOJ@2_oNAvAP+mbDc+^83`1S=Iw?s|@Hv8)YIYt1l zoLUFA)4B0#cS>ujV?qBVIyIu0#`l6bVFyCN;Ggm|c$H!?8f|v+GHSop&iTU2u6e~2 zV{XqP`^z23?o^y*`4*xoiydb|o(f(f`K>iSOv)u0XU$QgM-3Rct6Ci57U4A1V z0O_SkxXe(24$Sk9yrBu`<#Wg8to@G`0C0mpv_*mcpbDmyU`h%}OwxP<0WrQ3*a@OQ z^Br6G%7_BUP}*zBht{E-C@_u812RhhhlljbSIZ!0(-Be-PYB=ILK#t+{6%B`g0JR> zAoL`-=Yt_6Ih4qOvRE?!bTdf0*ZS4+=rl*)VMk zCt#>~-~Tm)1lM5Fc{LT|-471LG{9p6(^u%T101NETL^U&`TTV>c$1{0q#%VW|1oA9 z$cunLpzIOzr`P2#x5l=r3nV}{h5wS}q7zew6*Ou0pAOf_qL?(s{t0Ti_cnnBoHb7{ zewdn-MUq{*b7$Mr<)5z!c?{j=1f<;iKD=4|fXnW$MV|rlZA}^s^U%=xmFel zm%y^jhvEC|m70k0Lm`=$4JG!{BVHQM4-~yjIrjE`Ca4+$NcE0h|A6LwB&D7g_m1~v z2qu{)F6au$3aoZYP>(dchM|n*)l?tiGmGMv${@%AGW|&?^HI`kjkQMr>ZB#D9*M`A zW2BdXtMp~GTWpL1MYLt#Xc8uwaOTl?hBUAa0-IW%lkB9&0lf6pU&F^y;}G&ek%to;@Q)^do|-t*yc>vRjG^HdG(U`S{VnFHQETyy zl)Y`A3zC-rt^Mx){uYocJTU^QG9VBjWY?2%a^i-otgHkwwIGOJ1jXB$k0qZJad?FR z%60hQGRVV(Y(CIXZ>|gmp~+bFnqwjOFL=97fCs|`vVXvQj~s47=u+?ZMAjG*5tuHe zLqW3-DQiG?32hb`ymmBc3V^gW-d@|fM6?Fxp&Ls!)dy48=sC;(=__u`L@1yq^6@cc zOhiVS@%NKbk*2hc+b4e_*JfkzV3t&VK>cB77>*F`zho$BRU$QwlrMVbqgf(`$3*w5 z5|^QX_76hcU#`3{EjFeK=Q6WLW`}s)&u1IGmT7Jewkvw4c%{*VG_ZdqWpb<(FG#By z^8fam!m6;Ush-QJevKEM`W2^i=%zMWCO>*`^i*f%;t-XcBYulyP_-MJz*Ev{V>DW)Ug}EvUmC=|!{~#P!QIh(H?ugw0vwL|` zWO5naL4qO8Y%!mR*y-m>NjIrv-x$88%x{g%jM8f66LgM@n+Cr$vffLqhO~grN|Mt&3z5QYT8JW*0 zPlW`pbJuf^6iY1De{Q(muR7Gc@bv^hH+a^br0?y!InSWvFEyj_skaCQBG|mGq~(mx z!aA^&Z*ilJM1EdBZxx0b70jq_%ea>7epWOaJ^qSH@=6AaEta4Q&Q~NEH&IP!G?ML5ioPmH>|<<7t-ZIvJSe078Gv0u#b~Mm%x9rT=3BOuhJf(*}*~CsSsKnl5Lu& zLFvp8S{PvP;US%~!(R}p0;KIuK-bG{I*8c?k?^=ZE^H}0_Fn?2OdnvTLg3ZKW(QiZ zy}Jrd0Gp;8`>iD0F<3dkL(>urk_zEC!3Z5fRzKdaJ~{yNC;Uf{pAr(W>f^+?*mVe{ zkMO*Dr3wJBz`!up__)0KASEsypu7fpKqWQ5 zFpGUQfJ;MKf>QNx89M)}zW_Jy4;0Frz+noeBdFcLg#)Q%0LX?49I$|82+};pX8gK@ zla`6}UTuvgv3S8qpg}WW^=qzpJ_|#H)URu0MZG(`|7qu4InyNgJD2;-{jn$jt3`u8 z36ta^7nOvG^w;0-26>GAION?c8U*`Q_C7)QdQ41LKP2+hMH?3~ev}W|$1{jLE5&te zkZNxwl^wQSu1N=Xx`f?*x~WAa<|Mi#1*0?uBEy#{ORdN`S0{u&>h{=4g-**@@R*tv z@wn<@Yq^s+&V|HAZndp$soGmS&~ajH%L1L51DgzMCCfc%`g)`YJ0pVgwYZp|v-4Snl_LX6?~ID5 zYL$BnT?U$X`!39Qg`S*SOd(Z%IfOA8qjZvd*eCYI%q&Ctex2i$Ppd@n_1fmJ>uv@4#Hd7n$T6;`lF-SDseWx2CR@I+ z3ly7C1z_5k?gTofYT|&+M4YW7CSihpg111c1nCVl^&F7W6p$5Xnt|HZLqP`~c(l47 zJIcz?eZc{uqoV@{#XFoW{cSy5&V-(JNWKO9XF%9Xhld8NnF!s0dmbi1L-w&7{-HCQ zX0Q)DHN)WX_wpcmD=m!zIdUF_n|(rklp%~dw6cJxBq@TuH55p~0(0)RUO@J2`epl{ z&9%D*ES{?b!1J}4U=DZUDtIIuIkXA#A;9az$pj){5P~R;*PI}Q5>N&p`XdzPvk1-$ z@R!0~H&?gV?8nn7%k#@FK=@qnmmkN&$;pZ01nJ`#ThlR!q<}l*Mp}1z{+~Xh=TfX} zK!P(InruSJA^nv86wfO>@pyA#^gm|KE=IPtw7l(B)wc_j-*0(hS2~}U(+9oDWw6i4 zN9B1ns5<2Jbf_`)bi4X?InsH$0S`@-dHdn%suF>w0=}4-gh?v-Kv}sMqxIoqLtw>u zb6t+KCxH%n0CR;J3_D;sf|)3piZ}Pv+Ao$?(4VlEsucDCQ+v*BduqsaEu{-_?bkp= z%UQb3^@Y!aWy+>2Zunq%j1Y47!ZW2c(DE@ZPC(TzRzAZ8J*m}(Uk8hu)gt#^<|NBC zBu>3%!BONHUtCY42e2i|f888pE|-9(bAIB{aC+qKny>L&UPAQxy1*fHYx&*IEw6F# z?wqmO@=@eA)--zLo30F*^A&OS<3Y}1jU)YXlWk#DEBYAE-Os}8{KTy9f5&<{4Aq6w zzmVdI^|B_A+YmE^$6g5WH{j$+nG7c%E_q-izSk!}KaQapVaf+N(#(qN>XyZ zvTOHPY5XRrTVO@3-H@~uLyP8joQ*?$%YREFA3LJGoXa*MK@%rP^KCSKJG?kWy>(RX z@K&(I_GbzVN#s>OK{p6VY57x}aRuDT-{@2Hdcp56tsYkpZh@b(2!zs0E(0^mHwf+y z=$%k#EFg~Fc0FbQcl7g*XtnChk~TKwM~at(6Fo0M`0WkNtvc@Q-bT=sEtJd(-4zrV z`hXHrx)Zpf>j6F9gx>QA7?c@X=h0V>$Azp}XeJjJ4EJvTVXWfqe zFz_e@dv0AbL#Q+@6^`x`_oeh{qjxiwq9a<7Ry(N>9yQ_T$DE;BHZn9bTR^Gg;Rf~S zH1bv+%Ro|oS*Lq{V@1B4r9QQcN)qV|ZDFfg;#N@GXG&$lf^6h)YE|qtVM6=@J^IIWgg^KIph`Lvm49*)BWV$VMtl<>GJs1(E2~Nx*pXKz@SzAk}bh76&>d=GF8?p3^hRY zbsK9wZChL8h|FpZ6ByKs(a3A4J6AFyEW(dJYr6K%K%EV`xNN1S6B=0ozW z8IkgCdhRdig<<^!%@HdQpZvDysJNKHVm!46sAR7|)!heh;P0)hAQJ`jJVi%iE6kVy z{V6K-LWjp|NcgE*k2ehx>$u%c%^uD~9uq*U&(pCwD8~JCuo-wepcr+l4)fb|JY&X#xuB*mHc@83gFF`ZoR!DFlkw1bcp z2{I`@bhL;J;{&hXSioOo5RolV+Pp|p_`MDL)L?I8 z!ve0uTp)wyXv*{dj{fspQyc$QnRp#~#o5r@gILuK2Yh)c8C85Cf0eRODGyot!LfGZLPG3M@F_Li(n?>^3+DE-)XLd|?^OdA0eO+k2&!XtFR^KIzCN9=uN`0KC|e`ZT23_Lv1 zE#`q1ZGCSM(E);d+r^i%sJ3HUSMQ2XK$}$$DbakY)#J;m#R4eSoX3rUnF{Ge0^{N& z(!Am31c$titEna4L8jC8_8}R}&(3Ujp2s)h_b-G-q<9a(#SCF=f%|T5j3b zzIs!f?~uVv#w{*uikI8$O~OO->doRmIQDh(v#_wAw znom~R&tU01X5OKfiEa7sz$8a#vjw>{H6*g{t7CC-EKCk;JoiG&@1p=UGXe^-ex}6d z2R5pi@87#YJ~kwcgwUEm0KWO(PC(#leQCGELoqfg1`laHp>!hPlT|V`r3FrE;7Fx7 zZt^+uSfvFuG{8aB10Mu{mw~{vY_DP@0Gnm>L|UTm!3~7r4Tq^l^g3oSnKc_RR>x zyZkOYP;-Fd7}B<~gJuonNL_u<{IDu=|3_INoyV$rzw7@__BWiKZ_`Vd3z(V9_H$(j zx$ID9M4f$Sv8Ps0>YSSTvy<(}-q@nrJztelMO3Qz!8Sz^wXyq@PEuM8pG>k(gNIJ> z%h<;XR<1UIns}@HCmueS((RvPH%ZkL1{Ug2e8=HcC)(fhs`4wb8bsNp6{^X;5lHyj za7dRW7bjO#6E$6kw#NQl9#`d-xv=#MXgvR-mKNUT5D~&i(?qJmjYqXW+I|KP+7HP+ zxf{$SyC;O_QVf4sqSV>sY&=i|T=ok;Kl(jrB^%cq_PvTE^;Ve@j8woI<2fDVXix;b zxc=0%lfJe9zn`UMD0I|#PD$z?wws9?w>3;zP-Ia>c9^w_IQU+`vFO4$LVJ5Ztnf2` zQYaekt4n@8bQsT5$A&Q`LyPG8?sWF87%JVm#zK9R^N2%5#lIGUUK%hr(a(eYQlrXhTic z@;=9??f#ESoQ{jF!>FC-rxBaGA*Lek&rp{i!3d<)Le9#@#zyw#Z$Olvp!6mT6oR{^ z>DvF@(mDzmh{)bdl^rq`;N`=P-fWJL9O`kfwH5DP zH_jkzH1<;y_w3f1ZS{UXg(@}LudrWSSrC-ifT0+bH~eZLSoBR?_pW|WK}i*t5#_Sl z1)6QfgwF@D(x^Nhb<-DS@dv!p6hch%{alMPOJWj9`maJwO-YfZ7_N6Xuv+LprP)?tw(W?|y@;niKr-If|EIsednHV4q0b&tT63f(dhGr+y;8s> zes_N@w$JfL&wmR5#e-8O;;^Dg#%Iv+WGNhw632y3ho4MtB$xA9-t_BaCq++-uJ+`5 zbRBh|cH(F}VEktI^tnSWYV+SVQ`xw}l1Q=Iy=$6co6hn=vp4x>z+{l!>7IN9$xBE4 z-U-+q<_bom9bRSGSvkke=J0i(iYk4VS7h&I1!9kF8CCvCdV34TquHK_vwCGhq!#pG_|G~?;~ zrgLzbcJH={L|$mXB=z-$P%tS*uN+L@<2R&|3ut#)p}^gf+H%>fjKv!)B6a2)o6A07 z*}!|PM7Q@a>wNxRsO*rrOV>`bV}p_TL`EomkG+#iD!eew(9zp|y;Qyo8Cz_gM+JYc z-g8=H)h$7qvN__HK$Fur+G9`HyRP27IZ7iE+4PVW{w~Snwu;ssS}Fgn#4m?TL5H@6 z2E*?3i!iq{CSwfNv${qqrQv`eoqc}yz`M@#%G>VSUesYSGTF2QeI z^C!!%){Rn&Vx&=noM~*t58?B4t^{3^`DC}s!`g5Ax{4|Cwtj8G`4T^aqWW8ByImNI_Dc z6Otidze(dX78|hxa{M=4;~L6~nozbj#7P07S!#+H$nyH3^ZNIP%Qg@pbNNT`e};aP zA_@Z7)?~vPjnC$Cv5eLeI8Iik=}TG%jYBAd?9%!-U~6V?$r0RrG^({ijOj>tuHKgY zrRSXY>v%EW5;{GV4czI)IYJRYq3;F^JlAth%8u7_BE_vzmh-3cDxb2%k#YQ=oQ9Du zbJk*NPMMqklq@r+t5L*YnejJRjwm{+$bDRU;Gt_Y-Pexzz86Nx2U22Jx*ZjyE~=$I zEX%!V1F9H9I7ZUps*b66nC3}QVpTjNe%e*u2l(`4MFF>U%15K$75tDE=<)vKwZh|4 z(_*s)63D5ym^m;syd$H<780yJ)sc)v%vbP?k(P54kvD&b!~)-%Tze6IF_9FrgVvQ+s`1VJh0b=~sOIKJe#LH1!~N0G^`Ahja`IdwJ6 zC32xTtC_Y< zy!#|CD6Z;0!6V>SLeTTk|_*U0$?UL$k+-ZGW^|s z${7c}s+XZwe|l$azc@~&+@LyWvirzxrv9o4 zwSjF0tM_8Xa!xd2a7Q&OrU4^Mo^x_8mXRd(p!)@%}RW%uN0*59t-pExkQnK(u1%N zs@!DbD?5~;H67Qz*UAoN7SpK~ty@1?I$rn}8W(M;eQq4dUHV|J(p>$#B)BV3noRg6PZmTUHs`=x? zIwF$S>sq9HNNVo<(n^BKL^*DeTCi6#Zz6~~-rDJt8{YmP!(TL6px$)7>S^OQ+y57< z`(-^hLBSa>W~gVv_uzy2?0&rDbjy88*G5U$Ghz?Wb*{86s5BR7!1B_*8KuD{e;HXj zg2dA3cb*cC`x`QZKd{_cZm-`8P1WZix&3cNVkIot>N&d7%SZ{-Sg6X? zchLZ_zLtFdtvAuIR&bbIh4h|E>S++|VuN&kk&x^y#p}<^U>5dxgIwYK;<<=t&fuVw z8r$<-y?ea)*f=w+z-SdSR&DWk0=hh!b1j#Q@~e0=ENKl@Ga;Wm-Pq5tQ8nUmlz1|X z zsTsq<)#yUMNHNjjW{I+$9{Vxf`?qb7%aI3BaFn)@woJCg%l(t z>YoXsbZI!o-W|!J0>QDyr*Zbg%(6r8Bkjg09ZvN@&ZkH)N{pP2?AT>G%q1Z z{Jkj}D2!xuE6wuXe0sUi;`O{>NU?kOXSC^ux6v_D^RyDy1ynp5m99h}%ye%ZB~%ke zE&KgP9R_U{LrHyXphABA6IsT6D_IlbPwn^ntBW&r8Iw^I@M5%SGPzQFaa+U!jV{N( zSvbBo`8)&O?t;!KeOIBIm=I7Apf&_cQ|ff1JvyK#Fpy)$Phg2;kF^l#_2<5$`&%ZRzZqM>l;EA=Qc>9LF*2Ew7&WFwe+V*2g=rk7nTT<{N^KJ&7)>=e`+CR~tRectnQj;g~xWi&S z6L?NR)HnKh@(qSa7wuwWR4PxW2r>)ucfp!(R)iPT{qqX4hM>x%9inM-jE&W?s+@N9 z2@Ytqm|pP#LB@Z~5&x;KN>FtaIn=)(OJX7#n?94&c*XSx|Bt#*mH?t-fVjspg-Myz z8}q5D&Jgh-GT9suIcKE^MDAP{!)Sa`@e0y-vV_Cok!16-F8js@dr3bZ#-4-Wi8l)7 zM#kz5doA;4zuCnpDOdw`yb{9!`+4U>t--yU0}>2bl!=Tw>jh0{LWR0g_tWC;wE zNODg=M?gzas0N9R)L7=x;G9Gx`-eg}iua@LgiUkmliT@#7W14OfiV13T@~6-;}7da zg7;TWwkdN~$^WATSZR))ClrzPGPR!&zVyT<`{|po;6JT(A2*23+)Xy7KfGKl9h|oC z8@r}kE}d^{m@@_rV~Hv${UOy(7guMTzPoNKr9$!y-&ic-nlAPGruM5;|3ZnlttvE5 z>M>OQPRPVvOLW)QrVR6h-%-;kv8n_$8*$YTybQy4qq7?6D0sdf8a4dk<`-dnn2;@DNh zGE4)OF&?=UO1JPzil5^2+&vYeiPk^@f*)9AiCLgq?r7Y6-wDdKPXVB*Kk?=-D{z?7 zr)Okn*O`sH5Gwlc(rTJ+f`5k$+{N=XR_XWlNVbschy_aufeDh zFRGvKU!)b4MRU$F30XbTbh&%Q1#^%m(t@;j>x|f3a57b|nwFGw^!^^_%O`R*xug|^ zcnVQ8_}`i&&|ifY?gB@PnCOoUnQ-K~;Qf1bTKzI3fAn&-h|kpc_=-bytbsZe%&LKm z83$YOHbMdgL3@<2h~IGrL22SeGB_b(T+#WfqNR*BrLn`Mvk01@a{KPrbA(PJ7(-m# zBwzQ+^6%x5wo&@J19s*b755{x%^EQ997G4=tK%`W_WgNBr}@p;TVTzGrOZJZoG2`u z-neeYhxF>YD%YPDpWm7p`ytM7s;Co;)qQX9+!$^6VeNM7ooUU28dm<{1hTXK_@My^ zFeg*x3Z4p3&Lgp~=hX|LC|r*)&@$&C-3F6*Fz;#^Yg})@2Di7a=Spw>&_RAzi;2t; z5F|DcCrvQ|MwTD}Tl0=;3SieV0X!)|&g*=DvKz={dOpqT4}m5;MmK064TFfop`sK6 zovDXs3<_&dXgK)Ey2J}Kf)6`B4_|iA?oaN$K{Lo^tRy8ShJa3ZFX%=tDw* zxIPyf5gd-dd0S^P5U%{uf_k*4mNlCH5aaHEdwhU^~=(|3DumBl}jhCTy{`+vK;H{7t2$t zkRU@R)jCsL-;q`97qD3G@XU@yL+!FfRq)?_LWOR9IBkq@@PilW;!JCXmSA+8Qi4J& zGqwP-2tk0jnl1$R1`m6{{sfGRQO5HEs4v%w$dj%@+q0XQ0Av$ z^Z8aU&v)Z?RWZgZ`ATsv(ZU)yYN|tP#OPC#Mzm?{W=>&7jaJu5+qN?{nnpp1uLART z7OCv=3Wj^>yJu0O^Qi;VX}jrO!!6gbnl(`2{^b0wP5|D9%$K{LOu4#k+DyB(CS1kK zX9*1o2%QI&xW8bFz6bJ?w067O&0DV? zes2B@C+0i7_{C8! zBufv!Rr_3+p35X&e9MsepdX`RHs4!fK1UNCS;34dNu`cNjX_6!U8p3fvd39rCwS6? z0tfoybkDL1-z`$v%jPT3ye-c1Mn-uR<2$P>)b=*VabF%`oR^$z2%`^YiK^bsNOm5< zDvhx5Piem%m#weyvxX3aPu@8vjRXr){*4!9@rYV)@(7u_TkGFm;M21u1fgm%_Q3kI zil^o%=v9T)JDOXKsF|s&TWPxm^ZV*5XqJnu1W?_MDw2YZWm7!Ja&)`Yck!Og=-8v2wl+E+{HMjkWAkgMLg($yZY7F6^ATBT*h{-kqN!=i_kK6O= zBe1@+cjbU_3Z3i*XiQrG>^6`S6)R=QfpG;i!v@+w2y+Fo=-oC&9`DWo|0WKo>cAn_ z0@xue>6d^Ta%$@f@i_owr>Lqby4vf&288~3eRL7?RENS_$pDN8G^3}Q> z0;cPYNCtQXFm=51*abaqB&c3(X-NaAjyw7`)!zWG3&JD!^@pq=v#L4n1c;k_zufhRZ0U|SG z@;eQi{p^}G^uFGPpec7Caj1Pe@M+1w(jh53O(dCY~)C^@Z%hr93@Io-v+gafA8P+|Qil#b_n zvJFkKdkf8hB*8MG<;F82p+>>JA8TAAidl0)s zUy!ceniX!SR`!cp$&?Np{=hf=y_q98u#)+O_1cm(4Lp;Z3_QYQScCC^P*)-UggN$= zOH-qo{=1=)K5XgAKl01jLi-DKaqsE;^+dvlyC(~H$k1Q~FSm^gzroWz!}@xlzSuEk zvQy^L*x8o!&EC$aZ;WN}_*9O!;{jfGMW^q=r^<5YHe=!XfkEeoZIRuk(woM{@3jp` zTkegvtKi5{GC5>xa@tn5-)J>l=|K`{PJa>-wG|@LkyOBt)tz(H0%+swxJ++wC|{eM zoap#7`>7BlmV}eeOxbKoJTDL9)p$2oot+NfQ6f@8`48n^!O7Z_U2bdKd+g_8k1tUi zx}Wy(t%Vw63cB;X;Sm43`b%^9-TCwPQ%xfbq|1tebx1Ism_$8nJNcJQT@u!t+;sE8 zN;{)S``RudY}Km+6GT3J7d!UmLmR7gPA5l;En5aIT@RKn99hbL>q4w_Pw*>`IPy*Z zML1V^MD-6A(eZN7b~s_B{fIJKYBFVTF*e6De^L`cg%%rVudmKSE~FvJV<66B5Kt!R zl`n-lKyMZ}{O%kzFPBkA^|>}^0$_T4BgMgACqccF zb{J7<$(8YgZLF~Fi=&1qv_7Lv0BTOz7t7#>eDI$mEU^I?Q8VC#Onu4%TgL;Kbiy5j zVO7n4##WV0jy~`tBHn@`w~Lb?^wbOtZK2f>Ng@9)N+zSv^l2IsJeeFFrpJ)0!T;Co_1ns^AEwn!K6#YTa87Bdf0x&CU2TKhO`bYqT z1Rz3QH)Ph#_9@(YGw5(3dH)nVq~|LcJQ?C$9CfddW-!v*tQ+oi8z zV2vwO(>X))6;CM;T#!kF@e2YWA9-I2JpAo?h@iaRm6p5(y99Y!e_p_Ri;B>t1!a>E2=HFHk%})Fd!md?7F3oF;S9{LJcjovpiIU1hXV*5Ta@!bvzWYWk( z6P-=9Qb^&z!GK~pXQM|G*1Y}+;Igsc9SJRo4A7FZe$Wi~7R8E<6>> z(=-L*sY|Cw^%rn6T`ts9S_EklZPk3&dv2@i+mgyB)4kFp&TA^2cTq>vtxg!xPevxN zX`ZI6SyS-h4LMwG+PzkT=}tyh>Xww+yp5Qn`g>T8SNQDkY)gxwS2n;7IPQlR7Nih{ zxL#IZx{T(V&ocyL|NWLx-QK;=QYHTWWh2Kmx75xDxx4{_&?9|D?-owav5!g4J!P>$yfVsYzZa?C z1M%Qrsi{BZQbyCD!B7C`k_sA@H{p$xY}G1-cm8*9ABP$}(<1Gby&tqDdQ-|xG)Egt zonZ&nnCM|S*|=hqbJ3dC6cllq))iuHrZskXH|6TTH8dH=P37sA?!51K>3^GB+LcMp z(Xe3@`5*stq+98Hd-bi6C{%(*&tZVTEeCwR#vbpXl?FnQ*TK3Op{=TF`AwRho(?yU z0NKZYNE54jw)7piUEqM+U+nwa%N>wiu*qV09d1tmQNdF59MOEh_t#xQ56Cw4p;A&I zTae^qSOjO{eL_f6tSdlxSy@}>gYzHY&_B1W5@_m8(OV%MgW%=wP1Q<3v@yoshUwd2 zGhg?9iUvwD0c0MamxO`^zES1Uyerz(Be7@jj^_!#MuY1BfgD zg^V2BZs2l($pDGpmEv>?li{Y5AS0!+le>^s=5w5KIK=5)M{sV^v*f6S>enBbCUST&L8L)2hAm>oGU92V zQIDB%aqnavR_(1)dX*`E`t(oRf&oM2Xx_$v+o`p!)t&#vAIt2?Gwpf?(gKQU;Z=T6 zjSPbAC%oEon}rY5S*By^=Kgboh6WR<3qMDjS***_$kQ@-Iih$z}9*$VRg>^8x zGBLz!M_{!F>~OW#b7iwWDAJL{PcvdHhMpmMIkDlI_z|!7X{E|qO5k+lg_`@R8S)F8 zdbjtbh;o)Np~%S}zi;-g{esbAi!AMRflu5YDQBwHVq2rdN|S&Q#KMx$=cDIJ|8RZD zDR8hbso1xdqG^2fJr9fg-T7NvxY^-Ef&EvssD=oa{98_Jt_?f(skXRUO2~g#R()kF z#n)o4=^WEAE0TGgKVSAbJE9_B6kGM0Bd4D|>+$!*cgJoD^le2Y#?rU?3OC63Rv&R( zTE(R-&hdbtc3kCqodPb4=P}Rq=b^H84R*gRu~cJR+;Y}HyUh>Al*q_jm_C-zdJt$O z5m`dEBATQt>uMyrl}0Vm3WVQ^y_ClnwoYOk-S&;*t3Vz-=-=tFlK2?@&5zFTow>!x zPzk16%4x+F*+8x0!ZGpMu(|*CB>p>hp_h~a5?QYYrsp~zJg5tT%7wqLtWcogWCBq= zDG+0D)Og>!rxu3+l(GixzPl-4z1^*Cb(U$Pw;9%-h>gYw3RKcP)KcEM`1Wh76K&A|voCfzgpxk8d1}_t$ z#&l<6VsFpk?(Y75b~X??Qm?@F9RoyoL#}(JU%=;Z6Zp{yh(6)qcp zEXLrcv{GxJAQtjIFQ8lpQf6^n#NC5~0g%2^K5+@|2!pE9Pr8Q&u4lB&A?D*Km0Bf z@Hnr0{|y|R37iE(4&x?Gf63A>b_ZMY7jn3qo~JbhAOB)$nmmdNM_s6{KOP)D&duZ| z=6UV2=K`d<$C1f!s6!0`PK6bpt;rnu#WzMI3_W54G|{zymI0OhQz67z@$UB2XPB(` zeI>eYQ=m0*HR7=|f~%rNdfTj-lI z&vL1-RuOc+KV_4ZouNig(vs$gLanHCe}&l|S<_d98F|hi7R|>DK*A2iwWm8(f#=aHNF=YqN>~dXB$;-1FeAPZ%$6#c+P7uZZ^Z{? zQvZjx1455`pfRF>Vk3S!jPu5lros6Fax`85GFC4TSgX$S0qaVco5I`#2_XCdk>Lr5$PgGkyPHnw z47AL4Lx#>c$k`)!vs*wcEQq;4A?)eu%%;90SMStIxrEur>Qk*JF!)}bnHXIMv)CB6 zFO9zCh-d!RvD-w9fI9iK`ufzy#?XhnOV3-#cDZM#(-Zqn4PLa{M1Qj^Zft8k3B8tI zJNb!#F0F)aw|P=Pj$8Noa1&;aA*G?8WsW;$azam_KEvku^^TvLr0v32l9`JK#B@gz z{8o%!zuMM*E|YYsVfgKz9J3;duiyiY+&KMJ#^ZxHe-oI{5TBtFyiTR^g|B-S>8piU zyo=0&VPwK@mJ@LN>Is8?i;ys@r6wZl+itkuxACaS`{*OS5}e)@EQMJpwNCFj+&N#; zHg+kT=;O+%^ipZ1v9ittQZ{pPf8#u`O*}*5`F$0x8gfj)UfrC88R*YCdBi0%V2;1a ze%QQMZIm25>X&@=`78WT!r$wfqDx{TZpHHGNOrmPmY~^xHv!%|IB*%S?WJ^eb#m1bdUm4U=Kims$B9x+6Q5Pu{Q;G zY+}Gz&Gx#`76gRAH=EWdXTa;X0k)_vGsmZ$=a zz+YYcQT8GI%O_|(%Ls&}3^yJ1_0J&0B51i(!3%kh)zx@jJC5gwP(pl0$Zi%%#*YU? zdY@VGI|=`hy{mNk0bUrC^BCX0eS2?X6Op+GzKDaMD?&46y;x@s>^I_H4}cd8;-&&~ z*;Dc7tc%mO(*9JKAq))uzBH)4kt`;30(Q?#q_9~Gn28a^{zRJL6ig4LFdo09ekmJ5wv(!W0VAyc5X@Qv*(*3J)2fuG>PHBUhZGGy*%A(;9x z9jWZ)j_uim|GeP)41s{uNh%sOXJ{JhA9P}34CeK5tmb}Z0orYcG1E&JDh6?hCSu9+ zWXdF@N?$jl5Bxae9De@@!oaBOTD$JRWj`|KrI6!V16 z^Cb7qeO`GC@$CNUHY>ucmbx*IB?6ZgeSpZpOC&vpFJ|E=vWMlO_iK}WRXWI!hl9xS z6yVkb`kUmSDjWhGo8z=e&tgMU2nG!GWE=pYbG@Q|LJSvi0W_SRr4cmn0X+3b5Y@K{ zdPRfai_Zy0rjRQ5K0TxO5kEpw&+}x!6}0T%qK3(#WMqhATmdud#~<33d0)PufFVyb zmu)i#M7B)@v0}g#8wF-Z;5v#67@R8NMa-m8QuW+t_eVaIO{?A>`wftgdG+Q;69ky< zb0CA#d|qDS!aApip>((^cIa6Rg{gq}-KSD^S@^-)5$ zSxgcxL||2fgs0KKW>rvGi3OeckX-bABp_n1gIJ_)V7?6my}~t6`lDkD9=`=Qz4zTQ ztDKlW!TR9?mxGVrMNuFXelHM|lK+2v{bg7c(f&VxZaSq?>Fx$W8YCp78w56jC`fmA zhcqG~AV`;hba$g5ARrymAzgRPIp=rp|J8jSUx5mHX3d)Q{iN$zDfA@Fh%wRJWr9Qs z9H4IQ2R0Oxe#a_s@hreHg#~~i5f6Hb&;NMa*Vfi97v;xA$+1J19QrCaBw;RHfJe%G z89ZNmTLzQZ0;m|WbHM?fcs(UBY@XG4Qe!F1ASWX){_G@pGJj=PO;;b4>gyFHlbUYz zy}vS_w{3eva~g~|B;=<~+HyoVHMXnYc3v2_oUG4_AV*q00P;0~7)*vXv}j8_SNLbC+6 zsYM+~6QHq!Wch}y2y64atBN84$D(J+dw)vrYIUFMuDVCjL}IqUblN1vV<>B|)ck z&Zi~+r)P@Uew*XMC;Zd=?gEcT(b51SLIg~jU~bUcPZ0!*ik~La<;M$QP?~tNF;bBR z#`cw;Irjp<@R{Y8^2tU*SnPf~r|KaPEf5789T8a?FSQ9-y7AN$FEtezLB9hJ86m

QUhdu!D` z{!j3WwQhL=GYLel0M8nv5mn)ifG=1vTmHqyW-H^=6!;_i$K4gt)O0Tj>Qf)Dp8%zpEzmh#T%1$*?q;^|{EFrpFsc1TuGoWr{6{cL6- zZ040e5;(snxn&Ww-rwKs9&i5khtFW-Tg(qJet4TR51SBpEzs1|bOb5}XWTy%piwvk zxEa3{pk@TUY9i}SA^;I1hIpDW$p;^33lQ}(1o!kb0S@pfjhW^5s@3{Ez-L)5$37Z> zkIaE>A-_jZk<1~#3l}t zUaqO)znZtN2(>g4zG&7%L?3?h>2$6LE6-GEJbdMgtBQH zI@Rh-r+1Gn|Ke6q=rG}Ohp%2FXHIs@Rkfj;!PVOjn+Mhn@zm8C?O6G-$EsLku`sK# zd2q`zkGmJL)wkh(T`0Qc*aX|3(Caz7k1+mvyPb|Hi9M7$;=iEuS$aA{Is{MS+xs(? zYKq&-&Cj?k;hKHtBJHU;$j4JfNwzD8rAI9VB2Z$0QChZf4-lr4S*rrY5X6@*=`R7z zHsDMN>E1zM!A4wmDmbJ1e9>=kSaF-50bk|?kH~(#IHgS8%?5q>V~er4?m1|A-z7xp)72yB{5hLEs%kWg()4ui#c2~geZT9+h$z0?DZUv$1wA z*CN^?@2Sp`^@ol`B7?Lt)|5A52;~?ZjdVN{q*rsNO5$wc4s~QioK}Yu$u?swp{$XH zEzXYv6l*arR9A?-hfkGKB?;izwsUJQ*@6;`pXld)8>dS*CrGbv)Jl^*N83cB@f|3o zj;M$qOjO|VyCOcu+Bi|jk(a)Zlbi6x!kWmuK@L!Iw_0_lHT5EtPJ4o38n)5#{e*Xm zlNK2vG3Z3VHWPs;YaHE zNSw5+U&+ON4hS{vx+3U*K^U#QR@gYTJ{CVcM5rSoY^+c4JsO$CTs-9yW|8ps2L0YG z!hl|5{abhP;PfK{*l^@ijODDKJwLiWtn(JdX^oMu8a!V)84~jtBgxNI|D{gaEI*e@ z2R4}8OTUD`e_?ZG3Fv(+%fy|x6B@lJJU^?K1#o5Nr_@4ka#1crM_DTTJ)2Xc{U-j} z57Oh2w(k{=N?okMFq*~c6J`19>rk#B{5MqSG*AH&~!iuX>K#2c%E+@?aX@p zJnt3l=D!nP%$UXICFiNGl>aU{a5;;yx&>s>BBjmn2n*kLyHMyC>KuTvQm;qAJavXq zp2g4+KRQ|$HAt~#l`+&98?$GGR@V`Enhir+r0{yT>oGdnStm>Ha%b>yTM!{K`3SFNLsu&ZAnD@KxN5Bj-zp z$Wv~V@q>DJHxi#CG2nkq)qOb-%G;sz?7Iq9%#R+=a|1jKy*inL4G{vFH1m&i#v(+sc-Ftm<4p+Ze8n=3W^gv6?<=R@h zSz{&RXo7E5)o&lm?={&l{2Mf|Fuq-7{E%=u?2hjt=OJ@NUmzhR&Qtlp!51Om?`&}w zX@KG_T|Ek%fNY(9^%~ylS}t!}>Lc+(PSsU3r0)_v(=m24co67bBDB=RU7Kr_|F=%( zba~`gQoQK#hk3fHmJ~bam~8tIuzz^`O{PiZAqhcD_~c@9My$i*laD8p_k+iCuRQC? z(cT*F>fBeV?y0}tYg#$kgr*93neYu)Rv9AF^5>3N+Yg>a3jY#A`BDZ_p0(vssA0#V zu5z(!lqD!XvP?_cGd>}g)nz08x1c$DS2Kopb(vW{LCi4PO2YQ^x0D^BXwDa>`yaJ6 zwH@9E6v~9{5#*TDc^=H7?a$re9bJ3Rh6h7+ zh7CWg-84x!^aH>Nz4hP>@HL^JS&9%q99I8+gJ!lkBfCZv`_?m(lPfW(Fw59=S|?r1 zlMl8G+U0uvL519!z5mSGxyPPP8#S zSTjU}I&S^dDji(Bpu@M1h9^rbz$Yho()T+NR-4|2@AU4qW{Oy0r0G2S?r<&A=fLrX z_pu}u0vTD!z(AP0WC1lM2!ry5$v=PMDk``j$Eom22;mV>Wg)^q7fp1f|J`o7xVI3Q zg+2(JfLdY7KnM0$Ywr^9CgX!NgwWS~fRV5p2q-YSd5%DfpTe-HsOT}k%m^TuCEMrZ z1-K_<+@Rdd)_dz=w^066IzW?piajtRzzA6d308AQr8g~(r-&)A@V8U8!p2-w1n*~% z(O%@x9^Fiwx-Rp5b|x|cZ<6%yx43JOBCk)S)DXrc?rC0mt#HrQcoLpx@)BC~sdd?T zt90`+XQ5Wk25Z`X|G`-h6s-jRNVUYJ`lXcJrHz9k!;OiJSljh}?Vp^nBH<_Dg)92B zp+JV-bi+A)z7Vp{F`YbX4@~Oc(cy*e&({jvR~Je#q>YhRo!57x5p~NaE(F${Q^MZP zp_7G5kECO1$hWkW*nOz6P%ZrB=wV0esCL3juKFrEzzYLE;hL)GFlCD19k+G zu%I5F%bTT#IKZ&2rCY>xf^K0@n6pFashE)!0-B^&L5e~T0M=1pP`{3R?Bh@Xkx_$! zkIw;Vl)M|l-U0%J!1dN18j0Yyw0NHrk@;P3B>Em?3D+F60AR1Gz+BY_wk+fU6)1A?I%IO#;jx=u&MjJl_dqV8(`|4-Z_u;QbnI&?-N`qp017 z{N)Wxq#c7n!@FAV&zNu#eZRYSGXs*itJ^dPMM8kFAKXd)J9p`3KmRoH zar~O}42i>$15;YXO^4XKneZm{`wBc}?;z^g?eqX`sa%HW3zs|nRHUCn2t}D_KVMqy zF*r40BPy}lGPhNXBf83`EY~KQD4&SQZ6&biM`{yh^=OJ4a1fc8`s5g+D-+`Swrl@+ zdw1BLUd4{C8*_!;VP^1>NQ`^DJiD4*GTfp$8_np4i}5&G!n>)}Rs9+PEkS=j?Az<( zQ_^S0`epML4R*#btbQAgLw4+$`0-Jto9>Tz9!qbU1M=22NZMO85qcg4?-v^tk-JF3 zm)6YFMQG4Zr!Wu2kTzYJYuf7F8}msjN{#@UZ4Mwz4^Z_vF*zBSolVsO*hyHxpFgiC zytZ?NHZtAy6z3IUqyeiZXX=h((+T6G5FoMq8EB zh7!bLf}&DmV#Sf)ffMi;VgXUS#5D_4isG|pLER0lW&nml%L&>uV9Nk9k_YmIIFU^<$OBIX z#AIziQLxh@6}w3vv>n8UP0-Zc@+G}Sb@&5OrpvX@?Nv3}ar^K+wZwVkT)OKvuY)q< z`lpQiM#Oh|M6|h=y2IvuEUF>%!?=^vO}vE|FW)i-za=*;;gg;e*BQ3djz`ywUwfIt zjvDfiibvnbbtphaXg?&QAp@h`Ic15Kpj!wf#!!puxDvSZOhWow>IS#%7}Y6X;Laws z>f#V>C=oflgfZWd`W~%YBWMEk{VNtHHtgCIFRDVA~FZU!0 z(<4LYu{I-_4i=xK*hQNK6Dtwc&MhSMlYw4t!=1jJ=}NOAL8^Mn%{X${pH~lJ8Rbmr zF@aZH=`&dlK925bB_j#5Ona{_?Yga3N-$H2v$H{YItiei0p|VWe9_$$)&X9rMlka* zJQ#qO0pcv#0Wh>EaG|LnX$B9F;sMpl5)8Hn;A~-_41w0dK>+=vk3QJyHM9@-+z*U7 z^s7E^3iVSsW1lbi`$Mrt5HlkIRGjQHH{d2mL9EFe$r}TgLmTL}_5kW_rHRX~{myLx zu!7s$+Z}>4#=&6upjNh=U;<4_ILI-AZf+mQ;|qi0JmSUA$w2Z~^!fQY0&C|lYXL`8 zx)vWJfG9Xw7gJg3EFRUP_!S5EXc0=dU(ZY|8ue)Tw~#*gZlJ&dKHgAcvnR=ttaO)d zkz9*W8!VhGYT7ntVNfcy*lP9(ly7@Q6?`hRq+b(IkiLvTLBA#N`KwXG4gXA0h9f{` zNX0{hwHS%!JALUxovfMeCWg0gCML`}MyBDSHTv}Zry`2DVmYcg5yr8nv_&inCMBnw zZbW553XP{UIr$uBgEx4GSZ%Ry=XlJ6uU|E>WH^cctO#Yq@Slz=(0!Ti!*!kE&Wu&H z(pEB#0&9WWj}$P8j;n|gidN>)4EA5#5oD@pt&OtpuGu7l3gD z4Rd%=0X}LuOaj$BM{1UW{oihje!^$={|Mi1aN}(3l18m~0eJvKh?s!)h3H`rC1h`Q zd9*V5ObtZjLaZ3HMO=5j1jJh{SXX#54t?Zr%yN9s5n#7K^UVwik+5(2XOY^jntAA0)6zVWiwSO+;LYyjeFP2-0p#u; zJW3jDwy~R3&Sn@}gEf2`GhK~xTk7am_6*;ms%aJ~j8Wx3;>r?bglIMyI~y^yiTt2` zOMWI@Gk20MvnBJE%UCLL+(dhb8Qo}lLGL6zW$nc{K~jJ5W@4f;CSbG-@S-F6T^E*O zuBt|j4Fu})yaNuOe!>-f056^|je5`CmsFrc(3hJo;um6miBFxO^(yWwCw^wCOtC&c zT%q77)45&PBw(?<%e;KSx`P1Lp)Acm1D72J1^`CkbT|2jg@3tl!+2ku2 zz9GAgC#iVH1D;-p+^X1xU!80~XT1L`2Ee_7m#p$=>0=<|cm;0dtj)<`M!XOpd{{`L zCl8+p*>2BxoZWt9LPsRRM1krj6CBP!&G{-Q8Hc*pp`5b|8yqm8f8%tdKm)Y;kkgxc za$yjqCI&Pl#lwP+RUde=I5?QGhR3>`IMjDKPXlPG0y+@WBLl9gIIx&_%`>brZ|LIC%xseS?pz9x4MX<_CP@p8*en0hF~)#=5FL7@)hst@kU&L zitr3^wIb(1)XZ27A8+*!8moU2-^(w3H$5dXvOK!OYj1ShzFLwR)&0;0os+`S0nJpU z``;cPk42xoH?_xjz1L=S>@@9FD$}c}=(oSG!XoB{jjfJy>?kOQx&T>)Y+Hwkftpx(C|h&9l`s~l*Z zbJba%BkV!1elXw#12Gg<+u@p;|23iC&HU18524yZC;yDK1O?A{`S9DG#g{RY*G+RN zp#<c!Xh#gAJ#hd~3LuPkyz= zKH8lzAF@k2E~w<}NOw$m_vkoN?jSjA(PG}TAxVy1rtDJI6KN}{xzb~{@scr$v5rDj zO71zU*NU%&=-`P!iaPV*_sSyVhS|Gc9n@fwl_kAkwsIbHc$3bOeZ2IDAS`@-&gWms z;8Xe}dwHRyC}Za*PNVNxNSZWu_Tw7MFYmh+1Rpn^TZ^ny!i;s>!Vw0s`Felb7_IM z0Tm014XDUNzvF^A3T&X%e&^qE%#W5kFL(6XOM=Y>d7+@rmiz17bdX95)DIC;d&OQ* zL?9IX0u5hK(>iP!2u`~}_GcKN|9m$2b2>p8=JA9qZYS%5MJtFWvR!NT||zuW6Mk`{y_nE6MR>wPB$wlYml*TeeGF2VJt38q9EYk^4>RC_ExU; zwp?yAVL{ig=fkaT697_q>V4k3OHV^*3lU{V^gKBl4<9Nk9G=rnA9!9(=K? zO`nGy)UZsG8W3q}4ATlTAC|?G2_KX}i)3{z&)+y@jb_N>!ON0;>p5FIrWAq7hA(X# zkM$hB)#dd8rkc>k|WGgHs6?aEQ!^L4}$`)&HhUF5}!2HF?CmBmWxatItu zA<_-uA(_2BZjXE?Ws?@=Meh6TCbExwd)w`?T#C(zp@|A2 zlwGfYRth3Czi{P%Vg3Gkrd_^$3EUK>UHkl@WvdM5#bSX)4%L$#~lS*fW`RyV-7rjJ?xi)W?a49oy)AOTIy#1Eh{?{by$ z=fXZXHF9aWywSo(E-S%`;-wDFRzi(y;Ch&2bEhHVjMZPT9rfmp};pz(tS(Eb_DF21P4TmjQmh3L5 z&pr!TQ;=&Z*>o#;c<2UBu5BqT&G<6n z=I!%^9jw*k*_Svjuy21`Ghm8`ZOreo}`~QKiANSRA07i12frk^k@w(i$LjuT{(0QdJ z@b8J2Xf_hR|K8B8HnZp267_31~2((=ZK8ZM5*A^Ich;@#U80 zw#5JL)~%4uqlm)7??HHsH_K+B7gD6;-mUafJFllS)06m+OV8vrGF#B|k?HBrEW*oE zp7B?0PpIgN8xplYDrM`r9pIrMPgj;^UNPoj_NDb!!Z=7`vYF5$XEeoT791JV4Ei?H zo!+l|3v({1xcb^)e0}@z-HHC>;l}u5`L}uBn9hs~8puXPbEMrAu|^8jlWj7DgbY)& zrf_Hi=Dv`eKLJGA|6u;dv4wsO=w^6$NgWU_jWS$gX28TTjL19Oxre%(7R6J3-z?X_ zjwvM~shsiad4SoaTCQm+jK)6ucFfzL zUO;gAoP(JV6&%-lFl15}I@JXG<()dou;{)%QNZcmLd;Ij(Vph*`CcxB8yZ|u(IRM0 zIitLJd9>{F>7Oc$K$Ny*fs4&uoqmxpzl>RK)`Q+M-Ek!hz=W|FEU$|3VikNV4=$1{ zMFd6H2I(kyIgx8cS)-B*7B}UeKN%D9WL>u8TyhKf+DFtD4hLc!UPc6# z{X9siZ@YNV?HbRWROW98ttqF%W*!<*EtvO$wjOSg&n4G?(xf6)&VEd99vb{YfWUOC zX%$Ae;b%?1kJ9KW@W4WmA72Qh9sR2vhb|OlR5(m8yqfsfE-JUJ(IX7>5?PWp+t}To zYh$F;AwT0vkG!baNrzjOO@-5&#t#sGwOi2f`c5eSi`*eWDHK4R|F^_cP10Wqt@M1Z zz_Lp2P{Eq2k>VtrGba4-qafBsdu7~lMQO}SiT#t3vlMJcvs>RnG`J_E)N6?J28dC4 zRD(FPK21*j2(nO3FbAm+2-&8Yzl zUP8$e^1-^LHuG~^O?lUpWlv(S{CKNV973=jTbM=!Hdf|7zTHTvdApPDp1D?whN=TKJi}K6}P5b1;d6GSILmjF=j>Ad?_-I3X@`&CYMwTX)M>&Q6NcM7 zqL=!_QM#j^e=@k#oa|^pT{u!E`X+ty3)^@6w_iBoEDUh=Y^iFeu*NTTp9H_@Pj2S1 zsxi2HC7k9X6rEje)JfJ|#JhHU{>esKg+KKxVan`_IQBMsuE&E1Oa}f{Sv)q;*RMQ{ z&yM8`)T9?0SBbqtW%=kGrd~b%KP><)c2V-aXTj@$CbE*zes&l4KBc8DOXRY>R1D{d zBAzgfIv<|$7Ui(!C2jbN!Sav~xL-Pw!NFVnd6~dU{$sYMxE9iMXeI4-a(;`ugW3dJ zCisS`uTN$A#{=XJQDkDaw-i5|_v-9QUYwk1rQ8l)S=BW?=KF3hW6d#QD$M-0^Hhp5 zFLi2^FKM*PjqgYaB_N$g6>;WtSfcJvmKPYz)Ycrsfp7Jw6gO_^hMlBF zJjip|_?5>zqvBq$`9@3H8yyuKL{vLs0CFtvhDk%0j2#%dA9c?V!!hzx7D^2Z^gkLa zv;0QEE|9U;QP34+))%+q(&5tOq&wF5?JkZ}mQF^5LlAnT;JhRIrdvS4qE3ZziBs;B zcu`a7OQOO(KdGK&Zu!I_26-E9%C6D@0jnJndXC_RYVVoKuuQ=3Jo7pNg=$-!Oa<|m zY*!1t2Ux5Nel~ifzZGIavIgZUuPTi0_mthz|2=iy&&s0^#?v4?63C+V{^?%wSSMIR5gWFmNBv_03Jf5cNku0k=HCQp}Bz%pj z+X$aTqjtt3HO=1COpaIZWI4BcGX@-)-+!i$>wMt4@rMPhwRw;PKC zDJ;YBxjBh~mmb08;g}ZKW!j3P8FYifHDSG-Z3L;xI{44?y<_?i*L~ZOnSW~QaF|DF za(t%aBM<4|JktiXQ7ZIYx)E0fXLOh@nQ;3wO(_iwb_$)wbRV^%BF2#dyP0{);SYRL zUmV=H=t}rgDCXl%#sZYiQ@2QfzUG^%wSIlZ=BgG(62{l!A9rjcDFC~=ZC&9H>v$QZ3p0C7Dco(CGF*>B{chzQ!~<+T zZI1+^J?zU_uy`7caeyXYlE?F89f8{Pbma}u^9Y}g@H=jPd?R1Usb2*Hu-pw!=KrW; z)n^C=DF-ewv@|P7iI$c_=DTO2d_SnNcZsEcQ0SHHm&OhbPwwEC?EHn39#lC|A?|d3 zh!aF7v)XgVI~U!Ka4=R{Ik$_&P@2rVQU6`kHMS1&^I{uw=@LF@(Bh87i}ZEz$&iSQ zdUUiZiX(lXP<5VH1f(dm|_l8g9R2pS}#=P$Wu{hnB&~{P?;>4*m$5^zi*doba zpG9!Ts&Y}eP*q)usENk2DQN!|uYA^C(oz=Y^i7?0Db_d;DV@51*qKt9?OUNlOl_5D z$m;a@sw}5*E10k#MIxl5t*y6{6jaau%MK={uDI-=|1C_mY@+~6#5rSqwmwR|7!2H5 zRx+8!Pf?0^rLwgphIs|EZ5a+ad;4*bujYK5OY~nGx{2|BjjNGXV&$`}{xVUAQTob@ z{FONtkP!Yd#wpB_bymg-tA7-Q%>J{+#tH-fXB0BilDiG2Uu|YxLD$%3Ae`H0358a- zO#6d7>A#`jUE04+-`-K-;>H7px1~X<<6Co{FBV)KK2KELqwSK8lt>rC)?fNcFHwJ$ zF}0Af`6|@ny3J_jYSW_l8O>0he!*?|wKuU;$&ofzlKuvV0AWnY^D$@==}hI)N-t(; z`j*J(a~GI4Cw~!<9N))Z@&mbx5*%`Nr~B~m4@tTH{nowp^329%E+zT*x3KEVjP2v! zm7deX9SaDeykPl33QXO~SBqcwE1M6V0WmWdG~Pzw(;op{J|WCu);wHpiCHZ>hEW-0 z!GI8dNbU)-QD9Yy`rV)AC|J0M<-9GBY;M1Q>9JhdPt~_Zf1eRPq0qj zlr9-%Kv2*Ez%lwxE8mYsa{R&tOSAh+fUqDRcOm@7-V<3o6=X+Jv2MZ2iBgA+Ap)!1k<$X$LMqqLI#lT zuF@_aA1d}AmdmJ-VlHN}oV(@D&WCE+yZ_rD_685P?Dt2!=Aw<;!?m_NkDqn^cy2BF zsgk`TOA`~`KVy;HMd#SBvnN~<`IPlAN#Jr8DReuc#8quz9v?2)V&acs60q_n7{uEa z{+m-|mFrWF&Sc056!~KLX-s2Xb{{bOXjg#g$^1dYy_ED^_i(kZ+08?QCWnbZCaepF0};ced$uJ*mi z_5S?spe2(x^Q%|c<(bY>G+$~GkgZs(h4hyWX*-E?6IAp#4cS(RkT-Czc)#M9iLswi zEH2l_dF zl@fx~_&#ETRHn>qMiD0aE-l(M!eu&OAQbMQefT zK4!$dwB0l;#9s97;fH<0v)YJB+XD${(W^<@)(JCMh$N)1LNwbA_t&1#;w@0eTvzR5 z2g#7i$5A1{wtv^4R95(5gmONa{MkqqdN4LC`zE(vWIDpBF-{7?8Y4w-xE7@8-Lt>(i=@{S86F(`O4H<-8=cNce0C)^Lmx0rc!C2! zj;l5!L9Icj%x(P!scw|1cQ;9t-qV}omBrgGB_yA@bM%he$~HgjROUyEZj`iUyHO8a ze2Zx?8Ppq3(!^}nF=^Yi+b$7#2wbP9H=e7HbsiJ>n)|*lo;n_Q%L%_PIAQh0QAPuf z3>Q4QYSZr_sRgu~LpC6gdK&@E{;)%!F|y49_f|pjsi2@ah=i}+0JTfAO?5v|Q$;I# zmX?6gA}mhswDU`At2lvr;QHMUAZMUKpIBUc1k-PJ7aYo#tpKU1|eD%I<0k=FmYXTVNg)ExXihwq6w1Z4>5Fip7g9 zk@A-6_5xc}+G+k2TdWYY-)W(;-=~5BN(=lD3EQCoy-FmWBGtlg`hxT^a<^xd*z;8g zAJ*4M4pnL7j(*D*_}@|T56Q7(1yUhV6wfo2C%oUpwh5j4(mjWU-Ocl1)Czdb^~?Z& zZ0&IaqFCSu3ylsYq{C_4{gKSs5m4ev&N%Zg;HvTdj{_8JrBI6rY#Ah^%itC5H=msV ze4WXUTGY+9y>DvIV_kOysS}u;jvyzDDIhITeQf`GTQUL}h+Z_@Fy21YkR|>>XPbOZ z(xn}QX(7#E?b!bTo%JSJ5l zQn#}0nhkQ20on)zdIMg8EDT||W?2{qga8ErfAI5N`#&w@AUS##@cl3tcgqnX(CFR! zQFot?OU6S%J7zH};C6LzeqRUz{`%IXwRdhD`SP(*i;_s4;4K{ud3k`D*tCO8Hdnoa zK3*)y9~=UanyCMKYpCB}pL}L$64ovXp_f9(t~{3FPAzfV!XpjH+hf|y*Pe}%aet$q zt;hEKCfT|8^?KuA#S_n^$(A9m`1;&#$Jqt{Zu1-ws%Dirr1Ie3X7e}z+94XM#!WTB z@gJ}2c~0eL3ooX3FD-6ryK0LDCz&X5*VI#F4!3NNO(NXYIK;*TBAA?l?z)>s%Cl4x z&XRBkUKS&_936J^((htpG*%_U;h1ryJXK9}QW16(Z8^2-_6Inth$fu0$}Tqp2b67x zh73LYosXFQG?8HHrR&RlB`C+1S@zC0oJH5yK6%VT!tNhS=|4A{JEWZ``sk#( zXSa(*b!3>GSo4CJijZ0jr*>%;h@eyfl9}Ollh1(-?b6z+w<1xscE9mH zzn)LdaF(FBq)9`bIG56)+b_Y3z*TTk$`E#>yI+&MM*_apouB96j81Cm!wdORA;D_r z=H?M~EjWxXL!LA>HC!lN(AZ-o)MGn096C>9Q%g{Qn1{|c5~m;isQX_qXN5pf{!q^$ z(1JnbSSvt(_V=P8gK`)$MFPFRGUyTL0`~PIP>pfnJpzdg!TU{kEruWJ_Mu4{Tqex9 zMD_zGA>57_$VmhaGLM6+J7oLmDGY;Z=;{=3d=@2%>S|U;zh<<5i^GBpG}&)!2)?*=_Xw zhD!C(!}nLL5^rP_UF@_Gk?{OK#E*S^+sS=+kvICye)YVvevlPq?Zc^FNk_N&+Zbp0{_5Z?YD9-R@`J+_%JXl4GU#%wwnI+u+2{MdbwCp++$%wz3Sx#Ho+2X8sF-0hwOp02Zs0OC0Dk9c)LM!I5#m(b5 z!|HLDMw2Rr+RnnDPBxQ1x06QWp9a$s1z`<3FC9Lk>hopX6Eembsb5eMX4c?oVdb2d!6O1dGGBH_{>As@k( zYvO6ZSE9n0+^dw0mldKOH#il?9U-QG(^T;{p72;E=%z=pPz+i6u8zN@ z%ifdF;ymOoK7~gW;wz5RBxPBgT*H>X9r@K~s#re!I6E@-Bl^ z|1~&7|G25_8hP4jZ5R4iuybI&YiXZ?;~R$5t#tV76PgV!*ATK5)9X;a&LZt9K+Fay z3dlFsjtX${^qCpD&EZdd|Ir~(5{XxLuECip_E`dS4MBr++SnZz)BZD*ncHQt%x{-Y zwuTQ}2e-Zc7PlcUSX|v@{O&h4f_UGg;iFbM^C}Xhz01Ot;Q*$U1-P1t9q-SYz!NqN zSSt+&{?8D-z4!XJgwz#sq!9$>{%5H2!YUGwT{5S4#hk>c>nWGe z#3s-lIED>6Kq`;&l=dyC)o&3!zAYE5~b7&zwTFI@tw`S^HW}25eN_#jZflZpj zuN_TRO*NQ5XAiH*xSUNrWBr2jPtlCW256hx`!gDN6J66U$H5Hh{*UPYyLvyYJ~{Fw z^qZ6!WcVD0u*ARv!$Z|)3QQU7s^PE7T;sOq*xZ1i$6)gwe z)=z{GWy4}SB!9I8VXXD(8jHv*H)=-kDW07o^cWkYz6a_%7MctzI?-V_r=#IU!MbS1X4tzSZT7LZH zad5b0CS|u7T{kRAV@gXS_Fjuc@9``d+Ul_=4^x^b**ssfIQ6wWF()C)7ua!Pc}i|A zfLs1MQ)i~?7cbusK~7`JMReZnx9zThcmEG>uoof_Z!61{CM{$^|EYRKn1o_J$nxU` zHzENt4sZ?yNyf3scBFoXHQG&{ykhN^0Cl*&nr`Wx(B;jlzbV?W(O{bq3j26=b<2$a4#;EpU7vem)AW3+@Pe;z|M!JwO_|F$!CmhXIK7X z+xxO_IWpGkGkL(e>s>w`%lt)iq}F?&hOe5S!@-io7d66pQ@zhD{dia7uRywsNR28A z2=vIP&+#Y-W&huJ20YDXc*8+&3DT_!#6I95^(+?z!Sy;FK0Viy9!EPx;%Q$H`okUM zwFvG6ixifG&nv_A@KsXIH-7}!{KyL*8IBFmezd~-wt5@2N$;|ug_1@H?@_wwsd<{C z>CqNXznL9l%S99?;n%U!aP@mQ0pfoQ(ghshbP+9l^(lBv*O+ImAyQUdFU$H_P|1rliU>H#g8`A#`i*8AxAw&gam2**_l%n{(?*)Yc#M9=u;jz)Dc|%c-zn=t zY1UBAND}}PephlJO2j8m{2BNEyNsukVY4I=kECczrj#=-Q9|Hp9Da>=cmuQ`^yr9QDOM&A^2z zmX4I~YMnfB32Ko}Jqp3I<`UPJr;C~+yrev+-F($%$DxsqS2o}pyj|RQ^_DJffxMbZ zL3JIjG-uKpM6Wj*)5a1Fq~kkIKnWq zR>pM0h8=1E9?-lLKhuVymwbQULx~2(U$dh?{LQ277U)zBazH@zf}>Rbw2#AFlPfzE zL?{N7n~+rsRArsKcRKvv0m6r94u3Um=t__zAd(!`#aHcL=84j3^wfN6KqI|o{`F<3 zDvN8_!vnv{lb#xS{1|;E>|q2cGkwh~HKZ@7{b<;!R4ru{Q)**eafxHSEO+Ej-l>YPWyV zDgx`2*yKvAbYE<#Z)9j;ynbtfrlYQ8u7Bbk+&NIfkJQSEk}hkQJX}wVw0?GL<^-kd zfUKbE84%qN#a_`sckO$;+ADlErS<({N`M*x*umn)#$L8O+~0Tr77Nwq7If^cfFVPv zr41Mspfp%u93ul=(om-3#yOP!V@?)khxd8X+U*?_P)Omv;0UG8fxy#hz<#Ylux=`J z^1U3=YYTdj#6+7mY(A9CDkwQ4Hr@>)3L}7onl5d4<#RAjSBXw3e3!$tjRN!%GXsko zBy$JC_+X{Q3cIGiOh9T0MjA5!6g2?9gT-*EFO`;3wZ}0W)Wzdm`A`83EeQGY!{>Ye zpkU(mh!q(sR9mUAYdc$okaM%JHLsFy&S59lz)1_L|jZAE@O zDkWo!r8^e(Gf~z`ozO|vXhO`1Cqn^8es|WKtYugc`x75(cVUdQcfUu>f(=36$igEF ztAjAdZ|?mKbIlebBPI#eLaRCc-iXR=H;)!B{3ZJd{k>oh&Z8*}e}7Zwe%B94a>REL z$2z=YR`=PB-}XF{aH+f(e3tWIYJ0!SU3FXxqGe9JY<+f^Y&~wj&K`|$SN-LFpcWE$ zCw=yCZe;8ESHh*-4{xzjJTCih&B^8eX#t+z$Nc%8BfDZ+s_tX|Na=}bu*L%H=V92O z5)WeXX$uD)ymMr|TZJyT!_BFRe}jS}bfUoNWic`@mjqcz$JlE$6?DQybMp(4_QE74 z%uU@!pM@&1Q767gDd%dANoOp;yaQVoL9I4CGw_QdLDiRzu5od7{6G%{sWZoK))Xlb zUE`s`64ZJNq&f7Y)_ELkIy0iIlF{vj1dZ!!2^XvfPhiI5!JL#OyP>O}vqr(0pWa+W zM`k$0mP>}Cpo3T>S=}V0R8HJLKh|!^{vxePy!||{gB44En&MN7)>n((nPU^zZx}Ez z<^?xWo|XsT=B|~r$54t2o##jZWoEV8z9B#ob*}WX-}eIeBo^Q!1WPx6E+8{U7Y{Zh z>5DvrTGpWSmst?rQa`@{PH~0Yz{W?Cb3OId0m9I>CvyKI0hYY?5Cgy`#A8*1h#x2o z8+bDx!XdjD1k!-mWH}Jef(}MYtvF9;vIm)s-B8k(iQ61XnyH^i-0j1h=%EMekoQCT z*Y_e>Z2J>Bh??5)J$V#-Mu*@axON44{W3S=xf#cEIl1HCa-9U&OuwQ-^$A)OW75#0 z28r3Tkc-2A){l(vw@X^R85`N#W7X8o9N%?)wRbQgHqJjj!gb?wetP8-{%8##v-w}X zgn)VVBnOalw+HU+7T_`Sx&HeV`-xBt5{_^HpuJ%ZAesi$$E!fOJCLEMq@-lF(fRAV zf>usHWL1clycf1_yJCVuD1lqmYN5gL-~N1BH?CwRkWVLrPv3N7KVKjFs@2O8?9&aE zS>QoWFC5&NE}d)h6@@53Mn*>PgOLKDh|;Umty56L`Lo(W0m``tKz=vi39vc9FmmPY%snMw;HMJFQbP_s)WU z2hKERr!tjomty{2XRc$-M-)*?-v#GVCmwN_)2akoZVq6}qWv>Qoz;DcG=dnDiK#+X z=$pBM+llsJ8kwcUCOmnXEU~O1Rnef1S~)5zm)P8k$UKUKxv;m22*aR;wC1Hly%nPq z;SuG8Qo~0>+LWKK$;C}_^vK7RRo?P`8qu0CmSIo-P8=qql(xKU{ygme!`6F;V;#Qz z;}Wten<$&iD5GR#W*4%vSA=9`tL!a%MoGqP-}WAnJqp=mZ?Z}Fp6}1|JiqVrJ&xZW z9d(p$xBGov=XGAM^ED`}b97e=CRbR@eDJwtZ!MTvyX8&z9~jDc4Qod{qqqz;YQLfdpETl$1(-t}^p*a30=r7K2!8eu9sbsmSyfM-`3>mI=$O95P z{(Tt`O^8!n1nZMoFbgs{`+I=cc|)SzK&^`%1~S7_8g$y!g|zvbh;A*wxa!msln{Dv z#>|~o2HwM5ug2?ObubWdc}oQ!dknD1jRaew;j;{?$o612%oR}6c7x&R38I?HVEd1? zEo5zER#myu^{M#T5hNJ6vlCEoHKDn{ALrJc>ID*v~ebF=-3?a7ba74Th3BiY{MfYaq%o8q(`7X|)g)fm}bAQ*1UM%$_?QhSd!%GK) z4Ac=`7}1E?>K$|??+{UdhZ`#r`el6d8s=N4X@)Q*MAeJ>N1#|&BKhfTu~2_6`7FC z-bZ-o@cT{9U8HGVGk%zM=hoiI#$Z(3BpN@nNbXlPRPw4dH zoy4xcpIFa6>W@n;`S)XmPuy1W;FHl44`VYv++}K4+|*C{B`hbF(|W~rmlH0W{0#{wFfAuACm=? z>*VwsO~+pjyxD`#ek3BUm&BTLgWgalZb~zJJS)?v(c>}*lL={|f&y*b4UwnvheL%- zLB;`K#g|;DUwaR%cwyky0cXl8?feHUqqp*Upgg3x|H=#qO}$$#P$2&`UL0MxZkCTc zfSEkPx9EVn*bfyJ1Ie2OEs7Zwa*(j3J3Z`$+3PnAE&VpB>!M}Ltn@7|6xSd9n>07Qp!a)48RaJ@eGz(hLTtJl9LppMxf?RDfz~Tn$ZYcgc@cMkfEqUm?)(U3W zi2~LXFuymSYYpDw+0C+o1fKsSJU6|+tOHX%s3+#I0f8Na_o}gS>J1H|!2q`Yu2^z7 zE-|C@sN*qsTaQ)PKA(=fbPWm+C~X|$RE>+dIEz|tGyygLKLIOX_qH-tdb?j_kI=L| z!W=@Q!8Uuew*>h(hKGl@j>6SB+Dh7KyWtpCtb8?OX1Dj)Irt#6m+02FV z!;fz|lYhG|_auFT(ey%u2l#5`pw?0XA;B7P`ag##c2zyS9>_gEhK!DlSC7E)ke!p$ z6uu7GHgLu|0CHb7!6H9b{Oy_}UJd-sJs`WNN7fsG5=8`DzA!dGb69jlY&`QN$MJ0l z2_BgYEA3!VJE%3Z*mzh-M-}nv?RTdNCab$cQcMN=uvN#zJ@pd5IrO$+y2n{R{#(*S^Vtson|8GkO&9GnZX0`-6aTA`Uvf zN4SW$Em6yuBDLS>;?AWZLjPxp9M&#BehN|(ytl(Qjw2-~H(jn^ryApbcjmoAPxbb< zOuns7XnRHN@hdOXwz1Rd&$a|(XE4CN3j&Svlm533poiZm_fB`6!-EyO?0q6~x>4%& zd4quR4wj7%#;2T|AUJm7fQE9Hv5*l1u?{{5AKpE1>iU7w;KTsqZDoj70V~JLadB~5 zMS~cK-a6*?Qwt>0H${-UtT#EC8mRV^?K1 z)9LHBxa@g^;#KBi@-_c8L2Q(~i zr!2hm=$uXV)>{&C@>{tm)Lgj#Q{I(!S>Mq|TdVc*eme0T{);s4h*7wt0l`}Viv)DU zzi8#0Yzg?)UAR!^ge6|2wQJ|WU*j@3?m5&^nUQlmymTy=_j`}N^Ao%GT-$SEo_MbB zLwsTrh7A0b_@>V^*6XmsrF0i78BR9d&oGmA;lj zKkntHWk*QzKx~&&R?Y2buP;#RVEE>uX5w7$4M*A%3YB>sT=l06IN5CPjLoQb$1zRu zC^%mK{gd|8bcBzq=KFctpIgNs;WH%Fg2$%^cBP1*Q0J%mXbsR2D@o?uz;Vi0)Mh>i>Y7@JN zrS(8=O#L4uoaW?5q<1SA!LC5B@Fl$+jN^@V7djz2<_e7DZtt%RheFr?pRqR?IXOa8 zoN=Xtgat$^4W)CrK~q!nv9ojeQ&CL~jm1}v8F+6t#}}>hP^b_z`kqT;@n*zkNq&A9 zKt=-Y|E9N?S}HFya4mSM&e8hjvwb4FBr_|l?W3+Q5Pe%%e)!+7d&bE@Jx>xK8I|zX z=MmGS?_w;C%s)TbE&Y?9*V*q%5jm=DA1ikhZu@FZD7JsoCY;e4` zU`_7B(o@&vtZYtat|q`7y7%Z&J^9rXDRF;|3WD{SzOvo)P*Y{8Yb9COzZcB>$L8^g z<@{ULedn)s|HdzPH!5A__UzC2gL-D2QL&eO4++k@;*O@BYlTA%IL&!8MT6*r$txo7 z>;`k{S3bIE!5riMn36S1z|vlKeS>zmwjUo6;__ggg4X97|x@KXw*Z28nslK<}<*r&nzFG5#}B(a{Mu*U5ig*~jt)n5~`*MaW2d|jj|=Be0f1#z8=X$cjy23N});qO6vr&D6$-*2F;q0tt8 zf4T$siQfU-IqK_tjARq=*+VnFY_59=UOj?AD&P;@#SR_fOYJr>xXKUxz*ktV;HeT5 z9sRx0hJ^%gt8VYfeHv@HGyts(neE;v=Ju7Pb;~?u8b%`9fKky6J#W?NR_zU5qjz~6 zAc|UKeH8go49OBak}U*ZAcXH20Xy*|C{H;>5D}p+jrCr+b~DJB3c2$T-h4n*oVN!b zS0BqDvCtrG+wm_NHT4h~m$RjPc2SR-j~8v@HbHPt1phMwunw{fjPRG%>#wRKBL* zcGST9{>O6I75bPi#^>chO60jkkDBvKp~^pt8rJg{k~!}ir)wN3{z<>qoX;4K6&-Fy z$Vo2Zesr>R&bBDxI^ialdH1CtV~F(S*|>W|0v30!^b{RpelV4(Ab%44xiwm>rMvSq z+O(~sggKspi0pnXwdu39obN$w4Eg`g966ZmI@}C?sqy98NH{!^kXraPmmF`WOdve- z{qGJc%cm&NzdBIo=2ZL4?|-^J^qs)_)%5g>yL|h_W?B;8zf(%wmB0Xn*yi(F4;FIF z*G@t>RYzHK%3c}J&ZK?!KEtbWTz&!%U@2M?Ty>onPcd!@zcHJru(g?Kn7UebEd$mE z(kmYMTS0?{gjZ#%u}60@17j+&XbM=>d~Y_i0Z~;jH)jEI)bHN=GfsSkk0Wk&B5pp& z?FgC%Wh*Oo=(_)Nr39movFYRp+!-dP&GERHCl7;jpJgMRI#;*Jc$pQzMX}Hx{3>ncpN0U#h+Mk(EweC4B9M~43LSK?w9m}HrTaI%k7u0#t+)KQH@Z3xTgenbieR5L zo^9HJb&VgO&L@2r(2UPFUB13=PLAocJ^c}oTYI>q+=KQ1W^1zZmdj)_(t&R|cEU6P z0EO3G?AZf=6(KH92s#BDhVM`GEuv}Bk2 zJ_>=i2GbmePbiSr5y*A`z9Z~90B)i6p(ze7fTedA9Jis1kd=|aW|ECCgMNN%M@!$C z90}(Hm#`O*!G|O+A&}-rVV8Sg00iAd8^kgpc~Gm9)qLUxZ$eP0*o1^Z*oO!hG+P_w zwzq_I)ajD=M$q1ah4x3d3?v{102pPjrpBkdp|7ds_*yyb9tv)7Lo9`0fZKzdGVo5U zhEe3eV>X6c@D}DNn39=6TZVX*BdFExt^<+^1&)E66&Ikqa0K)R0cv1J-%fL71SS%C z;xPcU00>_yko1t|`4|#Dp6>CkS#2KcdFUBy!J3V!2*T)euLv3jvuP zIo&5Wk^d^}vb6x;AshNhIE0e`wCbDk-v1%X2OcR|N=YpsqhA>*qJs>d8tWu3PR{v* z5yNE=rocJ4^$AR?kSNQBDnG9u?T|c(gqch(cbY{*M%4qgifwM~a~W0Sb{qLc@Z0!; zKkrp$`R`~4H|Z98=^U{+{0@)ll~LWCe-3~54rjUCzYXa{2j<{EbJvM);w3Cg?X}-r zrYk+{?$6CDVEu?{=clF^+L4ZyMhBsHHTOkUWdAv>thQc1CeBK`B>rR08#{!Bx74bs z>0W7&&7DbFq9k{&&!@H@7=6txXjoe4XRhJ-=`wEK9g|M#NBr2W z-moo(IwvJja_ZN17FX$JS#s|(7qCVCK@qUkshC)X_++w1#a1aY`r683dA26_rDj|1 zYPt||g!-HcS|}4p4a94AFj7${(H?56#vFQxFT{v7c#C$i=xF{Rkx4u_(Qz`S`1T3A zLCzuFGoE(>JXocz1( zQ?>*`JmGIoLW5!vWCZDapyW4PKVFY^dGL31o;V((8&DaKA6APk1>D^RP1+PKBoH{t zB@Ysa*z}t_^Q;pW=`4ytR@5lW9qrV)pZFxfR48gG4Gnb-2@MT187uzOsiD%u#}vg5 zSSsJ5TNMd~2%d1qJCSP{YYg~=&P%%8QDzu2iDk;Glh$nJ-IzR-w!eX<{sO5_(a|Jj zRky}%S9D&YTvQFUq`dTRtvV&I)#!WfZy8#8h|8YO=kLi6Yo7EAX(c_0H!pL=6pcC5 zDB?rkAQbgA$D0umz*96zyumzJA>qy)Wx$wkoTBU}Fv?hp%XFkmDxEl|5zv;ZRQ%7g z*z2*MJl@2;DmtkZoUB(SNtk@rMl}*gSDCdWS`>pB+7_pZwyr+?(u<>ecLL#TB5h5V|QDbhOH>) zlcSc0MB&T3YODP4be`P0Ca$SIPcbB(w~9M_Y;LPs^qyt7h# zq?G;iV9AV0{vIkBOW;P0PGXi_VT#RtIX`n-la706ZAn=w9WK%ES7y9Q?^Ao(Ta+#< zP4!)|j>UDfiFPOr;+2n&(jb>-ouRExkI^*Bt82i!WXV~}}dh`B_!{GU|?LGh4KA zb!T1d{%ae7;&7tHe81&SrrVo)Z&dHW_Wj#~Ybi}6m}XDgx><1rq;N@srGJ;V#4D?& zk1aQE6sJGOX8NBU1fOzoAcGPv*PRp^#!Y{6?GFm*pImwA)TMic`%a<(Q3u4D5u5#a zCVxn@B^MDn*Oa|Z9Kg$~bh*2Oe(l*MnM7qjm}}<@I4ZPH%}5CwRbbrsY?wsIJ>+(RDUUa>t(#^!R&3e5-PSguJu~0{`pIb zZk-_kEMw_cbhq|et1J0K^sF5}96K1{kxowVKAIH472Z=|($V{6WT#1{#ZsO9dR2yU z_fKjycKSB)gY@@V@2S~H^Iq`H3Yj_U?CZ0e#Cg17>utV1KSlYUqV(U@X`7#Ls-n(| z)Gz9Z|L+gaC3ZRFeqzaUr(<#%G3`ctt4)vUjSf03@Te*LVx{}71V_E>Rr}8EtKT}t z;~Q}n)xT-ieJ~%sW=jztsaIOLsKs^0TCBkte#Ie>A*FDy_c_%iil^~{oc%KuqV7xm zBvdt9bT6JHE$z==ZHc%YDjuB+xv||vn$L16P9pTP>EtRe>waN139=Clu=A;-n5ah0ci zxn*_3%b1$t#9(iSBeA04Ei}UXKx-yekF=$Q_uoR6*=VTEi_cq!;UBM3JpJ3r!9!Sn zGdF`K7>%|#uruS6v%nwhFfo5=yOxHZ9zThF|zq8EzUQ0Wcs(qG?}i6KEKrTvd)zF6MPW|evg@&d~0(4^^H?q_6UL9 z2S*0By|3o4?7#Z&lk&f+>6T=?xjOfI>QK^9t5%b{VM_IiPpE3%Gjc6x6Ato!U~VE} z3&BZNp7V=loWYRrNF5?~brc~wkfv(BNB8ZY_iu({Dyk)Yd(cMrmNmb--L=r9-5w7))fIrsk)<-LGEm*gHr!*Ng{theK!seTWe)$1GO=n+HSR5r>YHtfiE%$VEF9vd)y=pc=kqtN zRYdhx;nQ%Zy`Ff@6=@-88#w-Ao#-)z)Kk+{AvA3IeX@9i8MayMg)wS#<#N15*KRKF zQ-XhSG>t+&SlR=JL3kD%l$O_PmETnxAH5`Gk8fq{^g7~KmyZ`ny0Vq-Kj2@4X~etU zpSOWYgf+8wm0=GxE>4o16->dl^4s$bw((b*e4kZ;=NN2anToUR)|DCYw~eoB6F}3A z^dkSg?Qv_d$G%MdIN+D;z~x)lB=%ccG_oo&GZ^OTd@^#lKWt>Y7p*$ItbDd!ks_rS zL~eIs>=*yVf+Xubij58Ro%Cp`Yw4{mbDA95@sz@kC^107-s*$zEE9Xxb~MjaL1wE@icaCLf6LDf98nqloOkR)W#50V2DJnc?Bz*8y-yviVkbCuSbuf^rMfPet-p&}4`6sQi4 z;3{hmUyg?Rhng(QJ)4wkHi$q(q+^)`@Ri-Y7ndiA|G`UM^K$^X8-^ctsqhBLw^m#YU2A$nD z-Q;g=i;yv5l52EN&~;brccR0XIkj7yxWn8I+c3#lHZ7#n{wg@gOUEQGX)&&jvjA|0Y$deK7+Q4t9IWR$=OZ7b9sLDVTL{c}EJszwHCC35)?yXl~~L+&L`(3?CX9p|p7cLtJFk zudc2>0AvP;7HtL+o#!bCt9^jN6fMmt(Vr%oBwWex-~b$JmjK_$l#Qf?Nzb*1E1&B6 ze}Y_}Nj`d;rwRx`B2wGa_43Rl0Nf-3mNYXJukaP&&eVGxJ&rdA23}VD6D>bnk8AP8 z@>j7S4A)^H#@1sm-<$g6;87YEi-EdNJR75``cKQznr9jVtKUM4MZSJlvAig*s4pT% ziLX4fU%jEO!>D1XIB|H3TC&wSW#fTcE7i2ueA|FMHu;MuwJ*80x({HNr^(0250l;0 za-8j^;}mxl+FR7+CBK-&GydEblk<{m-*s@{E;^~s)Q=aS2!d2f?H1|&tN}junFdtW z*pUKyXj3ZMJmC`umXvmf!m-%3&o8NTlp;SWL@z$x{`$#$@Rj1hnZE>X?ONI%<>Or; z=G490eobTndHB%i6Edxz1AcDC=WM1Xu$6Ay^(mg7vRsONU1{!JL+iDbz+d)6JB6~U zL+jECZ=I;kFZX?#`{QWkH6&9ev?i&0%bS+vO8BRoQ=++#5mK*2sTBTxd9E)%T$yDd z>vM}nxx!25+tS-t7K2v|OJ?oTOICe(j*n#X#{TW-R(PV*Hq-4)me+dK?Is^@E`7|b z82K=6AXUMNt=4i*>VLr#VH9JipeMx{LdwI#I+hh{mZGNcuq-2A@wx87hIn4uElWq0 z7vo2p3W1lVRz;4*A6^&x(Dmh7)^3jP>Vq7<&FiR7%39&SZef2d7-SB8^GSX^N-b|i zyMny;FEu))Y4n=K)y*}r%*}u{GVZsb(Qp67MZY}{kA8aoWGtJL?Q||Zw%|PMr?cVs zTN**N8e=B%i*d=$!-6eCdkukLePQ;(+$knUV%0CT!658?J0TVHM-)kd1bFhPW$ur9 ze`JP^}J z_W|y2%9)Es(_~@i z_I|-Za@imb784;50PHzG?XhhRuM8**B}8ab$VWd|N;E~Nqgs&NOq<$?OPqX#Q}&Kg zF774C#GH^27Qzp{W&sj{`o5_6`Ln4>gV70v&-6P#6V*C8eK}%fhX>xwe=xtntx7g- zp;AKLW9!h7$;+8$mY~TLljl8BX#2dvwuJnkb55<{eB?2i#+M2)W!8_o*qMsaN?fXw z14T(sW36^Fg$>aeCitbFIdu3svX`3j_VN3^9;N!e9x{y1CnGGcBqT=t#C&dL!N41a z*@e;*xNn?%$DWztOIwT^bAtb$QNdo3XzulWhE6eoI4K{Yg{UlMuL++U&ztuMDh8=i z4?Tr!--kFhjIib75_X?Es2g6Zd->pni|p)T8ACURW&O;F;-UE_j_t$ z{**1^{X@o?{?Bvo>K_PfUZGR8uT87Ar?R>DV;;6vw5x6)Zt$)?e@RY8Lniv9*}`3b z@=bYrme}=2{ts>L{ZJTeczQ#H;-w1~Q2?o@9foto0rBJ?k7c3J8%9pT-j)5PjkgPt ztStlz2efSU$CoRJGdCiG#BeMrXzOYdSfoJYpXds_e6D&|0sSrr+IJBqA)=$j z;CfyWhA_Cm&_DJ3>~#4|O;1a!eSdY(ZS`wHPHyfjMC2`ixj?4J(blO6KGOy^5)uKv z;27O#SFkHZruJ0)mLKfW;lQ|O-bFU;eQJw=FxL^L0id54t}y*{gI{AnIUpw|2l8tC zgk9rDZLaS?FX)8OxK@DM`oUWRLE3rh_eo&SEdwZzFxi|=bMyDJ7jFbWO0gbb>LN`L zZJ$>!Li!)l!3$(B!6bp|&BiG533^RHRQ;ORFaB_t`tAZ6OK!6sK=bO4Xd@Vx3qgjW zcB8i_44i+1?P@E(GJNjuQK&GgyFRez_YgW70I2^(bQ8qNi=Y+=fy}~Er&TpN`>$*v zr&IJn|IHn900t)}B7Fs56UbwKt{}TOT8>$-g@bmcUO|bN(UX+QJ%9@b_ZBC`ZQ4)| zbq;)VrcsQVrtex8gP}tgi!dc;Dm`A_yX8-J=UU%WRCeMRQ|BZu)y^i;g zs{WUh%&;fVBXm)<(S5as`n-sC)gC*E%3=o>pi_RmJ+qd;`A<+BtMw`*k|7M94(wUSYG+t z%!gdfQ;64Jf=wWnpiIm34Q&bur;j!<|95*GA96Y`r95q^Bq1HmvBEc5IZ`gVaV*4R z4>6=GXuJ76e?3-A#AULcpz&Yr-uGz{l(kI7h#BtKq6!d=JNkORUNL60sHhKy>)i;4 z5aAMnp^qEz1rau0C?(GlJSQ9@U>U&RVGly1KLY#dsrN1^k}`sjL?UhpBW@a1KuUlN zcM_m;&6N#4`I5tSF*RCltp!ApcA%x4KuXEfh_7LqZw?A&0_70NnnWyL5c8GaK+DQ5 zEBpMi9TuIqvhr1Md=P`xZ2L;mr@ZzY$9Z2 zWDsZOZuA3SQUmSG5sZQEW1NQe!zgEUIFAyUVgWp#`7HYh!chd=z66#S!gYi9b?LNw z5MllTUGnmkYi66{

cO*rg7@UZ^^o29`e(-GF3&o>~ebmlES6h+88;D5D^P=!1?< z>L>{$z>TL<+rV+Y4ezGz*rZDIHX#z_2Zx4z@cI7`x5{U&hak_%4V;FhBKytmA*BG= zH^&BVVe2CW$ZDkU7SrRf-w-76wW?}#^V`YitK!kj*Mv8CH4F8|Htc1Cii_yw@4XZW zMxk<0KB)25_Ze&*Xd6C z+1j*mc5`GE7uClMlE*Y7*kM0GX+Kj_7-3=n&k(I;G{!TB%sy|KcRH(CM-VI|nl_vT z;-06xFoi|zW167x?t?0wB}$OAng$|K%eo@X$51n@!vFb1^If_ z(ci8K+eC)5w76VZA1PYye|yen=ygC|pj(cK`1M2eN7y;QYgj$Uzy2C(H=ozRSU)?a?qAjo8Dq#tNAkm+m#KU@?1!2dZ=Ml{$;H8)hten)5l?HX8Bz5(Ay#KTRs|?^upGjyq#^ zZswPL=XM()ioes1QdU_CYE{|o=ilYXUL8})!EI8cuC91E$d!ZdD98Dtf%+M*zlJCw zQ^L&@6O{vU=H!+jv28Kq5aI2~t#~x&k=QG|)T5j%91aou_xZ=ZC*Nwz`nlz@g!ik!z*(x(9zin&KOOR1bgrtC)v1QO$A$3xC6&|MKj2_qs=cR*^vi{f40J__6maTndql zqIYoS|0sBVe`cq7xi&PM=6=mD$t%;#*1z&E{T_Pu^k9=Tvi-}NhkMeff2+HY1)0A8=1x; zJplxU<>us!<}LpRo}Iz^f5>0Rh#cvS;7W=9VcOl*#m33`1tzg@uk{C#*Dmxm{O&!7 zE(5rQh@XXLQarE*5h_omorVTE{JCL-5bDP94z%R~2q%Wi3#OA9r&TW7)3LF!uR#{0 zrmw#l;XG2P@8*S^%i$41l73#kI1bX$u__tAX}(=OdzI-DxyF&k)l1ACV)q%9?MVL9 zY)sZtC|<(uaa?7uk$=ml@$Y#X=wYL)t?#}Nk+wh-ulVbCjob#U&x=H^zoQ6M)l++{ zDvu{4!}4$8IA--nJ;S;zuJHbI?hl-q+3R34gcHva_`JPXo?Ro{IQj9bJJc2AYD?M~@5y$FN$(Y&@s#lh8QPmY*VsEE zM=;!ivH09C9asJQCjtV=qRehE-!T4rdGXsos%IW=Mh-j8XFf_}X#=XA#SJ=XbXAxV zYFd<4dv>5Y;V4V_?#ECuHOz`$8^M$pi%xRdftGt56Vyz5^cP+P=O>Oqk1N+Q16|8v z8C60CI*4`dtWp&&4Gtb$b+fL%%Yk|<_&iXWx~({JgpZw>?`lg&sd#eMrL2g7XJV&c z68@=~a41CV?`pc0EjwNm?N`11sEh$i=g!W&(ZSlVTauXn05}2F@nkhG8~B}N>#Lc} zjIKJ3_m;qwDW$d^9=#h@>`}E;EHYt-Rzc8ulDOdlYE~<7mY85ePvCSUpFN25(7@6~+~ST-#TfwX@@Q;t!&=0ikUZFw);uoo#JAuTZzK6kKGQ;^eg`}68&c~Ty!;m%3D56VFV?KO* zfbh$EC10F_DDn&}eyOGVc{Di;3RCe*wr=v*J^rDex{Z*f+MiDR;ry!SA1jsNic7g% zJ@R*154;PSx>LZ z$EATgi0mxYeJ%GNkUS7$sW~7~Ex`3+0eOI>5p*Cag?lx2q{wbiiv0mRmH-RAOK^xs z!P74RYT?{rGz*A=yN!CEfCO~}n4JFsH)BnlGhlo+@ zJ)rm_a<&?v)AoH7KG{pZ=;?@JqA8b=K0eQ|9w|iJ!$BDs2l%P64h1NNOo1x`1QRq6 z!l9x;o6v#Yn7%(9q7L7%hk&jDJQ9JAg#&yIgsqFf2f!AC`;@}z;U-+&eC;lPe~5q( zh!WY$VH&xC4XFL=zxa2(X1e%g{cHdYLMneMcEbGi>sN#-4p>||@X(`x>4Eg7;P5o} z9Tx+k#z6gTE8ne0Sha7@Peg!a3noITPUGi`e6*2F@+1&rwFDfe+4$$LX5n`vUJUtf zTo620+*t|+T9}9l;{WA)twOq37`(lK8fR;<(+xg&iw?+DaQquj%?cyJ6sNeO*8!bW zHFUuMtt^3+kwg2(PP1Yz;eX@2gg;lE?wDFOp1V`d*7~q+IC_vCN{(;MbXZ6h$QUPS z8K858E^Qm1x{>Q#d%rNXG~JUvqXT3x+)5`~k&ncWkmF;cTC+9xa+ zScm_Na_sbEGe-iQ&5pI1^r}(!CWDi7@k2AxOx2tzhwENq{`y7gwi?sUS8FMgB~2-Q z1O&|Ec47$Nyo`9a-xK%+e~;tm#?C^JvJ;sxy~9yq<@gt4>Y=Ui_i5}|THB_Rf_%dF z(Tl#fH{W2skv%Qhc;+qiI*7Ljzo!KqjE)ylkSZ~JTZ%x*h<73^bYl?QA)5d|jAWok zWv%+YhjP3Jgi;5D76f+@#}0UK6W=~WDr^of?@$v zE}f=n&9mAT$VZSpO^q02BFTk0IXS;m9s7_(yjQhIm=$;@{zgPXAiF`(Y=rm0gOD1JbkQdL!Lh8+hXD^VW*5NQ!e7+irK zdxPJS2)U<%t*AK=w~&PmiJ5nenlK=4$@!tn7U3wqIFGu<*SfmY!_A59TGB`aHKd@o z{K$Fd4r`QLRr(7QY8URHe758KYPqqez5~DvUZLFsal;OD*)^@h0G8zD=I)GLZoX#q z2&lK9)A|47EWtZ%o!SOz8-dZ=gx9YTrk4K$1NT)H@3VEoQtOdB58rHb^m`xjy=pkI zaG3$sU^1MZNK+0iophu38A1%Rny4tK?T1cjgQGct`}ucZ-FHEO>p^-dj~HqONm8N~ z$sKKbd<&^f><6uKrbI0qa!LX+ngW{sJR2fjs6>n?bF)%r-wH-i-za6%^1@Gb&NL0v z{{%K29=Qe*KV=jbaozk7Q9f|PWprnni%v9UH#d1Q#53e2r<#a#l$k%LdR?aeiu3h= zrR5Hq7k3LgI6^4sKluI0&7v;wOUyG{{-A3>9+6^5Ch3}#m6Tx5BEpd_tt$SJrbm~c z`^Mgaq7b=2{g`^+Nuars&;+#mOvP>#+&7EYcEl zYlu9f7!_DwpkK=j;u>BAE)Su{`6?{>kZd3 z9}$-nw4r4Col~zqpzyG&b*E4Hf-&!uC6B$@FWkKS$M)}OT;POQzYnP6k?A@xHq)PA z8XYsl$Pkl_UX=V(f-c*d%xAaqq?!hUdCkJD2(d#~KNkAz4$>AkE~0pI9xiSIV?3^I$#~}YJNjKuBaZE3HZS^X71F4xw0Q>2V>!8+ms)q!$uvEWi7#Il4J#5mqblxqR%rj5Yb~rl0W|)#q+}T%y;}Te@@jE#fLi7qdL8>c(x)eW!Zs7yG){ z1mQnCBKpLP3?p6Xjc7WaIbhG~FL-ReOM}3$Hi66BAa}=8Ii>Z$8oJ;DqWE% zEw3MAl`2%;(;k@57gyNMTRPGuM{XEFA+VV#iIE7Tn{CiE)avfKp1}8MCUUYNRjg(F zFpcSVO6YG-p+Bf7pJkddS@-2;MLldzQJmoR->yFMueg|DmgF248-9!O*BjF#$kOah_hNcC=2x}O+#P#>VdPs z$`}`#%W>%G)6Y`bcc_xozX(2h;Ta*>Me}54z$KA7|8w%E5k{RA`)BxZ+8I?pP+>-# z-~KabtvwT0sp9Re3*)>+q3F0EZIvaH*RDflw`=O$z^xDZ*8VNh$HaPh@&?_#ns*ZD4asDFFAdUZ_wn<$+_ z1h+o}R~hD*ys?7NcJ+81hdrmlwb{7sDRDN8ui+EZ zqcc8m-T5})o4YxyLRM~+_@-F*GYDWy+h?`#gfv!2o=&1 ztg7mdQ576TBqpN|Huk#c8npx#r`oMIZTj2-dn2{#7yY#g7E=`;jIGpFhVZWEO;xlM z8h-wL{=53&g?q4)2O({3i4_q6QE<(>#H__J24CCSE^)gjdJ#caBaENYGZrQ{A)r6} zy0E>@^uLQ5KYEo6O_+tsV7nKR{|Ti#ct!9ML%zy{3Xyz~Z2@-mb6t^HR8U8 zOF-&7N1gadUgsB4+}(FwcDUQ3p^Nwk6qMT-S7`q+0UMG>?72+j)|9Gaq{qR=d!je? z{%~;ZiIdW{UwYu>LPql}$mtKb0;7U0< z`Xu}2cMvN(@ILR9R^#_eDx$S|vlRa#UqY>`R#YzDHIiU`L^0EKxz}31JI`C|6Zh!@ zY-4IMbJY(<`z<9|sAP&K*F0>3`h=H zy`KV6vmV;V^k{$emQ(}xfcJKl*Oj1;lG{L_YbMEhs=QoZS$Fs&>$l#cWyeyYTsEcm zna7X5a6gm1_76=|$J2b_eHdMAFk#||Z^TbYY)}5bIcpXYD>{T45~^lO`Yo|dSSr{g zK3QwS6OHE+(mqkW3uIi?lbrY8P3GokjjB-u6pNrNB%*)tmAerYhFN~djSdh3S2K9z=U6jJw(7vt_@41D#l!>F*G?no|Qr{ew8 zXy^H%z1EMTSvL$5pF<{;DG3L^T8PM^v`B`xO0=JZJR=jI$=>s9QQbwe@6GrhhvSyf z+DOI?rQ6DT&oh(;r3p&f$4m(gKTRyh7;5lTSssmJY?|)MGujo`l|FU6{F6Xu7JqYn z^i2IJwgUr~)}@uL_0HjFasiQ8gTw}|JIhr|AHoBOKt(!Z-O^RWzasNcBlPFw5nA~1 zqgkqW;&>M&xsKXOUDFTw1in*|k79a+pGx@j)b~Y)vGj=0n7#hjY=8gpT(HgM6J6Xa zqAiam2~9g%oz0IlS0q~ETMFkWm_Ta#zc`lzTth<}CKG-7a4}a1iM}~dC_sY8r6@B< zt)&IvV1^)9z~)V6QihgqV;_wyi_keG6)Df|5>W@SZJ%>%;83}LcL}@Ss;g=0S!W^? zlJ9WV6R0voRrJr8w*L`d!g#X2%>+7WJ}~wByYy7K`fCR_Vlr-K|IC`YWHZs=TcaK@ zXU0eN%mdG#E4uf+BR8}BV-0iWuVp{1si+rh7h`0?{hhB!^>Smm*U)mSN`J>~tjNkn z8L5bl4A@=1WX>QNXM4@_6dQB+<6S}jtb1Y13wl4^|D*q7R1xhZc6dBxy~>bb)|PHh zzA-Yyhx-gqW6PgCFLlouozwDrA;j(Ti#@)$I?ZA2x>3rG8SO+*23HNc-fCI{^Ass< zH@Zr)!h5|j#=l~3@jpoW&h>uawb(Q!nS>AVzqKA4L4uc`x?VK(-O$A5v$S`fxTfuQ zWY#to^#8DiB}5}e(Oh3%Qp1q>#*Ld%;VepFHaHrgwfMomwasOW_x|>;4!$K)ct!kn zR28PIwcg)849f1!&j&CjJ+!`W^GPaOAw=PMb^F7LkLq6BDD%7;y>5y!x%Y>*^oi-_ zQDu3G6|q<`K3yciuIM4wXZQn8YqwY|DEgwx6dOAD8NkxPOA`|4Cuu~tX?B5Ax~07H;kC&&m8gsR4*Z^ zX%eeh_BlV}>J=wcW`2Gu3bmGXov=AgZ-}4Zm3HN-=8ClwS9F2;U8VQNW>b&gLOsl1 z=IY~$CgYCZADdy8&$7@WH@AIwl59QlnN&9Y!A)$0i2;(ZZo)98BauRFq1~pY0lv&N z)Mn#2#}SXdmU2yDvXWQ9DNlS;hegNGNJjShkHLe)B=<0z?`Nc0Rxv#BxVQP=Tt?^D zm>Hp~^4)}<3*ip#NA?rsN(f}O**eE|5aUQJTKwnMFRNjCIM+x#*WBs28*#g?>$88F{QXJUYLCv8Z1vYY*m8L-msb7Rah@%_ z;1K%7KRDpHT@oftOJ_fiCw@I8#t65Xa=N0$=5ycV{a*ntZ)JujPfJ+3c&|6kLKv<1z#-v6{_0LYdk3O?y2y8RyoXzsq1l zz@0lKe?WZ{d`G|L_z=8du7khKY31EIyIU}qT&$XpIIRfWsc%81HGqSI;?*47!#wKF z5OP*K-CL3E1CX6Lz;!o9iPdVVMqoMpt@p|fVxS+*j93-Stb>`-3z%QR{ddx96SOkF z5wQ~>Lr!Z$!JxM8Jjz>#jL9~biXIIlK|?zm7y+xpVNm&gb-zE6p2uc+ncYm<+?)ww z8~|fm8r%7#7ipgXcZWg_!v7vfPngNLYXiPaU}mNQa$V??lkS;^SWg`@9Gxf^$`B!< zMxZY+N68I5wlcFMi!7u@;7JxNY;6HUsUuPTgZXC$lqos=i%kO z+@~7%&)g2y58Q$DmSV&vt#cyh?)%=4b>jJTdPNfSWaGHfh=7xRDMgSMf#a9xFY;wF z88~AWVlDMkejc@?xM8gU<@=F0fA9W%y-ZH^dH1qRudbFaU-G&Mq9vYb zWHR4lK~c48*cH>r1XD>H4LoJDBzm`VU0DO~04L1t=hZe9ho$ImizT=?@bAMcG4vr` zt#S@473Bl{Dl&IY9;`5#I&nX7reL}@*BNlESFQIUf-qF}JASIrf=VtbLLSy;-AoDt1lOMb57R z#mCGv8r#e=`!f5fm4{zHT)^{JvWO%8M?NAoM(|7#kn&LMELE;DaDffZzzN=a;f^aV@kzI^UtRr-r%KG0r@2cD`>P z@d1!)J%K1bft{iQ+f8$GCm(&-e4aKG*enzu%vnzS!sc*c{QUHPa0ATfY{tHRyYmg@Vh-dEdYy7>xA7^LfP&ACADWk=s(khzmnol)f>WrGU7c{;g z5)xT*5)D<%4rD@ea47!!K0w0gX?c?X_u1f;Azd5pS*zRTQA{X`Km#mF9Y zU#feZEa`H-%-?51xzx3EEO&C4hRPFbi(cMW6iT;RRb%+Nn5aLnnj(1_#y~cmr1|yf zARLDGHwI7)Bns#u$er;mOequ=e!PB~S5_7c`xNj_Bd|}EPSHai0uWc~;3fnEM8rSh zvvZ!F)Be^RViyM4E{N_LaqJ2vq}DDmKmB*x?WZm>28Z`w3{L+@2LQ1(dL};F+p7pB zVUmMGL+l(JR)8D1x>L0!*VNWlfpG=$Szg{%=!EA%%FIjfaft<^O6HpPUi(i_Dpt_9 z$3or`yw6`s`u`(!%BuV zDGbpw?yA%v>*Pdc2jFdo&@u8$zNJI%zM!YHh6ZV3QWC$zCpJX44Exoy^ty6_vgRFC zWGsQ$!@yto8siY~Yl<||%dImIe|dFP2V4$dK=ugd*9GtgKzz)QFfL@8g+wU5q<&KG zzwLK^3|5+N;8lZ7A4H))x!V?waRMR*aRFWWV|^CW*9{jgRG#sx>x8;Ti#bC5Ah+Ww z%p2HrtbuW)w*Ld8W@oqom~q7JK<5m3ny9^%Oam$3R^tW_GB=YxTu!KQJlU&jTY*;V zDopxV@7#F@ui(PF(Z2IzzjNMv{$F1k5)dW1#8&;Q@o{Y={aU}&xaXpKYJRBm$)Iqik$!^TSSfr8apk^grlxb+@g%j=X z-^-8EehDguI^#AOrjzWO_U5sZ4h{~bd3Ul8OKcx=8M;goQm@E38GzHD806H7J@Kg3~s?4NY5;ttcdXN7DF zILwAT5nt7&I9iF(6waPL`cL%4pXp8ged8y2Jy-O-PUFT~+t+L=!AHZ73PvScF~c0R zvNfN)@&Yv78?Qba-t1ZVXXMz>a>=OFWBvY*3Nh2S(zj#SYzfhI!O1~9{kCmGIC^@d z@zUfJ>h~C~E1(slf^`CRjyL*rjZ~t$8>&k@#NOx#rw$6M>u?3V&0{v+uX<1GHz%)B zwMCdPJm~(!_WPf`j^&EKt-eR-sh(?nSg|?X{KZ9Z3)UP>X$!6#B|7>nr~jk8+cQb3 zWP0HQ{Euv*rf3HDimwofg&6JC)YM@8hUwQE*s^y3b{YHnbr@##sc@f~nVAU*3j@S1 z0J8+8hYwk!qN2RFy}sYGZ)7M*3?v8`gUrtyXNA9f`2rP^M2W>!9vCmd4h$AI3s5TMmX?l)$3QMq zC^Y+a&yKfEHbIvi40{FwDPkdx3UHIk7#Q3@EDsRfa_1TJn>tsXRoYMF)g)u<=^0g7 z<0C5P_wSRyM$!co5M)%E@6Pa41?Y2|^_@nwupd%-t|TSB>S~)22;fP(_P^kMXBBA9|WC5{fU} z78YLIC+6AhggZ}Iz!EgxfGu~t_%=D&15R$K!j9?h9lu2UHedfm$sjeNZ8$1})lG6*^uNvWcT2mi&lRj)=NnKcq8{0z- z1bV$<-|S}6`KBvMIWObl5>DuJ-YWI$>zSDUtIK#aUp1d*lB?@bnx`raR9p(LR z3@XE_VaeR+c(Q)-klEMc!OoA}BQm;HR74fyX)9X^1-Qsn9B<;xjwPg)ZIR z3$0UOiD8{_PZ=n?US2V5OFjI){6IPZX8gW`>(ZltPOXc+E+!eA3TMd1+33%zNgL?t zId>C^ef#Xd-nK|#ns@Quy}`NwX^CB}`A}3D;u<+PIEW<*s{&!Zkzp(r5Dh=T3=-7u zbSXoK$xLY1!aUS4wP)GW_0CKg85zqfEBro3e`RBs;08$MGO~(t1APXNHTmCprI4ip z8!*h(bPNqcxrUIz@`1Os`}VgHz_x~AHQsY}=10hK#5@yfketH8u+GlAh=txgh1?Bs zn3*j=c~bqwqS2Kdd{RR({op`@gqf8$?}YzroZb8Z){R4=tsoP*&SfZLZce9>pP*N) zPa36o2zY&|kGC{Evda>^>|3$~$431RI<>okt6PZo?8ZNV$J2aITK?&SBjoFe+lP&r zZ5wz_pe{llvQPqoo980pU;_o&hiTjA&qd;t1K|Mk2D$xz{IEq#{ys?Vsuhm_ELZ*F z-_II?3bh09k&R#rKl%0W4igPgHGtH}y@Wm8odgR!mE%6_`+kC6?%O%l zOAJ8@LCc2(u?fCeBBW7)<24@wT@OXalzAO5?^W9GD*c*mit*v5 z{q^m8FY7GTboKM6U))XK>YAi*Nlg5>(X*;!OH_5=LJK1=Ei20?w?S%10TJOrI=C zk>?Mi85eLQ^74w<9aB9`SV$9z2Ku^-yJ(&~?Inm$zOAlN8%j0BdgiNK>XfRgYNO3& zqeIhE2e;oxp-V>YdAhX2pHd3n?k-=OAK+|X;s5bfH~D9JFjo^7;~45M7Uw-~ZXEvg z)W0~dQ4&s#J0%UO`*h<%a~!Q7-$n7|+R4VBiZtAp@h;P=rKvfnT#5Hdz7pLZSqyXk zJjw6X4~en7_I_0+D%`Ia15ici_HDG8*$99J9SDYq_|E}I+WU-liU>ZL4+y;SBep^@|C-H?+To3 zTi>6VNl`2qa+CB@bPdJHZxVpLJdjC0TWK7vOfalhqA&awkDEC~=SShb+ zo0z<=R4<=`MTnG)-Ww+0FV5eAjHY_a>+ZK3 zl5?h|rS6XEae>2PUSW_#{wi{I4&>oXVo7WdnYH}wy?pI=wLCDgLxI!FM5E+(K5gdCbB{X$XYU(V{Q3g+4?YFP5VR3SDf)P^4zw|tNq@*k= z;%L{BY5|0mM$#h|>7xL?ZDgUi7&lao1*ZW+aMK%~o=(;OVydSXRJMU{(GJJI(y9M= zH~RWQ?#qzH0g%7{!PCv({-OT|B|QSXdxEEly@P`lUFUT!*_4F#i`E%nBC?&=|e|GPV)&F?zCh75;0bp8T#AOc(Cb0C3 zfOZYLWpu(eI)7pSD2H+LJ7@}fM@JiY(j%@%q)dv4V`J@;xj}W2xx~)|)G>%R6jC}s zAe{8k8WS83kTSr{0zjg!UabYFp6;=6pbZU`fv%_b{_X$X5l$-yr@l~UOxHNlc>Sux zKi+8k0LCl=Tkp0!6wqYPI7Oa(RaQ~K&sNMO);nYQE0+2wu51)o{Ex=2MKbNQ7BYKQ(vV}kWG-R_wEth317p1NIVkL zCnK1^AfjjRMMAE~V%Y-ZX=bm-znS~rP0!SiU? z*6&qN8u`OZHN>$WR0>qna=+N3$W#m6)9$_R@wm!te@ThW84;_2bWBQDZv{-2ZzDh& zXmqfzQZMlO{<$K3e&WIyhllk4;Q3npK|CTj7#HzVzMDk?4|6y?;m9f%^H2c}2U&pl zmNNtWpQp0!LzRIS&<@DrpW{=u@J^5gsWXsdLU9fz*VRzBi%UqXudN~a0~>hmUw38> zXGGAN|AjHtD)8N1UA1&|yX&2ou$cN5z;BQKM_+pkd0&={~SRvgRf} ze-=iqiU3mCxxgp#)#=s0M-O#$$Uz!6{Id5zPswkJp9C+HjR1%wSqcRrI?4X?)3$Sw ztSET&K;d5-=y>O7EXD&^g8j2 z>Bxx$K+XfuYz>_QFNaw36CE}KEZ5bG*b+k(^+x8C1<*!_MH_-9LzD$X33q@2S}H{I zVS$KBwV&*ygV?tnj>&yUPxk3kUc?s(N_d2I|I)X*Ycvxv0LOa7&4a4{Rd;+pwe5-fP{&xbM|9kb<>3#l^!ZH5Na^@!Ql~de{eX(J~c2aBk z&Qs=8&o^!Q-eS|(Nu*BlB;lv$kr3gQknOVkwR@^K-e0nog8w;y@>K;IGt*~Nwn;N! zBwZ=v6wxe~Wp8oCMEd){s>EK!=B|{`<|A1&uIBvMfk@k5~s>jb?W;k5BNwFE)2vKFpOi?H`9K^;O6}+`TmIhhV9e9@+MM+3uua~ z;{qcMeJ0cs8QEPcwIwg`AJkqvx5?q+;G*Sr6xMI#UnK|`%8+5mtL9k^2-MmaJz_O^ zudbreO!R^)P&%b3nuW_GE5kYICLp2A5bey})6;`^y(3t9d`~%$m5>1-0IfwR^%3Nf zxAlM#bUuN1Zy{+T&=tA~=>j6(JeUy5P1=HkS_)v%>%8V_K0Z?LqY#pk{n&bALu-Eb z&;$J7ry;`tvFQS<%9B37laPP!hT)tUJ-e9)hFM2PF9@z&@dWig*%w6Xhp3qllnz+e zs#*((fkZ69pzY)gblGmP#c8qU%RYimXlYR^+C@EIfWt_Er=!(s0^PUqwn51oq&<`0pKyJ&d!y& zsf{~>oDBdsBW+UT*nu#z2=x!z!cdGdblf`Sl5OBMvvYHgh<^rsVIuqu4h{~;ZF`6) zW!`knIl^^&z<>nE{5kZ-PxA%OS=#f}^Amd8k#x9}m%=f>0Sz=PM;v6~9v^z)JFdd| z2X>HM(1)c$v+wMn?+zlQG~PS?{8^tdPPy|uW&p|d_4M>any(<&LV_-xc1J`^%G=;k zkDqfck~?}_54#&4 z|9WbEv_U>!*0iOnMJx@*ga|VGc^7shXL#j4j-kc=9J2A8!C~?8e}0ov5Yx-bw#LX* zq-fUpD)Lbbe7sv*$;Q5W9UT;@H>azvr1xIFlO_6uggNY+R_fe z$yWpQUUlCqD=3g>tY7S}ZaF5x*oohE%f2abX6NuTa(k$0pRRvXKH=j#PDXOZ%2?Z{ z=F*MJ6}{&Q9W_sScq7#(Roj$5#0t>g4G#B%6(trXkDiRYwTSIsNF+$V{^3@}j(no^ zy_=uOuObd~)?!kX#@YfG+u9@)qyL&w-=di(yqZed{gh89X<}UJY8aGmB+6)cw#1*r-2$@zaAYrL~`_2hJJKh>)@tMFCp zV}!H@m(z4`pj&n#?g@@!B0|pI=SSt|s+N|w5C-)i-|r~@O|%Idf~kccGf)s1dAj_k zDmO%oCn3v#-(Q(hRT7xkW?10ts-Jnuz9&li9dywPAlBb27H2(MyH`44H4Ul=KFnID zS`%+9qmHmQ6Y1=7n`5}@N~=Eg(Tx^O;sI+;%<`zlch+w+O5{)DoT%B8uTO4hyBj}^H$0*m)Id>h3j@Rcz2QgjX+AqlI3c;@PQV$(ANTXX6M zJ4e6l{ogX=<}w#H7|Liew6`V`<@tEocJ9@E_l|OYptuyvKo#}-Fj^{-*3Wg(^AUkb zowur++cnR!uah^WEU!KF<%gZhwWbaed}1VMzm#Ri*tm?zsY$%ADMGthiv5#Xdv$i< zFN1_x;46O$uehOvr?LJjvXcXjsA7wki6;fFOUkwFKJ|x8y_1@1{pP3M5onR zzGeN1W=YN58R2ZcvwLR8l)~N~;Zc);WCR~8TH>7Dl9q1}RpT|<}D{e5B&~@?{pP-UowqN8#@jx>}mgzcs17^$>zndaQ1$EJZ1o;B9?;?TN(1T^&Zt z4Ug(5*V@|UN4G+)tlle|MFhR(6k7>fxu~v3PLUbFmOIiBPJbuITuxn2XQz00S55zg zO(XBpclxI1BDYk@9`w>XZccsq(z!)Dd(*@qP5+Q(NMqwgXnbTI2m6vnFhi(E1X49M zgF~s&{z%|WL0g)%g1F7OW@XFH#)VA=St6$9sZd-ayPYPemG}O*>N_ENYnN;Z^wpk~VzR63V9tG-F3=aCcc_nv(?lU^VC z6<$Z+P@gd{X;5u2tESZWuO<204>4VR+1K?);fqb*PoI1-4TNHG2l9XX4za7i`xRP7 zaQ3!jx`G<;M^RsSeBlB*kpyS1q6Dv(cl(Fcu&KNRt-#w`1&>+qtUg>p>A_9ZNYAIt z>5|1FL35Q}f7t(rbg?-bg*;j>Je-V^*=sidTBX z_8VOfy?iQrH;ZUzrx`C^jbZwp$+0X4N90AU`0E!!SY>ZsqsOJ!zhwMnc72_{_bE`q zur+iMG%xo=c~uB^m5Zz0OA{1(%0<>8(LbD-^%6B`SJ}Q1Z+RGsQF|2f4&$LAql0%K zVee>fY3-S2lU8lM6%x90e7by%a^EqgjVV{#)DLgZb&1+2tZTvgsn?YtPdWw^)bcd(iGLK-m{n80eXhwF)^8V2T{)rviW(z+&7%5BW1)KHd> zo7iZLu^P$3=7%-UXJ)^j^c43GyNGb=`=Uh`LyMt_e(pqUsr(!Idvsg3;3EI`YR8ew zqwgl0^~2gsM4{MiuTga43^BYMTI$(!ADf&>%k&LbYX2TI3V&lNS8NTQV}|0i+gyD% zxp_jy77m8BgaEfAkvUb2HvYzTUi^S*f8*CD+3A+gFY|<856soQ)YXe}LMf}yt>I{w zmwFO|HG*6+3a+^8;q31f&qB)ES3`%S$1{to6SUa63&PQ&bJCbfg}gFFn6p-t=f1Km z`uNaIX!L0;LB934)>I_J@0th;S+!xd!B0O(NQiCMn&dPF^~Z&*`#!GreJLp+6C2sp)#U0bgc%~Y!Y^iN zg)Z1Ukw@pX*xVs{TJ%qVT1ZbFP1O4?#UZk<`h?&ti)MHdCp z)KmkJRF2mJ@|wc&oMy+0(Ua|Ax<>9s4%Hrvf+>{+#t!e*ZV*ONX;jJ`KWcQHd_F1cBK zLa64dr)rD;hvCVoU`o;vhQIMiyhTNru=ONaxhU7`MOse4}ZiHrG40w!pxe8`h{xNgqV6yI)6y3M72sT64biR!U_MC2Mi@N_@ zDPXY}R&r-RYx|SB*`c*`0vS1cI{6(UY?-j$BTdGFc0-ap>pl4{cHu$~n#XgRs3MZz z$If1o{Z=nF%x&~aNek%zkn75Gva-^_Rh*=W9*!`!@Fg8N-p^(uAbpc+Osp3%^<*U) z)J!>gEQHS21hAONF3PA9yoix!lvDM!mdm^3)40h~e#79GmFOFuh{PaW?c1Dzx@1M) z1rq01-S8;RJ^EF^|YYQ@oYmqw3M}odvylQk~k+#cQ31PsjMQ7 zffU0qc{1syzlN=;`1r46D41`iuzqKtc`!T9-q!x1{{OaXclD-3*0xAEiJ>_9Xu3Ln z%!$$v4RR<=%*{mpif5xUmt~ud;u8CP;GH>9Zk1V5`h^B$|oxM#jJ1iS8O;m0~YvHQSz2((r`>>5mj_OO+IGPiZKf- zj>Nt+HP1~e*`{+r`mVgzvBA!AK$dX{(ItT(_5FOVW5&1$apneNlV(QNqPQ^@4>liT zpPs^WUFLYfuq5s!Hk~}}XZO9Hc?~RS)N<@iZ7&4GT}XQCI{u7->@pNBxFsIide;Wx zlu;b%!4nJZ3qlkXY5i=w-;|Z&(~{(EX2QCpT*aOVJ0~$wD0D11A@(zX)=X?wgWwQ` zsPZl@yD5^5T?j#ezzb#di{V{TiA=bAZ@&ERs%>>}^6(bT;NOTR3!3iyG2fw&qn=ga zLD3|APJ*5gd-3!6OyeOTj^658VSdGfp*tj({Kv@is-E^;$H{#5i@#>eQ9hno71C=b z8|lZ^8QYvFv+iTblEC2G-cfNKkDrN?MTA-1$e!K2?)BDvUR9Ku{QzG0jt~A|!NDct zdWrU}%_yvco#se-v)B5BS#~cR+#`#qk_&{c=o=*$7IWRxN~i2t598qVdr1AZ*;~?_ z-jnF#R|U4B53BDSEAP&#>n0M_aVf96iZ5uDqg(iJ6aI$VeY7Cc7B8MR2rCFz(!IxA zh8g>Ny|*i@OeXfj2c8#l{6VQGw6x?qNekaj-vJ}Dn{hd*R0S_ob*^pDeRf?s8!hCp zyly?HOU5j?&-2c%{sx+2;>*9POTnvTy>Fv&$Q4Lc_Htqa|MV$i-e3Y%6&qV`t9QlO zep7F9;UQrb1B-(y9Tr*lMuE3-;?^9-nS}(HSt-6NR%A3hn#06#2S)Eo_2>IW9XoW8h#(LopVmNdJ%fCksssn@XZy zw5_}mGlp$`@5h3x7m0$uazVUqb>@)#SGEg6mno4n#b!@77b5lhbC*i8kVqz7-Y&#d6 z#yu;NPSqvs?Co=P7pTMf`Es+9p?JB0`aCW@E}*@)p9!=6Pz& z3G<=BUJr!7`;RW%uoS$MeUzQp^XxStPdRa*{9SeQ5gx6Jmmkcy3GgtVwtb26^LcL+ z)5EeMiQ-^)7_(zj7Nu17keBNiUP_7_jF)rld4J77>@EpTS?kfyl4GDFp22L&SB2@w zq5VYD0}!DQFE%BbU@Hy3zuEN8^X(T9T_H@1k>=FHH_o`n``eoA6OWN+mc?a+=s*H? z07^hY)({OZqS{3gk?TWjyLv?~n$b(CPcL;W?UDSU><%5;>{$OG_sqjdoVH&By8U5Y zNg>Owi~~;?=g^Wo#F!~OY~Dgj$7$?K{zZQhxQpkfRagyu)DJ#C?jm9fjeI8n7MoWk ztIFuO$#7-66D$JrsE*~6@ES1z4C62E6Q`5qR@4O0&I)6c^jO}ChB(4YyuXN_zq8(J z5U0Sp6!UsuPxD*fEqvW6zX+))@Vm)K)Qic6a*zm}3E%m4E84K9n-LzWivM0=ir5F^ zl^@Hpsm51kjsyn2ba~~C_sdbyy%9lp3^Y?|C7x#$a8#lAF*S+t7;mB@Z2RIQ`*e+p z{L2axXe*q+U#-Pc~#$1itfFDUDu)wttA zf zFTbLYu%u$-%-|@#BcMDXgyZIvB%F|yO{#xMk>V;7RTPQcQ`S2vsxbkn2^R;yDuo52 zlM4R5)z}xaxz5e7eljWa&a5ceLGF`~6Q8SayQxz*dl_Vl41!191H>i^l(gVWWZaoz zq=2pmCxpV{;_UkRRHV`Gxof-e4~d}!8!jDPU3uVBVE7c}_J#oujLeh3;m!r3W|21f zbmfDa67F1ZqPh=);bcb6lvd<-3?^}cX$}uKj9*1QK=o^^u{tw7-47O0N)SN_9lhZ< zVhJBUO!MlMmLfhQ0RF&U*8mneKviCz2X(9Uc#aCbhpPYC{ zi~nSUTp!2HCSYa2>!|^P1yTVt&c#a?b74UOWU*i&uSN=f$gHVJ1oWX5;y{oD*!&u2 z==BSLj2B5p0|Mbmpz{x>|95<@>cbQ=!iEz$_1R8Jo8c4}37*#f%(dexwh=-UVu3CI z#DiE$5#2CzB}Gya5PLYkvsFK`JwE^j5&b^2O_1>e5K_DwhH6m!?f}|mGWz=UYf>El z+S=MgF+!Y+(ELYc<>1ky3_W3xHs=)<4p6PaxUK%|Xal*#FlXk$A|xb4!nMGpbN=6p zhQ)AByQfbd0(LAGHHK7~tq%W@BqDY_AiM^$0|_Q-hW8f9x(e~K6MpQ?#D{4OAboI; zy^K4rqEp>6EwJ3M<28Nzrh}|4@!d7SwZlZa*`~m~W{vHwl(m^Xp^Vpb`7TRT#@`NZ zbC-YD-1zQ$Z&spM?BMLYuftDLWmQRY;@^P9pQk=yGD{|Zf4zvA|3KZjF+|rZ0Z+^jSDdD+! z6~%o*`cvAq;_-)_SJ4KH3lx(E7jed3q}KK!p*oGV!6z_D(AVYj+(G53z3pBeNTAd+ zPmX8G?tSk_cPHzNjioO-P0KG)!T8@MYd(!vJwJus;NmqY7RGQ{c^U_sE>m6UbzQ50 z)ydh}2v**tVb`X)WVesq_jkrGljo!CNsD=1TAzu1cU>+Fb4^o?vvXgWzK=caBBe2< ztINDgDWpDd^uj`7ATTv`?{)-5xXvlNs%Y|+Bwyd#ddw7m$%%0BE}ee*B)^~D9luI88|Mm>z7ci_M~0t$cIg+%UUiTb)*m4*6A+Q}{C@`z z58rySz#2(RPTu*y5qN0u4@BHAkh>lR$%xW1<6Y=ya>%!%Ynz)Zf#e$V0Oirbt}*h$7ba;)R4+mT0+vWd5OnZuzqJph7}|Kb z9^hgT3!BDEunet$`0hu?$S;5b%CO$)78WonClJ4>#*p~d^T$mjeiU)90Lr`%UOw!Z z556^fdc&CijdSl!$)mOGH$HnaNT|{q@KFW`#2I`Nt!YN@{{bv{2kdC(okR_x;S906 z%P_NB0+x6gZ~$uvPldsK_ZL5i;`)3DqliDCFGeipV8@YKeo&1Z+j*&gpG2nrfF>Hv zBI&5IvKJt%?iM+#hGb-RwdK-lY}w>kQvsqB?0lWx_1HKY_C1m~W_)NYqe#&dBt6q@ z0e|Xl)sS6vODxMSq-w-q*wGB(RD_xArI`U=iZi<@1k&Mi9F2L@eo7DYsb|6%1{uUi zX%!19mj5y+Ymk^J^AHE1m_mtg2K*T$LgmH(h|b}~lPj#-$a`AgD6g!wj>hwo=NtQJ z!b5#yJ3IQF4bF`#jM*`1!DJ?1ZxB)Yx8+LQVxzr!k$HMfwuvgo@w zhvh(1o#h}-XMtWMYE0%=6Zb^FVW;?xk|GLdGFGY$oo8>3k2o zMmXcBA2IRZoUYTm2XCP!O_hjP+}OBkJ)#QB`1FzS2mL|Qtn8abJ*aD#BI`1q!fYF6 z?S$gvb;|wM&>)`CZy>2!xcY!UY{QPtj&$+VZ2xg>hinqt$V;a9`bHSzfe{uq0=-%S zm@Nq?^vRmi9V>7nLVOVQ+mDbaIyngIgjw^*^VVHjEa4|#`@tiN4Jh=Zzw58)lxkaB z&ri3pahu#Bd=QbEU-9fP&!jebRwEAA#Arr}_2M1q{z1 z^-9aaLK8;sdU|@u9aRFUzo7oX{0}Y2dgm}~@(j$TOWTmV+GfvPWK0PinoV~Xh(fiY zv4APx-LomMo2v)Qoc}cqjvcS-X`F z+z%3lVtaZU0oa9Gi+&$R@gDt%xx)ffPRSH>iU0ibUyCKhiM{Wncj>`LOmC-7RMA>d zaGAZGD&B1>K63-zPv)0swXBv6#4lczNt~N^VhSfy{(y5)Es;5pQp}e0{w-j$sPp^6 zFu|l>6=Xz+Qdlh`RZ#(DZrbjjt_G(Vz>0Pdij*iPshg#~;#bzbK2ojB_fokcEsM9w2vE2KWA zAz9P@^{@W!Pk?>;lc&mN_AOTS>Ps6!k-@@)1@D>kv5cJ(Q+1F?9i9g$Hpj_1uuMl z{T53wdP=ltuRBm!kNK|UXdl+W9X~ldyQT(W=aScS*OK8p8zN+`;SP2OP0 z9FwkL;3b%Q?Y&(b-<`ud$-DecjgICIy<7`f@6mL1Az*1BQvIt-a2-gBkvR zfPfw#5vZRJxY9o)7$7iJYSOn^_x%F`W&@~)g)F+Uf2|_wer=(1;9QQtMF^G`PsXHH zk&}bUit2c40SF%K!f?{MonN~cx1N3q?9VcIFC!8kz?s6@AQ~LMJiqCk+Bg!93qGEl z5e^K$54{5yy*F%YC-293`vQmr>?)WeJunNQKV4Ho?7xsmIG~e$#~%GpJwY85gy_=1 z#f08)a2ga6OZ&%2ZYc5Y8f<;eC>huOP@G0@n*MRCz_8!>IH=CQ2n= zs=9M2l|h0qDCL*HE7iGdO2`Vv(hAr+ywlk?*zmQCvOj|`#Vp`$EC&OU% zBiMYWz=e2Qgr z%}pM2>qV0UJ5RZ6lssO@3pPsqfM`V&C1ZJJf7K&evJ1%{F)g>$zN97w^SUeLTe1xfAz5D0;>K{|kV)`B)1 zud&PpPNoR06j4v65Z4oNV;6k9E1Z`Uk@~!NGdh|Go_>@f9}Y%;fi7ejP?*(l&a!?_ zZ@}zfxfogxz^5e{v{_~kMb3miyyi9d+R0MjpSE zJpDUyVd+H%lot3!EQlv55-AM~6v(TZyWpxIPF)x30kk;$@VvFlK0l)us8SYe|{&|v0I8f=OYa!2UfmW>2V>Yl)ub#rSIQ6=mH=tutXwVOVfbhg1#sw z(he0s6^0_Y|Klzd!^a7^Bwpt&FRzRJA83ji2rt@Zp55p7HN_Bc$vTrOUv1DJT8U8- zN-X$Eh6=fcMgQHlasEm1=`@YP?cd??xs0m)#;S~w<1^!#ygKYNKMRUDc-S=<{6mM9 zn5l?*!YEr&gN%gs?5f&r-FgCJw&s57Is);Aq|DCWE`v2{&)>a~!uRQ*$oQDXRz?9>?c@${`_fJ_aq~U={BV}W?+_(0bZ#&?If2kHZ~;#2s-5?p!vReM>qm&W!^1=5K=&VFt_>!3@ZfESo2{_C zJU>4_Bs`n|3eiR1u;Oi>ZLgDcO+WZaIO-GAP0x7&KLdRYoG9x-UVOO1>zDTIE8J3} z04EJr*$g2HMZ{DQbi_FGKw&=sBlWL<^dY>b{FEEg=_+eGJMtafg|D&%AJfmK?_l+V zppIqLQ?(aPu=U^*iJVrU0Y(6QxOq6~3nE%h5O@W4S;8@~4-Wc$fE^>;gLj4#)azqo zV;%4l@Ni!tPMPeJmO$VAS&`A95JJmL%4)gBQn(u3O+g8%$Rx2P)1lY1<9;p zG5ySVSdCP4Rg#O+|8B?-4FJLBBa=rn6dy#`vfZ29nFX#CSmxjPhW1h|gaQWn zdt-<%bq%o<^WpK;m512H$-YbrWo;LNJjjWpWUP&?$JyD%*voebcE~dX;e6gNuf=F7 zPF#z{S7J>eHAkyl6)IBRuieo9AxkH6IS^%%q>^b@Ju^;YWik6lwMwl! zAg?G{T-hKyRNMUACF_w<={xq%HKH4qcV!wG@|agTJ7o6G$b)xQW^e>aHHwOIhs!Bl zc-9+|Ur=<{xXTnvp{*J69f}I8u5t4<(u#MoQ{gW?vt==I3HlF@R&x6P&7<{B;ejP6 zBKgH+W!>r^Xz)IK1{*peB6xm)`|!Ur<2a^oFHZF|(#5W*PsvP;xy>Euna8j{cbzl* zv@V`r22}`#;Wu;^o^}4UKdn8lGdQD;=?j`&Y4-`$yA%~NRz{c7mCatsVe8zs_gaiS zVEP7?6h)f8@R5?_;p7e9@}82IUN;>k0*B!pJL#Cw(}3=IuYq-(fr%Rs2~C2!DSvYy zErdZL%E^1zB1EE2vV<~GIW?G*wFH&8@-Ix2&$PKv$7%82{--nj z-ijjoZn9knau;RyM1~!}AZ0YsQJ_?3i2SqCRK3tNvzqn9$iJ zxrx8G&>7GtH1U$qb6ff-6x7n>u4SCw>c^-2wqXALL8!KPlXw_z)8)iV4dsVeZVw_I zQq(1+^J}cTU;emr({XcCNQ8dgWTMT{F+!24`Fy|bri85!QKe?w%FZ5X6!g|;N7C=9 z>uGZsqz`7FaTritI0&<%NMUXJzCliKR8402XOkoRE)HupM-dEV?8PeHNv4eXY8o<^ zJ5eeGDf|!nmRx<0!p5~G(O0q+nIwF{ay4>abn;p!bhV}R+c7jVr;n0&zThfKDR^eL z@&5DY>+ajrAL<(&P&1Y!NjC|IQhi=uQ&K=H&y4;DmXq(2H9chd{Xf{4Sj=rYcp`}k zTr&`Ud=eZ z6ebS_K0kWE^6vgAC_SELKjMJTt<=MCH29Yj-(G#fvD7H0s+CclzV+xv1lBCPwODTC z`Bl%4S+R5@)0Dk-HL!wHrp71cF39*U@O8FyNMH0HPA+l9q|DY*!rgvbrFSALM-z`hQ*7R-9>v zl5)CW#slf36V<^}0=CcJZ}(iIxDlS|{)!=M0d;ifqI*Q$LF{;@sZ$!G@{@NYErd%V zj+vFm!lB>GPjs*8;e_Y?8*mNn|51KY#z9j!t*&GhQeoIgey-mli{fi;PEMYi4GZ?V z=?C}3W8cd!v-30VcKvAMFZsgu22MIb*>**Ptr;e=&$NvMgKM$9;uOL#@y{5?*s5l= zc-FD;Zd@kQwHmWSiI`a3(GsHNXHT6Q)*VdVMlmpU_jBp#MEX4VnPkaGYgM;DO9?%6#ya!BO-j)jqM04t>@Gr`n}OG3gkxDE79& zwra-QL!GA^DzlqIQ>)C9yd1?HZ5#CU)~uM(S5){~rrP$TylJ`?Fu@t2tovpCw|m|7 z(gRdb9!AVsUIm82WKoJTBaCDq?fAm-{(sY=4z))Cl`1b_6cX9Gz{1R&^h+ z3r?S{E50FO)mw^QkeP6A$D7@+qi?^-)S{-BIOgbZsom6)=Cy~#MtU?#<+?pnH5@N9&i2m#OiExrKu_FlPhGuDOMGDL2kRMK-p zS4PkMgtlj+*i<8nidJeGTy6^bG6qu1Y^vI8#+ug9x$d4!X#PHBz9DCNRbAgJLl-aL zhCH!dOXlSVSzBQ^X)3-qoo&|f`EEUNeoA&9^Ekl*EA&Zm)q~C-fsYcpFpVCTofB$- zdOI6`aP(zIoQ2xxjomio(>yqcD_>KnagpWFKS4bOF=aiW-6cD?I~ZQXzD&WsL!h&=Y3J3f7}ds%zGUHO0h6XW_Rvc;Gq`jO)1$hyp=E``EfG;M!;sGM_V0TD_?evGD{=q8#X_S)qt zMy3HW3~K9e|6vKA9ctwCq*_hs@@KBu&MVdLEWdUOuFq|Akd0AtruYq2YfAPm@ABrk z*k8z_n=QX1JD9^xl56#lFf`<;chtPqzjR6xIX7|k{(1gR z_cliv$;O1R|1=C<`#5c860xY-wO&)y-m{1=;1UjZ?u%~pClO&XJRG*4Uo(_lu+*?~ z6=DTkGn7AyuPVAU61>!zN}_JHSvCXTz{}Ymgf+{w{o- zKRlTgI@Wi{VnRqrblw`27P?~CFm+tpk2=4Fvz>W#4tHFgG>K56%nReF3)RW9%)M88 zRL&f4ZDWlc8)~%Q!o?ZNn93dRz;RcdL??-1|K9fOe)WD>{gDEYz$vN=;H5P%r-NPyS-4vAomVnC zv~+TJlk_h7^Jxqei8A-T(!az#!EiI?);-*{u*A`boEo*ykT#@ljgL-_HP(KFQc!$s z=H4I5O@4Rm7Jci-D$N%WVZjXfyFVTg^Dj>0U%mOcFTCtoN5z8v;O9r>&E20&o+^CI zY-lCDU5ZVl$NXtJa5g~^)krkCei5ybOO%coO=qC8R2IJbY|2-TpD@E<72?=6==!4R zW&0NC4}xfL?*um-bzs`|R@zigjzr{(TV`uiXw~kNMtQh>+*ag%IFW1yvzsGAy57dy z#gw;gvE-*NO7GxCUd|>ZOJX>bts1}h&klP)G}J*nfJLtP;yYf|W?u=#PyRQ9g^6=#>_WNRGp~u-{3th8iH?G|AAvQ`D-K+n@pcp2i z2l$&mgBagmR8Q`ycF4!~+vrg4MeWrmD~`?Yu&hVqe9d{*TQ$}c$Azdo@--|G*< zp;lRAF=`0Xsl@vnkT$S`OcFzK=qsx#h`&rSX9i zn@nlS3=%ZwwJPUrUF8QVRuBHqf4eU6Cew5SS@GykH}%jTh3F5|-xOULOCjR-&l!qh z?F;lv7Vh$SrdDtsQe^Zpl=ZJl}wsj1Qm810U|w z%S0?Q&G`IAab)C2H2kS`tIdEgkl$QiAND;{c(G4E91!zkjOMD-w-p1j2*r|tx1>t3 z6Eh8^Vb>n%lZOTN4~%5}A6%UUR8>*et`8w4El4*A(%mg7AxJ9?QX*Z_B`w|3C?(y} z-Hk{{cb9bDwZHHG$Gzh+00TIj*n6$H=X~GiU1}5M$2TW=WEx^$Kt^9}{``-S*PWEC zas54YQatLZKGL$x4DO3}6L?D8i1IZP=vcA(S869FC@Lih{z#HaOd{~{lqkBO%gM>GKWVU_^rzXp zd@oKE8uQiN$K9e<+EzWPfFQEaKe5lXe=$ia`{7@!H#Wu;TZ>iV1cckUcKcTNbU-23 zW?=1?O8BY9EBAKK$V?|jN6_}oxWAn&r6hof;QT01$W#wholdlh%qbqr9vycRCXX;p zixj!Zrw-%%Hy6WQTtFr57|VVk8TlNP=1t{r7QBIlCfG*YShNnSRp zbnEhj`EHkqx6GjT7eU5f&3Y@G9OH2mWu*X91pd?H>+NTX!W-x<+Q&rMhS7)31N_F~ z1|g;J?O(F+${SxuI?_riyNlXn!cJblL$VIl_qS?}fYFk$uO*;Jsf~YlIdlx?)#&~D z;*y|>`imk52CUrzzWHJ7rFX2)=&8|ngjzJSR^o~wRdHu&->`%C{9Bh=Sp}Tu008p) ziQJ{tnSe3n8?hV8khpeL-(|V2d(cY`R2%KVtNQG+=~T)2Z+o#S?Z;qZg?sl~)`nAK z*rK<|3-ZiNa8q`_n$(Zx`sMR8yK(M|m$HvqE?$r|)aIM(u;#@psPXr#N^3fIwjfM~ z_BcB<5i3VM)yl*HU`gC3Y6SMbFqk^nYl%e?+r}^umGVA*ezPfjiB6y4f*Gi#(_8So zYWd%1ektTItL0Ih5CP7Bqjte}6?o zy!chkiIM@WUk*X%^B0uZFb4TsX}_AcyoR(nv{a1B?wBM|F%dKaXae2oA<`__FX()U zUc?yE;1Hi&ajC&;_Z}kXw4NydAgbe0yA<)yliSOA^K*QXvDdE)i{>NQX!y=sviA&Y zMdM7E2(8G}@g5LUMC{LgFr;}5IAQwb@yXiS8x=Pc5wjPIP3O+> zAJC!L0snAL(H{c@PEJlY;A@5Q+jhpXJE`9J_&^b;HUKLH;Q}DUntwZ`0ieRQdW`@+ zlp93)1j@JmfdONnA_7>8OIhNY|CBPrYymTGB@~@MV+!e(_0Y zmNfAlD+xPe&3r{KOiEP-PrA}EoEc8$^SR*vY5^2uaquxDlwLV`giP_SV0#j_IPF>m zxYZQL!}11Zo*?5G;QXPY;f znxsWgkt7RJ<5bk*k4IiK#3yFg-!YK0S$-ySTlM=J+O3B;tyLX*b($#2joVXbNo(S~ zofpnR^5=Mt>CyCT+a!d3wdr)?sgwzP0J5vJoaVotLEB14Sq$)7-}9B2^o3MJked)W zw4TkA#Ge!OrT#Eb)2In=YVwqcBvWwFL}s!Y9QQNK?GGB>JNY%St-CmjJ9H-aGbd-; zYHjkv3li)Qqnvk^Q6;yBB==JTm-y}Rk;{E18(}Q!*7_LYjTcXx4pbwV`QAxpe)hHC zl;{Mz)ke|z+4ds7gn>g})SOm%B_nDoGEWn-io%Ej%cIb^rpIMWSi>AWP(}MAMGA}F zZfl&Ph0m1R;43T9v=)#JCNUdd^?BnZny#s+^OpRT%x9%5)~!X7PuyAj$@epnjpq4R zyMZHCXhE@< z-Ucdv2ngxTQMXx=F|v6^Xhbb9_EC#@WA$e~6%+A?h1=MaZ;@(p{xjt9xY3@5Jsi(4 z2vB0s>@hVDxS#s&7K}5EFRLdts&{NeJt<%;Lc!BelKbwS_$R=538O@j%Jm@s4v_~yo-Y47p|$nJW@Bj_lmQGhbPkS= zFTtb%sOsqPDj)J^=jS6RQG`$XXwZqdLjVi}Li&PHBuv4&0W1XlgM*z%muhd{c7VB| znir7qMF0zBY(|DMpxQwU3c1?k&1QhIfCBe`pmrkv4Fxo*XbJyw4+LpOfNlv~{18bJ z$Xy+P_H@mq5r8ov4r;LT{3DRuY)_X_h-OA*zY2DMIA-tOxodxdgW`BVoMiI5qlq6+ zAt5bTr|w3MvYVPn%cd2;yd4^GoFq=PMu|P}gE6CZ)g#d1#n6UA(?r133qmLA0HV6^ z$sJmH`d}zN2m(}HJhqG`gBdv_m;(96@&E#wny0F%*#o$jPurluJP7ZB@@%)~e{q2Z z;tNvDe?VWvZZSqVF*yk>b3lj;6t|w{-ym5408(ZTpClwEf(dHcZvdm=i!3f?2Hy## zMFXV~|Msuy|6IUd7goG5`7^k4lG`B6&rM({@Wt(3r+^hpnyfJ{K`U@_Enn^OVg0#l z``&0y(-Om+^T8KBmH-=BQY9G|(b><^+x@g(Yo>rvaf0*T*u15Mz8L;r-YhF+2Zw)f zA%P{K)=HmPj0BLolN2~p#2tUBcs}7rbFVO7(A4)i&@dA_VQ@6~j5)g^?qt!`?Lym) z>wlt~nk$f;XD#i_pN3epiWs2zeY#$4go=Lh)h#An#J4MwmK$r)lY;PuPa33rHs}O; zp9Rbf>;%m9oLCIJPh04CQ5hRQx^NxU5C|BLji)&;cJ~#<5j==K{qAIkS8n+UpNqUc zs^q=PDG*j4k2Oc($mf{|3YNQ_Xg*xu2{qk}3e10A!w_~Fb>g+1SCanG_N}a`Q!LXb zc)xivk&oOwzpEVjaeq?(AkXqRYAM!hCS7+D%@j+bqKTBo zUbX()lp$_HNXaXB;eS+3^LSp~;1>IO_mS_j>!ke#%^YYyEGk`#6wtUePS-eb9@W2^4m4VJ;=>?tna+@DS2QoD?g90HTO|bjLzWn3EJ=P4AK`G{j&dXckIqi&# z8B7EQ5|A<*h%8CRE#e^<6S(R*oiT~}aRUqwY*)Y#V9!sg3)n4?+EW;4goZLiz5yn7 zx!Eu=SXv58O99dt(-$C|A_X=HA-*pZn+-mo#5VAwFYV0%YaK`;fJ75(Pn(gE5pqm` z_OT(5nL+Vr5V{o5djEmn=J5AZojq`cReD~Z9tj@;6bqExDsnmB`Gr8g4=6DR#k_@C zllG#w(6azI65NYpkepUSv;@8dVk$wo!~sYcbGCQCe*J>X1rR?TvIrSR-nT7l1;n(TEwex$IUOlk0!-a1U zv;+F^zQ3uNbpgcS6QG|uOuC>S`+^=b4n>|2!#wLFpfA=x>->K7Dlbh>FOuF%_G#llv-( zb92-yU2U{Ex#>a=5U@p3me)Spj`{T2Ny$sb;;&XP=qEk1)pupbFrAX8#_8R0qUpyJ zeKZw)&s(~2H969`HEP`Z=j)KqzbCMvh_{GJxt4?PCb<5oA^lcPLYCi?p-mOXlST`h ztMcyOTF1MQ8)eNZ%*Gr~@T)Rph>=PodtZkeUP?tC4w#dn-DHNZ17Ar5MG8jVk&5*j zlF3Gqb_TfKiy7M!&>D^?MA@It5==IGxGJh{UZ-FkZ)}D0yLYMhxAPCS=(GtWDX(3{ zjV^;!tIeY~!{4*?P-V%yxK{%EK^u6*^O47?udXX6_{fJ;!#RfmO{mUxrMQ1}wiT`d3A?JVl)a_rwrFM%cYEhoUdNdrV2=}9h9PY9bcCvWL2n%Ko&C$-@3x{k;qgO#@$u&|~!_cA5W`nea}o zeZ#zFLrIq3dY7N%)X2fMJjghH#g8o+o%RWfb5<^MvH7#lq7bQ&y|6#xQ$RpEHi_(3 zc@aDXW*Hf~jbL#Dr2|wC?P4(o?&CWj zQCp@Lws{`6)IuY~SKP5NNXgVn*63;@?bvu?zB#E~_jEWtXmW!N7c+-}xM=djwds8b z{2!k{yQv=v1dtB|_-aC>s0%N7luUr~Fjz!2_C0zJ#JK`S1yIuh=9;(pH=saduMr0L zWk{L=!JtyVdmDK75n4Z7UX|`aZV1F>&<#Rr+i*C60x>`hSBnEV*HT~0e`7b2WTckW z01a`-4)y^gsIG5r#(w*Fzp)0i;~hYb4p=)hDDV*G9h9H*K=Ac)<@F>tFjBe9^sd_R zCyROsRx$%%JVm7Nshs=Sc6$g84Q!7bw4ZJPPd`}r5cta=YA+1>8i41fg*_Mg-Fyy= z8tkTh(f1hyp#IkNI-gQZ;rs&D#(lmA5SqbLGY=BBfrAg1R2{NrmlIpZj^*WJITc(W|YrBo%brD>;>l+?Jsp4V7wpR)+@m342p{b7RU8f-|Nd~ zq)#G*uGJsT9!s-p8)Ax!J;9aqQ#7H=tQKSXz3CFut8$z!6_t0^RMB@?F4VaA7FH;6 ziHE&~waH(P)_izYA{=M*)D*S=o1UD9mQIthftlv+x3s;*QZYq1uf~%nU*&X-SGF?k zPNpWYSNCGpzEL6B95K8Wbp0?@Nrx^{M3COFfrI+xYWW~(htG|$5|3tlUR>WBj)KJp zxoj!;=f+!}obwQ~XL+U1FrNTvfHu4Tcm7am8iw5rxnFL~iABu$VDtMvhg{bCv@#R) z-(uOsu0t-;8?r2wYi(!6ds%;s#mXd8>&ORBI9O$Tj?D{Vuld?&iOD^F89;-M6ao-+mX~+zS1CJnRnMc1&w)h8D{Ix18^bA)GOH879bPC0*P`~ zPT7Tg%fKDyp_m%}9PY67pUi*Xg(ha%l#GUt^2-zTOG6iHA)$ENqKa&3xVMa;;~K*+HZ9xFLJg+%_6=>PMmJ@BJ9D*Ar^n+ z8s|I=`eBRnb7B6)6I^+Tx5apJuhi`elo92TRAu7vWBb`fm9pd&m;W_{@YLQ%;-WI` za?}-Ym5yw%Ah2({bg3o>MN+ZE+#Q|hP4@%y8~|uq#!;IS zB8BCQ0c7&;99{DdAAZydr7MF@9SkbIfP7rnb-@|%2_wPs=>SX)Z}s&@zy&^7Fgx{q zK0~3^6`-l`+g({%`8BN|>BYj*feXNi&zLQ6E2Vz>*7~oWiILG_sm1GC%cZ{9@8%lY z)a6A;mE0}c>$XK7r% zk_qvC=xPDlPvFAvR}Xx4S8lH8?k-rj;6eg@fCP6a*8x}=FP*l>RF4qC|bORvo4Z#A72oI+$uz?3a{*g;ZVooL`;O(0MBG~PN zBh&2~(t;O>25D#5l{6ot%uopX`GG2$$@cEqM=jPov!nzwpSzvb-1ncc_U>rc2pg0o z>`^OsyDSRR%uv!&#SuTx-!QP);-=Y(7B*v`0fGfA!k^EDtZJe_7(FPQh ztaT)1TnO?mD$_H8n@&_H*r-obdFb^9+;Od~XmO%qw6qo9xg!M`#VWq&>l>jW$H2k8 zFVI$XzkVXkJ*BzIJ`|6g>f|DwC+l)Gf;e|5sPsP|6B&k`T)|cj< z)AVq1bHEAzh!ULol9}Ib~~I z>bq4=SkCJNZ#wxCA&++>A9)XfdPn|WzM4iw+=@vrho`9+icjO#cX~z%COYz{)d_Vu zUgI#!VqG;Qu*#}i|CKHmkh_f)=2ntjPRbUTY3ov>f2+Oj-eb}VZ11Tl8m}hD;T4U1@}D%xe{L!o z&uHn#E$}oxeyxuUk?AN%eRc*TN)Z5~0(r|z)nxzIpPb27RJizc10^vRJ=XA9TTg7z zo=%86okrzT$R=PN&ySPXyYoPc?RnAE{(N}t-hiWE2IfsRqJ z&B;reE@K>!YmhQKYuICnB4hWfWIsroKgcqb)OiRMrDB6c-{uL!p(ozUucpktyQk4H z3E**~{3;d6`Hn-!wlvDo`)0jA`0)GVvJokd75dJDr`$euXr?(uYj|#?K*rOu)YlAS zL&fyu60y=jQTwvxtQ|RJ&pCI}mg>@kzLt=^A!6h2ZCRqPSC z-&cFdz-oRzQR8{jFJ^&>#K3&mc7?ijY@Ywh`aI*`M!C278?WVI1brHTjRUF`xz9C3 z{j_;ThP0O<2HRP(v5C_JS@g~k-z5Z*dTNL97X|GWGDlvuFa$hr)Nqox09b8o=)A zbtL*iF}V#`UBH5OcYoxw1uTu(z>Jk(Q_TlNdAz`rzy^#q`AuM${{}=>s5cl75c#kP zlMgnF5r575y$w{box}kmvsJU-0`%xXU6T*ozkot<;d=nBOH~G{cpy^@0s?1ORKx(I zfj#hZoq&|3$x=Nbs1s_L`trmIBrxIOIOI?U!Hpd13rDa6D|;?uK*JpY=8D&^k`M{{f)2syO-LV7vRf=VEu<|K>*tt0IJePr34vhRRhbK zP>H0vWfTp=fjy!>gAuV{|4fD=wvMyIj&ohzr~JLN&x>>bN0_0=e({})fpJG}xD*W> z>n1ZC^p)qN*99p^|HS9DJo@t@<$3(6rA&Shi*_{`&_l^GKZ~_SLXnbQ6&JMH`mmc)q zPuvj;9Mr|}pBLLFs=7CQXqCbTMG?oIR_OReCT|~+Tf1Xzx+IQg)nsu-EP0~jvj2Jgcz!Zcl8UJ(7YSoS5j91ry*pgDUM4@DI41y6i%jdk+RaT+N&`J^o=rr*I^7 zcOXf1jA}6qvkc7rW?!p*BXknscy$vVmEt)*b@gu5j<;k142hciQd%36_nSx)J*%R7 z$;hUtflweREksJoGpn4k!)BBpQc1MhKVWX|mP}@I}Lm|6oEJCk_)a3e|Ua zj5U2L`(}6h#FS*xL-m|;py<4;)3RBeFN8C8RYpYwpmro4>?7tLX@+Jm^8gSK0*(M` zfzMGb37^e6$flwv{t9{^0s;b>g?c(Ns(4@$3S23AR*#^~20|nB8nnY!fI|c1qUc-Q z`pubs_%Pn$<+13#$I_O1B?@Y_U>+orZ<;N8f+--`1ynGQ%~PDx*D`e<%y68C$-+QV zOFZZyX6*@*Mlm>GY8Pkx{D9~wyM&rr=!ykp`J_k zAZ9oqbCGNQ1w{R5KwdyY!!%wGO{mN-vLea70ZA#K4-I9+;7J3j*Jm(f`CI)=I;KC4 z{@-?P6lCuj5qrG*T?=jlN?`)mmYBvBgi!R1t$(7*slPnsR&{Lhm0_%6bfl!iz)O7^YspO(KD-b->lG5A0C8)G8kBBY^( zOg2g&W`bOH`NVB|$+gYfE5T`hDE=?S>PYb8$hFp@FQskJC2>j`;T5xVpEY?ywL4}3 zc|2jbHq45*L`PoDizmnk8};e$PjAXUp4-&26=oTazc5w>khh?M1{8Jm7RqdhKIvZ!=2+}A%9?|RAg z5SUBk(=mR=Jou!UJYRQIIw>ts%?9UJ1h@;Q^`}^gy>YZs^;WwYZhH1|niGZZ!8M@6 zlM^}Lo}dLq!GEMk6e92%imU1-io$Em89tkA^Un7*o}5QKH|T`c(p4#{ruhiL3Q8$U zOs{=UeXYEe{#Oe?zMxa($uax+dVS+I<_A(WH{FKLi;yfvBS9CI4-ZY#muYM?Xz~ib zL!~4W$IPTcdHHe+Qa6ZfWF(v_yf@xyvKe&n)Xfh|Pb+S?YAuB9tJry9lA_9(;_G-T zAPVpKD||l4e5AyEUQn_q?PB9cmrBQo6Y(NVlwf6Z^LgCuc7~G%*d%k>8B&eEvXEDL zzgMV4=m4~z<7;|!B75}ohV`{c7cS2sdp9pj=J!qT-y`mW>gwd2v(71=aHYBzTH2(g z=!19R&pTIPm2yYPvS!ng4g=x+N0Tuf4|*1S^(0^Jg<{?(zA{7RYbi!l))K)q65=jv zD=?69+L8_Y)2!UNI{TZ|ZGUWyAN}E{86_ATyti#m;Q9E6GR&BBHUC$)}t7x?y0H><4}?0Qh5qnCtx`Bb%VIk-Nqv zvjS5JyY0PoD8>wUI3Zk;3WF2?WCPsLq0x^tfVQ*;s3&Okz?06lU21_Y|9lhtFF=;s ze{7^)H%=216UhKK1Y&CM<)i8nUXfjbdTJPqTKmCu?>3l<66o5&l>s0b)!!C?CQ1V^ zqNVHEO5nE^drSdSTB>t>Kp=wx*dSKa?CdOv9f68SP-FeA76Ini`n}S|ZIIXbS{NRR z^#qY+%F=Zk>+9^GMHeqNOJtsQ(wzApgc*2}mL4wZKJ|y46MVeRcpoAZPs8SD z(6GNs+5KAJ$9tla7=xeSChRwP09qnN#Kui``z+N=J5n;5&nqm@RqtfzdV5mAjLk*6`V?)iy;xRHLL?U~AJ63IiUsrtnsjJYW=bRKlg2AgRu0y{K`3u%SgBg)qY zu|j)u3R0g&3^ca{_{Z<~P!mf(r*Ya=4>Ka%4kc7h3b$hjv1CN?4|t)b=bm0!X&XI^YG*0&c$yM2BLn78y0tZDCtjt;a9v zN03L6HjHE4k*dbNU7c=u8F6BVt)mJ?vcGwFV+>SGr4tI3pL<`x=?%KCj1GMGoA}l9 zE|O<4c0{kA$wHQz+@!D1KA3JkG%W7x-t=k5&@GWiN59jNxrW61Mq>^~1FwupZ&&;u zBJNc3)UJB2IIWGRGN%{BgH6*Juim^6Sc&-e`D7EOf<$Vwb{514Ld%`XIY0M^rdEV&rUQWl^RtoO2|4R|Rsc$-eV8i_Hv~O?mX#m-qKW z;#LC9D2GHg{jT_Lwq2H`^UqT9oYtoVGGkKSgT6VH9GZdm1x}0|7lED^k6#}4<&rlS zfvyX}L1Q&dcBdLw-egG=fov3UPY=f5&-dM}j`!(U+KcZTSbctNX$}nBaNb<0svlV` zkKZ1xzKOb{2u*cWb&xq-)^p{!=u+F(&oGxB_#AXx2f%#G(Yf2xe2t%^NB%f|2xPIh zUphA+LLKc#g!e;uJ|IX6*36qFeESb3Cja&}LC|;>*f&7+Tmc}n0JSn6aHCoC*1%vC zj7hA=2mY(h-PBSjgL^gZOg1@&)%*{uD{NWt%H`LOcQwTY>znJ}r3y@$C0l7qtU}y{ zCGBr9?+yn@-ohtazVp@zrg;ZPc!HwWn80}*Mxt}v{?U{B=o1Wx-}wKn?rqQ4;L(sv zIK0Doo0|9IhF38}+N7RGL4AUo9tgy?8zdaFLPr-pST_78l4wWjkWgKVW)yzt)eO z;@0z7%0&M3>0dv~=-q}S&o5fglXXe_;J^6mJ&{7oL+oL58BA7C z$mMs{$1O}CyOU%te?n!1`X|qbGUQL?*jqdaY!{k=#QMi7FM~&;J6m#~867rK1rdK) z5&@X?pP*^k+1M+w-7PQB_Js%!UB(=hRaL(L|L_{hMM(ctSy>4}%jTj4G5@pYg5@sr zDGd=l6Bk#_T{snK#{Ee)VtFSOQ8;*bfwAFbuPk0tnhAGL;CR+p^L0KR1sg^qW{&m`9G zM_D*sG>NhkOw1{ety21`Ub2KW;t#FQP{k-?6bL~7PF+<)l3n#eKZ+k#$ zTR6k6JZ8v=qF+0{KBMgbo86eo_=Mr@TZt${>~}Q#t5mor46%mB#PUOlAC;Z7mpc6r z+2v!@{?Z1g;kM2tFFnrqhY>w#E}8jlb}t?y%aW6%@VgC`O7$0E-{Un3KfyAP)9ia6w~zev$3YpfORtLSjAty3`xV+l!{QqT+fM-~&w{<;>r$ z1&||M8yx$;{-{S-Fm79fTVRvRm+w+P6M36&&g4E_er`@%p!Ti_(^zoFm}kRyi=#B> zy8pVzR>-K!AH_Y*jv-?3U~}7qp7UsGD^#Yquab)9jrcUi4JOg>zHGkQ`>OEpy!n{j zpBmAE$-d5%T&|sR#@mAZ+VI^QR5+oavt>FJiWHceSea8VY`Rg?2`VXeTnl}SsWp?u zpOZwKtJ+8y6ycO%%y-tJOf7o84D$S>%EqaF+aoWGkWhbXnRk4x zLGh12rF)JsPHIh^Umj>-!m}byrt|Cix8^50A_YlO-M4tnRAKa0 z(VM$yl#zo69U(|#aj3NIT_IouB&dEyu+QcjT6wn?#%Kmo;@7_YMS1rrHsM?b(F?UQ zD`ukyx4pyToM?)j_U2!aq*HZY(M6Au5oQy8qS-rWY zna;$@!+|q-uc9s~?+CXBS$hPtx?VM1C6^$3Ze@WJ;+nWD|CI}}=O6&U=(}I^gozY~24E zR7J4kExcvhYv%mkH<}qA&JNDaW8Pb9)Lwkpj5PrDXsrG1-S-cht4^O|I?!TsvKfdQ zn8@Uj$J4(uDbT8Dg|l&mYjeMzJk)c$OXoOwR!~M&QjZ06eB9GVdF2XN9ezO~@Y)5T zo6Xd1vExX1Ndz>{sd2-p_-!=%5*xw52b!+gO|gQl)d z?>G`Qi5Ah@du4Yy!4ouvlglHGXqxeiXu1p3`y>xepIFPIb?)R{e$Pe-^I)xn{7s zQ0~P0@I_o(R-@#s_>X!s?`yp;qh|uHj7$>W!YfCD-ylAjt-&}WeTf0v2ym@#JE=rw_7NQz*cE+%@ZCn5VpeuzIjyXt4%kGC@TT_`lB2~)#kq4U+b4`T?EVJ4Pv zvIse}&Z$`7men|YIyb5ED^6T3es#hDUgIxH4{zC9KnDGx+Oq*K~EtUWO)A14{ zpQH;V9c%@k>vc&g6>bECYI___0=LD>BUV`EXxMiv{7GT`uYR%^z3j$+FoQ-4Q1kN= z6$U+2Tt;)ZLlI*;{VWN)I){&+rCw8nG(TaV+K_P8F;3G`J-MlRdsMdy9xzL7qMjbt z+oQ(j9Z;*szLNguCfBw05>D|gH}|l#;ywJOT5FD5vzaqg1*^rU>g*a^N}#(12aNS`mpkgVT~Ov4e^vY@Kx z5L=%6{UGvdzv>?IFZ5(Kc-lWvTc(0pTJKc$xh^TBI8(X+m>-Dz8YNRP0NY^=veU;Z zuwMTN{*TS?-{Y*%zhj0Xr$?XB!reoshDmw!=xA{jN^F#@K2{)PKvp4@COVIF?Xg$a zHA|zw1bUO{4bjo`laV23&qL?N$jhQ!E>?s^`)=PTdjz~_-w?QXuej)P)4gInXKx>M zt@GGJWj>uEtQLxcU}dj2TCIA8PM6nzZd-yWQT+Kojvo|SMtdp6q=P?oCPEN z86$H4m>cAM+yuTC+Dli|rTAd6Yk4C2MkrGFqZ;B686u!@mYfiEiw?p_1Q~nh$ZdQD z(v;WH83QMGBwQjRFCyd+&{G1k>MSgd_7MjKuvl2oh)JyM7mw}vKig5vrS94mmcH(+NKkq50U~Z!`uzg7Ffs zdt8t3^EtwDAnXsIqxvmmV_UX?9xl`=_}=>_QW4rFj7iWI zFVzYw_eTlF7WzPM;oRDC4*r&@dG3ys7Q)bh`q-iqJPcUEw@YF~DsnK`O?2-PC~u1q zD=DIx-i3~HV?=P+k^7|R^bmsko#7o3CTCvSd@)CUM8n5N0Bmwt%9)~HL8{)*aD4-V zC_n&T13J+jfC>%*HU!V>jU+q%k@8m*64+7{|9Zt9aC~n6E**mokje3Kdp*dzvIj}F zCI@phF2OR`;CToP3``Q2Av6>~=s+*e{&PjOm8g9guJB6fag^yBy53W9XMPo@#R68O z^mofxqCPUfvxQ33IrAF3_1vKtSnr_EPAJ4p9Nr{E%T zmc`7fuU6D}pB7@N&6qh{k!^BlJ%16e+lJl;A z@J}VD7*q_9AFwyCHZmZ>mVxl9>v*LzCN3@j$i41X30ljm5s)#VTvKU~lmM~{?Lmva z^N3H`A2iz8dyYX%9kKxs0wwPQATt?)&Kl0GnA0{kh}Kwa_P{|wY$NOhL4q)tBns3b zBjmFo1tIBS;o&D|lW*Qf-GkV44#!PJpjI;mSTqQBcDoXS-P{dckMOCVTJOcCfB*L7 z2zo}3uH^-^bAOKh3TKl0+}Q&rG8u47LiQ~Ct79Wr8=KFy0%-aXT!ET60EjzQ0o@7? zrVIF(^&nx}4h%!PBUZrU3+!EM2Q$fFVD12Ie27wf?B2}L`wUTHW*9(ZzXIDn7N9@3 zfgDIkW`_zYuUF2_H4E7|;1xtXAq!$cQ_p{DNJ^9y49|N%lzhusR_bqHm>a)SMb~?aQss#Pe%KGSvW;?SZ>*^ z>y{%P1hC0W`U0Dk6W6U!+$B7LNhB_(9|={_A1Yv_-9e9vb>FT}NUTdXn+Q<)eo- zI!9}d4{YWyLGW=WSTl}+Cg7+7vYqa4FV}!bxdXiP6+lKE z;sp_)ufQu^;q&MXL8&3~7q9K2^$x%-!b9_35XnrL3IOr&tpG)T0%%{*O#_)uGIzh7 zQ=RQnB+wE*hEF+ocL%?!gHBIk3QV0J-8ZNZurd9rw{h z0g@nV8=&z;05{Asn1R2s@_~TRJ&|PLAd!@siRmdgc5pTsz?myJJ~rkXfQ)545dZQ| zZEP&=m8Yon-`e4xJ`{hj)Kj_#o1&NdNz*hC8b(GaMlgJfn0T4gmax;^he}{{_N8jY z!F+YT@~Nt>I~-sqS2`e33b9duC2d|uz?X}lblw=HJJ@WU(qtR2njg)+i0i3N?q+to zp8vBZ!r5oGQfi0lzi(N6Z3m*p5OZXTD0mxy{QO{wwEDn>&8v;+8Z9?2v zA}%Dc$LrCPy4HIPg+%6^gI5yYQNdnNH*f`7zkyJCu!Rr3a#~w3g?9)@dPlWwIza+} z;c(DwGaAd1XntEH2kj8tyu9%2qHj9;`}-@n|MSeEPJ& zfvqEEn8MhOt?4;uDXxmHZUo4ESp_>?FHrphLsJl7s#5@kDE`IKQWTI;giJj;=><>j zNP(7h{4y%Q>fu$40;2L0@bKDmqeR1iFFOkmOhI6&-q4m9NErt%FnqPYtv+J4*0Z=L zcLxUtguK?;Zwz>2de8~k+Zv8s8pisCEm8U;@PEr@}$yL|X=!ku5E*XiJ`ueyA(b$*6*;=*}yudPd z#sf_QKr}DlO0xsNCaevd&*L*QA^%3jmNvKldtQXJ_?qRT&QzIWL1EkA=0F^=F?hWV zBP295p!*D-rFszG41NxU3K5e+G@@?FTWCd8VC!l;$~%xg(-RlOUl4nr#$|Sqd4OGI z4IE)CfQw4fl1#5soh11Sk2vR@u%aI{RKru@G!+RejG51z1TsKGiJ*spY%pUlWaA z-d)tSb_1n2yZ4gA5V?IR#Hrxx>cm z#!l-0zScJ=E)9ptA@nx$X9A_#;?K1Id;a=I`wj3Mtv0RDERQ(R^XN}=Z%Z1=I`iZy zrB57OMNOB!GLu0{D@8XotzUK$1n=35jOrR+iWpTi@O4!|dO82ras`*r(*=fjCkBt_27q(9{j(g^pVC@-+8I>P ztx$0SG!aq2`HJrI@Go=6D~i$|oUppwx5nF&brFo&d%oD%lEJKqfvm8QWkNU4mg0=IpTdB26G2!Mk!fk9px#;|XuWy@ zGX&Z1e_Cl|BfE}#9z9@f&~Xl;szEQ@=xlo&%JnMo>UM{+=-UWiy?_6W=Mb!;-Szfs z4PX7Dzv)z&tw0P@7!Z;P@q;q`1jLzQ0^u8ES%7S}IUre5eBUuYI~xw#n82+gMfC>w z`@_$J{@G0Jr*EIiK%8Js*=H~TvIh)xC|ZD!-;VO(EMLqBa7GJCOKXL={jZdxSDYv( zfgN*4D)BFzhQ`S!gyW5InC6jH`)+!Pwre>)31+qN-*Mjk!o9Za8<#Yz@v+~^JsF>u0uo1H(6u|CK5CnKJ;-wS>xyEH3YJAVG%J3;;<#5K}%cUYREMXK*0TtU$@ z)-Qfcq-jicMd+9s2!@I(!Xsnn&ShMu?;0nmmNoGT&;kbFdWh7`EQrEjTJaBpc+deM zCf=g~uRg^u4CSAIVY-8Z13SjSqPh6*#cy^mMWc5qkRG2^4>n zlP&X%_8trpD*xeWY3+auqRG4!S+NFz4KFl3@oDE|{2(-Q6?`P=4LkNu_SG;n=?xXU zClN0V(*h(YvmA4|W8nOmRPZs`gD{n{)R5s>WYWk|G4pX3+4ZYxk>MpA6%MSFQ&K|( zdI|}9w8Zzys}=K~6%}>h%zw2^g`-*<+FMVQPh4RiYEY!dF9v7j86UKl)YlV&xRWkO z*7QRm37ntk(5xSr7>nwouEERr=I*@ANBYwz7H};EXI95@zoy&RnqJ zizF8zcD)0eGY7C*{wGu7uwjq2y1M#56*E|3Du50&1UebhFhE%gliAeZKR-WDl);t? z5wd9|gO-4H1Z0|80xYty_uh9jxdI+x>?3Ug!K_Xe4Zbw>dXrE1C$k09RQ!W*wn#C* z1lVK3AxXm`n0j3Cda@jz7^2&N3%hOi?M8)sBz`hdbYED&7>`rX_1lJ0KgVv)3_%`~ z_i_Y(o)|hdmGWnIx`_wpNd$|_9#iF6npp@cRt*)}Ia!eDDRSg9E)UzaZ>TI|rs|s| zCR@6F5YXUPM=E=*0~CqaB4CBJ(XO_@fl5vQ;%)-=PzXT`;PWvlDYGB;0W3QJ(rXnI z7k7c|EjSn`-qM{D!vB?OS%AD9n8{RqLB? z(n06_<0**=&;McTE5oYX)@T=Er5hv! zq*)*!At51(ao?r;oPF+nE`Rp3*t-1Y{N{XfjPbUM%2^So3%m8O2FblDz%UEIBw1h9 zmI&;i!$$5DYhefpwl&5Dwv{|w$CI6zK(JG2F#$R{ zI$ANu*yHRiPbqhFcmop|>ikGDWFON58jzcZ2Ll0_(K*1%^*{`P!Ln|HOHAtz;zB5( zqV@nm4GCBmRI0;ERbJecW`$A@2Ph4IuaA*Aq1|mc)T*hg`%_pN%~lWw6@eG*oM4qM zJQp;N0J1eZ~R(~i3=H~>u9vP?B3HZ ziAO|l$VuoxiVPHGUyblsRGMyQLzXzo_%RkOPEtAgJz`weK6dlC88y!MiP#aJ*~&f? zLoRwcIC`XyUm$@*lVy~(Lyi4h!r;)Zh;Vg_M(5yXU6f(1;Lo?*&5Z-dA&o|2f6PR2tL*R*`f{Dwl3%ehoQfyxEP&<8rM2gB@vKg zyH9;7x&4#y)y+(02+Lp)hmiNK8NeUMcVFYPeg3xh>g6+1sUy*$nuy?3^KO%xO^R_z z8_W5I?(xp3k`%uy?_6K)hK)J!F}#`;w^5tGna`Gyn_z#+%$71kHF)^N8~=1pQtLFp z-=1Xj*^C7vnN0>^sGjimHT$NTu#m6sVHfacEMIL$cmF(^ZP@fMtMvEd`6q@7BGxbW zrAZz+dpY)2EzEL{`|ypGS@`n1rcu@)gaa|uOgd|d^qLlaC-7Yh5bZqoY7i%M0w=VS zU=rn@Q>>l1tZC5JXk98nJJevEj;F~_(v#w@V7(fFPv+w0)Px9pUDfP=8e$Ym{m5)T zGZtm{{EG65zJv%vr8*sk@r=3tfC{N%m74=6{e=saK!_Ig`vLh4&%c2oTgIj-E?txr zTVqF^qP=(Oy3y&;O=G*rR=Z3HM1R!}?5F6M^+>c~ryx>DdCG*ipOqYU zZ|#+DVj{OKr9umc-118VS=wj=duZQt+i*PMkn{Hzwouu7D8rz4{&vyWnh>$Th@{!b zsMi&QCa9b{-Syz^A&f$CAe+jw1rRJO+7rZuW-OLl0bYY*Sjb;iCUk^mBseZgfz#dD z_c4--SvuQMgO;}U$-2D5T%t}@AFi~)j!z2A#KYSt z&iBTxdA%c)rKg9%wd_f2VrGwPBuBd{EyjqCpYEtbI(jalM07OTQACuXPdhcKe@!=v z^Y9HZ4ine$DqEOmuo@1;`hU_B6@rmKdy3WN^gyL!eO-w_%Xw1+q4D=Zo-)n`?d9kC z*e}?{{aP4fEXLG4zgbLQ?$JQH)oMp?W`8-QaY3xX8ns92II5_4Vkp6c7r5otwjnlD z#^7D3IJSXp=Srq{?SIZMkBz;NJ9V>3L$eX1^~DCTIXH?_O>5ezG#zV| z@SrH7^YO#vr>#+Jtr|CM&vSU&$CgFb_%VU)8K~EOZocXByqZT14BDi<;_UcrcK@4q zy`fOFe-iw{B2GDZrd0NkLARsFAoElp(P-(Ht`UD~o#!d5<7IDd(UEA`g=5FD{r7yM zqe9xT5?=bCp)&1t>a1q-~Q&ZQwp@m&Z!g&PsMiU$lg)33c|DYxXL!3y;!q2A%*%(^va z!0~0zcnuRH83e~(-oC84Mx;YXwbet?!HRs$vu!w}hk2-&i- zNg{%lMmZ!rM-DY4R32nyk!lx;6y_u9_V@1JVaxCw*JK}hKRkX7IwxFJRqhiDsc6TUpFSh&fYrB z4&@en>*uf;uR=jWXOYmIV6{v>cau-vIRA6z{%cPjY<}xxp~Z7xKpqyVHi8jF5S^@8 znKQdSH&k+AhjrLZo%6UAP|*AIYFqXeTlubj7bUlm&WhnQ?Qf01CkT`qK*LO6aRuDNkFw6}eE#Lal! z@Z}99EzX-~@rwU$BHA>MCzj`@Ox+Y77BDwrdA1fcW*3E8pBh=sm^vvX#*w6xb18Th zU_pf?I>DtL`R^Lz-5VU2|`)n``!A8fK*H-t{d0uoYlRk z|1DNs43$fs96|WAI+_YIYFwe`dU42E{WPiILII5pF};oUs+juaWphr4JRt3D=6wxe zy5~YSyw9kHKvBn~=C6U%aGV?+pR#w_@W~*XF_FCzdQ0i^ADDl!$1(| z*59Z1bC6Sb$fZy)F^ZLufsY?TAuu#BvPJCZR!E3zD;c*s9=B>3yP>n}3h&V76gY-rH(EyHBcXC=hXMQC<~kCAB=*OB*2o8A0e!N(f7dxzA+3*-=JH87-mvdI_!rj@ zXjyz39li5Ep6Nbz6dywSnb9YM;OnTXr8><;)me>Hei{;lF=FM`TLk|chgQ$v7c{I5 zwX;^PqrX2d|0h0(4H>=#rNSf(7F!{u-*?E~46u;je1r}i*y#Rsy=;Os!zoNB6c8nf zR6H}$L&oW#J>wApy72dphcuI#RZ!0&Ldd@sTID5&7l@Tu_<3DhlScVksRUDU!G+=3 z)uilL^m$1Te6>iy{og=348LO#t8-5QAD=ag2>Z-DxT?Yvb$KV+4#3;Q zW8~vDBe1{i&c4l?5}Z#&d+wo)t(9<(yi`a2sDvgBL9#AHhG3}7wOYBfi~f8KeAA;F zss&ete!MYZD+~-c=)22j^M)-8f`yUx#vuO5HN6a-79hw3#?Psi!ba8%IK^7 z`KDyOJs#(^-fe&bl)k7e%_h;DU{Ux_1@+Yj1Dg_3q)x z4h90rAStr$Q$LsS{)xGu(YSD4)$IhR=V!y5ET9^>6#7bu8vPa}6e>;nP1)U-vjVnH z-oQZr-eTDG)k}dL1`YFc+LTmCVSFLJxdHS=!f}{Sxq&ZtZpu5QASs92(z1tv{VvCK zk8ztGo1yCxe=imJcAB02G4bTueG_J_bdSM?@dpbcBOY69UqA;#D#ACy{zx#8d|X?5AT3K3c#)l*eY0{Q!vp$}r)advz1fm^Yn{&Pan`L{k1BtqG&vlLD>~+@rOz zhYt*{hjv<-n}Z@9nTb&W#xazw(dAzp9GvGmRD7!gF0wz5^pF>>kig@3g~rDMz262Z zLE~MiTDQBbt$I=iXzZmWymnG3-J8q=omM=hGAJD`jWN5|)z&_^R`{Y)FquePT%7i* z&+FQ?7E3Niwac*s64EhhNr*Ezlo(#3r#N^~x zKM#ib`r2UHvbKRi(uq5Wr%(ZO13h>xHZG2AOm3k?jmgD~&YmhXhg+M9s+{;rItf+r z7Q#rskOapcvz&W5J-`Deg51<9RutEqmX9=TEvT5>x#Et7oBX>Avr`5!^N_-Ub!}qs z+xw#o4ad9i)_b#PM z==E!1kUIn`PR!0mcj;I6z9*g*I4y)QP%@;v&+gfBP75=W_b2zF{ZdP$@q!6@K{I*Jvwy*u$}9h zZ@AD9db5D?Y!?e2lBmBo7oslMc(G=S8RUG2&g}cMeBI|Z@5`?dHsr|b1V+syX?szx zUQJP@GS$>xL-7&eW)j6Ey!f>9+O302{vQWcz{Qk6SUjv+^ADEKTyr3!*aiTg#1nU5L!zKjf71u&Dx<{xkNC>b45=sXFQpz3 zzS7E2^LrNSY^cJ!+AOMq)}a8iz5-^N=LHXnj%y(fnM$rzbKvpg)Ey1S0<}i-x>xeW zsWC+w%8zB4LD~Z4CebtuYTsg_NfPnGDqsNu;EkY%doM(bSFS!Tt*xbkop1Q@W$^50 zqn?sZV$Ee7|5)MC+1WJR^Vz?8pmPM63`Z9ituq@buN~t@fXYh|b%jZmg`d#@SR60xXi$NZIkE&s=e9tP?{wqo zFNbY4*9NB~?up{Jnx$aytw2PRET4U|57ik8D~5wvS9ci(>Y^O3otY$mE{auCRsp+s z`T@G82q6)nmAHu1cr_anmT&7-aG0TA_3rAShVCj6A)#(WZhhL+Wic^19m<;e`dn~O zcA{uWIMooyb5&*RHRL_=vf}udy_5r0* zaD0|9xYhyu+SfL{(KRE)o{eS=pec$*apeLS;^bY9F(;V~F?1aoV9q=G*Dxj88Z-hB zmUP;vuk2BLRK=Z6w#LFF_DMJ)Rb>*ZWHW}9k9hg!A~g8XVK9!ql1?d;5o-7YA0MCl zq=AtY;4TT&u|8ieCt;Kd0=WV->g5BX^x^jb?agwN9e}Sw{YzqJp_xW*$?jF&I1z`1 zNo)?c&sNbZwz_=hg1m7DjwD^?2@OfVBW`GyHfavtTqF7hWZeWNqKmh^jzD>N83rLg znRS?Dl=8%fA(p_rNn6PFR0l&a>tKQCc^F1KJd>gIiZUd2a80c!wIKsM5scZC{rqmC zqeC917gGVe@U?Ve5V$I~YuA`HH8pv@9&Ft-6QmJr*_UUKeI)Vu=~r;L?I5TUH)ZGJ zZ-u+N^p?3dhWUoOd*uSEtNX`->ue1H#39w<&wYBREX|f1q4Bp5eR>-(U(m|7OnzcC zHe(c#Bd3FWY1AZSbP;LJR!Ed95p>W;ew{)9+VbKyB=^pzqloKoLp1!!4*u{Ig`PKyt(q8<*$(Cl~k2W&ALez39 zVW>AZOckL`7)Y+ruhP@qM3LXiL-%_?&aVUHV3UtzcXHsOg6yjL_N7XH_uc8q$$U@2 z86|UbMnHp>CC!Z|DTI(iSp}Ig4Eq! zF)l7Vi2XFSd&W5-N)iN^ZpO)sRjzVW2ehoB0U&@5J{U+sCylQriJ*S_lgjYOE-KRlnQlL}M6DOu|8}LbAXeC#b4|c4IjLGeDa& z2~n-VN6qkx$fmrFHcJ>oiQstD+Oj8pQyw9YSSA~u4H%8z!fhG+7>bUXGdv}aU*@Ex z8p?--DI;Ozut$BWA;1k)uj$+zO7sE6Y|Eh(VKiYuUBVqxNl6JduU(Kx#+)U*cI3VliPBnzM$?mFA+OwYfGZ%0r0A1nY9m*t~PZ>bE} zGL2p_I8`tP-RbShW-O}$`US269uj@zK&IEstsTel?p=*-4bHZ{2=m7K`INn$fVwz^ z`#14R8lnz8!2S%>{EoI}nkX*jg=g*Dbz6auL-=p|i5!ff>WjBUZW9A7*I?c9UA3x6;yQtcNa1(C>LmK409#Ycyl{N_!R06|7JMp#OCJtuGh3VZrt z%}rN4r1AzD)TeJy3k!QcIcWv%yOsq7)g)yyr052{;dzcT7%S(6Z1Co z=Y&9{WK>GXS2I-yz$a_Hyb2BsQ<-xDn(KOk z1beQ)v5U>ji~)hnS2b$+j2dZT1R!dza<<0t z2ne)a%G-Rbfswm02MJbQ*yInk%w50@?94anMHnA``2zjW=O>l+c6I?C(a`G6KZdC& zBB>Uj`dRa?3B#X&f>Xt=s(=416NISXw+4VT;V4sgtFEdN0uf|5`RI|p;7Egzw8EI+ zwE)K$SQcW*b{HWX0%GxK*?%ACj{kj#6BA<5 ziY~s=T;*-?R5WOqJl}oM?8>gk-%vY$^5Hw?Dr5;vj%Vx)JzxI@pHrkPXOC-kisli3 ziqLuqc|uqgPrli~sS^8K(J(zVg^op>p4!nO(CAQMn;w;evx=gkcDrQr=O=HUwizGa z2TZ$em*1C_F-Z( z+CtR*G=Gr%z%I?`&(w0iO%4b|F6Oj`Cb@UhzPBV`=@6}a)>?ub=Fg#PwzJ?cRuy`b zLqYU+BkZOqVpMUGJfdOD!84C&qDw8KBBe;mWfk_~=FGD|K>b{YFzI#?9^%gxvuH7n zFa}i|4*(Wk`pjj7K%Y!_1ceA=@4dw+5am`Q+lHq_50ai`RMve2&>LN`X4gA+6o5=Z z`S$6mn&0;e{QhGaKLGot+a(3zl#^i_KR0(Qn<1c#0D9%5aal7lE(_y~sn*Be9yvNX#_rde_>_WUq0|#BjaNr{GW5 z`H1uw4Hy8s8o6&_wCQMy(FR#eFbt)C_4qag0)27xE8!ro>2`gG>#Rbt4d~iPz~|nM zF#h@E?c~1Hg77dEo%KB@r|T9LFDWb2O5}7(Th##x4nxMdrz{E}WMh7`AE00P5)k2^ zMN@4f(C-Fvk~rQeNIze7N2G)gmB59t1g6g^MEAmw$P0-^+zLq&#BO^wV>o6{Wi#rT zOV`{{#uerxYmOjgb4d-K`5N)Zm>*TE?-6XBf3lASU{;BotD`^mH_Klch?u$p9`*+o zMC5U76YBtmMA&FV7{@SQi-vRq#%6qARMTw%EEjs>vx7ISDq6wLX12yj*ESgNa0qnH zLs<#Q5GBYB>vlN{atJDvq6RZxNy}!QfAHXeZr9eapZmu?GAHz%yaB-lgtnhaxLEB= z&%W;U0zhyFJ^-i;1m)Tw>mC2~FkpJS8;({qh*F7tR_|@KxP;~<|~70&WUA*6MrruHKO9)9^#kan?CsW*jon^UdK!qjAd-eC2TZ&^`?UW!*#q%r?L-<(-~k`a{(Pga%dJ znLq~~_)A6+#&*0=eN?r<#ZV5kryF8nsUe?*IN~$-M-Zis0%>}6ca$9(a0$?I_s#rd zsJ7KZP-+d1R5!gEN@6_#r8n?qxykyc#Q1Y( zOnh)?i_W=5lFB@jNvkCZ`>d)x2e!Z_MkeGoFpzXLbkP9wAIo^xVy(NIfzaVE%-M~N zgMg}BF!Rq(H+0kSAXAIutEAIiQo(>*_@HoL&+~u!YU}Dg1GFVMR#Z+}N8mz@bRh8dEml zW%g<9hOEW%xoCkjI81=0b^j@2a;qM|nY9M+mac~WSAcMV5|Nq}K4wV&Wl$dCiT(`X zMP5H4ra!nrbq}T#O3{G|6hz#1 zJ_z%?VdsbUi3XMmIlt#d`>*yuyxgoTL~U)Y)9uBSq@>`z$9oTr-#%%jOzkA1=9dHA zAb^dJfBB$%<&LY1OAl~C93RUTs(os`ZiP^=&6MOY+aN~7d~opD3@f^E_2oY+RoQDD zXbI{uD77&98JTojm}7pbKvge4^FfVyjc;*!r;_*g8cx%D+`gY%c7z0-%x-WY7h# zy1cS84X&W3t-xqjZ5X49+z%)DTTgX(vG{Olf`Z--f$qd|SoN5;8?yyBSFAm5V)4 z50}osy`T@?-48-eD@py12|R{v+;8tdd5p~>rWdOxMQmLS=3~5k`pcK6Dh1Jqyj)#l z@Z7_y{TU7#>YeZCzjxpR6=sdQ^9?!?oTuwcGeBCoD~_Asd%o6>punf{1-jMY7wIBe z-XU80eY>-7$Rd7C-2+aYOUr?>lUk=?g@u4-9hGI*8T0Q0X0OmVN;D21u*CV2G-&Dx z&^4V#f+1whMxP>|^Ndm#hZ_-c#Ynyx4@d? z@IO2JB*or$^`*?iJfVsq5BL)P&ruriS2BNmi04p<$P ziMiscD&69{d@}>s-a8*ylfrrQHW}rVwQsK+etZ33+mL67kR_4o;^4zQK#-5k&+`W# zIH&PdB_`5PQCSVAiH~>PdA{5~s=o;D8*(4x#`_#kPO39!7`5ur-VCTMaGuM>me|G3 zjcIBhv}e68Z*mb3?QYhv_}j7h?Xo2k{OZ>21c2{j13BlmshO`@2=J=Z+$Z1LLPYQ< zVMXT6RNCNy$g~T1>T1Ywz^@hgZt zKz6cL8kv_W;m#)e?IT5Vr%D6&MU+e4X(nJa{a|}biZrd}ZzD~ssp!u0)Jaj@E%(W3D5Ak^ zRCB0M>(8jeu~0TKN%cG!aO-A{t);o0+|`g3A&()iwm-8rD6voDZ*H20X6%f6qq^|$XC%qj{XQm#)Ojtzg7#rMOKB7 zyyNbR9=haB5iS~99UB+_I{yTht=7h3%N23wvpCQ(2P%_An!XbRf<_j;I7BppHL$p% z!a_NC#09I1!&7Cq@*}(H9NigylIJI_pB82Ug&;f?g+V(p~c@OAppqn&zN|f*j3WhB0)x%kX*=-2} z`0-_zjI6A(#R>>n9G-tb8;Gr8rS-p^QpOK1W~rQ`0Go%7p_A<(NeN*1(SJmQ$9B+S zw&_8M{*0Um{XN)sT{8>bA~%_zuM!N7@C*mg^7_!>OCk? z^rH7cvIp8rDUu%cre7&0JY`V4I{%!(#kmj8W@W~em_SU-72}MZi8be>Q0ci_0y|n1 zU5T7guR5-eKcIajjVi(Ce5iiq%a<>C0}b&4fdsJ??~;6xc9J7ZF*lkP&DI@4@AgV8 zT*wTCNp%qkTsL!yi{WH7Wo=3UUTj)vsGs1kf6V(D>}&VJ-LBxv;Cn8$x{w|JM>B^1 z+(rFf<2sS+a&LAx=qjtZjBclDZ`!+nieVN^i@Tj!&DEFE4wZu-2v^bjo04w@YqWP2 zG#MeH8%FbW!C>a)lTi{?Uz>&jM-#=iqv?rmz+u=Hk^CEDW*j-T)@$(B8lA+mJ$cKF zCRH5_-u^Wn{puR~(4{1iB=Iy3ZxK4mTlFqVzP^nMR(V}8R3uO8k}bHI%9_fze)scl zaq5@)1d%@eVg}y1DGA4posUnw$;J%WrBr-|Djrrts|S{VS_kUTb55*QNdMv6lAMp1 zfNs135xf#8KvOP74pj|-dH^+=Q2Ut#4^gVB>KM#@xYcAI^`A#I_Pbfhu{tnh7QZ$~ z!g5=|tIg3(P_Hh@iDbajB9`F&HGLx^_34z>OPpt34iXtWkEy&34WH}F_TdmJAzpFrAFI(SEn`sHns05I%Bf!yZsT%g?7>14 z0W0WI9DIHIn-O>hjkN+lsAZ?-Z=cGp$i#dz8=JGCyBGc>y4JOt^$f&0*^c&a<=8wQ z3M#GVx(7!Fs@uAnNCdlr#`8;WIjhPz@%v_$)ap`xK6x5bHETOqxW(h}-Oui>m!QoM zu(Qz*9&(*k&sDHZh#O{(?U1l@3=9tDN0>}$2+yPqg4O`3qH99pIck@S93o{My+PXr z2l~)=0`Ya4)YMcc^Q9Fi&36pHG7d4Qkxc4qiC{`V3e(&fg7ufLK3=*#+2N91zStCX|Q{Zc*? zsB(adq2uM_Lt8q)I-sMkB5R;yu!JoJVTEfZ7~^V}?vxnU?-Lh8^a>m)G|zdK+C?ka zHS%&*$FWcSC!dZzF5W$&cl!}f7S@w{A>rVB)LO~(kQ3Liiq14VR(wva=Swa6@RXJg z?F#A2_xv&x8GrviQD3!p#%25{aW^`~2{V79_*Os5t#{lMseT?9%8glfQ?1w5)^y9J z@cL4D(8&z?z#n@%o?KVQOVFM;4k}Un3*FK3bM1UMSQGI}ay}N?dbHrI0)S3<_MC?b zAG?XxC_t`l+=lMffk<(aXhp|w&7oViu^}8?s zr#&RKIp*h@YV6D={Bn$9!Fzy#;_+?#0MLo0g&qx>H<^CpP002KCfi5NG<3aR6%M8q zj;FEYS(b-`*ZZ&E`sM4$#}IJR&OT-#HZaR&LoAQKZ|Uu)IZ=AH?j@>q_$K_D@!^tB z#YA3XBON+6W`fRQN{F7=IyUcYDW+vNEtA60ua&YVDO+7T5RbMqde6s=+w2q+6et%@ zKGuK>_8NwvpkI{9@MXC-R5+j_1qvou%RA;&LX4J3t2TcO)nxkuB6tDgc9()*$cZrC znZS{8mJmOx zrn5fzV3=OvpWUfEdPzRf5RqhHOI~5(=Sje5nL-}w{U}_zAUedmyK{eck$7>8T9kBS zlYZIr-24qM3`p7{Bnnmx&Ofc`r+(b>(Agq&#!%$3Bp&iEJ>7639|Y&=i0Bl07bg+@t8QkMAF!p1`EO$8*(Bp)_7PL9xKV zGw^}=bmd+WmwUyk5aE&!<(sVs?wTbj0S{{0jao^9U9UzwdwLb~ol$1jqv%hx*4=4^ z=Z$LKIJ{%RXGQnlgRVqe=~YVR3AylKOmnT1V2Qed+3;qp@EoC#MhE!$KQCA`*>=a3 zW3}>mEpixc6_m5QLdV!`B~L`2zs9)l5Yewsg4;KfIkNBB_0{OoZ;c*x-T$FCkqor-WEqn2=7*xVZ@*>Ip6)(Xa4J-H zwCEm0s!={YO+nZGz}J)6bet>ww0LU_uAeGDmca8d>KI#Mf$Dj!%UFewze(v~3JqPJ z@w<<4-(Ij^vBBy7N*BTAzy-VRjl&0-;0v-&Z)N4HQ1#-D{PbyX8L8Q!l*Vy7BAj z!zJb={l^u*KVB3Vod|l5OHO`o?FK75H?_S{AvO+`bFUFD#nbtck!+W(o}Sj`=C4n@ zuVkD(*q9vNeBifG?0qQR&Gw>cE+5~3$BqyO;9BKOsqm)b3AlrNcXiV!_)fM)VTI zuu{GbswH?E@%APTbWijNR9Am?%4nbawrufOT3LfCE)Ai$ zW**nVV|9|G%}*|94l)>cX#Dd40rzEg;dw<)-v)tmExk)U=wf_Jd1@z;Iyycszd#8x6dSt9t%}b&od!2@ z#7VDZxcS1Eg!fNmGcV45cD-T8h?TcMf7*c zr0Fx;-^xE~I{Loa%ImkBobM5Rd4P1dx+)sQjZz!<$v)3H;zu4~m|jnl@A_M^B!>!P z$(=NR;{B)AbrS4aQ4ALHmJxRbNB~eKj2rmfvHW zP#E)5i;0QZDsgKV-o?Zl0RbMX~zA71T#~LsQxBA?E;)X`NKNYzK4yF+>fSR%>o>!1hF3g{ z*O+zBCB37;h}`&=NPU#5EM={3WJHs$)eO`U;(V9sl3&z`tm-=cO}|lcis&X zXzRkJNgl*$UJ&HzaIBrpi^*_mx4T-I4@7y0(e))eem=SO{rmTqK(v>zNL;veuks-^P-gK|GDR z->6Hi+xL6Pj8L#2SN_$U+C}t^Kwx|K@~xp0{ds|YwghXUqKfizm-)wsszR6e_yQMP zUX85T*P4RrlUx#_>+ovr13;nxK8MM^TJp~HC6h$t;|L~;LhL}By=1y~K7SUSyfP6? z7)xE;)o6%d%U)Hi0sFT6<7bM?63*H;6p|{5zrjNR{psm94tz={wi#WueDd7f+_=ne zEcL5OLbSwaU6_<>Ph~x&80E7`)fP`FJOwUk7}t=`OM1HgBFNUpcPRfZjR>m|QIjn9 zKQK3vAKj|M?6{Y@aut^z%*AVHfSM)8i8v0|576ZC@}51C{dD}j@ZQW_4*K&&VFC!y z_}O*;s#=%i*s{a(OrJqdH^&m%)p>}Ezofeq%CTwKhB(=q^5)bMRsWdW_mj@zN%x{R zZI#!^aRUPekb;5jq^VOkCTiuM9c+UH4m2!F8QA@F7Pu#fd zZRKm&@NtE0-W}pQstLdLyr)>h_BrxmjQUPf1eYm6{lr$Cvy00JAB|>}n^cDHblr3Q z@&5V&J8c)x|3M(7*LYrBZ|t`<>Fxw92iwxCm9~MJ4^X|2KdKD)=xko&sH6K;+{Ahi z`ifyttSqRN7*X10X&iAfeUEjt?lDI1rPZysq#&AEqKK@6|~I?!aqxH_YA1e$Xr zL*a(l?JNb%kIpI3JjP%b9kgLE(zTxR!K5B`Dd~3;u^5e-RtH}~e#vJ2kZ>qVmvTsG z+u4Avh!VDGnp_D2dsLE&44;Tctf@O}dtlR3_xNq_hOfS%p)OAo_+uCxM#h;C-n5+_ zfc{}+vSu){RtY!0NaVbw%2m@#!tvuLS?2lMuE(fC%NLCu{ze-#a%z!VJ6|jpP-IAa zwIAQ_V?EI(U;3s!|BI>MrRPez)03{Ti`4#I*O;MY3#Xjs_9J%*L&gJ&d2DV4c3+ zsHjL+5&ej0K*smW#T~DQ`UOM+<&{%YhL9`X^lRP3ef?@Stv6P-#`InflXs=Ul^0o) zjo3jrSx|w{t`{nJz{^HP%%LMN26U)k-|@7?@z;}Qxfyv zul#7LWwhu{ENt@Mmj_fAzjHgo%?37KB~bEOeWIJ`dc6_o0npBiA~TM6;u^^RAa7<^ zBjD-3f2?a_q8eq)p(to7Dk?56l(a#q@O{)#j4osJipdJq@CZjje-MC9im8tf3o(*W z*{HS;Hd-$b*p|AO@2UgPfK_5*TY*=R8etLBxE+5Dn8TxjY(LOeWWPpwJ%S(6C7)#6 z)kKjYw|+;Bz}CtA`qT4LE4KH8D4G>M?9?>FscA*w_H;4R$7#JW5EP!F zz!Bvz#;`JCBkIgFE1Y!px%v{h=pbl{=Y%=zBK#$r>K^J#O-Kfo4JPTm4yt#DFd4J` z*Uz(}v;Bw$qQQXyk?)I<$gAhsX{#ly{>Kaz!$b#mX9b8vAUnDERCS9Qq`lBeKn4L5 zZAC+Z)SQH?D%a2>i@7NyxP`-PRpTlECJ&CyXE^|mZNvKea?%HB;;5{mJCsxfPAPmY zg~U9f|GmK2bdd z&}MDGmxOSQ2t(p83Uv!cHFfi2J7#Qp-yMS{o%3})*)a}lG`FyNuvs7ioU9!=yo#o_ zK(C%Qst4IZ10&p`iQc;We;h1P^oDQj92BFVz=h57#PXpKZ5K!@M!>}STt`oCb|qWP z;`S%8Ke(;@uVT1I0%YSndSIxEmJv6lJZh7v|7>UH#Pahl)4Z<_{*7EIHib{J?)0_I z4_|-VXOW8EdCtGzWHWy!obyUVJyf*wDTOj_zMi?O-&6*8U}9XXq?MR=8@Y!37X>P3 zlrJmt#q=f|iOGZv$(0#)e)e+s{HvPBWt@JL1R3s9bDg_s4EM|1;GWr%k`h2K>(Xb% zpI`Q6dU5%lyn=#4xwBCvIjvF*$w2xxMOp3k&BBK{I}mQ6jwWl=qhq%eR*i(jMG7Z+b^bAB>|1$%VBf8 zw8S}<%ZVQ!<07!Ja(!|a0`GW#UEXC^kT^+Ip~4R)B}T3cpU9TRQPx}QeEN*zUKXyz zr+eue@2`iWJ7{-PU@DhgtLawNm3g-fEM#T#%`aHYn82Hp84A1Wk24Vnw=VP$DUfAuhMJGsbGcv zF{_}y+V5T8TEXHvAJRxykhtoCK}JQMwsK^DJ#ujy_oX>R)kI&SRIGK;WsG<*9o>ypR+_tVRE*O!rviv45(*+m6 zEa=xsiwL2A5bi-G+T4_fJ?S+w=6;*`arbhSCaR51omKSJU0p8$oX@J()TRN#cGNrU ze8m(UUF7ZeDX+bK30zXj{k30=CsBetk8(?G3-%S~q_E^^+0w~ge8YZze*niRm)Z2Y z)az|i<~B}7ufwBjQrZgg`6^UQ-`qM7@s$}%qr&l@trJH;8uGqQiu~*OC?WbNeW_%G zqS=tvE79JhylAlA&U1`(wCEqU4uhO4sKCHL5TpC$52`pf?lGtNx=#_RQz?iFMt@ID zkCD%A14HQ!@-m7Cis^dXl>12n@hvw=2#5H2dfwg9@VVnlaM`IbjJx}K03FBGCrwxR zjTaK-UbDfUi;%XKd6}g&Zzv`up~8n1r6tV5z}nacFPVP zo&Vfw2YOX;2GDz>fa!u=0F%p|Js24o%EXzSNku6&86%_sY42ZobCuwxBD|ZRUy;<- zg^K*zZpN)2!deH_-E!e^=aZ60Iu_Sxme`_&9FpY-EuA;`Tp-d-p39J%60_Hx)*yLhh+*ubL@+s( zbETzt&#)dBmob^ohG2VP6D32hl1xZ=#}l+@rSpQJ+=oi&0mN;KaAK!1s)MtEuzYr# zGl2q!t664r<4{QiK_`1n<*QV#Zxsth*-FgJ-GVyvQA;6h0s8TId*{n9itc%f(Gr9E zOda*SQ3X`moUZ@L+8z}s@~fgES_t+&f9^i{JXZZ(s1r>-8s1yT*cl>42oMm(HG z^ULJ5KgjgD>a$3ry01j9E}M9AJgTl@uR66i$l8l9xfml*YSeP-berqg#Vq$(? zqil{at67s20ZF-sxx8s#kekw=M=+}>#4Vt%EGhj&YWl)(IS0$mkL=n>9g-NCvX%3n z%lXneM~3Z1A@f87i^uokln7GEm8iMcb1{%eT-twDdFE=ID7gwwry-GFyP zyTo95jC@@>cEs^J6RF+ng!+VzL=AoSOffT!RI>d|#p^1R>8M|kXFolOrzI<_s5p<7 zr8O)!qm$K%jwCAyTFRU-57LV)SL9Y$rDxyhbeE|8q?SHmPU&IBgAw`YX7k(t%1wK2 zMdjfO7Kl<i{@ zCe_ML^>lPF0^4J&P7}_vn3zMohNqSoGHMKybbQzUT#v|a8Z5;WS}C{f>gO(zb0Ir(Tg@_&tt$WZpzy{4N>~p=Rg9 znXO&Ag8lSUd;4_&7ND|2nbev?%-S~pPg`FB73I72JAg<^GmMDzzzB#SQqrALA|NRt zpmc|T0}L%G-5n|*p@1OD&>=`kH%Pa1-Dm#icd@y2tn7!2>4)x8_s3#?oxUJRVV_qA z7Qix<6f$e~NM6jn;?qc$*9*=EAj!l5yl><<8}wu7Y_0}k*61T~5f>+W-ZUb;@&n4F zsS?J!0`#veiT6zC2ZPz+`UJSF&LU60V%^rA^2cg!AQVD~fQ~gr&e)Gbvh8R4q~(Z-O-u9>5&-gu&yjDBNpg(9`}SAX*1F!GKE?u{!s%{* zIOx}325~ZSW&Ygwk}Lc^qB^Zm>op@xRR|vbw`Esl>2eyLm>>c^O2B5dZXx;y*cu{V zx;h#)l1x{sRB9EIfp4>4d~VD0e<`K~rqv+esl#}goou3(kregi+8orqeF&M6aD$z1 z>))c)b!LJxart*>Ie0#hi0B80tIYAI^jBqH&-&0vbX9+OwxaJu1b!e;xggxx2~HTo z9+5UZJ&mZLj?Aw6K@y{I@jzYXnpPGf`Ccxy%vR3G`rQ7BvynWNR-HJInCz8ZT1dUB z&oEpo8vZ0}Xb#+V!oq&m9k}h&Z0DbxXr{%+qcy{Pv8|$;FD+RvU%sLYi8^EQF|g-> z<*$<-JDp!ZM~%I1Mmo^RT74T5%W7Y3cF0?OO}l&A#C?ptFd{PPf?s~M$-g1uOuH;M zsnJe=Rjs&TL;2LluJW3Uw;vI&@z!OBaFBW)j-tBGi;Tc6!VxPK@&Ss z?*R)x@aWTkbby*g>5$-7FA%^xY|l9ksDi9u{Csguo|#M<;BnHHxFjBvs`TG{fLD!U zK6qkXI`i_A)-7ie#`)8ngXSc#UWTql@_2O10#*Y$&t}Ar=lG7deihB(_qK4^k@<>U z{46~a&OA+`MqGS&!*@pC;35N*RT+m*5^*u*Gf0>w&Mzm7+k$BED zm2aJ~+pcq=`n3tSdX(rG(!=guE#5hwc*2LyqQjdSy_gkry0XFfX`~&FtiN@+XRzBr zd1R(k;rjJ5@LN;HjDx@5l3Dsy`PKLBZ+lsudp1NG_>jB|&n4aHxhWfl=7T}4S9BdQ z0l;)rJ3{s}K88SZj(oXE5pwTuSz;#sm|3SKuG;s^9TRG+dDmU5PG`OcUSacMlm~C> zmw}`6F8|FNwxm>Qt(~nS*%RJG!8crTqe?Uo7>O@rPJJ?nX=VPiWJNKYDkHR5*1p9{ z&fen8b0U9B!IPz(`qv0(zQF6J+5a86^m1t;*GCkX>H)s8{N)WnGpKW?ECqRZV%8}J zq~D>L?D|N9H)M(imrBj=q^v&yHDU(kb5M}j>#}S{Re!dL`+(3lGMDowNf+HA&wM#9 z=7lHr8rCQAhija(F>u+oe7@lJ>sFJjTC8_hC%E)>!j#j?8-Ah(-ARs?C(#vChcvcV zE-aUO5eX}=wycgX&dfivQ4G=B*AZneEU|xFSY)>K-E#0eX{Fg+F5L8dmcsDpn=cka zCec;zsvv!9bA91_8@q8U=RJYh;UvER+P;0yl`&EtuBVO?)2~k45Dv!#^rv&tI}8$f zL5<%U-Z;(?(%tRbLW z`P=E4AAbx@5ElxPCii;FGMvk1PY_SYM^hgq&;QW1{0q*e?o1FL%{{gH4)C}9*|0~> ztKr+Q;gwuEmBmA#+xq~H4gsi~S|&T(@8l>SS81m) zme>HTGRDtT?Dp@L>D?3?9tmCc;oFyxm6erjeNPqKljC%Z_7W%t-EL;t0N}p?>eyay z|DrF9`ReM07~VkHArSX3eu*attZlPyF0RKVojJPQ;AMIJG|KP6i+R(PAtpMZLUh51 zQKWDXBwKQK-mSQFXKt!cARUWmz?aNjmmsmU9{V~Rg3$c3;r(IAW8ue$c)&-NXw_Ah zhosG*g|H6Bjd&Df8ka`UT~PHs;{Yv42r1f~w!!1|S(Ue~HqhY<($T5g_UOrgFfn@3zC57F*ov10RW4%$ z<$txOjzF*zExLyf^dRK$!j=sLf;BS~PHeXUS=I)L?JMp0^g?wM$mnt6t zyQexP`le=yWM2RG^@HDE-k=m+FS?jUXFwhAd*dk=6qshg{}Kcm$~*`QX;!#;!{E1o z=jpaXcs{#oVzwSRVtRFX@z!N$79lS~N2uLZVMj$7dEpA{PhwQic; zQzU?+gMb1a+I&ZDyQuTOv4UdYCUydu0SeEx@b|Ov6~*z${jvQWy;(cMC_c~N1~xeg zX!C?hRzQ8BoT5a!NDl@%&28SDEp^Swkw~;D1L3)`WX|`K7qo9w2WM?p<#yKZwaxa7 z?W`}q5ze`W{Z_;Cq1zf2(7geLD_M!cy9~`WtEdGs;_EruQD1Ko1WCtEayoOx*~nE^ zwA|E1pHcoodExzMX<^SAwG6XN1;RjI#u8(Ym-PV{@nVAWXAdv`h`1T~KT+COv@XzhGMwuymW4*9$n)qCv)^^mtfFQt* z0bU?{JrskGOI>PU_1_H$leP$Aras9;rQ?_fP?LM2@Pnjbsr;l?R=x5a6ydfkXJH1* z@yhUc>?ZbUi$;%WFTC}U^5_kPEtwK+`C-Xxh>93E@k@5B&Ba$a<`MXA(pV}8z1W$E zq!Kt>A8XI?pSE7^E%5$o-0C3undKlC)8Q1?mrIQ!^G;FVV}?LS&Q$DSj87gf*E!~1 z@;dV)YusvH*?Z*wVppqYFnC5K_Cv7}LDxO~@QLlGL5X-Ue0+~#Q#ziHcI zZ(#&Agu9k-=J=HJxUIZqzA(BGrQ&vRTw97a$oWU(T7vWs4s6iXu=}~*^4mYWnS6O^ zva|T9D(B%?xD~w@nSmNg<7##|84IEzdHPNAd_-g^Xnm(U_{q+nLz$f6yy}lceKRAd zID;(7gAyyJzM3oIt-bDSXHnEl`70{*sXDUGBM}r+&-!@fbCvLKKLAwm{dtL(Me_Jjv8gRTt=Kg z*uNwQfR4vyPW=gD%--lE|FC>Ffvco5lK*Mq5sXfC-7l)hPXlL0Wu`sj>hOM)Z{oVe z16mgQE!&Z2dS@;VY+vDflySA=2E%I)a%N^N2N|{b?zOzR1JMYr6O@Qb%6tW>F%%~% zc&_8KzN)ZGy-9Zbl+79*&zX5-p14gV{v>U8;jF9`M6c`V_}!2g|AM`2eD(UH8?HZk z_2&yAV(&92#Px8p#+-RXs0k9fIJ|HOA?g(J#xp>6i`NB71VyZL5aJhpA+%9bLFp3eF@Y7gpxF|!8BAob1QYuMukARbV zV!X8+RL`uRUGtY-V@_RNig$m=p$|9m(&zndiwtchDG;Op{Xrdfpg*&s(FoW}Yn=fQ z%9%YZz`Dh&dZq_NT=l8%)SK8NPd8t;3pN@=AK~R1>5he9pSSAHzW1iHG8%!Q>0lJ?g)g7FCHd zKWsOxoe7w!HIbc8%KU^`J)=dI@ZFPMUAf~K-1ar8mT@F@r%v+!gO<(vrL(~I@C}w* z<`d#=ltiCIhswxiQ>e|e%up_C<(_G9Bw#$=z+faOs~^$AANCqrvlW)1XC|1W_njG? z7N4e!s3gGU+`R}}$4ra*pkp(%p!U`p7d3GWunR6m^7=xKvye}BnUJD%=3$cE`%UWy z(s}*hOzz|N%v7+lvMTFVB$!`MJJb=86raC!8y)>1^!T^yLl+}u3JtS1>MJDs>sO@E z+UeF1E3|`qq&y4K7VigM|EDW{I?=7xpC|h;(F1W~&m9_T!cz3_a&Adap&4O1uXQ&e zZyzC#OVQrU(U79oe_+!Y74&H%v=TOJB0+_C_RXbNdscL$z>)TmD>ZDkh++0D zS#m`OBDHq?+K^VBc2D+vch$22JMfmvGqB}Ige zSt!nUt6N-ZM@7qtL0F|CYCgHvZ+Exz@bJ(bARBAAlz_i-dzC~dn^jiEy_O-q%SJfB ztk1hhicw-5ot2z^WA%xg^P&eiC_@>6WX@zWJ(heJfXDk_%`oY{sa~lLcwCM7wkO%6 z&LZ@F)!5sd0T3a8RS1V{EO7-nUhWW$emPJOqQQoc$W@g$Nk|-)*H&8CGR*k1?@qlw z{RShzLQ)LU_~DXXu8DKqp{*}Mmg7x{5Bw3lq0+bu*;+r>6|JxlDYH4J3_md|u1=ag z%<{q0RVCeiQoU$={-;rW_p8Y?>dCi7GTJBT>O+&=^;=!=swx!B9b|&)cU7FEbd&!o zEHv9KET1Dfx}d6=K4zt|l6M^YH8WfJVpUA~dLR}6iybpIqPUdX*kohXM{r^<{!1hh zdas9!Hx!jh#7;yg$7z}@OzzX+KGz3fHt|26+gOAxz85mL0j5%nfjeIh4n-qJv)!54 zsU}fw1h`zgmuTMteGWbZznCbLT5*0?%}Dn4!rgxum3hpbd+L>C|WnIeU_@Im+C+M+M#7w!<5i# zm80=mjl`j@;fxD$-?nuN4M&psNo7GY#et3kZR5^S^ulntr(@+2S3F$4X8_6;YRQgo zCRUvxJpu|p-Z)!PANYS>qTG;; zi|EL(=RCF3y;xtA8MKZx2g%}U9u^H3Egbp`)U9&q%38UJ$Bn2ne7P#mfXAX((a7{X zGP5QnF2k@R2L}f{WU-)Wb(jw8gM>uE=G~ve!>zqc>Wt|K#WZVN2u5zFEgRhFuT~TY zD9$}$DdRxvte1F_&}ESSA}suNvl9RPFh_(-N7=fvzx08sVe-z5V8|VPoGyyww7LN4 zuvK3|YpWkkn;t&5fjX`Bon^`5Hiy@3?$lD197~dygFcFhhS|Y6Tvg?Ava-6$4Y~>A zZU2T=&OLqJg-%X*63JD>uueno#TbcZs0)RuzcfJ;9I>B~kdlJ1q}v!_z_@~5#7FrO zM|Y-{r@9ttLT{BP%MgvN-9ISsDk&RFO73*o$$^i9x_!U8X0$Wskp{^!m>~KO z=OGDBK_cgl(EBN>+Umb?+Sn%giJ1!redt@<6rsfeo`x=kmrfvbxd`9KEH; zYB5XDE2dC~v!(-Y8({6gPv>3ZEDcAHEb-pg%PSSZ`B|#J_k7@b9}FrVjz?82f=cRZ4%;IvDVx z&2uq9p`(DHSl41B&Ro_sFu0ZSQ-Kfrf3RF}?pdDPj5$11eV=4o?&Mgrz~#e?bmupv zNg((dZc3!6UA^hm81}lsIhE{-ju6vV3 zuhPb}vV2RphsvK_KXcz$$-nav2M_eoevlq5FFF5jm|HLcC-zm;q74xN>$7ij~{ z_RCM8U9O&WuCrLuj>EBbh}=8z`MIiOtJ%RYlUKQa-F03h`m*B#!Aw^keikdFqQmJ zVm($|k|b}}Zn!9*Q``NFHK$sfX8(l%cne~^^T%-qsY|s=pRBPxk?^Mr_zuYR10pg> zdP;Kt9WS8x0Bc)dR8}fjHDKAx)!iNQ87zk<Ujs~4dJ2_%`L@^<=3t-O6l-tM>cnq-JBrjYQ zAU{`KheBT9UH~NM0Jzc& zmBo9imoC;8-}?Ky%)}`bPmS9sttbc{&nx+KK1_1o81;XYCID~P4*MmNf*Fir!4yAg zEAY;M7+E18C5$ibOh&%HB%I0(CiWa`MmYx}~g*mEA3MeG=c;{E=e=cc04B}KS$*rC#cFm;55(jyAii4Av=Ki+c~gD&FxsPP%(fOpZH@_aQ5NH5B3|ON@qfQ}$2s!<_y9a}(TR&CXzCFj zPV|&{%|uC7C_bt+v#YBMv$m}<4`786aYJWedo;%7f+KK?YxBrMAHN?Fcy)`0odrf3 z+;2}pU%hc3p@x9-s>!ly>1(ng6mFp$@9FecuGWy;7av;C)$tXd(dTig1_J2Nay@tZ z%xppWm*Avhpao3i5qQtx_+i!Rvey;|*$_#Fh&oj&Fd!w#flMU9I*4vERI++j=FEnG zTv@#KM@TLDgoRq z7`gNaYSssY9&fu=azoMxmo%`1w{GRuLn0s8{_M;DkzbdkvbW4VmWuB;<~kEk;X|{q8_1iD9+$> z96<7IZ1lL@yeXC2z&&oL3#x43a{%YfjXKm1oIT1pYY!u=x$Hxr?;JBU|5w41BH7kF z#vTA79@hfZ{CR7J!LZ+S@H@Uv`D%~yL3r3Mbi|q9!4c*va0P9*6l!nJ`S`+bt-NA) zoW3A9dyz9#QTo+c9S=kJp$iiO{ZD#(5)^J0V6WG%*Z{f=!Z%BqAf2l0s`9c?HKZwI i)a4g}|6v#xu5f}7CW|(AMdBdfOG!>mwoLk2!2bc&!TK-& literal 0 HcmV?d00001 diff --git a/ros_ign_gazebo_demos/launch/navsat.launch.py b/ros_ign_gazebo_demos/launch/navsat.launch.py new file mode 100644 index 00000000..1099de0e --- /dev/null +++ b/ros_ign_gazebo_demos/launch/navsat.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + + ign_gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + launch_arguments={ + 'ign_args': '-v 4 -r spherical_coordinates.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # Bridge + bridge = Node( + package='ros_ign_bridge', + executable='parameter_bridge', + arguments=['/navsat@sensor_msgs/msg/NavSatFix@ignition.msgs.NavSat'], + output='screen' + ) + + return LaunchDescription([ + ign_gazebo, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ])